From 7ce5ed918a95d48c0d8fed4f2b0691e168e939bb Mon Sep 17 00:00:00 2001 From: democat Date: Mon, 15 Sep 2025 22:03:21 -0500 Subject: [PATCH 01/47] Add new profile/controller --- include/robot/profiledPIDController.h | 40 ++++++++ include/robot/trapezoidalProfileNew.h | 72 ++++++++++++++ src/robot/trapezoidalProfileNew.cpp | 130 ++++++++++++++++++++++++++ 3 files changed, 242 insertions(+) create mode 100644 include/robot/profiledPIDController.h create mode 100644 include/robot/trapezoidalProfileNew.h create mode 100644 src/robot/trapezoidalProfileNew.cpp diff --git a/include/robot/profiledPIDController.h b/include/robot/profiledPIDController.h new file mode 100644 index 0000000..aa4f8a3 --- /dev/null +++ b/include/robot/profiledPIDController.h @@ -0,0 +1,40 @@ +#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, + const TrapezoidProfile::Constraints& constraints) + : pid(kp, ki, kd, minOutput, maxOutput), 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..855a180 --- /dev/null +++ b/include/robot/trapezoidalProfileNew.h @@ -0,0 +1,72 @@ +#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), m_direction(1), m_endAccel(0), m_endFullSpeed(0), m_endDecel(0) {} + + State calculate(double t, const State& current, const State& goal); + + double timeLeftUntil(double target); + + double totalTime() const { return m_endDecel; } + + 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) const + { + return State(in.position * m_direction, in.velocity * m_direction); + } + + int m_direction; + Constraints m_constraints; + State m_current; + double m_endAccel; + double m_endFullSpeed; + double m_endDecel; +}; + +#endif \ No newline at end of file diff --git a/src/robot/trapezoidalProfileNew.cpp b/src/robot/trapezoidalProfileNew.cpp new file mode 100644 index 0000000..5a75c3c --- /dev/null +++ b/src/robot/trapezoidalProfileNew.cpp @@ -0,0 +1,130 @@ +#include "robot/trapezoidalProfileNew.h" + +TrapezoidProfile::State TrapezoidProfile::calculate(double t, const State ¤t, const State &goal) +{ + m_direction = shouldFlipAcceleration(current, goal) ? -1 : 1; + m_current = direct(current); + State goalDir = direct(goal); + + if (std::abs(m_current.velocity) > m_constraints.maxVelocity) + { + m_current.velocity = std::copysign(m_constraints.maxVelocity, m_current.velocity); + } + + double cutoffBegin = m_current.velocity / m_constraints.maxAcceleration; + double cutoffDistBegin = cutoffBegin * cutoffBegin * m_constraints.maxAcceleration / 2.0; + + double cutoffEnd = goalDir.velocity / 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; + } + + m_endAccel = accelerationTime - cutoffBegin; + m_endFullSpeed = m_endAccel + fullSpeedDist / m_constraints.maxVelocity; + m_endDecel = m_endFullSpeed + accelerationTime - cutoffEnd; + State result(m_current.position, m_current.velocity); + + if (t < m_endAccel) + { + result.velocity += t * m_constraints.maxAcceleration; + result.position += (m_current.velocity + t * m_constraints.maxAcceleration / 2.0) * t; + } + 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); + } + else if (t <= m_endDecel) + { + result.velocity = goalDir.velocity + (m_endDecel - t) * m_constraints.maxAcceleration; + double timeLeft = m_endDecel - t; + result.position = + goalDir.position - (goalDir.velocity + timeLeft * m_constraints.maxAcceleration / 2.0) * timeLeft; + } + else + { + result = goalDir; + } + + return direct(result); +} + +double TrapezoidProfile::timeLeftUntil(double target) +{ + double position = m_current.position * m_direction; + double velocity = m_current.velocity * m_direction; + + double endAccel = m_endAccel * m_direction; + double endFullSpeed = m_endFullSpeed * m_direction - endAccel; + + if (target < position) + { + endAccel = -endAccel; + endFullSpeed = -endFullSpeed; + velocity = -velocity; + } + + endAccel = std::max(endAccel, 0.0); + endFullSpeed = std::max(endFullSpeed, 0.0); + + const double acceleration = m_constraints.maxAcceleration; + const double deceleration = -m_constraints.maxAcceleration; + + double distToTarget = std::abs(target - position); + if (distToTarget < 1e-6) + { + return 0; + } + + double accelDist = velocity * endAccel + 0.5 * acceleration * endAccel * endAccel; + + double decelVelocity; + if (endAccel > 0) + { + decelVelocity = std::sqrt(std::abs(velocity * velocity + 2 * acceleration * accelDist)); + } + else + { + decelVelocity = velocity; + } + + double fullSpeedDist = m_constraints.maxVelocity * endFullSpeed; + double decelDist; + + if (accelDist > distToTarget) + { + accelDist = distToTarget; + fullSpeedDist = 0; + decelDist = 0; + } + else if (accelDist + fullSpeedDist > distToTarget) + { + fullSpeedDist = distToTarget - accelDist; + decelDist = 0; + } + else + { + decelDist = distToTarget - fullSpeedDist - accelDist; + } + + double accelTime = + (-velocity + std::sqrt(std::abs(velocity * velocity + 2 * acceleration * accelDist))) / acceleration; + + double decelTime = + (-decelVelocity + std::sqrt(std::abs(decelVelocity * decelVelocity + 2 * deceleration * decelDist))) / deceleration; + + double fullSpeedTime = fullSpeedDist / m_constraints.maxVelocity; + + return accelTime + fullSpeedTime + decelTime; +} \ No newline at end of file From 59a84a52da0ea0ffacc037b431e2aa7849440767 Mon Sep 17 00:00:00 2001 From: democat Date: Mon, 15 Sep 2025 22:07:37 -0500 Subject: [PATCH 02/47] Use new trapezoid profile implementation --- src/robot/control.cpp | 45 +++++++++++++++++++++++++++---------------- 1 file changed, 28 insertions(+), 17 deletions(-) diff --git a/src/robot/control.cpp b/src/robot/control.cpp index 383c6f8..46fca2c 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,8 +23,15 @@ #include #include "utils/functions.h" +#include "robot/profiledPIDController.h" +#include "robot/trapezoidalProfileNew.h" + //PLEASE ONLY USE CHESSBOT #4 FOR TESTING -PIDController encoderAVelocityController(0.00008, 0.0000035, 0.000001, -1, +1); //Blue +TrapezoidProfile::Constraints profileConstraints(MAX_VELOCITY_TPS, MAX_ACCELERATION_TPSPS); +TrapezoidProfile leftProfile(profileConstraints); +TrapezoidProfile rightProfile(profileConstraints); +TrapezoidProfile::State leftSetpoint, rightSetpoint; +PIDController encoderAVelocityController(0.00008, 0.0000035, 0.000001, -1, +1); // Blue PIDController encoderBVelocityController(0.00008, 0.0000035, 0.000001, -1, +1); //Red //put this in manually for each bot. Dist between the two front encoders, or the two back encoders. In meters. @@ -245,27 +251,30 @@ void controlLoop(int loopDelayMs, int8_t framesUntilPrint) { profileB.currentPosition = currentPositionEncoderB; profileB.currentVelocity = currentVelocityB; - double desiredVelocityA, desiredVelocityB; - + // Generate trapezoidal profile setpoints if (getLeftMotorControl().mode == POSITION) { - desiredVelocityA = updateTrapezoidalProfile(profileA, loopDelaySeconds, framesUntilPrint); + leftSetpoint = leftProfile.calculate(loopDelaySeconds, + leftSetpoint, + TrapezoidProfile::State(getLeftMotorControl().value, 0.0)); } else { - desiredVelocityA = getLeftMotorControl().value; + leftSetpoint = TrapezoidProfile::State(currentPositionEncoderA, getLeftMotorControl().value); } if (getRightMotorControl().mode == POSITION) { - desiredVelocityB = updateTrapezoidalProfile(profileB, loopDelaySeconds, framesUntilPrint); + rightSetpoint = rightProfile.calculate(loopDelaySeconds, + rightSetpoint, + TrapezoidProfile::State(getRightMotorControl().value, 0.0)); } else { - desiredVelocityB = getRightMotorControl().value; + rightSetpoint = TrapezoidProfile::State(currentPositionEncoderB, getRightMotorControl().value); } prevPositionA = currentPositionEncoderA; prevPositionB = currentPositionEncoderB; - double leftFeedForward = desiredVelocityA / MAX_VELOCITY_TPS; - double rightFeedForward = desiredVelocityB / MAX_VELOCITY_TPS; + double leftFeedForward = leftSetpoint.velocity / MAX_VELOCITY_TPS; + double rightFeedForward = rightSetpoint.velocity / MAX_VELOCITY_TPS; - double leftMotorPower = encoderAVelocityController.Compute(desiredVelocityA, currentVelocityA, loopDelaySeconds) + leftFeedForward; - double rightMotorPower = encoderBVelocityController.Compute(desiredVelocityB, currentVelocityB, loopDelaySeconds) + rightFeedForward; + double leftMotorPower = encoderAVelocityController.Compute(leftSetpoint.velocity, currentVelocityA, loopDelaySeconds) + leftFeedForward; + double rightMotorPower = encoderBVelocityController.Compute(rightSetpoint.velocity, currentVelocityB, loopDelaySeconds) + rightFeedForward; if (leftMotorPower > 1) leftMotorPower = 1; if (leftMotorPower < -1) leftMotorPower = -1; @@ -273,21 +282,21 @@ void controlLoop(int loopDelayMs, int8_t framesUntilPrint) { if (rightMotorPower < -1) rightMotorPower = -1; //using macros this code isn't uploaded if not proper loging levels - #if LOGGING_LEVEL >= 4 + #if LOGGING_LEVEL >= 3 if(framesUntilPrint == 0) { serialLog("Current encoder A pos: ", 2); - serialLog(currentEncoderA, 2); + serialLog(currentPositionEncoderA, 2); serialLog(", ", 2); serialLog("Current encoder B pos: ", 2); - serialLog(currentEncoderB, 2); + serialLog(currentPositionEncoderB, 2); serialLog(", ", 2); serialLog("Desired encoder A speed: ", 2); - serialLog(desiredVelocityA, 2); + serialLog(leftSetpoint.velocity, 2); serialLog(", ", 2); serialLog("Desired encoder B speed: ", 2); - serialLog(desiredVelocityB, 2); + serialLog(rightSetpoint.velocity, 2); serialLog(", ", 2); serialLog("current encoder a speed: ", 2); serialLog(currentVelocityA, 2); @@ -484,6 +493,7 @@ bool checkIfCanUpdateMovement() void setLeftMotorControl(ControlSetting control) { leftMotorControl = control; + leftSetpoint = TrapezoidProfile::State(readLeftEncoder(), profileA.currentVelocity); if (control.mode == POSITION) profileA.targetPosition = control.value; else @@ -492,6 +502,7 @@ void setLeftMotorControl(ControlSetting control) { void setRightMotorControl(ControlSetting control) { rightMotorControl = control; + rightSetpoint = TrapezoidProfile::State(readRightEncoder(), profileB.currentVelocity); if (control.mode == POSITION) profileB.targetPosition = control.value; else From 490dadb24fc765d49f926d6a6e30e4fef7966b3a Mon Sep 17 00:00:00 2001 From: democat Date: Mon, 15 Sep 2025 22:56:01 -0500 Subject: [PATCH 03/47] Tune PID? encoders are dead now --- pid_test.csv | 4234 +++++++++++++++++++++++++++++++++-------- pid_vis.py | 44 +- src/robot/control.cpp | 86 +- 3 files changed, 3552 insertions(+), 812 deletions(-) diff --git a/pid_test.csv b/pid_test.csv index 11adc7a..72e5b82 100644 --- a/pid_test.csv +++ b/pid_test.csv @@ -1,755 +1,3479 @@ -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 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +-100.00,0.00,-100.00,-100.00,0.00,-100.00 +-200.00,0.00,-200.00,-200.00,0.00,-200.00 +-300.00,0.00,-300.00,-300.00,0.00,-300.00 +-400.00,0.00,-400.00,-400.00,0.00,-400.00 +-500.00,0.00,-500.00,-500.00,0.00,-500.00 +-600.00,0.00,-600.00,-600.00,0.00,-600.00 +-700.00,0.00,-700.00,-700.00,0.00,-700.00 +-800.00,0.00,-800.00,-800.00,0.00,-800.00 +-900.00,0.00,-900.00,-900.00,0.00,-900.00 +-1000.00,0.00,-1000.00,-1000.00,0.00,-1000.00 +-1100.00,0.00,-1100.00,-1100.00,0.00,-1100.00 +-1200.00,0.00,-1200.00,-1200.00,0.00,-1200.00 +-1300.00,0.00,-1300.00,-1300.00,0.00,-1300.00 +-1400.00,0.00,-1400.00,-1400.00,0.00,-1400.00 +-1500.00,0.00,-1500.00,-1500.00,0.00,-1500.00 +-1600.00,0.00,-1600.00,-1600.00,0.00,-1600.00 +-1700.00,-400.00,-1300.00,-1700.00,-500.00,-1200.00 +-1800.00,-600.00,-1200.00,-1800.00,-600.00,-1200.00 +-1900.00,650.00,-2550.00,-1900.00,800.00,-2700.00 +-2000.00,-450.00,-1550.00,-2000.00,-500.00,-1500.00 +-2100.00,-3150.00,1050.00,-2100.00,-3350.00,1250.00 +-2200.00,-4000.00,1800.00,-2200.00,-3600.00,1400.00 +-2300.00,-3150.00,850.00,-2300.00,-2500.00,200.00 +-2400.00,-2400.00,0.00,-2400.00,-1300.00,-1100.00 +-2500.00,-1300.00,-1200.00,-2500.00,-350.00,-2150.00 +-2600.00,-1200.00,-1400.00,-2600.00,-1100.00,-1500.00 +-2700.00,-2750.00,50.00,-2700.00,-3750.00,1050.00 +-2800.00,-3600.00,800.00,-2800.00,-4000.00,1200.00 +-2900.00,-2650.00,-250.00,-2900.00,-2850.00,-50.00 +-3000.00,-2150.00,-850.00,-3000.00,-1200.00,-1800.00 +-3100.00,-650.00,-2450.00,-3100.00,-1200.00,-1900.00 +-3200.00,-750.00,-2450.00,-3200.00,-3600.00,400.00 +-3300.00,-5050.00,1750.00,-3300.00,-4800.00,1500.00 +-3400.00,-6800.00,3400.00,-3400.00,-3500.00,100.00 +-3500.00,-4900.00,1400.00,-3500.00,-2400.00,-1100.00 +-3600.00,-1300.00,-2300.00,-3600.00,-1450.00,-2150.00 +-3700.00,-1750.00,-1950.00,-3700.00,-3150.00,-550.00 +-3800.00,-5300.00,1500.00,-3800.00,-4800.00,1000.00 +-3900.00,-6850.00,2950.00,-3900.00,-3850.00,-50.00 +-4000.00,-5750.00,1750.00,-4000.00,-2550.00,-1450.00 +-4100.00,-4900.00,800.00,-4100.00,-2300.00,-1800.00 +-4200.00,-3950.00,-250.00,-4200.00,-4200.00,0.00 +-4300.00,-3050.00,-1250.00,-4300.00,-5350.00,1050.00 +-4400.00,-3050.00,-1350.00,-4400.00,-4150.00,-250.00 +-4500.00,-4900.00,400.00,-4500.00,-3200.00,-1300.00 +-4600.00,-5900.00,1300.00,-4600.00,-2900.00,-1700.00 +-4700.00,-4950.00,250.00,-4700.00,-4850.00,150.00 +-4800.00,-4100.00,-700.00,-4800.00,-6050.00,1250.00 +-4900.00,-3750.00,-1150.00,-4900.00,-5150.00,250.00 +-5000.00,-4700.00,-300.00,-5000.00,-4050.00,-950.00 +-5100.00,-5400.00,300.00,-5100.00,-3500.00,-1600.00 +-5200.00,-4650.00,-550.00,-5200.00,-5250.00,50.00 +-5300.00,-4450.00,-850.00,-5300.00,-6550.00,1250.00 +-5400.00,-5100.00,-300.00,-5400.00,-5500.00,100.00 +-5500.00,-6150.00,650.00,-5500.00,-4700.00,-800.00 +-5600.00,-5800.00,200.00,-5600.00,-4300.00,-1300.00 +-5700.00,-4850.00,-850.00,-5700.00,-5900.00,200.00 +-5800.00,-4750.00,-1050.00,-5800.00,-6950.00,1150.00 +-5900.00,-6300.00,400.00,-5900.00,-5650.00,-250.00 +-6000.00,-7200.00,1200.00,-6000.00,-5350.00,-650.00 +-6100.00,-5800.00,-300.00,-6100.00,-5850.00,-250.00 +-6200.00,-5500.00,-700.00,-6200.00,-6600.00,400.00 +-6300.00,-6300.00,0.00,-6300.00,-6200.00,-100.00 +-6400.00,-7050.00,650.00,-6400.00,-5900.00,-500.00 +-6500.00,-6850.00,350.00,-6500.00,-6650.00,150.00 +-6600.00,-5750.00,-850.00,-6600.00,-6450.00,-150.00 +-6700.00,-5650.00,-1050.00,-6700.00,-6000.00,-700.00 +-6800.00,-7400.00,600.00,-6800.00,-6700.00,-100.00 +-6900.00,-8100.00,1200.00,-6900.00,-7450.00,550.00 +-7000.00,-6500.00,-500.00,-7000.00,-7050.00,50.00 +-7100.00,-6350.00,-750.00,-7100.00,-6300.00,-800.00 +-7200.00,-7450.00,250.00,-7200.00,-7200.00,0.00 +-7300.00,-8400.00,1100.00,-7300.00,-8100.00,800.00 +-7400.00,-8200.00,800.00,-7400.00,-7800.00,400.00 +-7500.00,-6450.00,-1050.00,-7500.00,-6150.00,-1350.00 +-7600.00,-6650.00,-950.00,-7600.00,-6700.00,-900.00 +-7700.00,-8900.00,1200.00,-7700.00,-8650.00,950.00 +-7800.00,-11050.00,3250.00,-7800.00,-10700.00,2900.00 +-7900.00,-7500.00,-400.00,-7900.00,-7100.00,-800.00 +-8000.00,-6850.00,-1150.00,-8000.00,-6800.00,-1200.00 +-8100.00,-8600.00,500.00,-8100.00,-8600.00,500.00 +-8200.00,-10100.00,1900.00,-8200.00,-9950.00,1750.00 +-8300.00,-9600.00,1300.00,-8300.00,-9350.00,1050.00 +-8400.00,-7750.00,-650.00,-8400.00,-7700.00,-700.00 +-8500.00,-7550.00,-950.00,-8500.00,-7300.00,-1200.00 +-8600.00,-9050.00,450.00,-8600.00,-8850.00,250.00 +-8700.00,-10750.00,2050.00,-8700.00,-10500.00,1800.00 +-8800.00,-10250.00,1450.00,-8800.00,-10250.00,1450.00 +-8900.00,-8300.00,-600.00,-8900.00,-8300.00,-600.00 +-9000.00,-7950.00,-1050.00,-9000.00,-7800.00,-1200.00 +-9100.00,-9750.00,650.00,-9100.00,-9600.00,500.00 +-9200.00,-11550.00,2350.00,-9200.00,-11250.00,2050.00 +-9300.00,-10950.00,1650.00,-9300.00,-10550.00,1250.00 +-9400.00,-8850.00,-550.00,-9400.00,-8400.00,-1000.00 +-9500.00,-8300.00,-1200.00,-9500.00,-8250.00,-1250.00 +-9600.00,-10000.00,400.00,-9600.00,-10200.00,600.00 +-9700.00,-12600.00,2900.00,-9700.00,-12150.00,2450.00 +-9800.00,-12050.00,2250.00,-9800.00,-11350.00,1550.00 +-9900.00,-9400.00,-500.00,-9900.00,-8500.00,-1400.00 +-10000.00,-9350.00,-650.00,-10000.00,-9000.00,-1000.00 +-10100.00,-10850.00,750.00,-10100.00,-11350.00,1250.00 +-10200.00,-12300.00,2100.00,-10200.00,-12000.00,1800.00 +-10300.00,-11650.00,1350.00,-10300.00,-9550.00,-750.00 +-10400.00,-9450.00,-950.00,-10400.00,-8800.00,-1600.00 +-10500.00,-9050.00,-1450.00,-10500.00,-11100.00,600.00 +-10600.00,-12200.00,1600.00,-10600.00,-13650.00,3050.00 +-10700.00,-14000.00,3300.00,-10700.00,-12500.00,1800.00 +-10800.00,-11150.00,350.00,-10800.00,-9750.00,-1050.00 +-10900.00,-9700.00,-1200.00,-10900.00,-9350.00,-1550.00 +-11000.00,-11300.00,300.00,-11000.00,-12050.00,1050.00 +-11100.00,-13950.00,2850.00,-11100.00,-14250.00,3150.00 +-11200.00,-13550.00,2350.00,-11200.00,-12900.00,1700.00 +-11300.00,-10750.00,-550.00,-11300.00,-9900.00,-1400.00 +-11400.00,-10000.00,-1400.00,-11400.00,-9700.00,-1700.00 +-11500.00,-12650.00,1150.00,-11500.00,-12950.00,1450.00 +-11600.00,-15100.00,3500.00,-11600.00,-15150.00,3550.00 +-11700.00,-13950.00,2250.00,-11700.00,-13500.00,1800.00 +-11800.00,-11000.00,-800.00,-11800.00,-10650.00,-1150.00 +-11900.00,-10700.00,-1200.00,-11900.00,-10650.00,-1250.00 +-12000.00,-13400.00,1400.00,-12000.00,-13350.00,1350.00 +-12100.00,-15600.00,3500.00,-12100.00,-15400.00,3300.00 +-12200.00,-14200.00,2000.00,-12200.00,-14100.00,1900.00 +-12300.00,-11300.00,-1000.00,-12300.00,-11650.00,-650.00 +-12400.00,-10450.00,-1950.00,-12400.00,-11950.00,-450.00 +-12500.00,-14350.00,1850.00,-12500.00,-14050.00,1550.00 +-12600.00,-17600.00,5000.00,-12600.00,-15000.00,2400.00 +-12700.00,-15550.00,2850.00,-12700.00,-13700.00,1000.00 +-12800.00,-12250.00,-550.00,-12800.00,-11450.00,-1350.00 +-12900.00,-11450.00,-1450.00,-12900.00,-13550.00,650.00 +-13000.00,-14300.00,1300.00,-13000.00,-15800.00,2800.00 +-13100.00,-17200.00,4100.00,-13100.00,-14800.00,1700.00 +-13200.00,-15750.00,2550.00,-13200.00,-12250.00,-950.00 +-13300.00,-12400.00,-900.00,-13300.00,-12800.00,-500.00 +-13400.00,-11500.00,-1900.00,-13400.00,-15550.00,2150.00 +-13500.00,-15200.00,1700.00,-13500.00,-16500.00,3000.00 +-13600.00,-18700.00,5100.00,-13600.00,-14700.00,1100.00 +-13700.00,-17200.00,3500.00,-13700.00,-12100.00,-1600.00 +-13800.00,-13150.00,-650.00,-13800.00,-13800.00,0.00 +-13900.00,-12000.00,-1900.00,-13900.00,-17300.00,3400.00 +-14000.00,-15800.00,1800.00,-14000.00,-16900.00,2900.00 +-14100.00,-19250.00,5150.00,-14100.00,-13150.00,-950.00 +-14200.00,-17550.00,3350.00,-14200.00,-12000.00,-2200.00 +-14300.00,-13450.00,-850.00,-14300.00,-16050.00,1750.00 +-14400.00,-12350.00,-2050.00,-14400.00,-19500.00,5100.00 +-14500.00,-16650.00,2150.00,-14500.00,-17650.00,3150.00 +-14600.00,-20450.00,5850.00,-14600.00,-13450.00,-1150.00 +-14700.00,-18250.00,3550.00,-14700.00,-12150.00,-2550.00 +-14800.00,-14450.00,-350.00,-14800.00,-17300.00,2500.00 +-14900.00,-12850.00,-2050.00,-14900.00,-21250.00,6350.00 +-15000.00,-16450.00,1450.00,-15000.00,-18150.00,3150.00 +-15100.00,-20550.00,5450.00,-15100.00,-13550.00,-1550.00 +-15200.00,-22900.00,7700.00,-15200.00,-15700.00,500.00 +-15300.00,-12400.00,-2900.00,-15300.00,-17250.00,1950.00 +-15400.00,-8150.00,-7250.00,-15400.00,-18200.00,2800.00 +-15500.00,-15900.00,400.00,-15500.00,-16150.00,650.00 +-15600.00,-22150.00,6550.00,-15600.00,-14500.00,-1100.00 +-15700.00,-21050.00,5350.00,-15700.00,-16000.00,300.00 +-15800.00,-16050.00,250.00,-15800.00,-18900.00,3100.00 +-15900.00,-13850.00,-2050.00,-15900.00,-18250.00,2350.00 +-16000.00,-16750.00,750.00,-16000.00,-15150.00,-850.00 +-16100.00,-21250.00,5150.00,-16100.00,-15400.00,-700.00 +-16200.00,-20800.00,4600.00,-16200.00,-19650.00,3450.00 +-16300.00,-15300.00,-1000.00,-16300.00,-19600.00,3300.00 +-16400.00,-13950.00,-2450.00,-16400.00,-15250.00,-1150.00 +-16500.00,-19500.00,3000.00,-16500.00,-13800.00,-2700.00 +-16600.00,-21600.00,5000.00,-16600.00,-16900.00,300.00 +-16700.00,-18850.00,2150.00,-16700.00,-21400.00,4700.00 +-16800.00,-15400.00,-1400.00,-16800.00,-20900.00,4100.00 +-16900.00,-16700.00,-200.00,-16900.00,-15750.00,-1150.00 +-17000.00,-21550.00,4550.00,-17000.00,-14700.00,-2300.00 +-17100.00,-20700.00,3600.00,-17100.00,-18350.00,1250.00 +-17200.00,-15950.00,-1250.00,-17200.00,-22350.00,5150.00 +-17300.00,-14450.00,-2850.00,-17300.00,-20850.00,3550.00 +-17400.00,-20700.00,3300.00,-17400.00,-16350.00,-1050.00 +-17500.00,-25000.00,7500.00,-17332.74,-14450.00,-2882.74 +-17404.00,-21150.00,3746.00,-17232.74,-18900.00,1667.26 +-17304.00,-15900.00,-1404.00,-17132.74,-23000.00,5867.26 +-17204.00,-14450.00,-2754.00,-17032.74,-21200.00,4167.26 +-17104.00,-20800.00,3696.00,-16932.74,-16650.00,-282.74 +-17004.00,-23300.00,6296.00,-16832.74,-13750.00,-3082.74 +-16904.00,-17950.00,1046.00,-16732.74,-17800.00,1067.26 +-16804.00,-14900.00,-1904.00,-16632.74,-22050.00,5417.26 +-16704.00,-17750.00,1046.00,-16532.74,-21350.00,4817.26 +-16604.00,-21400.00,4796.00,-16432.74,-15800.00,-632.74 +-16504.00,-20400.00,3896.00,-16332.74,-13500.00,-2832.74 +-16404.00,-16000.00,-404.00,-16232.74,-18700.00,2467.26 +-16304.00,-14100.00,-2204.00,-16132.74,-22800.00,6667.26 +-16204.00,-18100.00,1896.00,-16032.74,-19300.00,3267.26 +-16104.00,-22000.00,5896.00,-15932.74,-14550.00,-1382.74 +-16004.00,-20900.00,4896.00,-15832.74,-13600.00,-2232.74 +-15904.00,-15700.00,-204.00,-15732.74,-18450.00,2717.26 +-15804.00,-13700.00,-2104.00,-15632.74,-22000.00,6367.26 +-15704.00,-17750.00,2046.00,-15532.74,-19100.00,3567.26 +-15604.00,-21050.00,5446.00,-15432.74,-14200.00,-1232.74 +-15504.00,-19100.00,3596.00,-15332.74,-12900.00,-2432.74 +-15404.00,-15000.00,-404.00,-15232.74,-18400.00,3167.26 +-15304.00,-13300.00,-2004.00,-15132.74,-20950.00,5817.26 +-15204.00,-17650.00,2446.00,-15032.74,-16250.00,1217.26 +-15104.00,-21550.00,6446.00,-14932.74,-13100.00,-1832.74 +-15004.00,-19050.00,4046.00,-14832.74,-15200.00,367.26 +-14904.00,-14400.00,-504.00,-14732.74,-19250.00,4517.26 +-14804.00,-12900.00,-1904.00,-14632.74,-18500.00,3867.26 +-14704.00,-17100.00,2396.00,-14532.74,-14050.00,-482.74 +-14604.00,-20850.00,6246.00,-14432.74,-12500.00,-1932.74 +-14504.00,-18600.00,4096.00,-14332.74,-16000.00,1667.26 +-14404.00,-14050.00,-354.00,-14232.74,-19700.00,5467.26 +-14304.00,-12400.00,-1904.00,-14132.74,-17900.00,3767.26 +-14204.00,-16400.00,2196.00,-14032.74,-13350.00,-682.74 +-14104.00,-20400.00,6296.00,-13932.74,-12150.00,-1782.74 +-14004.00,-18200.00,4196.00,-13832.74,-15700.00,1867.26 +-13904.00,-12950.00,-954.00,-13732.74,-17400.00,3667.26 +-13804.00,-12750.00,-1054.00,-13632.74,-16700.00,3067.26 +-13704.00,-16750.00,3046.00,-13532.74,-12750.00,-782.74 +-13604.00,-18250.00,4646.00,-13432.74,-11700.00,-1732.74 +-13504.00,-14100.00,596.00,-13332.74,-15150.00,1817.26 +-13404.00,-11550.00,-1854.00,-13232.74,-17600.00,4367.26 +-13304.00,-14150.00,846.00,-13132.74,-16450.00,3317.26 +-13204.00,-18600.00,5396.00,-13032.74,-12250.00,-782.74 +-13104.00,-17200.00,4096.00,-12932.74,-10900.00,-2032.74 +-13004.00,-13700.00,696.00,-12832.74,-14800.00,1967.26 +-12904.00,-11450.00,-1454.00,-12732.74,-18200.00,5467.26 +-12804.00,-13550.00,746.00,-12632.74,-16200.00,3567.26 +-12704.00,-17250.00,4546.00,-12532.74,-12400.00,-132.74 +-12604.00,-16350.00,3746.00,-12432.74,-10600.00,-1832.74 +-12504.00,-14600.00,2096.00,-12332.74,-15900.00,3567.26 +-12404.00,-9100.00,-3304.00,-12232.74,-15700.00,3467.26 +-12304.00,-10300.00,-2004.00,-12132.74,-12500.00,367.26 +-12204.00,-17200.00,4996.00,-12032.74,-10550.00,-1482.74 +-12104.00,-16150.00,4046.00,-11932.74,-10100.00,-1832.74 +-12004.00,-14600.00,2596.00,-11832.74,-15650.00,3817.26 +-11904.00,-10650.00,-1254.00,-11732.74,-16600.00,4867.26 +-11804.00,-10350.00,-1454.00,-11632.74,-12900.00,1267.26 +-11704.00,-14900.00,3196.00,-11532.74,-10900.00,-632.74 +-11604.00,-16500.00,4896.00,-11432.74,-11600.00,167.26 +-11504.00,-12600.00,1096.00,-11332.74,-12900.00,1567.26 +-11404.00,-10350.00,-1054.00,-11232.74,-13350.00,2117.26 +-11304.00,-12000.00,696.00,-11132.74,-12300.00,1167.26 +-11204.00,-14100.00,2896.00,-11032.74,-9750.00,-1282.74 +-11104.00,-13350.00,2246.00,-10932.74,-11200.00,267.26 +-11004.00,-10650.00,-354.00,-10832.74,-13000.00,2167.26 +-10904.00,-9550.00,-1354.00,-10732.74,-12950.00,2217.26 +-10804.00,-12100.00,1296.00,-10632.74,-9800.00,-832.74 +-10704.00,-14550.00,3846.00,-10532.74,-9550.00,-982.74 +-10604.00,-13250.00,2646.00,-10432.74,-11800.00,1367.26 +-10504.00,-10450.00,-54.00,-10332.74,-12600.00,2267.26 +-10404.00,-9350.00,-1054.00,-10232.74,-10100.00,-132.74 +-10304.00,-10900.00,596.00,-10132.74,-9000.00,-1132.74 +-10204.00,-13100.00,2896.00,-10032.74,-10300.00,267.26 +-10104.00,-12350.00,2246.00,-9932.74,-12300.00,2367.26 +-10004.00,-9900.00,-104.00,-9832.74,-11950.00,2117.26 +-9904.00,-8800.00,-1104.00,-9732.74,-9250.00,-482.74 +-9804.00,-10700.00,896.00,-9632.74,-8700.00,-932.74 +-9704.00,-12950.00,3246.00,-9532.74,-10300.00,767.26 +-9604.00,-12000.00,2396.00,-9432.74,-11700.00,2267.26 +-9504.00,-9650.00,146.00,-9332.74,-10800.00,1467.26 +-9404.00,-8500.00,-904.00,-9232.74,-8400.00,-832.74 +-9304.00,-9850.00,546.00,-9132.74,-8200.00,-932.74 +-9204.00,-11750.00,2546.00,-9032.74,-10050.00,1017.26 +-9104.00,-11150.00,2046.00,-8932.74,-10550.00,1617.26 +-9004.00,-9000.00,-4.00,-8832.74,-8500.00,-332.74 +-8904.00,-8450.00,-454.00,-8732.74,-8100.00,-632.74 +-8804.00,-9500.00,696.00,-8632.74,-9000.00,367.26 +-8704.00,-10350.00,1646.00,-8532.74,-9650.00,1117.26 +-8604.00,-9750.00,1146.00,-8432.74,-9200.00,767.26 +-8504.00,-8100.00,-404.00,-8332.74,-7350.00,-982.74 +-8404.00,-7600.00,-804.00,-8232.74,-6750.00,-1482.74 +-8304.00,-9600.00,1296.00,-8132.74,-9400.00,1267.26 +-8204.00,-10300.00,2096.00,-8032.74,-10150.00,2117.26 +-8104.00,-8450.00,346.00,-7932.74,-8150.00,217.26 +-8004.00,-7500.00,-504.00,-7832.74,-6950.00,-882.74 +-7904.00,-8400.00,496.00,-7732.74,-7200.00,-532.74 +-7804.00,-9550.00,1746.00,-7632.74,-8850.00,1217.26 +-7704.00,-8900.00,1196.00,-7532.74,-8600.00,1067.26 +-7604.00,-7400.00,-204.00,-7432.74,-6950.00,-482.74 +-7504.00,-7200.00,-304.00,-7332.74,-6250.00,-1082.74 +-7404.00,-7800.00,396.00,-7232.74,-7350.00,117.26 +-7304.00,-8250.00,946.00,-7132.74,-8650.00,1517.26 +-7204.00,-6850.00,-354.00,-7032.74,-8350.00,1317.26 +-7104.00,-6500.00,-604.00,-6932.74,-6800.00,-132.74 +-7004.00,-7550.00,546.00,-6832.74,-5900.00,-932.74 +-6904.00,-8200.00,1296.00,-6732.74,-6450.00,-282.74 +-6804.00,-7000.00,196.00,-6632.74,-7950.00,1317.26 +-6704.00,-5850.00,-854.00,-6532.74,-7550.00,1017.26 +-6604.00,-5800.00,-804.00,-6432.74,-6250.00,-182.74 +-6504.00,-7350.00,846.00,-6332.74,-5400.00,-932.74 +-6404.00,-8050.00,1646.00,-6232.74,-5950.00,-282.74 +-6304.00,-6750.00,446.00,-6132.74,-7050.00,917.26 +-6204.00,-5800.00,-404.00,-6032.74,-6900.00,867.26 +-6104.00,-5450.00,-654.00,-5932.74,-5550.00,-382.74 +-6004.00,-6250.00,246.00,-5832.74,-4850.00,-982.74 +-5904.00,-6750.00,846.00,-5732.74,-5450.00,-282.74 +-5804.00,-5650.00,-154.00,-5632.74,-6450.00,817.26 +-5704.00,-5350.00,-354.00,-5532.74,-6150.00,617.26 +-5604.00,-5700.00,96.00,-5432.74,-4850.00,-582.74 +-5504.00,-5850.00,346.00,-5332.74,-4100.00,-1232.74 +-5404.00,-4800.00,-604.00,-5232.74,-5050.00,-182.74 +-5304.00,-4450.00,-854.00,-5132.74,-5850.00,717.26 +-5204.00,-5800.00,596.00,-5032.74,-4700.00,-332.74 +-5104.00,-7150.00,2046.00,-4932.74,-4100.00,-832.74 +-5004.00,-5150.00,146.00,-4832.74,-2900.00,-1932.74 +-4904.00,-4250.00,-654.00,-4732.74,-4500.00,-232.74 +-4804.00,-3950.00,-854.00,-4632.74,-6250.00,1617.26 +-4704.00,-4900.00,196.00,-4532.74,-5150.00,617.26 +-4604.00,-5450.00,846.00,-4432.74,-4400.00,-32.74 +-4504.00,-4550.00,46.00,-4332.74,-3400.00,-932.74 +-4404.00,-3600.00,-804.00,-4232.74,-2850.00,-1382.74 +-4304.00,-3450.00,-854.00,-4132.74,-4250.00,117.26 +-4204.00,-4300.00,96.00,-4032.74,-5200.00,1167.26 +-4104.00,-4750.00,646.00,-3932.74,-4400.00,467.26 +-4004.00,-4000.00,-4.00,-3832.74,-3400.00,-432.74 +-3904.00,-3100.00,-804.00,-3732.74,-2650.00,-1082.74 +-3804.00,-2750.00,-1054.00,-3632.74,-2350.00,-1282.74 +-3704.00,-3900.00,196.00,-3532.74,-3700.00,167.26 +-3604.00,-4350.00,746.00,-3432.74,-4500.00,1067.26 +-3504.00,-3600.00,96.00,-3332.74,-3650.00,317.26 +-3404.00,-2850.00,-554.00,-3232.74,-2650.00,-582.74 +-3304.00,-1800.00,-1504.00,-3132.74,-1600.00,-1532.74 +-3204.00,-2050.00,-1154.00,-3032.74,-2100.00,-932.74 +-3104.00,-3800.00,696.00,-2932.74,-3100.00,167.26 +-3004.00,-4350.00,1346.00,-2832.74,-2100.00,-732.74 +-2904.00,-3500.00,596.00,-2732.74,-1650.00,-1082.74 +-2804.00,-2650.00,-154.00,-2632.74,200.00,-2832.74 +-2704.00,-1950.00,-754.00,-2532.74,-450.00,-2082.74 +-2604.00,-800.00,-1804.00,-2432.74,-4450.00,2017.26 +-2504.00,-1900.00,-604.00,-2332.74,-5950.00,3617.26 +-2404.00,-3150.00,746.00,-2232.74,-3100.00,867.26 +-2304.00,-2500.00,196.00,-2132.74,1200.00,-3332.74 +-2204.00,-1700.00,-504.00,-2032.74,-650.00,-1382.74 +-2104.00,-350.00,-1754.00,-1932.74,-4400.00,2467.26 +-2004.00,-1300.00,-704.00,-1832.74,-4600.00,2767.26 +-1904.00,-2450.00,546.00,-1732.74,-2650.00,917.26 +-1804.00,-2200.00,396.00,-1632.74,-500.00,-1132.74 +-1704.00,-750.00,-954.00,-1532.74,-300.00,-1232.74 +-1604.00,-750.00,-854.00,-1432.74,50.00,-1482.74 +-1504.00,-950.00,-554.00,-1332.74,0.00,-1332.74 +-1404.00,300.00,-1704.00,-1232.74,0.00,-1232.74 +-1304.00,-400.00,-904.00,-1132.74,0.00,-1132.74 +-1204.00,-950.00,-254.00,-1032.74,0.00,-1032.74 +-1104.00,450.00,-1554.00,-932.74,0.00,-932.74 +-1004.00,1050.00,-2054.00,-832.74,0.00,-832.74 +-904.00,-550.00,-354.00,-732.74,0.00,-732.74 +-804.00,-1200.00,396.00,-632.74,0.00,-632.74 +-704.00,-200.00,-504.00,-532.74,0.00,-532.74 +-604.00,0.00,-604.00,-432.74,0.00,-432.74 +-504.00,0.00,-504.00,-332.74,0.00,-332.74 +-404.00,0.00,-404.00,-232.74,0.00,-232.74 +-304.00,0.00,-304.00,-132.74,0.00,-132.74 +-204.00,0.00,-204.00,-32.74,0.00,-32.74 +-104.00,0.00,-104.00,0.00,0.00,0.00 +-4.00,0.00,-4.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +100.00,0.00,100.00,100.00,0.00,100.00 +200.00,0.00,200.00,200.00,0.00,200.00 +300.00,0.00,300.00,300.00,0.00,300.00 +400.00,0.00,400.00,400.00,0.00,400.00 +500.00,0.00,500.00,500.00,0.00,500.00 +600.00,0.00,600.00,600.00,0.00,600.00 +700.00,0.00,700.00,700.00,0.00,700.00 +800.00,0.00,800.00,800.00,0.00,800.00 +900.00,0.00,900.00,900.00,0.00,900.00 +1000.00,0.00,1000.00,1000.00,0.00,1000.00 +1100.00,0.00,1100.00,1100.00,0.00,1100.00 +1200.00,0.00,1200.00,1200.00,0.00,1200.00 +1300.00,0.00,1300.00,1300.00,0.00,1300.00 +1400.00,0.00,1400.00,1400.00,0.00,1400.00 +1500.00,0.00,1500.00,1500.00,0.00,1500.00 +1600.00,0.00,1600.00,1600.00,0.00,1600.00 +1700.00,550.00,1150.00,1700.00,550.00,1150.00 +1800.00,1950.00,-150.00,1800.00,550.00,1250.00 +1900.00,300.00,1600.00,1900.00,-700.00,2600.00 +2000.00,0.00,2000.00,2000.00,250.00,1750.00 +2100.00,750.00,1350.00,2100.00,3100.00,-1000.00 +2200.00,2450.00,-250.00,2200.00,3600.00,-1400.00 +2300.00,2700.00,-400.00,2300.00,2200.00,100.00 +2400.00,1800.00,600.00,2400.00,1450.00,950.00 +2500.00,1750.00,750.00,2500.00,-350.00,2850.00 +2600.00,350.00,2250.00,2600.00,400.00,2200.00 +2700.00,550.00,2150.00,2700.00,4000.00,-1300.00 +2800.00,3350.00,-550.00,2800.00,5100.00,-2300.00 +2900.00,5200.00,-2300.00,2900.00,4300.00,-1400.00 +3000.00,4200.00,-1200.00,3000.00,3100.00,-100.00 +3100.00,3350.00,-250.00,3100.00,1700.00,1400.00 +3200.00,2900.00,300.00,3200.00,2000.00,1200.00 +3300.00,1850.00,1450.00,3300.00,2950.00,350.00 +3400.00,2450.00,950.00,3400.00,3400.00,0.00 +3500.00,3550.00,-50.00,3500.00,2400.00,1100.00 +3600.00,3750.00,-150.00,3600.00,2050.00,1550.00 +3700.00,3200.00,500.00,3700.00,3250.00,450.00 +3800.00,2650.00,1150.00,3800.00,4150.00,-350.00 +3900.00,2350.00,1550.00,3900.00,3300.00,600.00 +4000.00,3700.00,300.00,4000.00,2100.00,1900.00 +4100.00,4850.00,-750.00,4100.00,2400.00,1700.00 +4200.00,4250.00,-50.00,4200.00,5200.00,-1000.00 +4300.00,3200.00,1100.00,4300.00,6000.00,-1700.00 +4400.00,3400.00,1000.00,4400.00,5100.00,-700.00 +4500.00,4900.00,-400.00,4500.00,4100.00,400.00 +4600.00,4800.00,-200.00,4600.00,2900.00,1700.00 +4700.00,4100.00,600.00,4700.00,2700.00,2000.00 +4800.00,4000.00,800.00,4800.00,5350.00,-550.00 +4900.00,4850.00,50.00,4900.00,6950.00,-2050.00 +5000.00,4900.00,100.00,5000.00,5650.00,-650.00 +5100.00,4200.00,900.00,5100.00,4350.00,750.00 +5200.00,4150.00,1050.00,5200.00,3500.00,1700.00 +5300.00,5200.00,100.00,5300.00,4700.00,600.00 +5400.00,5950.00,-550.00,5400.00,6500.00,-1100.00 +5500.00,5100.00,400.00,5500.00,6300.00,-800.00 +5600.00,4600.00,1000.00,5600.00,5000.00,600.00 +5700.00,5450.00,250.00,5700.00,4250.00,1450.00 +5800.00,6400.00,-600.00,5800.00,5200.00,600.00 +5900.00,6400.00,-500.00,5900.00,6800.00,-900.00 +6000.00,5600.00,400.00,6000.00,6850.00,-850.00 +6100.00,4900.00,1200.00,6100.00,5500.00,600.00 +6200.00,6150.00,50.00,6200.00,4800.00,1400.00 +6300.00,6900.00,-600.00,6300.00,5800.00,500.00 +6400.00,5900.00,500.00,6400.00,7400.00,-1000.00 +6500.00,5400.00,1100.00,6500.00,7200.00,-700.00 +6600.00,6700.00,-100.00,6600.00,5900.00,700.00 +6700.00,7750.00,-1050.00,6700.00,5450.00,1250.00 +6800.00,7700.00,-900.00,6800.00,6850.00,-50.00 +6900.00,6250.00,650.00,6900.00,8050.00,-1150.00 +7000.00,6050.00,950.00,7000.00,7600.00,-600.00 +7100.00,7200.00,-100.00,7100.00,6250.00,850.00 +7200.00,8100.00,-900.00,7200.00,5700.00,1500.00 +7300.00,8350.00,-1050.00,7300.00,7950.00,-650.00 +7400.00,6850.00,550.00,7400.00,8900.00,-1500.00 +7500.00,6450.00,1050.00,7500.00,7250.00,250.00 +7600.00,7700.00,-100.00,7600.00,6600.00,1000.00 +7700.00,9050.00,-1350.00,7700.00,7300.00,400.00 +7800.00,8700.00,-900.00,7800.00,8600.00,-800.00 +7900.00,7250.00,650.00,7900.00,8600.00,-700.00 +8000.00,7000.00,1000.00,8000.00,6900.00,1100.00 +8100.00,8350.00,-250.00,8100.00,6550.00,1550.00 +8200.00,11600.00,-3400.00,8200.00,10850.00,-2650.00 +8300.00,9600.00,-1300.00,8300.00,10800.00,-2500.00 +8400.00,7950.00,450.00,8400.00,8650.00,-250.00 +8500.00,7200.00,1300.00,8500.00,7350.00,1150.00 +8600.00,8700.00,-100.00,8600.00,8200.00,400.00 +8700.00,10600.00,-1900.00,8700.00,9800.00,-1100.00 +8800.00,10150.00,-1350.00,8800.00,9700.00,-900.00 +8900.00,8750.00,150.00,8900.00,8100.00,800.00 +9000.00,7650.00,1350.00,9000.00,7600.00,1400.00 +9100.00,9100.00,0.00,9100.00,9600.00,-500.00 +9200.00,11700.00,-2500.00,9200.00,11850.00,-2650.00 +9300.00,11500.00,-2200.00,9300.00,11000.00,-1700.00 +9400.00,9350.00,50.00,9400.00,8750.00,650.00 +9500.00,8100.00,1400.00,9500.00,8150.00,1350.00 +9600.00,9550.00,50.00,9600.00,10050.00,-450.00 +9700.00,12500.00,-2800.00,9700.00,12350.00,-2650.00 +9800.00,12200.00,-2400.00,9800.00,11550.00,-1750.00 +9900.00,9900.00,0.00,9900.00,9100.00,800.00 +10000.00,8500.00,1500.00,10000.00,8500.00,1500.00 +10100.00,10700.00,-600.00,10100.00,11300.00,-1200.00 +10200.00,13200.00,-3000.00,10200.00,13200.00,-3000.00 +10300.00,12450.00,-2150.00,10300.00,12000.00,-1700.00 +10400.00,10100.00,300.00,10400.00,9400.00,1000.00 +10500.00,8850.00,1650.00,10500.00,8900.00,1600.00 +10600.00,11100.00,-500.00,10600.00,11400.00,-800.00 +10700.00,14200.00,-3500.00,10700.00,14050.00,-3350.00 +10800.00,13500.00,-2700.00,10800.00,13000.00,-2200.00 +10900.00,10900.00,0.00,10900.00,10100.00,800.00 +11000.00,9400.00,1600.00,11000.00,9450.00,1550.00 +11100.00,11400.00,-300.00,11100.00,11550.00,-450.00 +11200.00,14500.00,-3300.00,11200.00,14450.00,-3250.00 +11300.00,13950.00,-2650.00,11300.00,13600.00,-2300.00 +11400.00,11200.00,200.00,11400.00,10500.00,900.00 +11500.00,9750.00,1750.00,11500.00,9700.00,1800.00 +11600.00,12100.00,-500.00,11600.00,12300.00,-700.00 +11700.00,15200.00,-3500.00,11700.00,15400.00,-3700.00 +11800.00,14500.00,-2700.00,11800.00,14400.00,-2600.00 +11900.00,11650.00,250.00,11900.00,10900.00,1000.00 +12000.00,10150.00,1850.00,12000.00,9900.00,2100.00 +12100.00,12550.00,-450.00,12100.00,12700.00,-600.00 +12200.00,15750.00,-3550.00,12200.00,15950.00,-3750.00 +12300.00,15100.00,-2800.00,12300.00,14650.00,-2350.00 +12400.00,11500.00,900.00,12400.00,10900.00,1500.00 +12500.00,10600.00,1900.00,12500.00,10350.00,2150.00 +12600.00,13550.00,-950.00,12600.00,13850.00,-1250.00 +12700.00,16600.00,-3900.00,12700.00,16850.00,-4150.00 +12800.00,15450.00,-2650.00,12800.00,15400.00,-2600.00 +12900.00,12200.00,700.00,12900.00,11850.00,1050.00 +13000.00,11200.00,1800.00,13000.00,11200.00,1800.00 +13100.00,14000.00,-900.00,13100.00,13900.00,-800.00 +13200.00,17000.00,-3800.00,13200.00,17050.00,-3850.00 +13300.00,15950.00,-2650.00,13300.00,16050.00,-2750.00 +13400.00,12600.00,800.00,13400.00,12200.00,1200.00 +13500.00,11050.00,2450.00,13500.00,11200.00,2300.00 +13600.00,14200.00,-600.00,13600.00,14500.00,-900.00 +13700.00,17950.00,-4250.00,13700.00,17850.00,-4150.00 +13800.00,16400.00,-2600.00,13800.00,16200.00,-2400.00 +13900.00,13250.00,650.00,13900.00,13950.00,-50.00 +14000.00,11700.00,2300.00,14000.00,13000.00,1000.00 +14100.00,15100.00,-1000.00,14100.00,14700.00,-600.00 +14200.00,18250.00,-4050.00,14200.00,16500.00,-2300.00 +14300.00,17800.00,-3500.00,14300.00,17100.00,-2800.00 +14400.00,13800.00,600.00,14400.00,15250.00,-850.00 +14500.00,12550.00,1950.00,14500.00,12650.00,1850.00 +14600.00,15550.00,-950.00,14600.00,14250.00,350.00 +14700.00,19000.00,-4300.00,14700.00,17850.00,-3150.00 +14800.00,17200.00,-2400.00,14800.00,17050.00,-2250.00 +14900.00,14750.00,150.00,14900.00,14450.00,450.00 +15000.00,14400.00,600.00,15000.00,14300.00,700.00 +15100.00,16650.00,-1550.00,15100.00,16500.00,-1400.00 +15200.00,18950.00,-3750.00,15200.00,18800.00,-3600.00 +15300.00,16950.00,-1650.00,15300.00,16950.00,-1650.00 +15400.00,14950.00,450.00,15400.00,14200.00,1200.00 +15500.00,15000.00,500.00,15500.00,15150.00,350.00 +15600.00,18200.00,-2600.00,15600.00,18650.00,-3050.00 +15700.00,19550.00,-3850.00,15700.00,18450.00,-2750.00 +15800.00,20150.00,-4350.00,15800.00,18000.00,-2200.00 +15900.00,12950.00,2950.00,15900.00,13700.00,2200.00 +16000.00,12150.00,3850.00,16000.00,13950.00,2050.00 +16100.00,16950.00,-850.00,16100.00,16950.00,-850.00 +16200.00,21300.00,-5100.00,16200.00,19250.00,-3050.00 +16300.00,20000.00,-3700.00,16300.00,18850.00,-2550.00 +16400.00,14900.00,1500.00,16400.00,16650.00,-250.00 +16500.00,14000.00,2500.00,16500.00,16250.00,250.00 +16600.00,18250.00,-1650.00,16600.00,17300.00,-700.00 +16700.00,21450.00,-4750.00,16700.00,18350.00,-1650.00 +16800.00,20400.00,-3600.00,16800.00,19650.00,-2850.00 +16900.00,15550.00,1350.00,16900.00,18900.00,-2000.00 +17000.00,13850.00,3150.00,17000.00,17200.00,-200.00 +17100.00,18850.00,-1750.00,17100.00,16900.00,200.00 +17200.00,22400.00,-5200.00,17200.00,17950.00,-750.00 +17300.00,21400.00,-4100.00,17300.00,20750.00,-3450.00 +17400.00,15700.00,1700.00,17400.00,19700.00,-2300.00 +17500.00,14600.00,2900.00,17500.00,18400.00,-900.00 +17600.00,19750.00,-2150.00,17600.00,18200.00,-600.00 +17700.00,24150.00,-6450.00,17700.00,19450.00,-1750.00 +17800.00,21750.00,-3950.00,17658.43,20350.00,-2691.57 +17900.00,16050.00,1850.00,17558.43,19350.00,-1791.57 +17897.35,14850.00,3047.35,17458.43,18700.00,-1241.57 +17797.35,20200.00,-2402.65,17358.43,18350.00,-991.57 +17697.35,24550.00,-6852.65,17258.43,19100.00,-1841.57 +17597.35,22200.00,-4602.65,17158.43,19600.00,-2441.57 +17497.35,16900.00,597.35,17058.43,19200.00,-2141.57 +17397.35,15250.00,2147.35,16958.43,18550.00,-1591.57 +17297.35,18900.00,-1602.65,16858.43,17250.00,-391.57 +17197.35,23400.00,-6202.65,16758.43,18100.00,-1341.57 +17097.35,20950.00,-3852.65,16658.43,18600.00,-1941.57 +16997.35,16150.00,847.35,16558.43,18600.00,-2041.57 +16897.35,14700.00,2197.35,16458.43,18150.00,-1691.57 +16797.35,18800.00,-2002.65,16358.43,17700.00,-1341.57 +16697.35,22200.00,-5502.65,16258.43,17100.00,-841.57 +16597.35,21000.00,-4402.65,16158.43,18050.00,-1891.57 +16497.35,16150.00,347.35,16058.43,18400.00,-2341.57 +16397.35,13850.00,2547.35,15958.43,17000.00,-1041.57 +16297.35,18300.00,-2002.65,15858.43,17150.00,-1291.57 +16197.35,22000.00,-5802.65,15758.43,17150.00,-1391.57 +16097.35,19450.00,-3352.65,15658.43,16700.00,-1041.57 +15997.35,14950.00,1047.35,15558.43,16800.00,-1241.57 +15897.35,13750.00,2147.35,15458.43,17100.00,-1641.57 +15797.35,18650.00,-2852.65,15358.43,17650.00,-2291.57 +15697.35,21900.00,-6202.65,15258.43,17000.00,-1741.57 +15597.35,18650.00,-3052.65,15158.43,15650.00,-491.57 +15497.35,14750.00,747.35,15058.43,16100.00,-1041.57 +15397.35,13400.00,1997.35,14958.43,16900.00,-1941.57 +15297.35,17600.00,-2302.65,14858.43,16950.00,-2091.57 +15197.35,20950.00,-5752.65,14758.43,16250.00,-1491.57 +15097.35,18800.00,-3702.65,14658.43,15650.00,-991.57 +14997.35,14400.00,597.35,14558.43,15850.00,-1291.57 +14897.35,13000.00,1897.35,14458.43,16150.00,-1691.57 +14797.35,16900.00,-2102.65,14358.43,16100.00,-1741.57 +14697.35,20400.00,-5702.65,14258.43,15750.00,-1491.57 +14597.35,18400.00,-3802.65,14158.43,15450.00,-1291.57 +14497.35,14250.00,247.35,14058.43,15400.00,-1341.57 +14397.35,12900.00,1497.35,13958.43,15500.00,-1541.57 +14297.35,15450.00,-1152.65,13858.43,14800.00,-941.57 +14197.35,19200.00,-5002.65,13758.43,15150.00,-1391.57 +14097.35,17550.00,-3452.65,13658.43,14850.00,-1191.57 +13997.35,14200.00,-202.65,13558.43,15300.00,-1741.57 +13897.35,12300.00,1597.35,13458.43,15100.00,-1641.57 +13797.35,15150.00,-1352.65,13358.43,14650.00,-1291.57 +13697.35,17500.00,-3802.65,13258.43,13800.00,-541.57 +13597.35,17050.00,-3452.65,13158.43,14500.00,-1341.57 +13497.35,13350.00,147.35,13058.43,14850.00,-1791.57 +13397.35,11800.00,1597.35,12958.43,14550.00,-1591.57 +13297.35,14900.00,-1602.65,12858.43,14000.00,-1141.57 +13197.35,17950.00,-4752.65,12758.43,13600.00,-841.57 +13097.35,16550.00,-3452.65,12658.43,13600.00,-941.57 +12997.35,12850.00,147.35,12558.43,13900.00,-1341.57 +12897.35,11450.00,1447.35,12458.43,13750.00,-1291.57 +12797.35,14100.00,-1302.65,12358.43,13250.00,-891.57 +12697.35,16750.00,-4052.65,12258.43,12950.00,-691.57 +12597.35,18050.00,-5452.65,12158.43,15450.00,-3291.57 +12497.35,11650.00,847.35,12058.43,12350.00,-291.57 +12397.35,10950.00,1447.35,11958.43,10650.00,1308.43 +12297.35,13500.00,-1202.65,11858.43,11900.00,-41.57 +12197.35,16350.00,-4152.65,11758.43,14800.00,-3041.57 +12097.35,15100.00,-3002.65,11658.43,14450.00,-2791.57 +11997.35,11950.00,47.35,11558.43,11250.00,308.43 +11897.35,10150.00,1747.35,11458.43,9850.00,1608.43 +11797.35,13000.00,-1202.65,11358.43,12500.00,-1141.57 +11697.35,15700.00,-4002.65,11258.43,14950.00,-3691.57 +11597.35,14450.00,-2852.65,11158.43,13650.00,-2491.57 +11497.35,11400.00,97.35,11058.43,10450.00,608.43 +11397.35,9650.00,1747.35,10958.43,9500.00,1458.43 +11297.35,12350.00,-1052.65,10858.43,11950.00,-1091.57 +11197.35,15100.00,-3902.65,10758.43,14100.00,-3341.57 +11097.35,14050.00,-2952.65,10658.43,12850.00,-2191.57 +10997.35,11150.00,-152.65,10558.43,10100.00,458.43 +10897.35,9800.00,1097.35,10458.43,9500.00,958.43 +10797.35,11050.00,-252.65,10358.43,10900.00,-541.57 +10697.35,13850.00,-3152.65,10258.43,12950.00,-2691.57 +10597.35,13400.00,-2802.65,10158.43,12450.00,-2291.57 +10497.35,10400.00,97.35,10058.43,9300.00,758.43 +10397.35,9550.00,847.35,9958.43,9400.00,558.43 +10297.35,11250.00,-952.65,9858.43,11050.00,-1191.57 +10197.35,12750.00,-2552.65,9758.43,11650.00,-1891.57 +10097.35,11900.00,-1802.65,9658.43,9100.00,558.43 +9997.35,9800.00,197.35,9558.43,8900.00,658.43 +9897.35,8850.00,1047.35,9458.43,10300.00,-841.57 +9797.35,10350.00,-552.65,9358.43,11050.00,-1691.57 +9697.35,12750.00,-3052.65,9258.43,10550.00,-1291.57 +9597.35,11650.00,-2052.65,9158.43,8200.00,958.43 +9497.35,9650.00,-152.65,9058.43,8150.00,908.43 +9397.35,9000.00,397.35,8958.43,10400.00,-1441.57 +9297.35,9900.00,-602.65,8858.43,11100.00,-2241.57 +9197.35,11000.00,-1802.65,8758.43,8850.00,-91.57 +9097.35,10000.00,-902.65,8658.43,7900.00,758.43 +8997.35,9250.00,-252.65,8558.43,9200.00,-641.57 +8897.35,9350.00,-452.65,8458.43,10200.00,-1741.57 +8797.35,9800.00,-1002.65,8358.43,9500.00,-1141.57 +8697.35,9500.00,-802.65,8258.43,7700.00,558.43 +8597.35,7550.00,1047.35,8158.43,7100.00,1058.43 +8497.35,7800.00,697.35,8058.43,8700.00,-641.57 +8397.35,10100.00,-1702.65,7958.43,9800.00,-1841.57 +8297.35,10300.00,-2002.65,7858.43,7600.00,258.43 +8197.35,8850.00,-652.65,7758.43,7400.00,358.43 +8097.35,7400.00,697.35,7658.43,8300.00,-641.57 +7997.35,6900.00,1097.35,7558.43,8000.00,-441.57 +7897.35,9100.00,-1202.65,7458.43,6800.00,658.43 +7797.35,9850.00,-2052.65,7358.43,6400.00,958.43 +7697.35,8050.00,-352.65,7258.43,7700.00,-441.57 +7597.35,7400.00,197.35,7158.43,8150.00,-991.57 +7497.35,7600.00,-102.65,7058.43,6800.00,258.43 +7397.35,8150.00,-752.65,6958.43,6450.00,508.43 +7297.35,8050.00,-752.65,6858.43,7000.00,-141.57 +7197.35,6700.00,497.35,6758.43,7450.00,-691.57 +7097.35,6300.00,797.35,6658.43,7200.00,-541.57 +6997.35,7600.00,-602.65,6558.43,5950.00,608.43 +6897.35,8050.00,-1152.65,6458.43,5400.00,1058.43 +6797.35,6700.00,97.35,6358.43,6400.00,-41.57 +6697.35,6350.00,347.35,6258.43,7700.00,-1441.57 +6597.35,6850.00,-252.65,6158.43,7000.00,-841.57 +6497.35,7150.00,-652.65,6058.43,5850.00,208.43 +6397.35,5800.00,597.35,5958.43,4650.00,1308.43 +6297.35,5500.00,797.35,5858.43,5400.00,458.43 +6197.35,6600.00,-402.65,5758.43,6750.00,-991.57 +6097.35,7350.00,-1252.65,5658.43,6850.00,-1191.57 +5997.35,6300.00,-302.65,5558.43,5400.00,158.43 +5897.35,5250.00,647.35,5458.43,4150.00,1308.43 +5797.35,5000.00,797.35,5358.43,3750.00,1608.43 +5697.35,6100.00,-402.65,5258.43,6150.00,-891.57 +5597.35,6350.00,-752.65,5158.43,7100.00,-1941.57 +5497.35,5350.00,147.35,5058.43,5850.00,-791.57 +5397.35,4850.00,547.35,4958.43,4900.00,58.43 +5297.35,4300.00,997.35,4858.43,3600.00,1258.43 +5197.35,5200.00,-2.65,4758.43,3400.00,1358.43 +5097.35,5850.00,-752.65,4658.43,5200.00,-541.57 +4997.35,5850.00,-852.65,4558.43,6900.00,-2341.57 +4897.35,4050.00,847.35,4458.43,4800.00,-341.57 +4797.35,3900.00,897.35,4358.43,3700.00,658.43 +4697.35,4900.00,-202.65,4258.43,3200.00,1058.43 +4597.35,5600.00,-1002.65,4158.43,4100.00,58.43 +4497.35,4700.00,-202.65,4058.43,4600.00,-541.57 +4397.35,3850.00,547.35,3958.43,3700.00,258.43 +4297.35,2850.00,1447.35,3858.43,2650.00,1208.43 +4197.35,3100.00,1097.35,3758.43,2450.00,1308.43 +4097.35,4950.00,-852.65,3658.43,4000.00,-341.57 +3997.35,5650.00,-1652.65,3558.43,4900.00,-1341.57 +3897.35,4800.00,-902.65,3458.43,3950.00,-491.57 +3797.35,3900.00,-102.65,3358.43,2750.00,608.43 +3697.35,3050.00,647.35,3258.43,2200.00,1058.43 +3597.35,2150.00,1447.35,3158.43,1400.00,1758.43 +3497.35,2250.00,1247.35,3058.43,3150.00,-91.57 +3397.35,4100.00,-702.65,2958.43,4450.00,-1491.57 +3297.35,4750.00,-1452.65,2858.43,3400.00,-541.57 +3197.35,3850.00,-652.65,2758.43,2400.00,358.43 +3097.35,3100.00,-2.65,2658.43,1700.00,958.43 +2997.35,2400.00,597.35,2558.43,-50.00,2608.43 +2897.35,1200.00,1697.35,2458.43,350.00,2108.43 +2797.35,1650.00,1147.35,2358.43,3700.00,-1341.57 +2697.35,3550.00,-852.65,2258.43,4950.00,-2691.57 +2597.35,3950.00,-1352.65,2158.43,4150.00,-1991.57 +2497.35,3200.00,-702.65,2058.43,3000.00,-941.57 +2397.35,2400.00,-2.65,1958.43,1800.00,158.43 +2297.35,1700.00,597.35,1858.43,1200.00,658.43 +2197.35,750.00,1447.35,1758.43,600.00,1158.43 +2097.35,1600.00,497.35,1658.43,-450.00,2108.43 +1997.35,2050.00,-52.65,1558.43,750.00,808.43 +1897.35,1800.00,97.35,1458.43,1900.00,-441.57 +1797.35,50.00,1747.35,1358.43,1500.00,-141.57 +1697.35,-100.00,1797.35,1258.43,-300.00,1558.43 +1597.35,1800.00,-202.65,1158.43,-500.00,1658.43 +1497.35,2900.00,-1402.65,1058.43,650.00,408.43 +1397.35,2250.00,-852.65,958.43,950.00,8.43 +1297.35,1300.00,-2.65,858.43,-200.00,1058.43 +1197.35,1400.00,-202.65,758.43,-950.00,1708.43 +1097.35,-450.00,1547.35,658.43,-650.00,1308.43 +997.35,-550.00,1547.35,558.43,350.00,208.43 +897.35,200.00,697.35,458.43,100.00,358.43 +797.35,0.00,797.35,358.43,0.00,358.43 +697.35,0.00,697.35,258.43,0.00,258.43 +597.35,0.00,597.35,158.43,0.00,158.43 +497.35,0.00,497.35,58.43,0.00,58.43 +397.35,0.00,397.35,0.00,0.00,0.00 +297.35,0.00,297.35,0.00,0.00,0.00 +197.35,0.00,197.35,0.00,0.00,0.00 +97.35,0.00,97.35,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +-100.00,0.00,-100.00,-100.00,0.00,-100.00 +-200.00,0.00,-200.00,-200.00,0.00,-200.00 +-300.00,0.00,-300.00,-300.00,0.00,-300.00 +-400.00,0.00,-400.00,-400.00,0.00,-400.00 +-500.00,0.00,-500.00,-500.00,0.00,-500.00 +-600.00,0.00,-600.00,-600.00,0.00,-600.00 +-700.00,0.00,-700.00,-700.00,0.00,-700.00 +-800.00,0.00,-800.00,-800.00,0.00,-800.00 +-900.00,0.00,-900.00,-900.00,0.00,-900.00 +-1000.00,0.00,-1000.00,-1000.00,0.00,-1000.00 +-1100.00,0.00,-1100.00,-1100.00,0.00,-1100.00 +-1200.00,0.00,-1200.00,-1200.00,0.00,-1200.00 +-1300.00,0.00,-1300.00,-1300.00,0.00,-1300.00 +-1400.00,0.00,-1400.00,-1400.00,0.00,-1400.00 +-1500.00,0.00,-1500.00,-1500.00,0.00,-1500.00 +-1600.00,0.00,-1600.00,-1600.00,0.00,-1600.00 +-1700.00,0.00,-1700.00,-1700.00,0.00,-1700.00 +-1800.00,0.00,-1800.00,-1800.00,0.00,-1800.00 +-1900.00,0.00,-1900.00,-1900.00,0.00,-1900.00 +-2000.00,0.00,-2000.00,-2000.00,0.00,-2000.00 +-2100.00,0.00,-2100.00,-2100.00,0.00,-2100.00 +-2200.00,0.00,-2200.00,-2200.00,0.00,-2200.00 +-2300.00,0.00,-2300.00,-2300.00,0.00,-2300.00 +-2400.00,0.00,-2400.00,-2400.00,0.00,-2400.00 +-2500.00,0.00,-2500.00,-2500.00,0.00,-2500.00 +-2600.00,-450.00,-2150.00,-2600.00,-450.00,-2150.00 +-2700.00,-450.00,-2250.00,-2700.00,-500.00,-2200.00 +-2800.00,800.00,-3600.00,-2800.00,800.00,-3600.00 +-2900.00,-500.00,-2400.00,-2900.00,-450.00,-2450.00 +-3000.00,-2600.00,-400.00,-3000.00,-2650.00,-350.00 +-3100.00,-3200.00,100.00,-3100.00,-2800.00,-300.00 +-3200.00,-2500.00,-700.00,-3200.00,-1800.00,-1400.00 +-3300.00,-2050.00,-1250.00,-3300.00,100.00,-3400.00 +-3400.00,-200.00,-3200.00,-3400.00,0.00,-3400.00 +-3500.00,-350.00,-3150.00,-3500.00,-2700.00,-800.00 +-3600.00,-3250.00,-350.00,-3600.00,-4150.00,550.00 +-3700.00,-4200.00,500.00,-3700.00,-2950.00,-750.00 +-3800.00,-3650.00,-150.00,-3800.00,-1600.00,-2200.00 +-3900.00,-2900.00,-1000.00,-3900.00,-1850.00,-2050.00 +-4000.00,-2250.00,-1750.00,-4000.00,-2750.00,-1250.00 +-4100.00,-1550.00,-2550.00,-4100.00,-3400.00,-700.00 +-4200.00,-3250.00,-950.00,-4200.00,-1900.00,-2300.00 +-4300.00,-4450.00,150.00,-4300.00,-2100.00,-2200.00 +-4400.00,-3550.00,-850.00,-4400.00,-3250.00,-1150.00 +-4500.00,-2850.00,-1650.00,-4500.00,-3850.00,-650.00 +-4600.00,-2700.00,-1900.00,-4600.00,-2700.00,-1900.00 +-4700.00,-3800.00,-900.00,-4700.00,-1750.00,-2950.00 +-4800.00,-4650.00,-150.00,-4800.00,-3350.00,-1450.00 +-4900.00,-3600.00,-1300.00,-4900.00,-4800.00,-100.00 +-5000.00,-3450.00,-1550.00,-5000.00,-4500.00,-500.00 +-5100.00,-4500.00,-600.00,-5100.00,-3300.00,-1800.00 +-5200.00,-5300.00,100.00,-5200.00,-2700.00,-2500.00 +-5300.00,-4200.00,-1100.00,-5300.00,-4000.00,-1300.00 +-5400.00,-3950.00,-1450.00,-5400.00,-5400.00,0.00 +-5500.00,-4950.00,-550.00,-5500.00,-5100.00,-400.00 +-5600.00,-5800.00,200.00,-5600.00,-3850.00,-1750.00 +-5700.00,-5900.00,200.00,-5700.00,-3200.00,-2500.00 +-5800.00,-5000.00,-800.00,-5800.00,-4750.00,-1050.00 +-5900.00,-4600.00,-1300.00,-5900.00,-6100.00,200.00 +-6000.00,-5450.00,-550.00,-6000.00,-6000.00,0.00 +-6100.00,-6500.00,400.00,-6100.00,-4700.00,-1400.00 +-6200.00,-6600.00,400.00,-6200.00,-4100.00,-2100.00 +-6300.00,-5550.00,-750.00,-6300.00,-5600.00,-700.00 +-6400.00,-5200.00,-1200.00,-6400.00,-6750.00,350.00 +-6500.00,-6150.00,-350.00,-6500.00,-6650.00,150.00 +-6600.00,-7200.00,600.00,-6600.00,-5800.00,-800.00 +-6700.00,-7200.00,500.00,-6700.00,-5850.00,-850.00 +-6800.00,-6100.00,-700.00,-6800.00,-6350.00,-450.00 +-6900.00,-5850.00,-1050.00,-6900.00,-6750.00,-150.00 +-7000.00,-6750.00,-250.00,-7000.00,-7050.00,50.00 +-7100.00,-7800.00,700.00,-7100.00,-7100.00,0.00 +-7200.00,-7900.00,700.00,-7200.00,-7200.00,0.00 +-7300.00,-6550.00,-750.00,-7300.00,-7250.00,-50.00 +-7400.00,-6300.00,-1100.00,-7400.00,-7350.00,-50.00 +-7500.00,-7400.00,-100.00,-7500.00,-7500.00,0.00 +-7600.00,-8450.00,850.00,-7600.00,-7600.00,0.00 +-7700.00,-8950.00,1250.00,-7700.00,-7800.00,100.00 +-7800.00,-9750.00,1950.00,-7800.00,-9400.00,1600.00 +-7900.00,-6900.00,-1000.00,-7900.00,-7500.00,-400.00 +-8000.00,-6600.00,-1400.00,-8000.00,-6700.00,-1300.00 +-8100.00,-7950.00,-150.00,-8100.00,-7450.00,-650.00 +-8200.00,-9800.00,1600.00,-8200.00,-9000.00,800.00 +-8300.00,-9550.00,1250.00,-8300.00,-9300.00,1000.00 +-8400.00,-8200.00,-200.00,-8400.00,-9100.00,700.00 +-8500.00,-8700.00,200.00,-8500.00,-9000.00,500.00 +-8600.00,-9150.00,550.00,-8600.00,-8950.00,350.00 +-8700.00,-9650.00,950.00,-8700.00,-9300.00,600.00 +-8800.00,-9950.00,1150.00,-8800.00,-9500.00,700.00 +-8900.00,-9950.00,1050.00,-8900.00,-9700.00,800.00 +-9000.00,-10000.00,1000.00,-9000.00,-9800.00,800.00 +-9100.00,-10000.00,900.00,-9100.00,-9900.00,800.00 +-9200.00,-10100.00,900.00,-9200.00,-10000.00,800.00 +-9300.00,-10350.00,1050.00,-9300.00,-10200.00,900.00 +-9400.00,-10450.00,1050.00,-9400.00,-10400.00,1000.00 +-9500.00,-10600.00,1100.00,-9500.00,-10500.00,1000.00 +-9600.00,-10700.00,1100.00,-9600.00,-10500.00,900.00 +-9700.00,-10850.00,1150.00,-9700.00,-10700.00,1000.00 +-9800.00,-11000.00,1200.00,-9800.00,-10900.00,1100.00 +-9900.00,-11250.00,1350.00,-9900.00,-11050.00,1150.00 +-10000.00,-11250.00,1250.00,-10000.00,-11150.00,1150.00 +-10100.00,-11350.00,1250.00,-10100.00,-11200.00,1100.00 +-10200.00,-11400.00,1200.00,-10200.00,-11350.00,1150.00 +-10300.00,-11600.00,1300.00,-10300.00,-11450.00,1150.00 +-10400.00,-11700.00,1300.00,-10400.00,-11600.00,1200.00 +-10500.00,-11800.00,1300.00,-10500.00,-11600.00,1100.00 +-10600.00,-11950.00,1350.00,-10600.00,-11900.00,1300.00 +-10700.00,-12150.00,1450.00,-10700.00,-12050.00,1350.00 +-10800.00,-12250.00,1450.00,-10800.00,-12100.00,1300.00 +-10900.00,-12350.00,1450.00,-10900.00,-12200.00,1300.00 +-11000.00,-12450.00,1450.00,-11000.00,-12250.00,1250.00 +-11100.00,-12600.00,1500.00,-11100.00,-12350.00,1250.00 +-11200.00,-12700.00,1500.00,-11200.00,-12400.00,1200.00 +-11300.00,-12850.00,1550.00,-11300.00,-12550.00,1250.00 +-11400.00,-13000.00,1600.00,-11400.00,-12600.00,1200.00 +-11500.00,-13150.00,1650.00,-11500.00,-12650.00,1150.00 +-11600.00,-13250.00,1650.00,-11600.00,-12850.00,1250.00 +-11700.00,-13350.00,1650.00,-11700.00,-13000.00,1300.00 +-11800.00,-13600.00,1800.00,-11800.00,-13000.00,1200.00 +-11900.00,-13650.00,1750.00,-11900.00,-13100.00,1200.00 +-12000.00,-13800.00,1800.00,-12000.00,-13100.00,1100.00 +-12100.00,-13900.00,1800.00,-12100.00,-13200.00,1100.00 +-12200.00,-14150.00,1950.00,-12200.00,-13400.00,1200.00 +-12300.00,-14200.00,1900.00,-12300.00,-13700.00,1400.00 +-12400.00,-14200.00,1800.00,-12400.00,-13900.00,1500.00 +-12500.00,-14450.00,1950.00,-12500.00,-13950.00,1450.00 +-12600.00,-14650.00,2050.00,-12600.00,-13950.00,1350.00 +-12700.00,-14700.00,2000.00,-12700.00,-13900.00,1200.00 +-12800.00,-14750.00,1950.00,-12800.00,-14050.00,1250.00 +-12900.00,-14900.00,2000.00,-12900.00,-14200.00,1300.00 +-13000.00,-15050.00,2050.00,-13000.00,-14300.00,1300.00 +-13100.00,-15250.00,2150.00,-13100.00,-14400.00,1300.00 +-13200.00,-15450.00,2250.00,-13200.00,-14600.00,1400.00 +-13300.00,-15500.00,2200.00,-13300.00,-14800.00,1500.00 +-13400.00,-15450.00,2050.00,-13400.00,-15050.00,1650.00 +-13500.00,-15550.00,2050.00,-13500.00,-15400.00,1900.00 +-13600.00,-15700.00,2100.00,-13600.00,-15700.00,2100.00 +-13700.00,-15800.00,2100.00,-13700.00,-15800.00,2100.00 +-13800.00,-16000.00,2200.00,-13800.00,-15750.00,1950.00 +-13900.00,-15550.00,1650.00,-13900.00,-15150.00,1250.00 +-14000.00,-16200.00,2200.00,-14000.00,-16000.00,2000.00 +-14100.00,-15900.00,1800.00,-14100.00,-15700.00,1600.00 +-14200.00,-16750.00,2550.00,-14200.00,-16500.00,2300.00 +-14300.00,-16850.00,2550.00,-14300.00,-16800.00,2500.00 +-14400.00,-16850.00,2450.00,-14400.00,-16750.00,2350.00 +-14500.00,-16800.00,2300.00,-14500.00,-16650.00,2150.00 +-14600.00,-16750.00,2150.00,-14600.00,-16750.00,2150.00 +-14700.00,-17000.00,2300.00,-14700.00,-16750.00,2050.00 +-14800.00,-17150.00,2350.00,-14800.00,-16950.00,2150.00 +-14900.00,-17450.00,2550.00,-14900.00,-17150.00,2250.00 +-15000.00,-17550.00,2550.00,-15000.00,-17300.00,2300.00 +-15100.00,-17550.00,2450.00,-15100.00,-17450.00,2350.00 +-15200.00,-20900.00,5700.00,-15200.00,-20900.00,5700.00 +-15300.00,-17350.00,2050.00,-15300.00,-17250.00,1950.00 +-15400.00,-16500.00,1100.00,-15400.00,-16400.00,1000.00 +-15500.00,-17450.00,1950.00,-15500.00,-17050.00,1550.00 +-15600.00,-17600.00,2000.00,-15600.00,-17200.00,1600.00 +-15700.00,-18700.00,3000.00,-15700.00,-18300.00,2600.00 +-15800.00,-19700.00,3900.00,-15800.00,-19000.00,3200.00 +-15900.00,-18850.00,2950.00,-15900.00,-17950.00,2050.00 +-16000.00,-18550.00,2550.00,-16000.00,-17800.00,1800.00 +-16100.00,-19250.00,3150.00,-16100.00,-18850.00,2750.00 +-16200.00,-18900.00,2700.00,-16200.00,-18450.00,2250.00 +-16300.00,-19700.00,3400.00,-16300.00,-19200.00,2900.00 +-16400.00,-19000.00,2600.00,-16400.00,-18450.00,2050.00 +-16500.00,-19150.00,2650.00,-16500.00,-18400.00,1900.00 +-16600.00,-19250.00,2650.00,-16600.00,-18550.00,1950.00 +-16700.00,-19650.00,2950.00,-16700.00,-18700.00,2000.00 +-16800.00,-20500.00,3700.00,-16800.00,-19800.00,3000.00 +-16900.00,-20600.00,3700.00,-16900.00,-20150.00,3250.00 +-17000.00,-19500.00,2500.00,-17000.00,-19500.00,2500.00 +-17100.00,-20200.00,3100.00,-17100.00,-20350.00,3250.00 +-17200.00,-19750.00,2550.00,-17200.00,-19800.00,2600.00 +-17300.00,-19950.00,2650.00,-17300.00,-19800.00,2500.00 +-17400.00,-20250.00,2850.00,-17400.00,-20100.00,2700.00 +-17500.00,-21500.00,4000.00,-17500.00,-21100.00,3600.00 +-17600.00,-21450.00,3850.00,-17600.00,-21150.00,3550.00 +-17700.00,-21100.00,3400.00,-17700.00,-20850.00,3150.00 +-17800.00,-20100.00,2300.00,-17800.00,-20100.00,2300.00 +-17900.00,-20550.00,2650.00,-17900.00,-20250.00,2350.00 +-18000.00,-21000.00,3000.00,-17952.47,-20750.00,2797.53 +-18047.75,-21500.00,3452.25,-17852.47,-21200.00,3347.53 +-17947.75,-21500.00,3552.25,-17752.47,-21300.00,3547.53 +-17847.75,-21550.00,3702.25,-17652.47,-21200.00,3547.53 +-17747.75,-21250.00,3502.25,-17552.47,-20900.00,3347.53 +-17647.75,-21850.00,4202.25,-17452.47,-21400.00,3947.53 +-17547.75,-21000.00,3452.25,-17352.47,-20350.00,2997.53 +-17447.75,-21550.00,4102.25,-17252.47,-20550.00,3297.53 +-17347.75,-21250.00,3902.25,-17152.47,-20300.00,3147.53 +-17247.75,-20300.00,3052.25,-17052.47,-19250.00,2197.53 +-17147.75,-19900.00,2752.25,-16952.47,-19300.00,2347.53 +-17047.75,-21000.00,3952.25,-16852.47,-20450.00,3597.53 +-16947.75,-20400.00,3452.25,-16752.47,-19700.00,2947.53 +-16847.75,-20050.00,3202.25,-16652.47,-19350.00,2697.53 +-16747.75,-20000.00,3252.25,-16552.47,-19150.00,2597.53 +-16647.75,-19900.00,3252.25,-16452.47,-19050.00,2597.53 +-16547.75,-19750.00,3202.25,-16352.47,-18800.00,2447.53 +-16447.75,-19750.00,3302.25,-16252.47,-18700.00,2447.53 +-16347.75,-19600.00,3252.25,-16152.47,-18750.00,2597.53 +-16247.75,-20300.00,4052.25,-16052.47,-19550.00,3497.53 +-16147.75,-19200.00,3052.25,-15952.47,-18900.00,2947.53 +-16047.75,-18850.00,2802.25,-15852.47,-18650.00,2797.53 +-15947.75,-18950.00,3002.25,-15752.47,-18650.00,2897.53 +-15847.75,-18750.00,2902.25,-15652.47,-18650.00,2997.53 +-15747.75,-18950.00,3202.25,-15552.47,-18600.00,3047.53 +-15647.75,-19550.00,3902.25,-15452.47,-19150.00,3697.53 +-15547.75,-18650.00,3102.25,-15352.47,-18250.00,2897.53 +-15447.75,-18850.00,3402.25,-15252.47,-18250.00,2997.53 +-15347.75,-18050.00,2702.25,-15152.47,-17300.00,2147.53 +-15247.75,-18550.00,3302.25,-15052.47,-17850.00,2797.53 +-15147.75,-17850.00,2702.25,-14952.47,-17300.00,2347.53 +-15047.75,-17750.00,2702.25,-14852.47,-17200.00,2347.53 +-14947.75,-18600.00,3652.25,-14752.47,-18000.00,3247.53 +-14847.75,-17700.00,2852.25,-14652.47,-17200.00,2547.53 +-14747.75,-17500.00,2752.25,-14552.47,-16950.00,2397.53 +-14647.75,-18150.00,3502.25,-14452.47,-17500.00,3047.53 +-14547.75,-17250.00,2702.25,-14352.47,-16800.00,2447.53 +-14447.75,-17750.00,3302.25,-14252.47,-17150.00,2897.53 +-14347.75,-17000.00,2652.25,-14152.47,-16600.00,2447.53 +-14247.75,-17450.00,3202.25,-14052.47,-16800.00,2747.53 +-14147.75,-17500.00,3352.25,-13952.47,-16500.00,2547.53 +-14047.75,-17100.00,3052.25,-13852.47,-15950.00,2097.53 +-13947.75,-16700.00,2752.25,-13752.47,-15700.00,1947.53 +-13847.75,-16750.00,2902.25,-13652.47,-15650.00,1997.53 +-13747.75,-16600.00,2852.25,-13552.47,-15850.00,2297.53 +-13647.75,-18750.00,5102.25,-13452.47,-18050.00,4597.53 +-13547.75,-14800.00,1252.25,-13352.47,-14700.00,1347.53 +-13447.75,-12750.00,-697.75,-13252.47,-13800.00,547.53 +-13347.75,-14000.00,652.25,-13152.47,-14300.00,1147.53 +-13247.75,-16100.00,2852.25,-13052.47,-14850.00,1797.53 +-13147.75,-17400.00,4252.25,-12952.47,-15550.00,2597.53 +-13047.75,-16600.00,3552.25,-12852.47,-15150.00,2297.53 +-12947.75,-15650.00,2702.25,-12752.47,-14700.00,1947.53 +-12847.75,-14750.00,1902.25,-12652.47,-13900.00,1247.53 +-12747.75,-14600.00,1852.25,-12552.47,-14050.00,1497.53 +-12647.75,-15350.00,2702.25,-12452.47,-14950.00,2497.53 +-12547.75,-15300.00,2752.25,-12352.47,-15150.00,2797.53 +-12447.75,-15000.00,2552.25,-12252.47,-14950.00,2697.53 +-12347.75,-14400.00,2052.25,-12152.47,-14000.00,1847.53 +-12247.75,-14650.00,2402.25,-12052.47,-14300.00,2247.53 +-12147.75,-14700.00,2552.25,-11952.47,-14350.00,2397.53 +-12047.75,-14000.00,1952.25,-11852.47,-13750.00,1897.53 +-11947.75,-13850.00,1902.25,-11752.47,-13550.00,1797.53 +-11847.75,-13950.00,2102.25,-11652.47,-13500.00,1847.53 +-11747.75,-13900.00,2152.25,-11552.47,-13600.00,2047.53 +-11647.75,-13900.00,2252.25,-11452.47,-13450.00,1997.53 +-11547.75,-13900.00,2352.25,-11352.47,-13350.00,1997.53 +-11447.75,-13600.00,2152.25,-11252.47,-13200.00,1947.53 +-11347.75,-13350.00,2002.25,-11152.47,-12900.00,1747.53 +-11247.75,-13300.00,2052.25,-11052.47,-12650.00,1597.53 +-11147.75,-13200.00,2052.25,-10952.47,-12400.00,1447.53 +-11047.75,-13000.00,1952.25,-10852.47,-12450.00,1597.53 +-10947.75,-12900.00,1952.25,-10752.47,-12400.00,1647.53 +-10847.75,-12800.00,1952.25,-10652.47,-12200.00,1547.53 +-10747.75,-12750.00,2002.25,-10552.47,-12050.00,1497.53 +-10647.75,-12650.00,2002.25,-10452.47,-11950.00,1497.53 +-10547.75,-12500.00,1952.25,-10352.47,-11900.00,1547.53 +-10447.75,-12500.00,2052.25,-10252.47,-11800.00,1547.53 +-10347.75,-12300.00,1952.25,-10152.47,-11650.00,1497.53 +-10247.75,-12150.00,1902.25,-10052.47,-11550.00,1497.53 +-10147.75,-12050.00,1902.25,-9952.47,-11400.00,1447.53 +-10047.75,-11900.00,1852.25,-9852.47,-11350.00,1497.53 +-9947.75,-11900.00,1952.25,-9752.47,-11150.00,1397.53 +-9847.75,-11700.00,1852.25,-9652.47,-11000.00,1347.53 +-9747.75,-11450.00,1702.25,-9552.47,-10700.00,1147.53 +-9647.75,-11350.00,1702.25,-9452.47,-10450.00,997.53 +-9547.75,-11400.00,1852.25,-9352.47,-10250.00,897.53 +-9447.75,-11200.00,1752.25,-9252.47,-10200.00,947.53 +-9347.75,-11050.00,1702.25,-9152.47,-10200.00,1047.53 +-9247.75,-11000.00,1752.25,-9052.47,-10150.00,1097.53 +-9147.75,-10750.00,1602.25,-8952.47,-10200.00,1247.53 +-9047.75,-10650.00,1602.25,-8852.47,-10050.00,1197.53 +-8947.75,-10550.00,1602.25,-8752.47,-9750.00,997.53 +-8847.75,-10400.00,1552.25,-8652.47,-9500.00,847.53 +-8747.75,-10250.00,1502.25,-8552.47,-9350.00,797.53 +-8647.75,-9750.00,1102.25,-8452.47,-8800.00,347.53 +-8547.75,-9700.00,1152.25,-8352.47,-8800.00,447.53 +-8447.75,-9700.00,1252.25,-8252.47,-8800.00,547.53 +-8347.75,-9700.00,1352.25,-8152.47,-8750.00,597.53 +-8247.75,-9400.00,1152.25,-8052.47,-9050.00,997.53 +-8147.75,-7800.00,-347.75,-7952.47,-8500.00,547.53 +-8047.75,-8500.00,452.25,-7852.47,-8300.00,447.53 +-7947.75,-8800.00,852.25,-7752.47,-8100.00,347.53 +-7847.75,-9300.00,1452.25,-7652.47,-8000.00,347.53 +-7747.75,-8650.00,902.25,-7552.47,-8000.00,447.53 +-7647.75,-7900.00,252.25,-7452.47,-8200.00,747.53 +-7547.75,-8300.00,752.25,-7352.47,-8200.00,847.53 +-7447.75,-8500.00,1052.25,-7252.47,-7700.00,447.53 +-7347.75,-8250.00,902.25,-7152.47,-6850.00,-302.47 +-7247.75,-6600.00,-647.75,-7052.47,-6850.00,-202.47 +-7147.75,-6550.00,-597.75,-6952.47,-7650.00,697.53 +-7047.75,-7400.00,352.25,-6852.47,-7700.00,847.53 +-6947.75,-8100.00,1152.25,-6752.47,-6500.00,-252.47 +-6847.75,-7950.00,1102.25,-6652.47,-5950.00,-702.47 +-6747.75,-6650.00,-97.75,-6552.47,-6950.00,397.53 +-6647.75,-5900.00,-747.75,-6452.47,-6850.00,397.53 +-6547.75,-6850.00,302.25,-6352.47,-5800.00,-552.47 +-6447.75,-6850.00,402.25,-6252.47,-5500.00,-752.47 +-6347.75,-5800.00,-547.75,-6152.47,-6200.00,47.53 +-6247.75,-6550.00,302.25,-6052.47,-7300.00,1247.53 +-6147.75,-5950.00,-197.75,-5952.47,-5200.00,-752.47 +-6047.75,-5100.00,-947.75,-5852.47,-4750.00,-1102.47 +-5947.75,-6100.00,152.25,-5752.47,-5450.00,-302.47 +-5847.75,-6150.00,302.25,-5652.47,-5800.00,147.53 +-5747.75,-5250.00,-497.75,-5552.47,-4900.00,-652.47 +-5647.75,-4800.00,-847.75,-5452.47,-4400.00,-1052.47 +-5547.75,-5450.00,-97.75,-5352.47,-4900.00,-452.47 +-5447.75,-5700.00,252.25,-5252.47,-5150.00,-102.47 +-5347.75,-4750.00,-597.75,-5152.47,-4400.00,-752.47 +-5247.75,-4200.00,-1047.75,-5052.47,-3850.00,-1202.47 +-5147.75,-5050.00,-97.75,-4952.47,-4300.00,-652.47 +-5047.75,-5250.00,202.25,-4852.47,-4600.00,-252.47 +-4947.75,-4450.00,-497.75,-4752.47,-3800.00,-952.47 +-4847.75,-3450.00,-1397.75,-4652.47,-2700.00,-1952.47 +-4747.75,-3100.00,-1647.75,-4552.47,-2850.00,-1702.47 +-4647.75,-4400.00,-247.75,-4452.47,-4100.00,-352.47 +-4547.75,-5050.00,502.25,-4352.47,-4650.00,297.53 +-4447.75,-4300.00,-147.75,-4252.47,-3750.00,-502.47 +-4347.75,-3350.00,-997.75,-4152.47,-2850.00,-1302.47 +-4247.75,-2550.00,-1697.75,-4052.47,-1650.00,-2402.47 +-4147.75,-2400.00,-1747.75,-3952.47,-2250.00,-1702.47 +-4047.75,-3650.00,-397.75,-3852.47,-3500.00,-352.47 +-3947.75,-4250.00,302.25,-3752.47,-3900.00,147.53 +-3847.75,-3400.00,-447.75,-3652.47,-3000.00,-652.47 +-3747.75,-2600.00,-1147.75,-3552.47,-2350.00,-1202.47 +-3647.75,-1800.00,-1847.75,-3452.47,-650.00,-2802.47 +-3547.75,-1300.00,-2247.75,-3352.47,-600.00,-2752.47 +-3447.75,-2800.00,-647.75,-3252.47,-3000.00,-252.47 +-3347.75,-3750.00,402.25,-3152.47,-4050.00,897.53 +-3247.75,-2800.00,-447.75,-3052.47,-3050.00,-2.47 +-3147.75,-2300.00,-847.75,-2952.47,-2400.00,-552.47 +-3047.75,-900.00,-2147.75,-2852.47,-1200.00,-1652.47 +-2947.75,-1600.00,-1347.75,-2752.47,-1200.00,-1552.47 +-2847.75,-1550.00,-1297.75,-2652.47,100.00,-2752.47 +-2747.75,-1450.00,-1297.75,-2552.47,-150.00,-2402.47 +-2647.75,-700.00,-1947.75,-2452.47,-1450.00,-1002.47 +-2547.75,600.00,-3147.75,-2352.47,-2050.00,-302.47 +-2447.75,-600.00,-1847.75,-2252.47,-650.00,-1602.47 +-2347.75,-1250.00,-1097.75,-2152.47,500.00,-2652.47 +-2247.75,-1250.00,-997.75,-2052.47,400.00,-2452.47 +-2147.75,-900.00,-1247.75,-1952.47,-600.00,-1352.47 +-2047.75,750.00,-2797.75,-1852.47,800.00,-2652.47 +-1947.75,-250.00,-1697.75,-1752.47,300.00,-2052.47 +-1847.75,-900.00,-947.75,-1652.47,-400.00,-1252.47 +-1747.75,350.00,-2097.75,-1552.47,50.00,-1602.47 +-1647.75,900.00,-2547.75,-1452.47,0.00,-1452.47 +-1547.75,50.00,-1597.75,-1352.47,0.00,-1352.47 +-1447.75,-200.00,-1247.75,-1252.47,0.00,-1252.47 +-1347.75,0.00,-1347.75,-1152.47,0.00,-1152.47 +-1247.75,0.00,-1247.75,-1052.47,0.00,-1052.47 +-1147.75,0.00,-1147.75,-952.47,0.00,-952.47 +-1047.75,0.00,-1047.75,-852.47,0.00,-852.47 +-947.75,0.00,-947.75,-752.47,0.00,-752.47 +-847.75,0.00,-847.75,-652.47,0.00,-652.47 +-747.75,0.00,-747.75,-552.47,0.00,-552.47 +-647.75,0.00,-647.75,-452.47,0.00,-452.47 +-547.75,0.00,-547.75,-352.47,0.00,-352.47 +-447.75,0.00,-447.75,-252.47,0.00,-252.47 +-347.75,0.00,-347.75,-152.47,0.00,-152.47 +-247.75,0.00,-247.75,-52.47,0.00,-52.47 +-147.75,0.00,-147.75,0.00,0.00,0.00 +-47.75,0.00,-47.75,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +100.00,0.00,100.00,100.00,0.00,100.00 +200.00,0.00,200.00,200.00,0.00,200.00 +300.00,0.00,300.00,300.00,0.00,300.00 +400.00,0.00,400.00,400.00,0.00,400.00 +500.00,0.00,500.00,500.00,0.00,500.00 +600.00,0.00,600.00,600.00,0.00,600.00 +700.00,0.00,700.00,700.00,0.00,700.00 +800.00,0.00,800.00,800.00,0.00,800.00 +900.00,0.00,900.00,900.00,0.00,900.00 +1000.00,0.00,1000.00,1000.00,0.00,1000.00 +1100.00,0.00,1100.00,1100.00,0.00,1100.00 +1200.00,0.00,1200.00,1200.00,0.00,1200.00 +1300.00,0.00,1300.00,1300.00,0.00,1300.00 +1400.00,0.00,1400.00,1400.00,0.00,1400.00 +1500.00,0.00,1500.00,1500.00,0.00,1500.00 +1600.00,0.00,1600.00,1600.00,0.00,1600.00 +1700.00,0.00,1700.00,1700.00,0.00,1700.00 +1800.00,0.00,1800.00,1800.00,0.00,1800.00 +1900.00,0.00,1900.00,1900.00,0.00,1900.00 +2000.00,0.00,2000.00,2000.00,0.00,2000.00 +2100.00,0.00,2100.00,2100.00,0.00,2100.00 +2200.00,0.00,2200.00,2200.00,0.00,2200.00 +2300.00,0.00,2300.00,2300.00,0.00,2300.00 +2400.00,0.00,2400.00,2400.00,0.00,2400.00 +2500.00,0.00,2500.00,2500.00,0.00,2500.00 +2600.00,500.00,2100.00,2600.00,500.00,2100.00 +2700.00,550.00,2150.00,2700.00,400.00,2300.00 +2800.00,-900.00,3700.00,2800.00,-250.00,3050.00 +2900.00,450.00,2450.00,2900.00,1250.00,1650.00 +3000.00,2400.00,600.00,3000.00,2350.00,650.00 +3100.00,2900.00,200.00,3100.00,800.00,2300.00 +3200.00,2450.00,750.00,3200.00,700.00,2500.00 +3300.00,2000.00,1300.00,3300.00,2400.00,900.00 +3400.00,750.00,2650.00,3400.00,2950.00,450.00 +3500.00,250.00,3250.00,3500.00,1600.00,1900.00 +3600.00,2700.00,900.00,3600.00,1850.00,1750.00 +3700.00,4100.00,-400.00,3700.00,2350.00,1350.00 +3800.00,3150.00,650.00,3800.00,2550.00,1250.00 +3900.00,2650.00,1250.00,3900.00,1700.00,2200.00 +4000.00,1650.00,2350.00,4000.00,900.00,3100.00 +4100.00,2450.00,1650.00,4100.00,3000.00,1100.00 +4200.00,3500.00,700.00,4200.00,4100.00,100.00 +4300.00,3950.00,350.00,4300.00,3100.00,1200.00 +4400.00,3250.00,1150.00,4400.00,2350.00,2050.00 +4500.00,2750.00,1750.00,4500.00,1650.00,2850.00 +4600.00,2650.00,1950.00,4600.00,3550.00,1050.00 +4700.00,3800.00,900.00,4700.00,4650.00,50.00 +4800.00,4600.00,200.00,4800.00,3700.00,1100.00 +4900.00,3800.00,1100.00,4900.00,3150.00,1750.00 +5000.00,3800.00,1200.00,5000.00,3700.00,1300.00 +5100.00,4500.00,600.00,5100.00,4550.00,550.00 +5200.00,4600.00,600.00,5200.00,4700.00,500.00 +5300.00,3900.00,1400.00,5300.00,3600.00,1700.00 +5400.00,4000.00,1400.00,5400.00,3200.00,2200.00 +5500.00,4950.00,550.00,5500.00,4500.00,1000.00 +5600.00,5850.00,-250.00,5600.00,5700.00,-100.00 +5700.00,6100.00,-400.00,5700.00,6000.00,-300.00 +5800.00,5150.00,650.00,5800.00,4800.00,1000.00 +5900.00,4850.00,1050.00,5900.00,4150.00,1750.00 +6000.00,5400.00,600.00,6000.00,5000.00,1000.00 +6100.00,6150.00,-50.00,6100.00,6050.00,50.00 +6200.00,6650.00,-450.00,6200.00,6300.00,-100.00 +6300.00,5300.00,1000.00,6300.00,5000.00,1300.00 +6400.00,5100.00,1300.00,6400.00,4900.00,1500.00 +6500.00,6450.00,50.00,6500.00,5750.00,750.00 +6600.00,6950.00,-350.00,6600.00,6650.00,-50.00 +6700.00,7000.00,-300.00,6700.00,7000.00,-300.00 +6800.00,6050.00,750.00,6800.00,6950.00,-150.00 +6900.00,5800.00,1100.00,6900.00,6150.00,750.00 +7000.00,7100.00,-100.00,7000.00,6300.00,700.00 +7100.00,7450.00,-350.00,7100.00,6800.00,300.00 +7200.00,7950.00,-750.00,7200.00,7300.00,-100.00 +7300.00,7900.00,-600.00,7300.00,7950.00,-650.00 +7400.00,7100.00,300.00,7400.00,7950.00,-550.00 +7500.00,7700.00,-200.00,7500.00,7900.00,-400.00 +7600.00,8250.00,-650.00,7600.00,7700.00,-100.00 +7700.00,8500.00,-800.00,7700.00,7750.00,-50.00 +7800.00,8300.00,-500.00,7800.00,7550.00,250.00 +7900.00,8750.00,-850.00,7900.00,8100.00,-200.00 +8000.00,8850.00,-850.00,8000.00,8300.00,-300.00 +8100.00,10550.00,-2450.00,8100.00,9800.00,-1700.00 +8200.00,8550.00,-350.00,8200.00,7800.00,400.00 +8300.00,7300.00,1000.00,8300.00,6500.00,1800.00 +8400.00,7950.00,450.00,8400.00,7500.00,900.00 +8500.00,9050.00,-550.00,8500.00,8900.00,-400.00 +8600.00,10050.00,-1450.00,8600.00,9950.00,-1350.00 +8700.00,10250.00,-1550.00,8700.00,9800.00,-1100.00 +8800.00,9900.00,-1100.00,8800.00,9400.00,-600.00 +8900.00,9700.00,-800.00,8900.00,9250.00,-350.00 +9000.00,9800.00,-800.00,9000.00,9400.00,-400.00 +9100.00,10050.00,-950.00,9100.00,9700.00,-600.00 +9200.00,10200.00,-1000.00,9200.00,10000.00,-800.00 +9300.00,10400.00,-1100.00,9300.00,10200.00,-900.00 +9400.00,10500.00,-1100.00,9400.00,10300.00,-900.00 +9500.00,10550.00,-1050.00,9500.00,10300.00,-800.00 +9600.00,10650.00,-1050.00,9600.00,10300.00,-700.00 +9700.00,10850.00,-1150.00,9700.00,10550.00,-850.00 +9800.00,10850.00,-1050.00,9800.00,10650.00,-850.00 +9900.00,11050.00,-1150.00,9900.00,10650.00,-750.00 +10000.00,11150.00,-1150.00,10000.00,10850.00,-850.00 +10100.00,11350.00,-1250.00,10100.00,11150.00,-1050.00 +10200.00,11500.00,-1300.00,10200.00,11450.00,-1250.00 +10300.00,11550.00,-1250.00,10300.00,11500.00,-1200.00 +10400.00,11700.00,-1300.00,10400.00,11650.00,-1250.00 +10500.00,11800.00,-1300.00,10500.00,11750.00,-1250.00 +10600.00,12050.00,-1450.00,10600.00,12000.00,-1400.00 +10700.00,12150.00,-1450.00,10700.00,12050.00,-1350.00 +10800.00,12250.00,-1450.00,10800.00,12150.00,-1350.00 +10900.00,12500.00,-1600.00,10900.00,12350.00,-1450.00 +11000.00,12600.00,-1600.00,11000.00,12400.00,-1400.00 +11100.00,12650.00,-1550.00,11100.00,12450.00,-1350.00 +11200.00,12750.00,-1550.00,11200.00,12450.00,-1250.00 +11300.00,12900.00,-1600.00,11300.00,12550.00,-1250.00 +11400.00,13050.00,-1650.00,11400.00,12600.00,-1200.00 +11500.00,13250.00,-1750.00,11500.00,12800.00,-1300.00 +11600.00,13300.00,-1700.00,11600.00,12900.00,-1300.00 +11700.00,13450.00,-1750.00,11700.00,13050.00,-1350.00 +11800.00,13650.00,-1850.00,11800.00,13250.00,-1450.00 +11900.00,13800.00,-1900.00,11900.00,13500.00,-1600.00 +12000.00,13950.00,-1950.00,12000.00,13650.00,-1650.00 +12100.00,14100.00,-2000.00,12100.00,13750.00,-1650.00 +12200.00,14050.00,-1850.00,12200.00,13850.00,-1650.00 +12300.00,14200.00,-1900.00,12300.00,13900.00,-1600.00 +12400.00,14300.00,-1900.00,12400.00,14050.00,-1650.00 +12500.00,14500.00,-2000.00,12500.00,14200.00,-1700.00 +12600.00,14600.00,-2000.00,12600.00,14450.00,-1850.00 +12700.00,14800.00,-2100.00,12700.00,14650.00,-1950.00 +12800.00,14900.00,-2100.00,12800.00,14800.00,-2000.00 +12900.00,15000.00,-2100.00,12900.00,14800.00,-1900.00 +13000.00,15050.00,-2050.00,13000.00,14750.00,-1750.00 +13100.00,15200.00,-2100.00,13100.00,14650.00,-1550.00 +13200.00,15250.00,-2050.00,13200.00,14700.00,-1500.00 +13300.00,15250.00,-1950.00,13300.00,14800.00,-1500.00 +13400.00,15500.00,-2100.00,13400.00,15050.00,-1650.00 +13500.00,15650.00,-2150.00,13500.00,15350.00,-1850.00 +13600.00,15650.00,-2050.00,13600.00,15500.00,-1900.00 +13700.00,15800.00,-2100.00,13700.00,15500.00,-1800.00 +13800.00,16000.00,-2200.00,13800.00,15700.00,-1900.00 +13900.00,16100.00,-2200.00,13900.00,16050.00,-2150.00 +14000.00,16150.00,-2150.00,14000.00,16100.00,-2100.00 +14100.00,16300.00,-2200.00,14100.00,16100.00,-2000.00 +14200.00,16450.00,-2250.00,14200.00,16150.00,-1950.00 +14300.00,16600.00,-2300.00,14300.00,16300.00,-2000.00 +14400.00,16800.00,-2400.00,14400.00,16600.00,-2200.00 +14500.00,16800.00,-2300.00,14500.00,16900.00,-2400.00 +14600.00,16950.00,-2350.00,14600.00,17000.00,-2400.00 +14700.00,17050.00,-2350.00,14700.00,17100.00,-2400.00 +14800.00,17150.00,-2350.00,14800.00,17300.00,-2500.00 +14900.00,17300.00,-2400.00,14900.00,17350.00,-2450.00 +15000.00,17500.00,-2500.00,15000.00,17200.00,-2200.00 +15100.00,17600.00,-2500.00,15100.00,17550.00,-2450.00 +15200.00,17750.00,-2550.00,15200.00,17500.00,-2300.00 +15300.00,17850.00,-2550.00,15300.00,17550.00,-2250.00 +15400.00,18050.00,-2650.00,15400.00,17550.00,-2150.00 +15500.00,18100.00,-2600.00,15500.00,17700.00,-2200.00 +15600.00,21700.00,-6100.00,15600.00,21400.00,-5800.00 +15700.00,17000.00,-1300.00,15700.00,17750.00,-2050.00 +15800.00,14800.00,1000.00,15800.00,16800.00,-1000.00 +15900.00,16600.00,-700.00,15900.00,17650.00,-1750.00 +16000.00,19250.00,-3250.00,16000.00,18550.00,-2550.00 +16100.00,20350.00,-4250.00,16100.00,19000.00,-2900.00 +16200.00,19700.00,-3500.00,16200.00,18950.00,-2750.00 +16300.00,19200.00,-2900.00,16300.00,19100.00,-2800.00 +16400.00,19300.00,-2900.00,16400.00,19150.00,-2750.00 +16500.00,19050.00,-2550.00,16500.00,18850.00,-2350.00 +16600.00,19300.00,-2700.00,16600.00,18900.00,-2300.00 +16700.00,19450.00,-2750.00,16700.00,19300.00,-2600.00 +16800.00,19600.00,-2800.00,16800.00,19450.00,-2650.00 +16900.00,19750.00,-2850.00,16900.00,19650.00,-2750.00 +17000.00,19900.00,-2900.00,17000.00,19750.00,-2750.00 +17100.00,20100.00,-3000.00,17100.00,19850.00,-2750.00 +17200.00,20200.00,-3000.00,17200.00,19900.00,-2700.00 +17300.00,20200.00,-2900.00,17300.00,20000.00,-2700.00 +17400.00,20300.00,-2900.00,17400.00,20200.00,-2800.00 +17500.00,20350.00,-2850.00,17500.00,20200.00,-2700.00 +17600.00,20600.00,-3000.00,17600.00,20350.00,-2750.00 +17700.00,20750.00,-3050.00,17700.00,20800.00,-3100.00 +17800.00,20900.00,-3100.00,17800.00,20850.00,-3050.00 +17900.00,21000.00,-3100.00,17900.00,21050.00,-3150.00 +18000.00,21200.00,-3200.00,17956.36,21250.00,-3293.64 +18100.00,21400.00,-3300.00,17856.36,21150.00,-3293.64 +18200.00,21450.00,-3250.00,17756.36,21450.00,-3693.64 +18189.72,21600.00,-3410.28,17656.36,21000.00,-3343.64 +18089.72,21800.00,-3710.28,17556.36,21100.00,-3543.64 +17989.72,21750.00,-3760.28,17456.36,20850.00,-3393.64 +17889.72,21600.00,-3710.28,17356.36,20650.00,-3293.64 +17789.72,21550.00,-3760.28,17256.36,20550.00,-3293.64 +17689.72,21400.00,-3710.28,17156.36,20350.00,-3193.64 +17589.72,21200.00,-3610.28,17056.36,20350.00,-3293.64 +17489.72,21100.00,-3610.28,16956.36,20200.00,-3243.64 +17389.72,20900.00,-3510.28,16856.36,20100.00,-3243.64 +17289.72,20850.00,-3560.28,16756.36,19950.00,-3193.64 +17189.72,20800.00,-3610.28,16656.36,19700.00,-3043.64 +17089.72,20450.00,-3360.28,16556.36,19700.00,-3143.64 +16989.72,20250.00,-3260.28,16456.36,19450.00,-2993.64 +16889.72,20150.00,-3260.28,16356.36,19250.00,-2893.64 +16789.72,20100.00,-3310.28,16256.36,18900.00,-2643.64 +16689.72,19950.00,-3260.28,16156.36,18800.00,-2643.64 +16589.72,19850.00,-3260.28,16056.36,18850.00,-2793.64 +16489.72,19750.00,-3260.28,15956.36,18850.00,-2893.64 +16389.72,19750.00,-3360.28,15856.36,18700.00,-2843.64 +16289.72,19600.00,-3310.28,15756.36,18800.00,-3043.64 +16189.72,19450.00,-3260.28,15656.36,18600.00,-2943.64 +16089.72,19150.00,-3060.28,15556.36,18200.00,-2643.64 +15989.72,19050.00,-3060.28,15456.36,18150.00,-2693.64 +15889.72,18950.00,-3060.28,15356.36,18050.00,-2693.64 +15789.72,18850.00,-3060.28,15256.36,17900.00,-2643.64 +15689.72,18850.00,-3160.28,15156.36,18050.00,-2893.64 +15589.72,18650.00,-3060.28,15056.36,17950.00,-2893.64 +15489.72,18650.00,-3160.28,14956.36,17900.00,-2943.64 +15389.72,18550.00,-3160.28,14856.36,17700.00,-2843.64 +15289.72,18300.00,-3010.28,14756.36,17700.00,-2943.64 +15189.72,18250.00,-3060.28,14656.36,17550.00,-2893.64 +15089.72,18150.00,-3060.28,14556.36,17200.00,-2643.64 +14989.72,18000.00,-3010.28,14456.36,17050.00,-2593.64 +14889.72,17950.00,-3060.28,14356.36,17200.00,-2843.64 +14789.72,17950.00,-3160.28,14256.36,16950.00,-2693.64 +14689.72,17900.00,-3210.28,14156.36,16650.00,-2493.64 +14589.72,17650.00,-3060.28,14056.36,16750.00,-2693.64 +14489.72,17400.00,-2910.28,13956.36,16550.00,-2593.64 +14389.72,17300.00,-2910.28,13856.36,16450.00,-2593.64 +14289.72,17100.00,-2810.28,13756.36,16300.00,-2543.64 +14189.72,17000.00,-2810.28,13656.36,16100.00,-2443.64 +14089.72,16950.00,-2860.28,13556.36,16050.00,-2493.64 +13989.72,17000.00,-3010.28,13456.36,15750.00,-2293.64 +13889.72,16800.00,-2910.28,13356.36,15850.00,-2493.64 +13789.72,16550.00,-2760.28,13256.36,15800.00,-2543.64 +13689.72,16350.00,-2660.28,13156.36,15700.00,-2543.64 +13589.72,16150.00,-2560.28,13056.36,15350.00,-2293.64 +13489.72,14250.00,-760.28,12956.36,13400.00,-443.64 +13389.72,19200.00,-5810.28,12856.36,17900.00,-5043.64 +13289.72,15650.00,-2360.28,12756.36,14650.00,-1893.64 +13189.72,13350.00,-160.28,12656.36,12150.00,506.36 +13089.72,13750.00,-660.28,12556.36,13200.00,-643.64 +12989.72,15100.00,-2110.28,12456.36,14500.00,-2043.64 +12889.72,15700.00,-2810.28,12356.36,15000.00,-2643.64 +12789.72,15800.00,-3010.28,12256.36,14750.00,-2493.64 +12689.72,15250.00,-2560.28,12156.36,14500.00,-2343.64 +12589.72,14900.00,-2310.28,12056.36,14100.00,-2043.64 +12489.72,14700.00,-2210.28,11956.36,13900.00,-1943.64 +12389.72,14600.00,-2210.28,11856.36,13700.00,-1843.64 +12289.72,14600.00,-2310.28,11756.36,13700.00,-1943.64 +12189.72,14500.00,-2310.28,11656.36,13500.00,-1843.64 +12089.72,14400.00,-2310.28,11556.36,13350.00,-1793.64 +11989.72,14250.00,-2260.28,11456.36,13300.00,-1843.64 +11889.72,14150.00,-2260.28,11356.36,13300.00,-1943.64 +11789.72,14150.00,-2360.28,11256.36,13150.00,-1893.64 +11689.72,13950.00,-2260.28,11156.36,13050.00,-1893.64 +11589.72,13700.00,-2110.28,11056.36,12950.00,-1893.64 +11489.72,13650.00,-2160.28,10956.36,12800.00,-1843.64 +11389.72,13700.00,-2310.28,10856.36,12750.00,-1893.64 +11289.72,13500.00,-2210.28,10756.36,12700.00,-1943.64 +11189.72,13400.00,-2210.28,10656.36,12550.00,-1893.64 +11089.72,13200.00,-2110.28,10556.36,12450.00,-1893.64 +10989.72,13150.00,-2160.28,10456.36,12300.00,-1843.64 +10889.72,13050.00,-2160.28,10356.36,12100.00,-1743.64 +10789.72,12900.00,-2110.28,10256.36,12000.00,-1743.64 +10689.72,12750.00,-2060.28,10156.36,11800.00,-1643.64 +10589.72,12650.00,-2060.28,10056.36,11650.00,-1593.64 +10489.72,12550.00,-2060.28,9956.36,11550.00,-1593.64 +10389.72,12400.00,-2010.28,9856.36,11450.00,-1593.64 +10289.72,12200.00,-1910.28,9756.36,11300.00,-1543.64 +10189.72,12150.00,-1960.28,9656.36,11150.00,-1493.64 +10089.72,12000.00,-1910.28,9556.36,11050.00,-1493.64 +9989.72,11850.00,-1860.28,9456.36,10900.00,-1443.64 +9889.72,11800.00,-1910.28,9356.36,10850.00,-1493.64 +9789.72,11700.00,-1910.28,9256.36,10750.00,-1493.64 +9689.72,11500.00,-1810.28,9156.36,10400.00,-1243.64 +9589.72,11300.00,-1710.28,9056.36,10300.00,-1243.64 +9489.72,11100.00,-1610.28,8956.36,10300.00,-1343.64 +9389.72,11000.00,-1610.28,8856.36,10150.00,-1293.64 +9289.72,10900.00,-1610.28,8756.36,10000.00,-1243.64 +9189.72,10750.00,-1560.28,8656.36,9900.00,-1243.64 +9089.72,10550.00,-1460.28,8556.36,9750.00,-1193.64 +8989.72,10450.00,-1460.28,8456.36,9700.00,-1243.64 +8889.72,10400.00,-1510.28,8356.36,9500.00,-1143.64 +8789.72,10250.00,-1460.28,8256.36,9250.00,-993.64 +8689.72,10050.00,-1360.28,8156.36,9000.00,-843.64 +8589.72,9950.00,-1360.28,8056.36,8850.00,-793.64 +8489.72,9900.00,-1410.28,7956.36,8700.00,-743.64 +8389.72,9800.00,-1410.28,7856.36,8600.00,-743.64 +8289.72,8900.00,-610.28,7756.36,8250.00,-493.64 +8189.72,8100.00,89.72,7656.36,8500.00,-843.64 +8089.72,8800.00,-710.28,7556.36,8450.00,-893.64 +7989.72,9250.00,-1260.28,7456.36,7900.00,-443.64 +7889.72,8900.00,-1010.28,7356.36,6900.00,456.36 +7789.72,7950.00,-160.28,7256.36,7200.00,56.36 +7689.72,7900.00,-210.28,7156.36,7450.00,-293.64 +7589.72,8650.00,-1060.28,7056.36,8050.00,-993.64 +7489.72,8500.00,-1010.28,6956.36,7700.00,-743.64 +7389.72,7050.00,339.72,6856.36,6500.00,356.36 +7289.72,6450.00,839.72,6756.36,5650.00,1106.36 +7189.72,7400.00,-210.28,6656.36,6650.00,6.36 +7089.72,8250.00,-1160.28,6556.36,7400.00,-843.64 +6989.72,7850.00,-860.28,6456.36,7150.00,-693.64 +6889.72,6600.00,289.72,6356.36,6050.00,306.36 +6789.72,6450.00,339.72,6256.36,5600.00,656.36 +6689.72,6750.00,-60.28,6156.36,5850.00,306.36 +6589.72,7350.00,-760.28,6056.36,6350.00,-293.64 +6489.72,7600.00,-1110.28,5956.36,6550.00,-593.64 +6389.72,6350.00,39.72,5856.36,5300.00,556.36 +6289.72,5800.00,489.72,5756.36,4500.00,1256.36 +6189.72,6300.00,-110.28,5656.36,5300.00,356.36 +6089.72,6550.00,-460.28,5556.36,5550.00,6.36 +5989.72,5300.00,689.72,5456.36,4400.00,1056.36 +5889.72,6250.00,-360.28,5356.36,4600.00,756.36 +5789.72,5600.00,189.72,5256.36,4750.00,506.36 +5689.72,4650.00,1039.72,5156.36,4550.00,606.36 +5589.72,4700.00,889.72,5056.36,3850.00,1206.36 +5489.72,5500.00,-10.28,4956.36,3350.00,1606.36 +5389.72,5750.00,-360.28,4856.36,4100.00,756.36 +5289.72,4950.00,339.72,4756.36,4500.00,256.36 +5189.72,4150.00,1039.72,4656.36,3700.00,956.36 +5089.72,4000.00,1089.72,4556.36,2800.00,1756.36 +4989.72,4750.00,239.72,4456.36,2600.00,1856.36 +4889.72,5250.00,-360.28,4356.36,3800.00,556.36 +4789.72,4750.00,39.72,4256.36,4650.00,-393.64 +4689.72,3750.00,939.72,4156.36,3650.00,506.36 +4589.72,3050.00,1539.72,4056.36,2750.00,1306.36 +4489.72,3000.00,1489.72,3956.36,2200.00,1756.36 +4389.72,4250.00,139.72,3856.36,1550.00,2306.36 +4289.72,4650.00,-360.28,3756.36,2900.00,856.36 +4189.72,4150.00,39.72,3656.36,3800.00,-143.64 +4089.72,3100.00,989.72,3556.36,3000.00,556.36 +3989.72,2600.00,1389.72,3456.36,2200.00,1256.36 +3889.72,2200.00,1689.72,3356.36,600.00,2756.36 +3789.72,1700.00,2089.72,3256.36,950.00,2306.36 +3689.72,3200.00,489.72,3156.36,2900.00,256.36 +3589.72,3750.00,-160.28,3056.36,3400.00,-343.64 +3489.72,3300.00,189.72,2956.36,2650.00,306.36 +3389.72,2500.00,889.72,2856.36,1800.00,1056.36 +3289.72,2150.00,1139.72,2756.36,1150.00,1606.36 +3189.72,700.00,2489.72,2656.36,-550.00,3206.36 +3089.72,1600.00,1489.72,2556.36,-200.00,2756.36 +2989.72,2400.00,589.72,2456.36,2150.00,306.36 +2889.72,2000.00,889.72,2356.36,2650.00,-293.64 +2789.72,800.00,1989.72,2256.36,2000.00,256.36 +2689.72,1000.00,1689.72,2156.36,900.00,1256.36 +2589.72,1000.00,1589.72,2056.36,-100.00,2156.36 +2489.72,-500.00,2989.72,1956.36,-450.00,2406.36 +2389.72,400.00,1989.72,1856.36,-1050.00,2906.36 +2289.72,750.00,1539.72,1756.36,500.00,1256.36 +2189.72,-100.00,2289.72,1656.36,1200.00,456.36 +2089.72,-700.00,2789.72,1556.36,-100.00,1656.36 +1989.72,-150.00,2139.72,1456.36,-700.00,2156.36 +1889.72,650.00,1239.72,1356.36,-900.00,2256.36 +1789.72,-700.00,2489.72,1256.36,100.00,1156.36 +1689.72,-300.00,1989.72,1156.36,200.00,956.36 +1589.72,0.00,1589.72,1056.36,0.00,1056.36 +1489.72,0.00,1489.72,956.36,0.00,956.36 +1389.72,0.00,1389.72,856.36,0.00,856.36 +1289.72,0.00,1289.72,756.36,0.00,756.36 +1189.72,0.00,1189.72,656.36,0.00,656.36 +1089.72,0.00,1089.72,556.36,0.00,556.36 +989.72,0.00,989.72,456.36,0.00,456.36 +889.72,0.00,889.72,356.36,0.00,356.36 +789.72,0.00,789.72,256.36,0.00,256.36 +689.72,0.00,689.72,156.36,0.00,156.36 +589.72,0.00,589.72,56.36,0.00,56.36 +489.72,0.00,489.72,0.00,0.00,0.00 +389.72,0.00,389.72,0.00,0.00,0.00 +289.72,0.00,289.72,0.00,0.00,0.00 +189.72,0.00,189.72,0.00,0.00,0.00 +89.72,0.00,89.72,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +-100.00,0.00,-100.00,-100.00,0.00,-100.00 +-200.00,0.00,-200.00,-200.00,0.00,-200.00 +-300.00,0.00,-300.00,-300.00,0.00,-300.00 +-400.00,0.00,-400.00,-400.00,0.00,-400.00 +-500.00,0.00,-500.00,-500.00,0.00,-500.00 +-600.00,0.00,-600.00,-600.00,0.00,-600.00 +-700.00,0.00,-700.00,-700.00,0.00,-700.00 +-800.00,0.00,-800.00,-800.00,0.00,-800.00 +-900.00,0.00,-900.00,-900.00,0.00,-900.00 +-1000.00,0.00,-1000.00,-1000.00,0.00,-1000.00 +-1100.00,0.00,-1100.00,-1100.00,0.00,-1100.00 +-1200.00,0.00,-1200.00,-1200.00,0.00,-1200.00 +-1300.00,0.00,-1300.00,-1300.00,0.00,-1300.00 +-1400.00,0.00,-1400.00,-1400.00,0.00,-1400.00 +-1500.00,0.00,-1500.00,-1500.00,0.00,-1500.00 +-1600.00,0.00,-1600.00,-1600.00,0.00,-1600.00 +-1700.00,0.00,-1700.00,-1700.00,0.00,-1700.00 +-1800.00,0.00,-1800.00,-1800.00,0.00,-1800.00 +-1900.00,0.00,-1900.00,-1900.00,0.00,-1900.00 +-2000.00,0.00,-2000.00,-2000.00,0.00,-2000.00 +-2100.00,0.00,-2100.00,-2100.00,0.00,-2100.00 +-2200.00,0.00,-2200.00,-2200.00,0.00,-2200.00 +-2300.00,0.00,-2300.00,-2300.00,0.00,-2300.00 +-2400.00,0.00,-2400.00,-2400.00,0.00,-2400.00 +-2500.00,0.00,-2500.00,-2500.00,0.00,-2500.00 +-2600.00,-400.00,-2200.00,-2600.00,-400.00,-2200.00 +-2700.00,-450.00,-2250.00,-2700.00,-350.00,-2350.00 +-2800.00,800.00,-3600.00,-2800.00,150.00,-2950.00 +-2900.00,-500.00,-2400.00,-2900.00,-750.00,-2150.00 +-3000.00,-2400.00,-600.00,-3000.00,-1950.00,-1050.00 +-3100.00,-3000.00,-100.00,-3100.00,-1700.00,-1400.00 +-3200.00,-2350.00,-850.00,-3200.00,-750.00,-2450.00 +-3300.00,-1900.00,-1400.00,-3300.00,-1100.00,-2200.00 +-3400.00,-950.00,-2450.00,-3400.00,-1900.00,-1500.00 +-3500.00,50.00,-3550.00,-3500.00,-2200.00,-1300.00 +-3600.00,-2050.00,-1550.00,-3600.00,-600.00,-3000.00 +-3700.00,-3900.00,200.00,-3700.00,-750.00,-2950.00 +-3800.00,-3050.00,-750.00,-3800.00,-3050.00,-750.00 +-3900.00,-2100.00,-1800.00,-3900.00,-3650.00,-250.00 +-4000.00,-2300.00,-1700.00,-4000.00,-2550.00,-1450.00 +-4100.00,-3300.00,-800.00,-4100.00,-1950.00,-2150.00 +-4200.00,-3500.00,-700.00,-4200.00,-2450.00,-1750.00 +-4300.00,-2800.00,-1500.00,-4300.00,-3350.00,-950.00 +-4400.00,-2550.00,-1850.00,-4400.00,-3550.00,-850.00 +-4500.00,-3600.00,-900.00,-4500.00,-2300.00,-2200.00 +-4600.00,-4100.00,-500.00,-4600.00,-2100.00,-2500.00 +-4700.00,-3250.00,-1450.00,-4700.00,-3400.00,-1300.00 +-4800.00,-2900.00,-1900.00,-4800.00,-4450.00,-350.00 +-4900.00,-4250.00,-650.00,-4900.00,-4450.00,-450.00 +-5000.00,-4700.00,-300.00,-5000.00,-3100.00,-1900.00 +-5100.00,-3800.00,-1300.00,-5100.00,-2700.00,-2400.00 +-5200.00,-3700.00,-1500.00,-5200.00,-4150.00,-1050.00 +-5300.00,-4450.00,-850.00,-5300.00,-5200.00,-100.00 +-5400.00,-5350.00,-50.00,-5400.00,-4800.00,-600.00 +-5500.00,-5500.00,0.00,-5500.00,-4300.00,-1200.00 +-5600.00,-4450.00,-1150.00,-5600.00,-4200.00,-1400.00 +-5700.00,-4300.00,-1400.00,-5700.00,-4750.00,-950.00 +-5800.00,-5000.00,-800.00,-5800.00,-5150.00,-650.00 +-5900.00,-6050.00,150.00,-5900.00,-5300.00,-600.00 +-6000.00,-6000.00,0.00,-6000.00,-5500.00,-500.00 +-6100.00,-5050.00,-1050.00,-6100.00,-5600.00,-500.00 +-6200.00,-4750.00,-1450.00,-6200.00,-5400.00,-800.00 +-6300.00,-5850.00,-450.00,-6300.00,-5850.00,-450.00 +-6400.00,-6700.00,300.00,-6400.00,-6150.00,-250.00 +-6500.00,-6950.00,450.00,-6500.00,-6700.00,200.00 +-6600.00,-5550.00,-1050.00,-6600.00,-6600.00,0.00 +-6700.00,-5450.00,-1250.00,-6700.00,-7000.00,300.00 +-6800.00,-6450.00,-350.00,-6800.00,-6650.00,-150.00 +-6900.00,-7350.00,450.00,-6900.00,-6050.00,-850.00 +-7000.00,-7200.00,200.00,-7000.00,-6600.00,-400.00 +-7100.00,-6200.00,-900.00,-7100.00,-7000.00,-100.00 +-7200.00,-7150.00,-50.00,-7200.00,-7750.00,550.00 +-7300.00,-7650.00,350.00,-7300.00,-7750.00,450.00 +-7400.00,-7950.00,550.00,-7400.00,-7900.00,500.00 +-7500.00,-7700.00,200.00,-7500.00,-7650.00,150.00 +-7600.00,-7800.00,200.00,-7600.00,-7750.00,150.00 +-7700.00,-8450.00,750.00,-7700.00,-8300.00,600.00 +-7800.00,-8650.00,850.00,-7800.00,-8550.00,750.00 +-7900.00,-8200.00,300.00,-7900.00,-8150.00,250.00 +-8000.00,-8650.00,650.00,-8000.00,-8650.00,650.00 +-8100.00,-10550.00,2450.00,-8100.00,-10450.00,2350.00 +-8200.00,-8550.00,350.00,-8200.00,-8300.00,100.00 +-8300.00,-7550.00,-750.00,-8300.00,-7450.00,-850.00 +-8400.00,-8150.00,-250.00,-8400.00,-8300.00,-100.00 +-8500.00,-9050.00,550.00,-8500.00,-9050.00,550.00 +-8600.00,-9600.00,1000.00,-8600.00,-9450.00,850.00 +-8700.00,-9850.00,1150.00,-8700.00,-9600.00,900.00 +-8800.00,-9800.00,1000.00,-8800.00,-9600.00,800.00 +-8900.00,-9750.00,850.00,-8900.00,-9600.00,700.00 +-9000.00,-9800.00,800.00,-9000.00,-9650.00,650.00 +-9100.00,-9900.00,800.00,-9100.00,-9950.00,850.00 +-9200.00,-10150.00,950.00,-9200.00,-9950.00,750.00 +-9300.00,-9850.00,550.00,-9300.00,-9750.00,450.00 +-9400.00,-10500.00,1100.00,-9400.00,-10350.00,950.00 +-9500.00,-10750.00,1250.00,-9500.00,-10550.00,1050.00 +-9600.00,-10800.00,1200.00,-9600.00,-10550.00,950.00 +-9700.00,-10550.00,850.00,-9700.00,-10250.00,550.00 +-9800.00,-11000.00,1200.00,-9800.00,-10650.00,850.00 +-9900.00,-11150.00,1250.00,-9900.00,-10950.00,1050.00 +-10000.00,-11300.00,1300.00,-10000.00,-11050.00,1050.00 +-10100.00,-11350.00,1250.00,-10100.00,-11150.00,1050.00 +-10200.00,-11500.00,1300.00,-10200.00,-11200.00,1000.00 +-10300.00,-11600.00,1300.00,-10300.00,-11350.00,1050.00 +-10400.00,-11700.00,1300.00,-10400.00,-11450.00,1050.00 +-10500.00,-11950.00,1450.00,-10500.00,-11600.00,1100.00 +-10600.00,-12050.00,1450.00,-10600.00,-11650.00,1050.00 +-10700.00,-11650.00,950.00,-10700.00,-11100.00,400.00 +-10800.00,-12250.00,1450.00,-10800.00,-11650.00,850.00 +-10900.00,-12500.00,1600.00,-10900.00,-11950.00,1050.00 +-11000.00,-13050.00,2050.00,-11000.00,-12350.00,1350.00 +-11100.00,-12550.00,1450.00,-11100.00,-11950.00,850.00 +-11200.00,-13050.00,1850.00,-11200.00,-12400.00,1200.00 +-11300.00,-12200.00,900.00,-11300.00,-11650.00,350.00 +-11400.00,-12750.00,1350.00,-11400.00,-12250.00,850.00 +-11500.00,-13150.00,1650.00,-11500.00,-12450.00,950.00 +-11600.00,-13250.00,1650.00,-11600.00,-12350.00,750.00 +-11700.00,-13850.00,2150.00,-11700.00,-13200.00,1500.00 +-11800.00,-13400.00,1600.00,-11800.00,-12800.00,1000.00 +-11900.00,-13250.00,1350.00,-11900.00,-12650.00,750.00 +-12000.00,-12750.00,750.00,-12000.00,-12250.00,250.00 +-12100.00,-13600.00,1500.00,-12100.00,-12950.00,850.00 +-12200.00,-14050.00,1850.00,-12200.00,-13200.00,1000.00 +-12300.00,-14200.00,1900.00,-12300.00,-13350.00,1050.00 +-12400.00,-14100.00,1700.00,-12400.00,-13500.00,1100.00 +-12500.00,-14200.00,1700.00,-12500.00,-13850.00,1350.00 +-12600.00,-15000.00,2400.00,-12600.00,-14750.00,2150.00 +-12700.00,-14950.00,2250.00,-12700.00,-14900.00,2200.00 +-12800.00,-14750.00,1950.00,-12800.00,-14700.00,1900.00 +-12900.00,-14050.00,1150.00,-12900.00,-14050.00,1150.00 +-13000.00,-14350.00,1350.00,-13000.00,-14150.00,1150.00 +-13100.00,-14900.00,1800.00,-13100.00,-14650.00,1550.00 +-13200.00,-14950.00,1750.00,-13200.00,-14950.00,1750.00 +-13300.00,-15250.00,1950.00,-13300.00,-15000.00,1700.00 +-13400.00,-15400.00,2000.00,-13400.00,-15150.00,1750.00 +-13500.00,-15500.00,2000.00,-13500.00,-15250.00,1750.00 +-13600.00,-15600.00,2000.00,-13600.00,-15350.00,1750.00 +-13700.00,-15700.00,2000.00,-13700.00,-15550.00,1850.00 +-13800.00,-15850.00,2050.00,-13800.00,-15600.00,1800.00 +-13900.00,-16100.00,2200.00,-13900.00,-15750.00,1850.00 +-14000.00,-16150.00,2150.00,-14000.00,-15850.00,1850.00 +-14100.00,-16200.00,2100.00,-14100.00,-16000.00,1900.00 +-14200.00,-16350.00,2150.00,-14200.00,-16050.00,1850.00 +-14300.00,-16450.00,2150.00,-14300.00,-16150.00,1850.00 +-14400.00,-16650.00,2250.00,-14400.00,-16200.00,1800.00 +-14500.00,-16850.00,2350.00,-14500.00,-16400.00,1900.00 +-14600.00,-16950.00,2350.00,-14600.00,-16500.00,1900.00 +-14700.00,-17050.00,2350.00,-14700.00,-16650.00,1950.00 +-14800.00,-17200.00,2400.00,-14800.00,-16650.00,1850.00 +-14900.00,-17250.00,2350.00,-14900.00,-16750.00,1850.00 +-15000.00,-17150.00,2150.00,-15000.00,-16550.00,1550.00 +-15100.00,-17600.00,2500.00,-15100.00,-16700.00,1600.00 +-15200.00,-17600.00,2400.00,-15200.00,-16950.00,1750.00 +-15300.00,-17650.00,2350.00,-15300.00,-17250.00,1950.00 +-15400.00,-17950.00,2550.00,-15400.00,-17350.00,1950.00 +-15500.00,-18600.00,3100.00,-15500.00,-18050.00,2550.00 +-15600.00,-17900.00,2300.00,-15600.00,-17250.00,1650.00 +-15700.00,-17800.00,2100.00,-15700.00,-17050.00,1350.00 +-15800.00,-21450.00,5650.00,-15800.00,-20550.00,4750.00 +-15900.00,-18550.00,2650.00,-15900.00,-17500.00,1600.00 +-16000.00,-16900.00,900.00,-16000.00,-16250.00,250.00 +-16100.00,-17600.00,1500.00,-16100.00,-16950.00,850.00 +-16200.00,-18450.00,2250.00,-16200.00,-17700.00,1500.00 +-16300.00,-19750.00,3450.00,-16300.00,-19650.00,3350.00 +-16400.00,-19100.00,2700.00,-16400.00,-19400.00,3000.00 +-16500.00,-19650.00,3150.00,-16500.00,-19700.00,3200.00 +-16600.00,-18800.00,2200.00,-16600.00,-18550.00,1950.00 +-16700.00,-18900.00,2200.00,-16700.00,-18650.00,1950.00 +-16800.00,-19200.00,2400.00,-16800.00,-18950.00,2150.00 +-16900.00,-19650.00,2750.00,-16900.00,-19300.00,2400.00 +-17000.00,-19900.00,2900.00,-17000.00,-19350.00,2350.00 +-17100.00,-20450.00,3350.00,-17100.00,-20400.00,3300.00 +-17200.00,-20650.00,3450.00,-17200.00,-20450.00,3250.00 +-17300.00,-19700.00,2400.00,-17300.00,-19400.00,2100.00 +-17400.00,-19750.00,2350.00,-17400.00,-19350.00,1950.00 +-17500.00,-21000.00,3500.00,-17500.00,-20750.00,3250.00 +-17600.00,-21250.00,3650.00,-17600.00,-21050.00,3450.00 +-17700.00,-20300.00,2600.00,-17700.00,-20150.00,2450.00 +-17800.00,-21150.00,3350.00,-17800.00,-20700.00,2900.00 +-17900.00,-20450.00,2550.00,-17743.79,-20200.00,2456.21 +-17951.36,-21550.00,3598.64,-17643.79,-20750.00,3106.21 +-17851.36,-20850.00,2998.64,-17543.79,-20100.00,2556.21 +-17751.36,-21650.00,3898.64,-17443.79,-20700.00,3256.21 +-17651.36,-20800.00,3148.64,-17343.79,-19650.00,2306.21 +-17551.36,-21300.00,3748.64,-17243.79,-20350.00,3106.21 +-17451.36,-21050.00,3598.64,-17143.79,-20300.00,3156.21 +-17351.36,-20750.00,3398.64,-17043.79,-20000.00,2956.21 +-17251.36,-20000.00,2748.64,-16943.79,-18450.00,1506.21 +-17151.36,-19650.00,2498.64,-16843.79,-18850.00,2006.21 +-17051.36,-20900.00,3848.64,-16743.79,-19650.00,2906.21 +-16951.36,-20900.00,3948.64,-16643.79,-19550.00,2906.21 +-16851.36,-19600.00,2748.64,-16543.79,-18600.00,2056.21 +-16751.36,-19350.00,2598.64,-16443.79,-18350.00,1906.21 +-16651.36,-19650.00,2998.64,-16343.79,-18750.00,2406.21 +-16551.36,-19450.00,2898.64,-16243.79,-19200.00,2956.21 +-16451.36,-19450.00,2998.64,-16143.79,-19250.00,3106.21 +-16351.36,-19200.00,2848.64,-16043.79,-19000.00,2956.21 +-16251.36,-19000.00,2748.64,-15943.79,-18850.00,2906.21 +-16151.36,-18950.00,2798.64,-15843.79,-18400.00,2556.21 +-16051.36,-18950.00,2898.64,-15743.79,-18200.00,2456.21 +-15951.36,-18800.00,2848.64,-15643.79,-17600.00,1956.21 +-15851.36,-19500.00,3648.64,-15543.79,-18550.00,3006.21 +-15751.36,-18700.00,2948.64,-15443.79,-17900.00,2456.21 +-15651.36,-18200.00,2548.64,-15343.79,-17550.00,2206.21 +-15551.36,-18850.00,3298.64,-15243.79,-18150.00,2906.21 +-15451.36,-18100.00,2648.64,-15143.79,-17450.00,2306.21 +-15351.36,-18550.00,3198.64,-15043.79,-17800.00,2756.21 +-15251.36,-17900.00,2648.64,-14943.79,-17050.00,2106.21 +-15151.36,-17650.00,2498.64,-14843.79,-16950.00,2106.21 +-15051.36,-16950.00,1898.64,-14743.79,-16250.00,1506.21 +-14951.36,-17900.00,2948.64,-14643.79,-17000.00,2356.21 +-14851.36,-17900.00,3048.64,-14543.79,-17200.00,2656.21 +-14751.36,-17600.00,2848.64,-14443.79,-16950.00,2506.21 +-14651.36,-17350.00,2698.64,-14343.79,-16450.00,2106.21 +-14551.36,-17200.00,2648.64,-14243.79,-16050.00,1806.21 +-14451.36,-16850.00,2398.64,-14143.79,-15800.00,1656.21 +-14351.36,-17050.00,2698.64,-14043.79,-15750.00,1706.21 +-14251.36,-16900.00,2648.64,-13943.79,-15750.00,1806.21 +-14151.36,-17300.00,3148.64,-13843.79,-16500.00,2656.21 +-14051.36,-16450.00,2398.64,-13743.79,-15500.00,1756.21 +-13951.36,-16100.00,2148.64,-13643.79,-15300.00,1656.21 +-13851.36,-16050.00,2198.64,-13543.79,-15150.00,1606.21 +-13751.36,-15500.00,1748.64,-13443.79,-14400.00,956.21 +-13651.36,-16050.00,2398.64,-13343.79,-14900.00,1556.21 +-13551.36,-16150.00,2598.64,-13243.79,-14950.00,1706.21 +-13451.36,-15950.00,2498.64,-13143.79,-14550.00,1406.21 +-13351.36,-15800.00,2448.64,-13043.79,-14450.00,1406.21 +-13251.36,-15500.00,2248.64,-12943.79,-14450.00,1506.21 +-13151.36,-15400.00,2248.64,-12843.79,-14500.00,1656.21 +-13051.36,-15200.00,2148.64,-12743.79,-14600.00,1856.21 +-12951.36,-15100.00,2148.64,-12643.79,-14700.00,2056.21 +-12851.36,-15050.00,2198.64,-12543.79,-14600.00,2056.21 +-12751.36,-14850.00,2098.64,-12443.79,-14450.00,2006.21 +-12651.36,-14650.00,1998.64,-12343.79,-14100.00,1756.21 +-12551.36,-14750.00,2198.64,-12243.79,-14300.00,2056.21 +-12451.36,-17350.00,4898.64,-12143.79,-16900.00,4756.21 +-12351.36,-13450.00,1098.64,-12043.79,-13100.00,1056.21 +-12251.36,-11750.00,-501.36,-11943.79,-11150.00,-793.79 +-12151.36,-12500.00,348.64,-11843.79,-12400.00,556.21 +-12051.36,-14000.00,1948.64,-11743.79,-13100.00,1356.21 +-11951.36,-14750.00,2798.64,-11643.79,-13450.00,1806.21 +-11851.36,-14500.00,2648.64,-11543.79,-13400.00,1856.21 +-11751.36,-14100.00,2348.64,-11443.79,-13200.00,1756.21 +-11651.36,-13900.00,2248.64,-11343.79,-13050.00,1706.21 +-11551.36,-13550.00,1998.64,-11243.79,-12850.00,1606.21 +-11451.36,-13400.00,1948.64,-11143.79,-12800.00,1656.21 +-11351.36,-13500.00,2148.64,-11043.79,-12700.00,1656.21 +-11251.36,-13250.00,1998.64,-10943.79,-12400.00,1456.21 +-11151.36,-13150.00,1998.64,-10843.79,-12300.00,1456.21 +-11051.36,-13050.00,1998.64,-10743.79,-12200.00,1456.21 +-10951.36,-12900.00,1948.64,-10643.79,-12000.00,1356.21 +-10851.36,-12800.00,1948.64,-10543.79,-12000.00,1456.21 +-10751.36,-12700.00,1948.64,-10443.79,-11900.00,1456.21 +-10651.36,-12600.00,1948.64,-10343.79,-11800.00,1456.21 +-10551.36,-12500.00,1948.64,-10243.79,-11700.00,1456.21 +-10451.36,-12300.00,1848.64,-10143.79,-11450.00,1306.21 +-10351.36,-12100.00,1748.64,-10043.79,-11200.00,1156.21 +-10251.36,-12050.00,1798.64,-9943.79,-10950.00,1006.21 +-10151.36,-11950.00,1798.64,-9843.79,-10750.00,906.21 +-10051.36,-11700.00,1648.64,-9743.79,-10550.00,806.21 +-9951.36,-11650.00,1698.64,-9643.79,-10450.00,806.21 +-9851.36,-11950.00,2098.64,-9543.79,-10750.00,1206.21 +-9751.36,-11300.00,1548.64,-9443.79,-10300.00,856.21 +-9651.36,-10950.00,1298.64,-9343.79,-10150.00,806.21 +-9551.36,-10950.00,1398.64,-9243.79,-10150.00,906.21 +-9451.36,-10950.00,1498.64,-9143.79,-10250.00,1106.21 +-9351.36,-10850.00,1498.64,-9043.79,-10050.00,1006.21 +-9251.36,-10800.00,1548.64,-8943.79,-9800.00,856.21 +-9151.36,-10700.00,1548.64,-8843.79,-9700.00,856.21 +-9051.36,-10500.00,1448.64,-8743.79,-9500.00,756.21 +-8951.36,-10400.00,1448.64,-8643.79,-9250.00,606.21 +-8851.36,-10200.00,1348.64,-8543.79,-9150.00,606.21 +-8751.36,-10100.00,1348.64,-8443.79,-8950.00,506.21 +-8651.36,-9950.00,1298.64,-8343.79,-8700.00,356.21 +-8551.36,-10250.00,1698.64,-8243.79,-8950.00,706.21 +-8451.36,-9200.00,748.64,-8143.79,-8300.00,156.21 +-8351.36,-8000.00,-351.36,-8043.79,-8150.00,106.21 +-8251.36,-8750.00,498.64,-7943.79,-8050.00,106.21 +-8151.36,-9250.00,1098.64,-7843.79,-8100.00,256.21 +-8051.36,-9450.00,1398.64,-7743.79,-8200.00,456.21 +-7951.36,-8850.00,898.64,-7643.79,-8100.00,456.21 +-7851.36,-7650.00,-201.36,-7543.79,-8100.00,556.21 +-7751.36,-8700.00,948.64,-7443.79,-8600.00,1156.21 +-7651.36,-8600.00,948.64,-7343.79,-7800.00,456.21 +-7551.36,-8200.00,648.64,-7243.79,-7000.00,-243.79 +-7451.36,-7250.00,-201.36,-7143.79,-7450.00,306.21 +-7351.36,-7800.00,448.64,-7043.79,-7500.00,456.21 +-7251.36,-8050.00,798.64,-6943.79,-7800.00,856.21 +-7151.36,-7850.00,698.64,-6843.79,-7400.00,556.21 +-7051.36,-6600.00,-451.36,-6743.79,-6300.00,-443.79 +-6951.36,-6300.00,-651.36,-6643.79,-5850.00,-793.79 +-6851.36,-6800.00,-51.36,-6543.79,-6350.00,-193.79 +-6751.36,-7450.00,698.64,-6443.79,-7000.00,556.21 +-6651.36,-7500.00,848.64,-6343.79,-6850.00,506.21 +-6551.36,-6250.00,-301.36,-6243.79,-5800.00,-443.79 +-6451.36,-6000.00,-451.36,-6143.79,-5350.00,-793.79 +-6351.36,-6500.00,148.64,-6043.79,-5950.00,-93.79 +-6251.36,-6550.00,298.64,-5943.79,-5850.00,-93.79 +-6151.36,-5600.00,-551.36,-5843.79,-4950.00,-893.79 +-6051.36,-5250.00,-801.36,-5743.79,-4750.00,-993.79 +-5951.36,-6100.00,148.64,-5643.79,-5350.00,-293.79 +-5851.36,-6350.00,498.64,-5543.79,-5500.00,-43.79 +-5751.36,-5400.00,-351.36,-5443.79,-4600.00,-843.79 +-5651.36,-4950.00,-701.36,-5343.79,-4300.00,-1043.79 +-5551.36,-5700.00,148.64,-5243.79,-4850.00,-393.79 +-5451.36,-5650.00,198.64,-5143.79,-4950.00,-193.79 +-5351.36,-4700.00,-651.36,-5043.79,-3950.00,-1093.79 +-5251.36,-4800.00,-451.36,-4943.79,-3900.00,-1043.79 +-5151.36,-4850.00,-301.36,-4843.79,-4150.00,-693.79 +-5051.36,-4100.00,-951.36,-4743.79,-4700.00,-43.79 +-4951.36,-3800.00,-1151.36,-4643.79,-3800.00,-843.79 +-4851.36,-4500.00,-351.36,-4543.79,-2950.00,-1593.79 +-4751.36,-5900.00,1148.64,-4443.79,-3450.00,-993.79 +-4651.36,-4200.00,-451.36,-4343.79,-3500.00,-843.79 +-4551.36,-3350.00,-1201.36,-4243.79,-2350.00,-1893.79 +-4451.36,-3050.00,-1401.36,-4143.79,-2450.00,-1693.79 +-4351.36,-3900.00,-451.36,-4043.79,-3300.00,-743.79 +-4251.36,-4300.00,48.64,-3943.79,-3600.00,-343.79 +-4151.36,-3500.00,-651.36,-3843.79,-2700.00,-1143.79 +-4051.36,-2900.00,-1151.36,-3743.79,-2300.00,-1443.79 +-3951.36,-2450.00,-1501.36,-3643.79,-1050.00,-2593.79 +-3851.36,-1850.00,-2001.36,-3543.79,-1650.00,-1893.79 +-3751.36,-3150.00,-601.36,-3443.79,-3100.00,-343.79 +-3651.36,-3800.00,148.64,-3343.79,-3300.00,-43.79 +-3551.36,-3100.00,-451.36,-3243.79,-2300.00,-943.79 +-3451.36,-2600.00,-851.36,-3143.79,-1900.00,-1243.79 +-3351.36,-1950.00,-1401.36,-3043.79,-250.00,-2793.79 +-3251.36,-850.00,-2401.36,-2943.79,100.00,-3043.79 +-3151.36,-150.00,-3001.36,-2843.79,-1900.00,-943.79 +-3051.36,-2100.00,-951.36,-2743.79,-2950.00,206.21 +-2951.36,-3550.00,598.64,-2643.79,-2300.00,-343.79 +-2851.36,-2850.00,-1.36,-2543.79,-1600.00,-943.79 +-2751.36,-2150.00,-601.36,-2443.79,-700.00,-1743.79 +-2651.36,-1850.00,-801.36,-2343.79,650.00,-2993.79 +-2551.36,-500.00,-2051.36,-2243.79,-350.00,-1893.79 +-2451.36,850.00,-3301.36,-2143.79,-1050.00,-1093.79 +-2351.36,-400.00,-1951.36,-2043.79,300.00,-2343.79 +-2251.36,-1200.00,-1051.36,-1943.79,850.00,-2793.79 +-2151.36,-850.00,-1301.36,-1843.79,50.00,-1893.79 +-2051.36,-1300.00,-751.36,-1743.79,-850.00,-893.79 +-1951.36,300.00,-2251.36,-1643.79,600.00,-2243.79 +-1851.36,400.00,-2251.36,-1543.79,850.00,-2393.79 +-1751.36,-150.00,-1601.36,-1443.79,-350.00,-1093.79 +-1651.36,0.00,-1651.36,-1343.79,-150.00,-1193.79 +-1551.36,0.00,-1551.36,-1243.79,50.00,-1293.79 +-1451.36,0.00,-1451.36,-1143.79,0.00,-1143.79 +-1351.36,0.00,-1351.36,-1043.79,0.00,-1043.79 +-1251.36,0.00,-1251.36,-943.79,0.00,-943.79 +-1151.36,0.00,-1151.36,-843.79,0.00,-843.79 +-1051.36,0.00,-1051.36,-743.79,0.00,-743.79 +-951.36,0.00,-951.36,-643.79,0.00,-643.79 +-851.36,0.00,-851.36,-543.79,0.00,-543.79 +-751.36,0.00,-751.36,-443.79,0.00,-443.79 +-651.36,0.00,-651.36,-343.79,0.00,-343.79 +-551.36,0.00,-551.36,-243.79,0.00,-243.79 +-451.36,0.00,-451.36,-143.79,0.00,-143.79 +-351.36,0.00,-351.36,-43.79,0.00,-43.79 +-251.36,0.00,-251.36,0.00,0.00,0.00 +-151.36,0.00,-151.36,0.00,0.00,0.00 +-51.36,0.00,-51.36,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +100.00,0.00,100.00,100.00,0.00,100.00 +200.00,0.00,200.00,200.00,0.00,200.00 +300.00,0.00,300.00,300.00,0.00,300.00 +400.00,0.00,400.00,400.00,0.00,400.00 +500.00,0.00,500.00,500.00,0.00,500.00 +600.00,0.00,600.00,600.00,0.00,600.00 +700.00,0.00,700.00,700.00,0.00,700.00 +800.00,0.00,800.00,800.00,0.00,800.00 +900.00,0.00,900.00,900.00,0.00,900.00 +1000.00,0.00,1000.00,1000.00,0.00,1000.00 +1100.00,0.00,1100.00,1100.00,0.00,1100.00 +1200.00,0.00,1200.00,1200.00,0.00,1200.00 +1300.00,0.00,1300.00,1300.00,0.00,1300.00 +1400.00,0.00,1400.00,1400.00,0.00,1400.00 +1500.00,0.00,1500.00,1500.00,0.00,1500.00 +1600.00,0.00,1600.00,1600.00,0.00,1600.00 +1700.00,0.00,1700.00,1700.00,0.00,1700.00 +1800.00,0.00,1800.00,1800.00,0.00,1800.00 +1900.00,0.00,1900.00,1900.00,0.00,1900.00 +2000.00,0.00,2000.00,2000.00,0.00,2000.00 +2100.00,0.00,2100.00,2100.00,0.00,2100.00 +2200.00,0.00,2200.00,2200.00,0.00,2200.00 +2300.00,0.00,2300.00,2300.00,0.00,2300.00 +2400.00,0.00,2400.00,2400.00,0.00,2400.00 +2500.00,0.00,2500.00,2500.00,0.00,2500.00 +2600.00,450.00,2150.00,2600.00,450.00,2150.00 +2700.00,300.00,2400.00,2700.00,450.00,2250.00 +2800.00,-200.00,3000.00,2800.00,-800.00,3600.00 +2900.00,1050.00,1850.00,2900.00,500.00,2400.00 +3000.00,2400.00,600.00,3000.00,2450.00,550.00 +3100.00,1300.00,1800.00,3100.00,2650.00,450.00 +3200.00,1450.00,1750.00,3200.00,2100.00,1100.00 +3300.00,300.00,3000.00,3300.00,400.00,2900.00 +3400.00,300.00,3100.00,3400.00,700.00,2700.00 +3500.00,1950.00,1550.00,3500.00,2600.00,900.00 +3600.00,3100.00,500.00,3600.00,3300.00,300.00 +3700.00,2700.00,1000.00,3700.00,2400.00,1300.00 +3800.00,2200.00,1600.00,3800.00,1050.00,2750.00 +3900.00,1300.00,2600.00,3900.00,1150.00,2750.00 +4000.00,2850.00,1150.00,4000.00,3200.00,800.00 +4100.00,3800.00,300.00,4100.00,3900.00,200.00 +4200.00,3050.00,1150.00,4200.00,2900.00,1300.00 +4300.00,2500.00,1800.00,4300.00,2600.00,1700.00 +4400.00,2000.00,2400.00,4400.00,3100.00,1300.00 +4500.00,3550.00,950.00,4500.00,3950.00,550.00 +4600.00,4200.00,400.00,4600.00,3650.00,950.00 +4700.00,3550.00,1150.00,4700.00,2900.00,1800.00 +4800.00,3300.00,1500.00,4800.00,2900.00,1900.00 +4900.00,4050.00,850.00,4900.00,3950.00,950.00 +5000.00,4600.00,400.00,5000.00,4650.00,350.00 +5100.00,5000.00,100.00,5100.00,4750.00,350.00 +5200.00,4000.00,1200.00,5200.00,3850.00,1350.00 +5300.00,3750.00,1550.00,5300.00,3350.00,1950.00 +5400.00,4550.00,850.00,5400.00,4350.00,1050.00 +5500.00,5600.00,-100.00,5500.00,5500.00,0.00 +5600.00,5800.00,-200.00,5600.00,5500.00,100.00 +5700.00,4750.00,950.00,5700.00,4500.00,1200.00 +5800.00,4300.00,1500.00,5800.00,4150.00,1650.00 +5900.00,5150.00,750.00,5900.00,4850.00,1050.00 +6000.00,6250.00,-250.00,6000.00,6000.00,0.00 +6100.00,6000.00,100.00,6100.00,6000.00,100.00 +6200.00,5650.00,550.00,6200.00,5450.00,750.00 +6300.00,6100.00,200.00,6300.00,5800.00,500.00 +6400.00,6550.00,-150.00,6400.00,6250.00,150.00 +6500.00,6250.00,250.00,6500.00,6300.00,200.00 +6600.00,6000.00,600.00,6600.00,6800.00,-200.00 +6700.00,6600.00,100.00,6700.00,6800.00,-100.00 +6800.00,6850.00,-50.00,6800.00,6600.00,200.00 +6900.00,7550.00,-650.00,6900.00,7000.00,-100.00 +7000.00,7350.00,-350.00,7000.00,7200.00,-200.00 +7100.00,6600.00,500.00,7100.00,7250.00,-150.00 +7200.00,7300.00,-100.00,7200.00,7450.00,-250.00 +7300.00,7750.00,-450.00,7300.00,7500.00,-200.00 +7400.00,8100.00,-700.00,7400.00,7650.00,-250.00 +7500.00,8300.00,-800.00,7500.00,7750.00,-250.00 +7600.00,8350.00,-750.00,7600.00,7900.00,-300.00 +7700.00,8100.00,-400.00,7700.00,7700.00,0.00 +7800.00,8500.00,-700.00,7800.00,8200.00,-400.00 +7900.00,8800.00,-900.00,7900.00,8200.00,-300.00 +8000.00,8850.00,-850.00,8000.00,8200.00,-200.00 +8100.00,8950.00,-850.00,8100.00,8150.00,-50.00 +8200.00,9000.00,-800.00,8200.00,8150.00,50.00 +8300.00,9150.00,-850.00,8300.00,8300.00,0.00 +8400.00,11100.00,-2700.00,8400.00,10100.00,-1700.00 +8500.00,8900.00,-400.00,8500.00,8050.00,450.00 +8600.00,7850.00,750.00,8600.00,7050.00,1550.00 +8700.00,9000.00,-300.00,8700.00,8050.00,650.00 +8800.00,9650.00,-850.00,8800.00,9250.00,-450.00 +8900.00,10050.00,-1150.00,8900.00,9750.00,-850.00 +9000.00,10300.00,-1300.00,9000.00,9700.00,-700.00 +9100.00,10350.00,-1250.00,9100.00,9650.00,-550.00 +9200.00,10150.00,-950.00,9200.00,9600.00,-400.00 +9300.00,10250.00,-950.00,9300.00,9800.00,-500.00 +9400.00,10500.00,-1100.00,9400.00,10000.00,-600.00 +9500.00,10650.00,-1150.00,9500.00,10250.00,-750.00 +9600.00,10800.00,-1200.00,9600.00,10450.00,-850.00 +9700.00,10800.00,-1100.00,9700.00,10500.00,-800.00 +9800.00,10900.00,-1100.00,9800.00,10600.00,-800.00 +9900.00,11050.00,-1150.00,9900.00,10750.00,-850.00 +10000.00,11200.00,-1200.00,10000.00,10750.00,-750.00 +10100.00,11200.00,-1100.00,10100.00,10900.00,-800.00 +10200.00,11250.00,-1050.00,10200.00,11100.00,-900.00 +10300.00,11500.00,-1200.00,10300.00,11200.00,-900.00 +10400.00,11650.00,-1250.00,10400.00,11500.00,-1100.00 +10500.00,11650.00,-1150.00,10500.00,11750.00,-1250.00 +10600.00,11800.00,-1200.00,10600.00,11850.00,-1250.00 +10700.00,11900.00,-1200.00,10700.00,11900.00,-1200.00 +10800.00,12150.00,-1350.00,10800.00,12100.00,-1300.00 +10900.00,12350.00,-1450.00,10900.00,12200.00,-1300.00 +11000.00,12350.00,-1350.00,11000.00,12200.00,-1200.00 +11100.00,12350.00,-1250.00,11100.00,12450.00,-1350.00 +11200.00,12500.00,-1300.00,11200.00,12650.00,-1450.00 +11300.00,12750.00,-1450.00,11300.00,12750.00,-1450.00 +11400.00,12850.00,-1450.00,11400.00,12750.00,-1350.00 +11500.00,12950.00,-1450.00,11500.00,12800.00,-1300.00 +11600.00,13050.00,-1450.00,11600.00,12950.00,-1350.00 +11700.00,13200.00,-1500.00,11700.00,13050.00,-1350.00 +11800.00,13300.00,-1500.00,11800.00,13000.00,-1200.00 +11900.00,13550.00,-1650.00,11900.00,13400.00,-1500.00 +12000.00,13750.00,-1750.00,12000.00,13600.00,-1600.00 +12100.00,13750.00,-1650.00,12100.00,13750.00,-1650.00 +12200.00,13800.00,-1600.00,12200.00,13750.00,-1550.00 +12300.00,14000.00,-1700.00,12300.00,13900.00,-1600.00 +12400.00,14150.00,-1750.00,12400.00,14000.00,-1600.00 +12500.00,14200.00,-1700.00,12500.00,14050.00,-1550.00 +12600.00,14450.00,-1850.00,12600.00,14150.00,-1550.00 +12700.00,14600.00,-1900.00,12700.00,14400.00,-1700.00 +12800.00,14750.00,-1950.00,12800.00,14400.00,-1600.00 +12900.00,14850.00,-1950.00,12900.00,14600.00,-1700.00 +13000.00,14950.00,-1950.00,13000.00,14800.00,-1800.00 +13100.00,15150.00,-2050.00,13100.00,14600.00,-1500.00 +13200.00,15250.00,-2050.00,13200.00,14750.00,-1550.00 +13300.00,15250.00,-1950.00,13300.00,14750.00,-1450.00 +13400.00,15450.00,-2050.00,13400.00,14900.00,-1500.00 +13500.00,15600.00,-2100.00,13500.00,15000.00,-1500.00 +13600.00,15550.00,-1950.00,13600.00,15150.00,-1550.00 +13700.00,15800.00,-2100.00,13700.00,15300.00,-1600.00 +13800.00,15800.00,-2000.00,13800.00,15450.00,-1650.00 +13900.00,15700.00,-1800.00,13900.00,15600.00,-1700.00 +14000.00,16150.00,-2150.00,14000.00,15800.00,-1800.00 +14100.00,16350.00,-2250.00,14100.00,16000.00,-1900.00 +14200.00,16350.00,-2150.00,14200.00,16000.00,-1800.00 +14300.00,16350.00,-2050.00,14300.00,16050.00,-1750.00 +14400.00,16350.00,-1950.00,14400.00,16150.00,-1750.00 +14500.00,16650.00,-2150.00,14500.00,16150.00,-1650.00 +14600.00,16750.00,-2150.00,14600.00,16350.00,-1750.00 +14700.00,16850.00,-2150.00,14700.00,16800.00,-2100.00 +14800.00,17000.00,-2200.00,14800.00,17100.00,-2300.00 +14900.00,16500.00,-1600.00,14900.00,16550.00,-1650.00 +15000.00,17250.00,-2250.00,15000.00,17500.00,-2500.00 +15100.00,17350.00,-2250.00,15100.00,17700.00,-2600.00 +15200.00,17600.00,-2400.00,15200.00,17750.00,-2550.00 +15300.00,17650.00,-2350.00,15300.00,17600.00,-2300.00 +15400.00,17650.00,-2250.00,15400.00,17450.00,-2050.00 +15500.00,17750.00,-2250.00,15500.00,17600.00,-2100.00 +15600.00,17800.00,-2200.00,15600.00,17800.00,-2200.00 +15700.00,17600.00,-1900.00,15700.00,17950.00,-2250.00 +15800.00,18300.00,-2500.00,15800.00,18200.00,-2400.00 +15900.00,18500.00,-2600.00,15900.00,18200.00,-2300.00 +16000.00,18350.00,-2350.00,16000.00,18300.00,-2300.00 +16100.00,22200.00,-6100.00,16100.00,22100.00,-6000.00 +16200.00,18200.00,-2000.00,16200.00,18200.00,-2000.00 +16300.00,17450.00,-1150.00,16300.00,17350.00,-1050.00 +16400.00,17950.00,-1550.00,16400.00,17900.00,-1500.00 +16500.00,18900.00,-2400.00,16500.00,18950.00,-2450.00 +16600.00,19450.00,-2850.00,16600.00,19600.00,-3000.00 +16700.00,19700.00,-3000.00,16700.00,19400.00,-2700.00 +16800.00,19750.00,-2950.00,16800.00,19150.00,-2350.00 +16900.00,19800.00,-2900.00,16900.00,19100.00,-2200.00 +17000.00,19850.00,-2850.00,17000.00,19150.00,-2150.00 +17100.00,19550.00,-2450.00,17100.00,19300.00,-2200.00 +17200.00,19950.00,-2750.00,17200.00,19300.00,-2100.00 +17300.00,20200.00,-2900.00,17300.00,19800.00,-2500.00 +17400.00,20100.00,-2700.00,17400.00,20200.00,-2800.00 +17500.00,20300.00,-2800.00,17500.00,20000.00,-2500.00 +17600.00,20500.00,-2900.00,17600.00,20250.00,-2650.00 +17700.00,20450.00,-2750.00,17700.00,20400.00,-2700.00 +17800.00,19650.00,-1850.00,17800.00,19650.00,-1850.00 +17900.00,20650.00,-2750.00,17741.55,20550.00,-2808.45 +18000.00,20700.00,-2700.00,17641.55,21150.00,-3508.45 +18100.00,21300.00,-3200.00,17541.55,21100.00,-3558.45 +18060.72,21250.00,-3189.28,17441.55,20900.00,-3458.45 +17960.72,21300.00,-3339.28,17341.55,20600.00,-3258.45 +17860.72,21100.00,-3239.28,17241.55,20450.00,-3208.45 +17760.72,20900.00,-3139.28,17141.55,20150.00,-3008.45 +17660.72,20700.00,-3039.28,17041.55,20000.00,-2958.45 +17560.72,20650.00,-3089.28,16941.55,19800.00,-2858.45 +17460.72,20450.00,-2989.28,16841.55,19700.00,-2858.45 +17360.72,20550.00,-3189.28,16741.55,19700.00,-2958.45 +17260.72,20450.00,-3189.28,16641.55,19600.00,-2958.45 +17160.72,20300.00,-3139.28,16541.55,19400.00,-2858.45 +17060.72,20200.00,-3139.28,16441.55,19350.00,-2908.45 +16960.72,20050.00,-3089.28,16341.55,19300.00,-2958.45 +16860.72,19950.00,-3089.28,16241.55,19250.00,-3008.45 +16760.72,19650.00,-2889.28,16141.55,19000.00,-2858.45 +16660.72,19800.00,-3139.28,16041.55,18850.00,-2808.45 +16560.72,19750.00,-3189.28,15941.55,18550.00,-2608.45 +16460.72,19700.00,-3239.28,15841.55,18100.00,-2258.45 +16360.72,19300.00,-2939.28,15741.55,18050.00,-2308.45 +16260.72,18600.00,-2339.28,15641.55,17300.00,-1658.45 +16160.72,19350.00,-3189.28,15541.55,18000.00,-2458.45 +16060.72,19200.00,-3139.28,15441.55,18150.00,-2708.45 +15960.72,18900.00,-2939.28,15341.55,17900.00,-2558.45 +15860.72,18550.00,-2689.28,15241.55,17750.00,-2508.45 +15760.72,18450.00,-2689.28,15141.55,17350.00,-2208.45 +15660.72,17700.00,-2039.28,15041.55,16850.00,-1808.45 +15560.72,18400.00,-2839.28,14941.55,17550.00,-2608.45 +15460.72,17800.00,-2339.28,14841.55,16850.00,-2008.45 +15360.72,18250.00,-2889.28,14741.55,17250.00,-2508.45 +15260.72,17450.00,-2189.28,14641.55,16500.00,-1858.45 +15160.72,18100.00,-2939.28,14541.55,17200.00,-2658.45 +15060.72,17950.00,-2889.28,14441.55,17100.00,-2658.45 +14960.72,17650.00,-2689.28,14341.55,16950.00,-2608.45 +14860.72,17400.00,-2539.28,14241.55,16850.00,-2608.45 +14760.72,17200.00,-2439.28,14141.55,16550.00,-2408.45 +14660.72,16400.00,-1739.28,14041.55,15850.00,-1808.45 +14560.72,16400.00,-1839.28,13941.55,16000.00,-2058.45 +14460.72,17100.00,-2639.28,13841.55,16800.00,-2958.45 +14360.72,17200.00,-2839.28,13741.55,16500.00,-2758.45 +14260.72,17150.00,-2889.28,13641.55,16050.00,-2408.45 +14160.72,16550.00,-2389.28,13541.55,15650.00,-2108.45 +14060.72,16350.00,-2289.28,13441.55,15600.00,-2158.45 +13960.72,15650.00,-1689.28,13341.55,15000.00,-1658.45 +13860.72,16400.00,-2539.28,13241.55,15500.00,-2258.45 +13760.72,16300.00,-2539.28,13141.55,15500.00,-2358.45 +13660.72,16350.00,-2689.28,13041.55,15550.00,-2508.45 +13560.72,15450.00,-1889.28,12941.55,14600.00,-1658.45 +13460.72,15350.00,-1889.28,12841.55,14400.00,-1558.45 +13360.72,16100.00,-2739.28,12741.55,15050.00,-2308.45 +13260.72,16000.00,-2739.28,12641.55,15050.00,-2408.45 +13160.72,15550.00,-2389.28,12541.55,14750.00,-2208.45 +13060.72,15250.00,-2189.28,12441.55,14200.00,-1758.45 +12960.72,15200.00,-2239.28,12341.55,14200.00,-1858.45 +12860.72,15250.00,-2389.28,12241.55,13950.00,-1708.45 +12760.72,15050.00,-2289.28,12141.55,13650.00,-1508.45 +12660.72,14700.00,-2039.28,12041.55,13400.00,-1358.45 +12560.72,14000.00,-1439.28,11941.55,12800.00,-858.45 +12460.72,14650.00,-2189.28,11841.55,13200.00,-1358.45 +12360.72,17700.00,-5339.28,11741.55,16000.00,-4258.45 +12260.72,13650.00,-1389.28,11641.55,12500.00,-858.45 +12160.72,11500.00,660.72,11541.55,10300.00,1241.55 +12060.72,12200.00,-139.28,11441.55,11400.00,41.55 +11960.72,14000.00,-2039.28,11341.55,13150.00,-1808.45 +11860.72,14550.00,-2689.28,11241.55,13550.00,-2308.45 +11760.72,14150.00,-2389.28,11141.55,13400.00,-2258.45 +11660.72,13800.00,-2139.28,11041.55,12850.00,-1808.45 +11560.72,13500.00,-1939.28,10941.55,12450.00,-1508.45 +11460.72,13200.00,-1739.28,10841.55,12200.00,-1358.45 +11360.72,13150.00,-1789.28,10741.55,12150.00,-1408.45 +11260.72,13150.00,-1889.28,10641.55,12000.00,-1358.45 +11160.72,13000.00,-1839.28,10541.55,11900.00,-1358.45 +11060.72,12900.00,-1839.28,10441.55,11950.00,-1508.45 +10960.72,12800.00,-1839.28,10341.55,12000.00,-1658.45 +10860.72,12650.00,-1789.28,10241.55,11850.00,-1608.45 +10760.72,12500.00,-1739.28,10141.55,11700.00,-1558.45 +10660.72,12400.00,-1739.28,10041.55,11650.00,-1608.45 +10560.72,12250.00,-1689.28,9941.55,11400.00,-1458.45 +10460.72,12100.00,-1639.28,9841.55,11400.00,-1558.45 +10360.72,12050.00,-1689.28,9741.55,11200.00,-1458.45 +10260.72,11900.00,-1639.28,9641.55,11250.00,-1608.45 +10160.72,11800.00,-1639.28,9541.55,11150.00,-1608.45 +10060.72,11250.00,-1189.28,9441.55,10600.00,-1158.45 +9960.72,11600.00,-1639.28,9341.55,10900.00,-1558.45 +9860.72,11650.00,-1789.28,9241.55,10850.00,-1608.45 +9760.72,11450.00,-1689.28,9141.55,10750.00,-1608.45 +9660.72,11300.00,-1639.28,9041.55,10450.00,-1408.45 +9560.72,11150.00,-1589.28,8941.55,10250.00,-1308.45 +9460.72,11000.00,-1539.28,8841.55,10000.00,-1158.45 +9360.72,10900.00,-1539.28,8741.55,10000.00,-1258.45 +9260.72,10900.00,-1639.28,8641.55,9900.00,-1258.45 +9160.72,10750.00,-1589.28,8541.55,9800.00,-1258.45 +9060.72,10550.00,-1489.28,8441.55,9600.00,-1158.45 +8960.72,10450.00,-1489.28,8341.55,9400.00,-1058.45 +8860.72,9900.00,-1039.28,8241.55,9000.00,-758.45 +8760.72,10250.00,-1489.28,8141.55,9300.00,-1158.45 +8660.72,10250.00,-1589.28,8041.55,9300.00,-1258.45 +8560.72,9700.00,-1139.28,7941.55,8700.00,-758.45 +8460.72,8500.00,-39.28,7841.55,7700.00,141.55 +8360.72,8800.00,-439.28,7741.55,7600.00,141.55 +8260.72,9050.00,-789.28,7641.55,8000.00,-358.45 +8160.72,9700.00,-1539.28,7541.55,8700.00,-1158.45 +8060.72,9300.00,-1239.28,7441.55,8400.00,-958.45 +7960.72,7450.00,510.72,7341.55,6750.00,591.55 +7860.72,7200.00,660.72,7241.55,6300.00,941.55 +7760.72,8250.00,-489.28,7141.55,7450.00,-308.45 +7660.72,9000.00,-1339.28,7041.55,7900.00,-858.45 +7560.72,8300.00,-739.28,6941.55,7400.00,-458.45 +7460.72,7350.00,110.72,6841.55,6200.00,641.55 +7360.72,8350.00,-989.28,6741.55,5950.00,791.55 +7260.72,7850.00,-589.28,6641.55,6150.00,491.55 +7160.72,7150.00,10.72,6541.55,7000.00,-458.45 +7060.72,7750.00,-689.28,6441.55,6850.00,-408.45 +6960.72,7600.00,-639.28,6341.55,5600.00,741.55 +6860.72,6050.00,810.72,6241.55,4650.00,1591.55 +6760.72,6000.00,760.72,6141.55,5500.00,641.55 +6660.72,6850.00,-189.28,6041.55,6150.00,-108.45 +6560.72,7400.00,-839.28,5941.55,5900.00,41.55 +6460.72,7600.00,-1139.28,5841.55,5000.00,841.55 +6360.72,6250.00,110.72,5741.55,4200.00,1541.55 +6260.72,5600.00,660.72,5641.55,4750.00,891.55 +6160.72,6300.00,-139.28,5541.55,5300.00,241.55 +6060.72,6350.00,-289.28,5441.55,5550.00,-108.45 +5960.72,5450.00,510.72,5341.55,4350.00,991.55 +5860.72,5250.00,610.72,5241.55,3750.00,1491.55 +5760.72,5550.00,210.72,5141.55,4350.00,791.55 +5660.72,5500.00,160.72,5041.55,4800.00,241.55 +5560.72,4900.00,660.72,4941.55,4850.00,91.55 +5460.72,4250.00,1210.72,4841.55,3800.00,1041.55 +5360.72,5150.00,210.72,4741.55,3200.00,1541.55 +5260.72,5100.00,160.72,4641.55,3700.00,941.55 +5160.72,4650.00,510.72,4541.55,4150.00,391.55 +5060.72,3750.00,1310.72,4441.55,3200.00,1241.55 +4960.72,3750.00,1210.72,4341.55,2700.00,1641.55 +4860.72,4350.00,510.72,4241.55,3400.00,841.55 +4760.72,4550.00,210.72,4141.55,3700.00,441.55 +4660.72,3950.00,710.72,4041.55,2900.00,1141.55 +4560.72,3900.00,660.72,3941.55,1750.00,2191.55 +4460.72,2400.00,2060.72,3841.55,1950.00,1891.55 +4360.72,2350.00,2010.72,3741.55,3100.00,641.55 +4260.72,3850.00,410.72,3641.55,3300.00,341.55 +4160.72,4600.00,-439.28,3541.55,2650.00,891.55 +4060.72,3650.00,410.72,3441.55,1600.00,1841.55 +3960.72,3150.00,810.72,3341.55,1200.00,2141.55 +3860.72,2450.00,1410.72,3241.55,2450.00,791.55 +3760.72,1450.00,2310.72,3141.55,3000.00,141.55 +3660.72,1450.00,2210.72,3041.55,2000.00,1041.55 +3560.72,3100.00,460.72,2941.55,1200.00,1741.55 +3460.72,3800.00,-339.28,2841.55,-50.00,2891.55 +3360.72,3050.00,310.72,2741.55,300.00,2441.55 +3260.72,2450.00,810.72,2641.55,2550.00,91.55 +3160.72,2050.00,1110.72,2541.55,3000.00,-458.45 +3060.72,300.00,2760.72,2441.55,1800.00,641.55 +2960.72,-150.00,3110.72,2341.55,1600.00,741.55 +2860.72,1750.00,1110.72,2241.55,150.00,2091.55 +2760.72,3100.00,-339.28,2141.55,-650.00,2791.55 +2660.72,2450.00,210.72,2041.55,500.00,1541.55 +2560.72,1950.00,610.72,1941.55,1000.00,941.55 +2460.72,1000.00,1460.72,1841.55,-300.00,2141.55 +2360.72,-450.00,2810.72,1741.55,-1000.00,2741.55 +2260.72,-450.00,2710.72,1641.55,-400.00,2041.55 +2160.72,1150.00,1010.72,1541.55,350.00,1191.55 +2060.72,1700.00,360.72,1441.55,50.00,1391.55 +1960.72,1150.00,810.72,1341.55,0.00,1341.55 +1860.72,-450.00,2310.72,1241.55,0.00,1241.55 +1760.72,-850.00,2610.72,1141.55,0.00,1141.55 +1660.72,250.00,1410.72,1041.55,0.00,1041.55 +1560.72,150.00,1410.72,941.55,0.00,941.55 +1460.72,0.00,1460.72,841.55,0.00,841.55 +1360.72,0.00,1360.72,741.55,0.00,741.55 +1260.72,0.00,1260.72,641.55,0.00,641.55 +1160.72,0.00,1160.72,541.55,0.00,541.55 +1060.72,0.00,1060.72,441.55,0.00,441.55 +960.72,0.00,960.72,341.55,0.00,341.55 +860.72,0.00,860.72,241.55,0.00,241.55 +760.72,0.00,760.72,141.55,0.00,141.55 +660.72,0.00,660.72,41.55,0.00,41.55 +560.72,0.00,560.72,0.00,0.00,0.00 +460.72,0.00,460.72,0.00,0.00,0.00 +360.72,0.00,360.72,0.00,0.00,0.00 +260.72,0.00,260.72,0.00,0.00,0.00 +160.72,0.00,160.72,0.00,0.00,0.00 +60.72,0.00,60.72,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +100.00,0.00,100.00,100.00,0.00,100.00 +200.00,0.00,200.00,200.00,0.00,200.00 +300.00,0.00,300.00,300.00,0.00,300.00 +400.00,0.00,400.00,400.00,0.00,400.00 +500.00,0.00,500.00,500.00,0.00,500.00 +600.00,0.00,600.00,600.00,0.00,600.00 +700.00,0.00,700.00,700.00,0.00,700.00 +800.00,0.00,800.00,800.00,0.00,800.00 +900.00,0.00,900.00,900.00,0.00,900.00 +1000.00,0.00,1000.00,1000.00,0.00,1000.00 +1100.00,0.00,1100.00,1100.00,0.00,1100.00 +1200.00,0.00,1200.00,1200.00,0.00,1200.00 +1300.00,0.00,1300.00,1300.00,0.00,1300.00 +1400.00,0.00,1400.00,1400.00,0.00,1400.00 +1500.00,0.00,1500.00,1500.00,0.00,1500.00 +1600.00,0.00,1600.00,1600.00,0.00,1600.00 +1700.00,0.00,1700.00,1700.00,0.00,1700.00 +1800.00,0.00,1800.00,1800.00,0.00,1800.00 +1900.00,0.00,1900.00,1900.00,0.00,1900.00 +2000.00,0.00,2000.00,2000.00,0.00,2000.00 +2100.00,0.00,2100.00,2100.00,0.00,2100.00 +2200.00,0.00,2200.00,2200.00,0.00,2200.00 +2300.00,0.00,2300.00,2300.00,0.00,2300.00 +2400.00,0.00,2400.00,2400.00,0.00,2400.00 +2500.00,400.00,2100.00,2500.00,350.00,2150.00 +2600.00,500.00,2100.00,2600.00,200.00,2400.00 +2700.00,-850.00,3550.00,2700.00,-150.00,2850.00 +2800.00,550.00,2250.00,2800.00,900.00,1900.00 +2900.00,2950.00,-50.00,2900.00,1950.00,950.00 +3000.00,2950.00,50.00,3000.00,550.00,2450.00 +3100.00,2200.00,900.00,3100.00,-200.00,3300.00 +3200.00,2100.00,1100.00,3200.00,1200.00,2000.00 +3300.00,850.00,2450.00,3300.00,2800.00,500.00 +3400.00,1750.00,1650.00,3400.00,2900.00,500.00 +3500.00,2100.00,1400.00,3500.00,1450.00,2050.00 +3600.00,1950.00,1650.00,3600.00,1500.00,2100.00 +3700.00,1400.00,2300.00,3700.00,2350.00,1350.00 +3800.00,2900.00,900.00,3800.00,2600.00,1200.00 +3900.00,3600.00,300.00,3900.00,1900.00,2000.00 +4000.00,2850.00,1150.00,4000.00,600.00,3400.00 +4100.00,2350.00,1750.00,4100.00,2300.00,1800.00 +4200.00,2200.00,2000.00,4200.00,4500.00,-300.00 +4300.00,3200.00,1100.00,4300.00,4200.00,100.00 +4400.00,4500.00,-100.00,4400.00,3050.00,1350.00 +4500.00,4550.00,-50.00,4500.00,2400.00,2100.00 +4600.00,3850.00,750.00,4600.00,2950.00,1650.00 +4700.00,3300.00,1400.00,4700.00,3900.00,800.00 +4800.00,3200.00,1600.00,4800.00,3900.00,900.00 +4900.00,4000.00,900.00,4900.00,2900.00,2000.00 +5000.00,4900.00,100.00,5000.00,2450.00,2550.00 +5100.00,5300.00,-200.00,5100.00,4050.00,1050.00 +5200.00,4450.00,750.00,5200.00,5600.00,-400.00 +5300.00,3800.00,1500.00,5300.00,5050.00,250.00 +5400.00,4900.00,500.00,5400.00,4000.00,1400.00 +5500.00,4900.00,600.00,5500.00,3300.00,2200.00 +5600.00,4600.00,1000.00,5600.00,4200.00,1400.00 +5700.00,5950.00,-250.00,5700.00,4150.00,1550.00 +5800.00,5600.00,200.00,5800.00,6600.00,-800.00 +5900.00,4400.00,1500.00,5900.00,6350.00,-450.00 +6000.00,4700.00,1300.00,6000.00,5200.00,800.00 +6100.00,5200.00,900.00,6100.00,4400.00,1700.00 +6200.00,6400.00,-200.00,6200.00,5100.00,1100.00 +6300.00,7100.00,-800.00,6300.00,5550.00,750.00 +6400.00,5650.00,750.00,6400.00,6800.00,-400.00 +6500.00,5550.00,950.00,6500.00,6750.00,-250.00 +6600.00,6100.00,500.00,6600.00,5550.00,1050.00 +6700.00,7000.00,-300.00,6700.00,5000.00,1700.00 +6800.00,6800.00,0.00,6800.00,5550.00,1250.00 +6900.00,6550.00,350.00,6900.00,7050.00,-150.00 +7000.00,7400.00,-400.00,7000.00,8200.00,-1200.00 +7100.00,7400.00,-300.00,7100.00,7450.00,-350.00 +7200.00,7850.00,-650.00,7200.00,6650.00,550.00 +7300.00,7550.00,-250.00,7300.00,6800.00,500.00 +7400.00,6600.00,800.00,7400.00,7000.00,400.00 +7500.00,7100.00,400.00,7500.00,7600.00,-100.00 +7600.00,8450.00,-850.00,7600.00,7400.00,200.00 +7700.00,8850.00,-1150.00,7700.00,8600.00,-900.00 +7800.00,8400.00,-600.00,7800.00,8700.00,-900.00 +7900.00,7450.00,450.00,7900.00,8800.00,-900.00 +8000.00,8100.00,-100.00,8000.00,8300.00,-300.00 +8100.00,8300.00,-200.00,8100.00,7000.00,1100.00 +8200.00,9350.00,-1150.00,8200.00,9300.00,-1100.00 +8300.00,9250.00,-950.00,8300.00,9200.00,-900.00 +8400.00,11300.00,-2900.00,8400.00,11600.00,-3200.00 +8500.00,9000.00,-500.00,8500.00,9150.00,-650.00 +8600.00,7800.00,800.00,8600.00,7850.00,750.00 +8700.00,8000.00,700.00,8700.00,8300.00,400.00 +8800.00,10000.00,-1200.00,8800.00,8650.00,150.00 +8900.00,10650.00,-1750.00,8900.00,9450.00,-550.00 +9000.00,9950.00,-950.00,9000.00,10600.00,-1600.00 +9100.00,8900.00,200.00,9100.00,10700.00,-1600.00 +9200.00,8900.00,300.00,9200.00,10050.00,-850.00 +9300.00,10150.00,-850.00,9300.00,9300.00,0.00 +9400.00,10300.00,-900.00,9400.00,10350.00,-950.00 +9500.00,11150.00,-1650.00,9500.00,10650.00,-1150.00 +9600.00,11200.00,-1600.00,9600.00,9450.00,150.00 +9700.00,11200.00,-1500.00,9700.00,10700.00,-1000.00 +9800.00,11800.00,-2000.00,9800.00,11350.00,-1550.00 +9900.00,11250.00,-1350.00,9900.00,11150.00,-1250.00 +10000.00,10800.00,-800.00,10000.00,10550.00,-550.00 +10100.00,11150.00,-1050.00,10100.00,10650.00,-550.00 +10200.00,11500.00,-1300.00,10200.00,11300.00,-1100.00 +10300.00,12000.00,-1700.00,10300.00,10200.00,100.00 +10296.86,11750.00,-1453.14,10400.00,11100.00,-700.00 +10196.86,11800.00,-1603.14,10500.00,11600.00,-1100.00 +10096.86,11650.00,-1553.14,10600.00,11600.00,-1000.00 +9996.86,12050.00,-2053.14,10700.00,12800.00,-2100.00 +9896.86,11900.00,-2003.14,10800.00,12500.00,-1700.00 +9796.86,11350.00,-1553.14,10900.00,12100.00,-1200.00 +9696.86,11150.00,-1453.14,11000.00,11300.00,-300.00 +9596.86,11450.00,-1853.14,11100.00,12100.00,-1000.00 +9496.86,11950.00,-2453.14,11200.00,13050.00,-1850.00 +9396.86,10700.00,-1303.14,11300.00,12650.00,-1350.00 +9296.86,9000.00,296.86,11400.00,11700.00,-300.00 +9196.86,9700.00,-503.14,11500.00,10700.00,800.00 +9096.86,10350.00,-1253.14,11600.00,10900.00,700.00 +8996.86,11600.00,-2603.14,11700.00,13600.00,-1900.00 +8896.86,10800.00,-1903.14,11800.00,15000.00,-3200.00 +8796.86,8200.00,596.86,11900.00,13600.00,-1700.00 +8696.86,7700.00,996.86,12000.00,12800.00,-800.00 +8596.86,9000.00,-403.14,12100.00,11150.00,950.00 +8496.86,10650.00,-2153.14,12200.00,13350.00,-1150.00 +8396.86,10450.00,-2053.14,12300.00,15000.00,-2700.00 +8296.86,8300.00,-3.14,12400.00,15250.00,-2850.00 +8196.86,7350.00,846.86,12500.00,14050.00,-1550.00 +8096.86,7850.00,246.86,12600.00,13200.00,-600.00 +7996.86,9400.00,-1403.14,12700.00,13000.00,-300.00 +7896.86,9400.00,-1503.14,12800.00,15700.00,-2900.00 +7796.86,7750.00,46.86,12900.00,15450.00,-2550.00 +7696.86,6900.00,796.86,13000.00,14650.00,-1650.00 +7596.86,7250.00,346.86,13100.00,14700.00,-1600.00 +7496.86,8500.00,-1003.14,13200.00,14650.00,-1450.00 +7396.86,9150.00,-1753.14,13300.00,16050.00,-2750.00 +7296.86,7300.00,-3.14,13400.00,15950.00,-2550.00 +7196.86,6400.00,796.86,13500.00,15250.00,-1750.00 +7096.86,6750.00,346.86,13600.00,14950.00,-1350.00 +6996.86,8000.00,-1003.14,13700.00,15650.00,-1950.00 +6896.86,8400.00,-1503.14,13800.00,14900.00,-1100.00 +6796.86,6550.00,246.86,13900.00,15700.00,-1800.00 +6696.86,6150.00,546.86,14000.00,16550.00,-2550.00 +6596.86,6800.00,-203.14,14100.00,16200.00,-2100.00 +6496.86,7500.00,-1003.14,14200.00,16350.00,-2150.00 +6396.86,7100.00,-703.14,14300.00,15550.00,-1250.00 +6296.86,5800.00,496.86,14400.00,16000.00,-1600.00 +6196.86,5500.00,696.86,14500.00,16850.00,-2350.00 +6096.86,6450.00,-353.14,14600.00,16700.00,-2100.00 +5996.86,6500.00,-503.14,14700.00,16800.00,-2100.00 +5896.86,5550.00,346.86,14740.48,17400.00,-2659.52 +5796.86,5100.00,696.86,14640.48,16950.00,-2309.52 +5696.86,5450.00,246.86,14540.48,16700.00,-2159.52 +5596.86,5900.00,-303.14,14440.48,17150.00,-2709.52 +5496.86,4750.00,746.86,14340.48,16200.00,-1859.52 +5396.86,4500.00,896.86,14240.48,15950.00,-1709.52 +5296.86,5000.00,296.86,14140.48,15950.00,-1809.52 +5196.86,5250.00,-53.14,14040.48,15900.00,-1859.52 +5096.86,4450.00,646.86,13940.48,15800.00,-1859.52 +4996.86,3650.00,1346.86,13840.48,15900.00,-2059.52 +4896.86,4050.00,846.86,13740.48,18850.00,-5109.52 +4796.86,4100.00,696.86,13640.48,15200.00,-1559.52 +4696.86,3250.00,1446.86,13540.48,12350.00,1190.48 +4596.86,3450.00,1146.86,13440.48,12300.00,1140.48 +4496.86,4850.00,-353.14,13340.48,15400.00,-2059.52 +4396.86,5150.00,-753.14,13240.48,19650.00,-6409.52 +4296.86,3950.00,346.86,13140.48,16550.00,-3409.52 +4196.86,2950.00,1246.86,13040.48,13200.00,-159.52 +4096.86,2150.00,1946.86,12940.48,13100.00,-159.52 +3996.86,2450.00,1546.86,12840.48,14700.00,-1859.52 +3896.86,4000.00,-103.14,12740.48,16500.00,-3759.52 +3796.86,4100.00,-303.14,12640.48,15250.00,-2609.52 +3696.86,3250.00,446.86,12540.48,14050.00,-1509.52 +3596.86,2700.00,896.86,12440.48,14000.00,-1559.52 +3496.86,1900.00,1596.86,12340.48,14250.00,-1909.52 +3396.86,1200.00,2196.86,12240.48,14300.00,-2059.52 +3296.86,400.00,2896.86,12140.48,14200.00,-2059.52 +3196.86,2800.00,396.86,12040.48,14950.00,-2909.52 +3096.86,3750.00,-653.14,11940.48,14150.00,-2209.52 +2996.86,3200.00,-203.14,11840.48,13250.00,-1409.52 +2896.86,2700.00,196.86,11740.48,13150.00,-1409.52 +2796.86,1800.00,996.86,11640.48,13350.00,-1709.52 +2696.86,1450.00,1246.86,11540.48,13900.00,-2359.52 +2596.86,-300.00,2896.86,11440.48,13100.00,-1659.52 +2496.86,-200.00,2696.86,11340.48,13100.00,-1759.52 +2396.86,1400.00,996.86,11240.48,13350.00,-2109.52 +2296.86,2650.00,-353.14,11140.48,13150.00,-2009.52 +2196.86,1650.00,546.86,11040.48,12000.00,-959.52 +2096.86,1450.00,646.86,10940.48,12300.00,-1359.52 +1996.86,-200.00,2196.86,10840.48,12500.00,-1659.52 +1896.86,-1000.00,2896.86,10740.48,12500.00,-1759.52 +1796.86,400.00,1396.86,10640.48,11850.00,-1209.52 +1696.86,900.00,796.86,10540.48,12200.00,-1659.52 +1596.86,-200.00,1796.86,10440.48,11550.00,-1109.52 +1496.86,-900.00,2396.86,10340.48,11900.00,-1559.52 +1396.86,-300.00,1696.86,10240.48,11800.00,-1559.52 +1296.86,250.00,1046.86,10140.48,10900.00,-759.52 +1196.86,0.00,1196.86,10040.48,11200.00,-1159.52 +1096.86,0.00,1096.86,9940.48,10700.00,-759.52 +996.86,0.00,996.86,9840.48,10650.00,-809.52 +896.86,0.00,896.86,9740.48,11150.00,-1409.52 +796.86,0.00,796.86,9640.48,10750.00,-1109.52 +696.86,0.00,696.86,9540.48,10600.00,-1059.52 +596.86,0.00,596.86,9440.48,10850.00,-1409.52 +496.86,0.00,496.86,9340.48,10400.00,-1059.52 +396.86,0.00,396.86,9240.48,10200.00,-959.52 +296.86,0.00,296.86,9140.48,10200.00,-1059.52 +196.86,0.00,196.86,9040.48,10150.00,-1109.52 +96.86,0.00,96.86,8940.48,9950.00,-1009.52 +0.00,0.00,0.00,8840.48,10200.00,-1359.52 +0.00,0.00,0.00,8740.48,9500.00,-759.52 +0.00,0.00,0.00,8640.48,9300.00,-659.52 +0.00,0.00,0.00,8540.48,9150.00,-609.52 +0.00,0.00,0.00,8440.48,9050.00,-609.52 +0.00,0.00,0.00,8340.48,8950.00,-609.52 +0.00,0.00,0.00,8240.48,8750.00,-509.52 +0.00,0.00,0.00,8140.48,9000.00,-859.52 +0.00,0.00,0.00,8040.48,8900.00,-859.52 +0.00,0.00,0.00,7940.48,8700.00,-759.52 +0.00,0.00,0.00,7840.48,8500.00,-659.52 +0.00,0.00,0.00,7740.48,8400.00,-659.52 +0.00,0.00,0.00,7640.48,8300.00,-659.52 +0.00,0.00,0.00,7540.48,8200.00,-659.52 +0.00,0.00,0.00,7440.48,7800.00,-359.52 +0.00,0.00,0.00,7340.48,6950.00,390.48 +0.00,0.00,0.00,7240.48,7050.00,190.48 +0.00,0.00,0.00,7140.48,7200.00,-59.52 +0.00,0.00,0.00,7040.48,7800.00,-759.52 +0.00,0.00,0.00,6940.48,7600.00,-659.52 +0.00,0.00,0.00,6840.48,6350.00,490.48 +0.00,0.00,0.00,6740.48,5650.00,1090.48 +0.00,0.00,0.00,6640.48,6550.00,90.48 +0.00,0.00,0.00,6540.48,7250.00,-709.52 +0.00,0.00,0.00,6440.48,7000.00,-559.52 +0.00,0.00,0.00,6340.48,5950.00,390.48 +0.00,0.00,0.00,6240.48,5500.00,740.48 +0.00,0.00,0.00,6140.48,6950.00,-809.52 +0.00,0.00,0.00,6040.48,6150.00,-109.52 +0.00,0.00,0.00,5940.48,4900.00,1040.48 +0.00,0.00,0.00,5840.48,4950.00,890.48 +0.00,0.00,0.00,5740.48,5550.00,190.48 +0.00,0.00,0.00,5640.48,5750.00,-109.52 +0.00,0.00,0.00,5540.48,4850.00,690.48 +0.00,0.00,0.00,5440.48,4250.00,1190.48 +0.00,0.00,0.00,5340.48,4650.00,690.48 +0.00,0.00,0.00,5240.48,5250.00,-9.52 +0.00,0.00,0.00,5140.48,5350.00,-209.52 +0.00,0.00,0.00,5040.48,4350.00,690.48 +0.00,0.00,0.00,4940.48,3600.00,1340.48 +0.00,0.00,0.00,4840.48,3350.00,1490.48 +0.00,0.00,0.00,4740.48,4050.00,690.48 +0.00,0.00,0.00,4640.48,4500.00,140.48 +0.00,0.00,0.00,4540.48,3600.00,940.48 +0.00,0.00,0.00,4440.48,2700.00,1740.48 +0.00,0.00,0.00,4340.48,2800.00,1540.48 +0.00,0.00,0.00,4240.48,3700.00,540.48 +0.00,0.00,0.00,4140.48,4150.00,-9.52 +0.00,0.00,0.00,4040.48,3350.00,690.48 +0.00,0.00,0.00,3940.48,2150.00,1790.48 +0.00,0.00,0.00,3840.48,2350.00,1490.48 +0.00,0.00,0.00,3740.48,2850.00,890.48 +0.00,0.00,0.00,3640.48,1550.00,2090.48 +0.00,0.00,0.00,3540.48,2250.00,1290.48 +0.00,0.00,0.00,3440.48,2650.00,790.48 +0.00,0.00,0.00,3340.48,1200.00,2140.48 +0.00,0.00,0.00,3240.48,1800.00,1440.48 +0.00,0.00,0.00,3140.48,2400.00,740.48 +0.00,0.00,0.00,3040.48,1650.00,1390.48 +0.00,0.00,0.00,2940.48,150.00,2790.48 +0.00,0.00,0.00,2840.48,350.00,2490.48 +0.00,0.00,0.00,2740.48,2450.00,290.48 +0.00,0.00,0.00,2640.48,2750.00,-109.52 +0.00,0.00,0.00,2540.48,1950.00,590.48 +0.00,0.00,0.00,2440.48,1650.00,790.48 +0.00,0.00,0.00,2340.48,650.00,1690.48 +0.00,0.00,0.00,2240.48,-850.00,3090.48 +0.00,0.00,0.00,2140.48,350.00,1790.48 +0.00,0.00,0.00,2040.48,1200.00,840.48 +0.00,0.00,0.00,1940.48,50.00,1890.48 +0.00,0.00,0.00,1840.48,0.00,1840.48 +0.00,0.00,0.00,1740.48,0.00,1740.48 +0.00,0.00,0.00,1640.48,0.00,1640.48 +0.00,0.00,0.00,1540.48,0.00,1540.48 +0.00,0.00,0.00,1440.48,0.00,1440.48 +0.00,0.00,0.00,1340.48,0.00,1340.48 +0.00,0.00,0.00,1240.48,0.00,1240.48 +0.00,0.00,0.00,1140.48,0.00,1140.48 +0.00,0.00,0.00,1040.48,0.00,1040.48 +0.00,0.00,0.00,940.48,0.00,940.48 +0.00,0.00,0.00,840.48,0.00,840.48 +0.00,0.00,0.00,740.48,0.00,740.48 +0.00,0.00,0.00,640.48,0.00,640.48 +0.00,0.00,0.00,540.48,0.00,540.48 +0.00,0.00,0.00,440.48,0.00,440.48 +0.00,0.00,0.00,340.48,0.00,340.48 +0.00,0.00,0.00,240.48,0.00,240.48 +0.00,0.00,0.00,140.48,0.00,140.48 +0.00,0.00,0.00,40.48,0.00,40.48 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +-100.00,0.00,-100.00,-100.00,0.00,-100.00 +-200.00,0.00,-200.00,-200.00,0.00,-200.00 +-300.00,0.00,-300.00,-300.00,0.00,-300.00 +-400.00,0.00,-400.00,-400.00,0.00,-400.00 +-500.00,0.00,-500.00,-500.00,0.00,-500.00 +-600.00,0.00,-600.00,-600.00,0.00,-600.00 +-700.00,0.00,-700.00,-700.00,0.00,-700.00 +-800.00,0.00,-800.00,-800.00,0.00,-800.00 +-900.00,0.00,-900.00,-900.00,0.00,-900.00 +-1000.00,0.00,-1000.00,-1000.00,0.00,-1000.00 +-1100.00,0.00,-1100.00,-1100.00,0.00,-1100.00 +-1200.00,0.00,-1200.00,-1200.00,0.00,-1200.00 +-1300.00,0.00,-1300.00,-1300.00,0.00,-1300.00 +-1400.00,0.00,-1400.00,-1400.00,0.00,-1400.00 +-1500.00,0.00,-1500.00,-1500.00,0.00,-1500.00 +-1600.00,0.00,-1600.00,-1600.00,0.00,-1600.00 +-1700.00,0.00,-1700.00,-1700.00,0.00,-1700.00 +-1800.00,0.00,-1800.00,-1800.00,0.00,-1800.00 +-1900.00,0.00,-1900.00,-1900.00,0.00,-1900.00 +-2000.00,0.00,-2000.00,-2000.00,0.00,-2000.00 +-2100.00,0.00,-2100.00,-2100.00,0.00,-2100.00 +-2200.00,0.00,-2200.00,-2200.00,0.00,-2200.00 +-2300.00,0.00,-2300.00,-2300.00,0.00,-2300.00 +-2400.00,0.00,-2400.00,-2400.00,0.00,-2400.00 +-2500.00,-450.00,-2050.00,-2500.00,-650.00,-1850.00 +-2600.00,-500.00,-2100.00,-2600.00,-1800.00,-800.00 +-2700.00,1050.00,-3750.00,-2700.00,150.00,-2850.00 +-2800.00,-350.00,-2450.00,-2800.00,-50.00,-2750.00 +-2900.00,-2950.00,50.00,-2900.00,-2000.00,-900.00 +-3000.00,-3850.00,850.00,-3000.00,-3000.00,0.00 +-3100.00,-2850.00,-250.00,-3100.00,-2100.00,-1000.00 +-3200.00,-1750.00,-1450.00,-3200.00,-500.00,-2700.00 +-3300.00,-1650.00,-1650.00,-3300.00,-950.00,-2350.00 +-3400.00,-100.00,-3300.00,-3400.00,-3050.00,-350.00 +-3500.00,-100.00,-3400.00,-3500.00,-3750.00,250.00 +-3600.00,-2500.00,-1100.00,-3600.00,-2550.00,-1050.00 +-3700.00,-4350.00,650.00,-3700.00,-3700.00,0.00 +-3800.00,-3550.00,-250.00,-3800.00,-600.00,-3200.00 +-3900.00,-3050.00,-850.00,-3900.00,-1400.00,-2500.00 +-4000.00,-2200.00,-1800.00,-4000.00,-3600.00,-400.00 +-4100.00,-1700.00,-2400.00,-4100.00,-4600.00,500.00 +-4200.00,-2900.00,-1300.00,-4200.00,-3500.00,-700.00 +-4300.00,-4600.00,300.00,-4300.00,-2800.00,-1500.00 +-4400.00,-5000.00,600.00,-4400.00,-2500.00,-1900.00 +-4500.00,-4050.00,-450.00,-4500.00,-3450.00,-1050.00 +-4600.00,-3300.00,-1300.00,-4600.00,-4150.00,-450.00 +-4700.00,-3100.00,-1600.00,-4700.00,-3150.00,-1550.00 +-4800.00,-3700.00,-1100.00,-4800.00,-2800.00,-2000.00 +-4900.00,-4600.00,-300.00,-4900.00,-4350.00,-550.00 +-5000.00,-5700.00,700.00,-5000.00,-5300.00,300.00 +-5100.00,-4150.00,-950.00,-5100.00,-3800.00,-1300.00 +-5200.00,-3950.00,-1250.00,-5200.00,-3500.00,-1700.00 +-5300.00,-4200.00,-1100.00,-5300.00,-4600.00,-700.00 +-5400.00,-5550.00,150.00,-5400.00,-6350.00,950.00 +-5500.00,-5700.00,200.00,-5500.00,-6450.00,950.00 +-5600.00,-5200.00,-400.00,-5600.00,-4500.00,-1100.00 +-5700.00,-4300.00,-1400.00,-5700.00,-4050.00,-1650.00 +-5800.00,-4100.00,-1700.00,-5800.00,-4750.00,-1050.00 +-5900.00,-4850.00,-1050.00,-5900.00,-5000.00,-900.00 +-6000.00,-6600.00,600.00,-6000.00,-6500.00,500.00 +-6100.00,-7100.00,1000.00,-6100.00,-6750.00,650.00 +-6200.00,-5800.00,-400.00,-6200.00,-5350.00,-850.00 +-6300.00,-5350.00,-950.00,-6300.00,-5000.00,-1300.00 +-6400.00,-6350.00,-50.00,-6400.00,-6000.00,-400.00 +-6500.00,-7050.00,550.00,-6500.00,-7400.00,900.00 +-6600.00,-6750.00,150.00,-6600.00,-6750.00,150.00 +-6700.00,-6450.00,-250.00,-6700.00,-5950.00,-750.00 +-6800.00,-6700.00,-100.00,-6800.00,-6900.00,100.00 +-6900.00,-7250.00,350.00,-6900.00,-6900.00,0.00 +-7000.00,-7500.00,500.00,-7000.00,-6900.00,-100.00 +-7100.00,-7050.00,-50.00,-7100.00,-7500.00,400.00 +-7200.00,-7000.00,-200.00,-7200.00,-7600.00,400.00 +-7300.00,-7450.00,150.00,-7300.00,-7700.00,400.00 +-7400.00,-7850.00,450.00,-7400.00,-7600.00,200.00 +-7500.00,-8200.00,700.00,-7500.00,-8400.00,900.00 +-7600.00,-8350.00,750.00,-7600.00,-7450.00,-150.00 +-7700.00,-8350.00,650.00,-7700.00,-6400.00,-1300.00 +-7800.00,-8350.00,550.00,-7800.00,-7700.00,-100.00 +-7900.00,-8500.00,600.00,-7900.00,-9250.00,1350.00 +-8000.00,-9000.00,1000.00,-8000.00,-8150.00,150.00 +-8100.00,-9250.00,1150.00,-8100.00,-7250.00,-850.00 +-8200.00,-8750.00,550.00,-8200.00,-8300.00,100.00 +-8300.00,-8450.00,150.00,-8300.00,-9950.00,1650.00 +-8400.00,-9550.00,1150.00,-8400.00,-8850.00,450.00 +-8500.00,-9850.00,1350.00,-8500.00,-7100.00,-1400.00 +-8600.00,-9800.00,1200.00,-8600.00,-7700.00,-900.00 +-8700.00,-11550.00,2850.00,-8700.00,-11500.00,2800.00 +-8800.00,-8550.00,-250.00,-8800.00,-9200.00,400.00 +-8900.00,-8150.00,-750.00,-8900.00,-7800.00,-1100.00 +-9000.00,-8000.00,-1000.00,-9000.00,-8600.00,-400.00 +-9100.00,-10700.00,1600.00,-9100.00,-10550.00,1450.00 +-9200.00,-11550.00,2350.00,-9200.00,-10400.00,1200.00 +-9300.00,-10200.00,900.00,-9300.00,-9700.00,400.00 +-9400.00,-9400.00,0.00,-9400.00,-9600.00,200.00 +-9500.00,-9250.00,-250.00,-9500.00,-10100.00,600.00 +-9600.00,-9900.00,300.00,-9600.00,-10900.00,1300.00 +-9700.00,-10950.00,1250.00,-9700.00,-10200.00,500.00 +-9800.00,-12000.00,2200.00,-9800.00,-10350.00,550.00 +-9900.00,-11600.00,1700.00,-9900.00,-10400.00,500.00 +-10000.00,-10600.00,600.00,-10000.00,-10650.00,650.00 +-10100.00,-11150.00,1050.00,-10100.00,-11200.00,1100.00 +-10200.00,-11550.00,1350.00,-10200.00,-11000.00,800.00 +-10300.00,-11500.00,1200.00,-10300.00,-10850.00,550.00 +-10400.00,-11600.00,1200.00,-10400.00,-10250.00,-150.00 +-10500.00,-11700.00,1200.00,-10500.00,-9950.00,-550.00 +-10600.00,-12550.00,1950.00,-10600.00,-11000.00,400.00 +-10700.00,-12450.00,1750.00,-10700.00,-12900.00,2200.00 +-10800.00,-11600.00,800.00,-10800.00,-12800.00,2000.00 +-10900.00,-11950.00,1050.00,-10900.00,-11800.00,900.00 +-11000.00,-12250.00,1250.00,-11000.00,-12200.00,1200.00 +-11100.00,-12750.00,1650.00,-11100.00,-13450.00,2350.00 +-11200.00,-13250.00,2050.00,-11200.00,-12450.00,1250.00 +-11300.00,-12900.00,1600.00,-11300.00,-12100.00,800.00 +-11400.00,-13200.00,1800.00,-11400.00,-13400.00,2000.00 +-11500.00,-13050.00,1550.00,-11500.00,-12650.00,1150.00 +-11600.00,-13350.00,1750.00,-11600.00,-12600.00,1000.00 +-11700.00,-12900.00,1200.00,-11700.00,-12700.00,1000.00 +-11800.00,-13050.00,1250.00,-11800.00,-14150.00,2350.00 +-11900.00,-13950.00,2050.00,-11900.00,-14000.00,2100.00 +-12000.00,-14300.00,2300.00,-12000.00,-14200.00,2200.00 +-12100.00,-14050.00,1950.00,-12100.00,-13850.00,1750.00 +-12200.00,-13900.00,1700.00,-12200.00,-12800.00,600.00 +-12300.00,-13550.00,1250.00,-12300.00,-12350.00,50.00 +-12400.00,-14500.00,2100.00,-12400.00,-13900.00,1500.00 +-12500.00,-14000.00,1500.00,-12500.00,-16000.00,3500.00 +-12600.00,-14100.00,1500.00,-12600.00,-15600.00,3000.00 +-12700.00,-15050.00,2350.00,-12700.00,-14750.00,2050.00 +-12800.00,-15350.00,2550.00,-12800.00,-14050.00,1250.00 +-12900.00,-15500.00,2600.00,-12900.00,-14200.00,1300.00 +-13000.00,-14650.00,1650.00,-13000.00,-14500.00,1500.00 +-13100.00,-14000.00,900.00,-13100.00,-14350.00,1250.00 +-13200.00,-14600.00,1400.00,-13200.00,-15050.00,1850.00 +-13300.00,-15400.00,2100.00,-13300.00,-16100.00,2800.00 +-13400.00,-15950.00,2550.00,-13400.00,-17500.00,4100.00 +-13500.00,-15900.00,2400.00,-13500.00,-15000.00,1500.00 +-13600.00,-15550.00,1950.00,-13600.00,-13500.00,-100.00 +-13700.00,-12650.00,-1050.00,-13700.00,-15300.00,1600.00 +-13800.00,-10550.00,-3250.00,-13800.00,-19000.00,5200.00 +-13900.00,-7850.00,-6050.00,-13900.00,-20500.00,6600.00 +-14000.00,-5200.00,-8800.00,-14000.00,-14400.00,400.00 +-14100.00,3200.00,-17300.00,-14100.00,-14000.00,-100.00 +-14200.00,5000.00,-19200.00,-14200.00,-2000.00,-12200.00 +-14300.00,0.00,-14300.00,-14300.00,-1200.00,-13100.00 +-14400.00,200.00,-14600.00,-14400.00,-1600.00,-12800.00 +-14500.00,-200.00,-14300.00,-14500.00,-400.00,-14100.00 +-14600.00,-200.00,-14400.00,-14600.00,-200.00,-14400.00 +-14700.00,400.00,-15100.00,-14700.00,-200.00,-14500.00 +-14800.00,0.00,-14800.00,-14800.00,-600.00,-14200.00 +-14900.00,200.00,-15100.00,-14900.00,-200.00,-14700.00 +-15000.00,600.00,-15600.00,-15000.00,-400.00,-14600.00 +-15100.00,1250.00,-16350.00,-15100.00,-800.00,-14300.00 +-15200.00,3350.00,-18550.00,-15200.00,-1600.00,-13600.00 +-15300.00,3600.00,-18900.00,-15300.00,-800.00,-14500.00 +-15400.00,2400.00,-17800.00,-15400.00,-400.00,-15000.00 +-15500.00,2800.00,-18300.00,-15500.00,-600.00,-14900.00 +-15600.00,2400.00,-18000.00,-15600.00,-200.00,-15400.00 +-15700.00,2600.00,-18300.00,-15700.00,0.00,-15700.00 +-15800.00,2600.00,-18400.00,-15800.00,-400.00,-15400.00 +-15900.00,2000.00,-17900.00,-15900.00,-800.00,-15100.00 +-16000.00,1200.00,-17200.00,-16000.00,-1150.00,-14850.00 +-16100.00,1200.00,-17300.00,-16100.00,-450.00,-15650.00 +-16200.00,400.00,-16600.00,-16200.00,-600.00,-15600.00 +-16300.00,600.00,-16900.00,-16300.00,-1400.00,-14900.00 +-16400.00,1000.00,-17400.00,-16400.00,-1000.00,-15400.00 +-16500.00,-200.00,-16300.00,-16500.00,-600.00,-15900.00 +-16600.00,600.00,-17200.00,-16600.00,-600.00,-16000.00 +-16700.00,450.00,-17150.00,-16700.00,-1600.00,-15100.00 +-16800.00,400.00,-17200.00,-16800.00,-2200.00,-14600.00 +-16900.00,150.00,-17050.00,-16900.00,-2400.00,-14500.00 +-17000.00,400.00,-17400.00,-17000.00,-1800.00,-15200.00 +-17100.00,0.00,-17100.00,-17100.00,-1600.00,-15500.00 +-17048.50,0.00,-17048.50,-17200.00,-600.00,-16600.00 +-16948.50,200.00,-17148.50,-17300.00,-1800.00,-15500.00 +-16848.50,400.00,-17248.50,-17400.00,-2800.00,-14600.00 +-16748.50,450.00,-17198.50,-17412.18,-2000.00,-15412.18 +-16648.50,350.00,-16998.50,-17312.18,-2200.00,-15112.18 +-16548.50,200.00,-16748.50,-17212.18,-2800.00,-14412.18 +-16448.50,-200.00,-16248.50,-17112.18,-1200.00,-15912.18 +-16348.50,200.00,-16548.50,-17012.18,-1600.00,-15412.18 +-16248.50,400.00,-16648.50,-16912.18,-1600.00,-15312.18 +-16148.50,800.00,-16948.50,-16812.18,-2400.00,-14412.18 +-16048.50,0.00,-16048.50,-16712.18,-1800.00,-14912.18 +-15948.50,400.00,-16348.50,-16612.18,-1400.00,-15212.18 +-15848.50,200.00,-16048.50,-16512.18,-2200.00,-14312.18 +-15748.50,400.00,-16148.50,-16412.18,-2200.00,-14212.18 +-15648.50,200.00,-15848.50,-16312.18,-1800.00,-14512.18 +-15548.50,0.00,-15548.50,-16212.18,-1800.00,-14412.18 +-15448.50,200.00,-15648.50,-16112.18,-2800.00,-13312.18 +-15348.50,0.00,-15348.50,-16012.18,-1800.00,-14212.18 +-15248.50,200.00,-15448.50,-15912.18,-2000.00,-13912.18 +-15148.50,200.00,-15348.50,-15812.18,-1400.00,-14412.18 +-15048.50,0.00,-15048.50,-15712.18,-1200.00,-14512.18 +-14948.50,400.00,-15348.50,-15612.18,-1600.00,-14012.18 +-14848.50,400.00,-15248.50,-15512.18,-1800.00,-13712.18 +-14748.50,200.00,-14948.50,-15412.18,-2800.00,-12612.18 +-14648.50,800.00,-15448.50,-15312.18,-2600.00,-12712.18 +-14548.50,0.00,-14548.50,-15212.18,-2600.00,-12612.18 +-14448.50,-200.00,-14248.50,-15112.18,-3800.00,-11312.18 +-14348.50,0.00,-14348.50,-15012.18,-4400.00,-10612.18 +-14248.50,-400.00,-13848.50,-14912.18,-13200.00,-1712.18 +-14148.50,-5800.00,-8348.50,-14812.18,-49500.00,34687.82 +-14048.50,-6400.00,-7648.50,-14712.18,-31900.00,17187.82 +-13948.50,0.00,-13948.50,-14612.18,0.00,-14612.18 +-13848.50,0.00,-13848.50,-14512.18,0.00,-14512.18 +-13748.50,0.00,-13748.50,-14412.18,0.00,-14412.18 +-13648.50,0.00,-13648.50,-14312.18,0.00,-14312.18 +-13548.50,0.00,-13548.50,-14212.18,0.00,-14212.18 +-13448.50,0.00,-13448.50,-14112.18,0.00,-14112.18 +-13348.50,0.00,-13348.50,-14012.18,0.00,-14012.18 +-13248.50,0.00,-13248.50,-13912.18,200.00,-14112.18 +-13148.50,0.00,-13148.50,-13812.18,0.00,-13812.18 +-13048.50,400.00,-13448.50,-13712.18,0.00,-13712.18 +-12948.50,0.00,-12948.50,-13612.18,0.00,-13612.18 +-12848.50,400.00,-13248.50,-13512.18,0.00,-13512.18 +-12748.50,800.00,-13548.50,-13412.18,0.00,-13412.18 +-12648.50,4000.00,-16648.50,-13312.18,0.00,-13312.18 +-12548.50,4250.00,-16798.50,-13212.18,0.00,-13212.18 +-12448.50,3550.00,-15998.50,-13112.18,0.00,-13112.18 +-12348.50,2600.00,-14948.50,-13012.18,0.00,-13012.18 +-12248.50,3000.00,-15248.50,-12912.18,0.00,-12912.18 +-12148.50,1200.00,-13348.50,-12812.18,0.00,-12812.18 +-12048.50,800.00,-12848.50,-12712.18,0.00,-12712.18 +-11948.50,200.00,-12148.50,-12612.18,-800.00,-11812.18 +-11848.50,0.00,-11848.50,-12512.18,-2000.00,-10512.18 +-11748.50,250.00,-11998.50,-12412.18,-10000.00,-2412.18 +-11648.50,-9400.00,-2248.50,-12312.18,-37800.00,25487.82 +-11548.50,-1850.00,-9698.50,-12212.18,-26600.00,14387.82 +-11448.50,0.00,-11448.50,-12112.18,0.00,-12112.18 +-11348.50,0.00,-11348.50,-12012.18,0.00,-12012.18 +-11248.50,0.00,-11248.50,-11912.18,0.00,-11912.18 +-11148.50,0.00,-11148.50,-11812.18,0.00,-11812.18 +-11048.50,0.00,-11048.50,-11712.18,0.00,-11712.18 +-10948.50,0.00,-10948.50,-11612.18,0.00,-11612.18 +-10848.50,0.00,-10848.50,-11512.18,0.00,-11512.18 +-10748.50,1000.00,-11748.50,-11412.18,0.00,-11412.18 +-10648.50,600.00,-11248.50,-11312.18,0.00,-11312.18 +-10548.50,1400.00,-11948.50,-11212.18,0.00,-11212.18 +-10448.50,2200.00,-12648.50,-11112.18,0.00,-11112.18 +-10348.50,1800.00,-12148.50,-11012.18,0.00,-11012.18 +-10248.50,4000.00,-14248.50,-10912.18,-200.00,-10712.18 +-10148.50,3600.00,-13748.50,-10812.18,0.00,-10812.18 +-10048.50,2600.00,-12648.50,-10712.18,-400.00,-10312.18 +-9948.50,400.00,-10348.50,-10612.18,-400.00,-10212.18 +-9848.50,0.00,-9848.50,-10512.18,-4400.00,-6112.18 +-9748.50,-1400.00,-8348.50,-10412.18,-25600.00,15187.82 +-9648.50,-400.00,-9248.50,-10312.18,-23000.00,12687.82 +-9548.50,200.00,-9748.50,-10212.18,-200.00,-10012.18 +-9448.50,400.00,-9848.50,-10112.18,-200.00,-9912.18 +-9348.50,0.00,-9348.50,-10012.18,0.00,-10012.18 +-9248.50,0.00,-9248.50,-9912.18,0.00,-9912.18 +-9148.50,1200.00,-10348.50,-9812.18,0.00,-9812.18 +-9048.50,2000.00,-11048.50,-9712.18,0.00,-9712.18 +-8948.50,1800.00,-10748.50,-9612.18,0.00,-9612.18 +-8848.50,2400.00,-11248.50,-9512.18,0.00,-9512.18 +-8748.50,2400.00,-11148.50,-9412.18,0.00,-9412.18 +-8648.50,1200.00,-9848.50,-9312.18,0.00,-9312.18 +-8548.50,400.00,-8948.50,-9212.18,-200.00,-9012.18 +-8448.50,0.00,-8448.50,-9112.18,-4200.00,-4912.18 +-8348.50,-2400.00,-5948.50,-9012.18,-24300.00,15287.82 +-8248.50,-600.00,-7648.50,-8912.18,-18300.00,9387.82 +-8148.50,-2900.00,-5248.50,-8812.18,-5400.00,-3412.18 +-8048.50,-2300.00,-5748.50,-8712.18,-16300.00,7587.82 +-7948.50,-13900.00,5951.50,-8612.18,-19700.00,11087.82 +-7848.50,-7300.00,-548.50,-8512.18,-11200.00,2687.82 +-7748.50,-18350.00,10601.50,-8412.18,-3500.00,-4912.18 +-7648.50,-8450.00,801.50,-8312.18,-1300.00,-7012.18 +-7548.50,200.00,-7748.50,-8212.18,0.00,-8212.18 +-7448.50,600.00,-8048.50,-8112.18,0.00,-8112.18 +-7348.50,0.00,-7348.50,-8012.18,0.00,-8012.18 +-7248.50,0.00,-7248.50,-7912.18,0.00,-7912.18 +-7148.50,1200.00,-8348.50,-7812.18,-200.00,-7612.18 +-7048.50,600.00,-7648.50,-7712.18,-1200.00,-6512.18 +-6948.50,0.00,-6948.50,-7612.18,-3600.00,-4012.18 +-6848.50,-600.00,-6248.50,-7512.18,-26800.00,19287.82 +-6748.50,0.00,-6748.50,-7412.18,-15200.00,7787.82 +-6648.50,-750.00,-5898.50,-7312.18,-1000.00,-6312.18 +-6548.50,-1850.00,-4698.50,-7212.18,-2800.00,-4412.18 +-6448.50,850.00,-7298.50,-7112.18,-6200.00,-912.18 +-6348.50,-200.00,-6148.50,-7012.18,-19400.00,12387.82 +-6248.50,350.00,-6598.50,-6912.18,-8800.00,1887.82 +-6148.50,-4300.00,-1848.50,-6812.18,100.00,-6912.18 +-6048.50,-4300.00,-1748.50,-6712.18,-100.00,-6612.18 +-5948.50,1600.00,-7548.50,-6612.18,-800.00,-5812.18 +-5848.50,200.00,-6048.50,-6512.18,-4200.00,-2312.18 +-5748.50,-2750.00,-2998.50,-6412.18,-11900.00,5487.82 +-5648.50,-14950.00,9301.50,-6312.18,-19350.00,13037.82 +-5548.50,-8100.00,2551.50,-6212.18,-5900.00,-312.18 +-5448.50,-2100.00,-3348.50,-6112.18,-150.00,-5962.18 +-5348.50,-700.00,-4648.50,-6012.18,-1100.00,-4912.18 +-5248.50,1400.00,-6648.50,-5912.18,-1800.00,-4112.18 +-5148.50,400.00,-5548.50,-5812.18,-4400.00,-1412.18 +-5048.50,-1600.00,-3448.50,-5712.18,-10300.00,4587.82 +-4948.50,-10400.00,5451.50,-5612.18,-13550.00,7937.82 +-4848.50,-8400.00,3551.50,-5512.18,-8450.00,2937.82 +-4748.50,-9850.00,5101.50,-5412.18,-2900.00,-2512.18 +-4648.50,-5050.00,401.50,-5312.18,-1800.00,-3512.18 +-4548.50,-800.00,-3748.50,-5212.18,-5400.00,187.82 +-4448.50,-2300.00,-2148.50,-5112.18,-8000.00,2887.82 +-4348.50,-7100.00,2751.50,-5012.18,-6200.00,1187.82 +-4248.50,-8750.00,4501.50,-4912.18,-4650.00,-262.18 +-4148.50,-7250.00,3101.50,-4812.18,-3250.00,-1562.18 +-4048.50,-6100.00,2051.50,-4712.18,-2650.00,-2062.18 +-3948.50,-5000.00,1051.50,-4612.18,-3750.00,-862.18 +-3848.50,-4050.00,201.50,-4512.18,-4700.00,187.82 +-3748.50,-3200.00,-548.50,-4412.18,-3400.00,-1012.18 +-3648.50,-2450.00,-1198.50,-4312.18,-2300.00,-2012.18 +-3548.50,-1200.00,-2348.50,-4212.18,-1600.00,-2612.18 +-3448.50,-1050.00,-2398.50,-4112.18,-3500.00,-612.18 +-3348.50,-2800.00,-548.50,-4012.18,-5900.00,1887.82 +-3248.50,-4450.00,1201.50,-3912.18,-3550.00,-362.18 +-3148.50,-3700.00,551.50,-3812.18,-2450.00,-1362.18 +-3048.50,-3000.00,-48.50,-3712.18,-450.00,-3262.18 +-2948.50,-1100.00,-1848.50,-3612.18,-1050.00,-2562.18 +-2848.50,-750.00,-2098.50,-3512.18,-4200.00,687.82 +-2748.50,450.00,-3198.50,-3412.18,-4100.00,687.82 +-2648.50,300.00,-2948.50,-3312.18,-3300.00,-12.18 +-2548.50,-1400.00,-1148.50,-3212.18,-2600.00,-612.18 +-2448.50,-2950.00,501.50,-3112.18,-500.00,-2612.18 +-2348.50,-2150.00,-198.50,-3012.18,0.00,-3012.18 +-2248.50,-1800.00,-448.50,-2912.18,-2200.00,-712.18 +-2148.50,-700.00,-1448.50,-2812.18,-3400.00,587.82 +-2048.50,750.00,-2798.50,-2712.18,-2000.00,-712.18 +-1948.50,-400.00,-1548.50,-2612.18,-1450.00,-1162.18 +-1848.50,-750.00,-1098.50,-2512.18,-400.00,-2112.18 +-1748.50,400.00,-2148.50,-2412.18,550.00,-2962.18 +-1648.50,850.00,-2498.50,-2312.18,-700.00,-1612.18 +-1548.50,-150.00,-1398.50,-2212.18,-1350.00,-862.18 +-1448.50,-50.00,-1398.50,-2112.18,-1000.00,-1112.18 +-1348.50,0.00,-1348.50,-2012.18,-450.00,-1562.18 +-1248.50,0.00,-1248.50,-1912.18,100.00,-2012.18 +-1148.50,0.00,-1148.50,-1812.18,50.00,-1862.18 +-1048.50,0.00,-1048.50,-1712.18,0.00,-1712.18 +-948.50,0.00,-948.50,-1612.18,0.00,-1612.18 +-848.50,0.00,-848.50,-1512.18,0.00,-1512.18 +-748.50,0.00,-748.50,-1412.18,0.00,-1412.18 +-648.50,0.00,-648.50,-1312.18,0.00,-1312.18 +-548.50,0.00,-548.50,-1212.18,0.00,-1212.18 +-448.50,0.00,-448.50,-1112.18,0.00,-1112.18 +-348.50,0.00,-348.50,-1012.18,0.00,-1012.18 +-248.50,0.00,-248.50,-912.18,0.00,-912.18 +-148.50,0.00,-148.50,-812.18,0.00,-812.18 +-48.50,0.00,-48.50,-712.18,0.00,-712.18 +0.00,0.00,0.00,-612.18,0.00,-612.18 +0.00,0.00,0.00,-512.18,0.00,-512.18 +0.00,0.00,0.00,-412.18,0.00,-412.18 +0.00,0.00,0.00,-312.18,0.00,-312.18 +0.00,0.00,0.00,-212.18,0.00,-212.18 +0.00,0.00,0.00,-112.18,0.00,-112.18 +0.00,0.00,0.00,-12.18,0.00,-12.18 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 \ No newline at end of file diff --git a/pid_vis.py b/pid_vis.py index da21df8..24a3218 100644 --- a/pid_vis.py +++ b/pid_vis.py @@ -6,7 +6,8 @@ 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" keys = header.split(",") for row in reader: for k in keys: @@ -15,24 +16,27 @@ val *= -1 # Correct for rotation test lists[k].append(val) - power_deadzone = [0.15] * len(lists["EncoderLeft"]) - neg_power_deadzone = [-0.15] * len(lists["EncoderLeft"]) + # 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") + # 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.plot(lists["LeftSetpoint"], "-b", lists["LeftVelocity"], "-r", lists["LeftError"], "-g", lists["RightSetpoint"], "--c", lists["RightVelocity"], "--m", lists["RightError"], "--y") plt.show() diff --git a/src/robot/control.cpp b/src/robot/control.cpp index 46fca2c..477c0a3 100644 --- a/src/robot/control.cpp +++ b/src/robot/control.cpp @@ -31,8 +31,8 @@ TrapezoidProfile::Constraints profileConstraints(MAX_VELOCITY_TPS, MAX_ACCELERAT TrapezoidProfile leftProfile(profileConstraints); TrapezoidProfile rightProfile(profileConstraints); TrapezoidProfile::State leftSetpoint, rightSetpoint; -PIDController encoderAVelocityController(0.00008, 0.0000035, 0.000001, -1, +1); // Blue -PIDController encoderBVelocityController(0.00008, 0.0000035, 0.000001, -1, +1); //Red +PIDController encoderAVelocityController(0.00004, 0.000001, 0.00000, -1, +1); // Blue +PIDController encoderBVelocityController(0.00004, 0.000001, 0.00000, -1, +1); //Red //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; @@ -286,42 +286,54 @@ void controlLoop(int loopDelayMs, int8_t framesUntilPrint) { if(framesUntilPrint == 0) { - serialLog("Current encoder A pos: ", 2); - serialLog(currentPositionEncoderA, 2); - serialLog(", ", 2); - serialLog("Current encoder B pos: ", 2); - serialLog(currentPositionEncoderB, 2); - serialLog(", ", 2); - serialLog("Desired encoder A speed: ", 2); - serialLog(leftSetpoint.velocity, 2); - serialLog(", ", 2); - serialLog("Desired encoder B speed: ", 2); - serialLog(rightSetpoint.velocity, 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); + // serialLog("Current encoder A pos: ", 2); + // serialLog(currentPositionEncoderA, 2); + // serialLog(", ", 2); + // serialLog("Current encoder B pos: ", 2); + // serialLog(currentPositionEncoderB, 2); + // serialLog(", ", 2); + // serialLog("Desired encoder A speed: ", 2); + // serialLog(leftSetpoint.velocity, 2); + // serialLog(", ", 2); + // serialLog("Desired encoder B speed: ", 2); + // serialLog(rightSetpoint.velocity, 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); } - + + serialLog(leftSetpoint.velocity, 3); + serialLog(",", 3); + serialLog(currentVelocityA, 3); + serialLog(",", 3); + serialLog(leftSetpoint.velocity - currentVelocityA, 3); + serialLog(",", 3); + serialLog(rightSetpoint.velocity, 3); + serialLog(",", 3); + serialLog(currentVelocityB, 3); + serialLog(",", 3); + serialLogln(rightSetpoint.velocity - currentVelocityB, 3); + #endif drive( From 53ed1184a3360a363d1b622d67f8154e6da1218c Mon Sep 17 00:00:00 2001 From: democat Date: Mon, 15 Sep 2025 23:24:42 -0500 Subject: [PATCH 04/47] tweak integral value --- pid_test.csv | 2768 ++++++++++++++++++++--------------------- pid_vis.py | 4 +- src/robot/control.cpp | 4 +- 3 files changed, 1384 insertions(+), 1392 deletions(-) diff --git a/pid_test.csv b/pid_test.csv index 72e5b82..df3ec6a 100644 --- a/pid_test.csv +++ b/pid_test.csv @@ -1727,365 +1727,6 @@ LeftSetpoint,LeftVelocity,LeftError,RightSetpoint,RightVelocity,RightError 0.00,0.00,0.00,0.00,0.00,0.00 0.00,0.00,0.00,0.00,0.00,0.00 0.00,0.00,0.00,0.00,0.00,0.00 --100.00,0.00,-100.00,-100.00,0.00,-100.00 --200.00,0.00,-200.00,-200.00,0.00,-200.00 --300.00,0.00,-300.00,-300.00,0.00,-300.00 --400.00,0.00,-400.00,-400.00,0.00,-400.00 --500.00,0.00,-500.00,-500.00,0.00,-500.00 --600.00,0.00,-600.00,-600.00,0.00,-600.00 --700.00,0.00,-700.00,-700.00,0.00,-700.00 --800.00,0.00,-800.00,-800.00,0.00,-800.00 --900.00,0.00,-900.00,-900.00,0.00,-900.00 --1000.00,0.00,-1000.00,-1000.00,0.00,-1000.00 --1100.00,0.00,-1100.00,-1100.00,0.00,-1100.00 --1200.00,0.00,-1200.00,-1200.00,0.00,-1200.00 --1300.00,0.00,-1300.00,-1300.00,0.00,-1300.00 --1400.00,0.00,-1400.00,-1400.00,0.00,-1400.00 --1500.00,0.00,-1500.00,-1500.00,0.00,-1500.00 --1600.00,0.00,-1600.00,-1600.00,0.00,-1600.00 --1700.00,0.00,-1700.00,-1700.00,0.00,-1700.00 --1800.00,0.00,-1800.00,-1800.00,0.00,-1800.00 --1900.00,0.00,-1900.00,-1900.00,0.00,-1900.00 --2000.00,0.00,-2000.00,-2000.00,0.00,-2000.00 --2100.00,0.00,-2100.00,-2100.00,0.00,-2100.00 --2200.00,0.00,-2200.00,-2200.00,0.00,-2200.00 --2300.00,0.00,-2300.00,-2300.00,0.00,-2300.00 --2400.00,0.00,-2400.00,-2400.00,0.00,-2400.00 --2500.00,0.00,-2500.00,-2500.00,0.00,-2500.00 --2600.00,-400.00,-2200.00,-2600.00,-400.00,-2200.00 --2700.00,-450.00,-2250.00,-2700.00,-350.00,-2350.00 --2800.00,800.00,-3600.00,-2800.00,150.00,-2950.00 --2900.00,-500.00,-2400.00,-2900.00,-750.00,-2150.00 --3000.00,-2400.00,-600.00,-3000.00,-1950.00,-1050.00 --3100.00,-3000.00,-100.00,-3100.00,-1700.00,-1400.00 --3200.00,-2350.00,-850.00,-3200.00,-750.00,-2450.00 --3300.00,-1900.00,-1400.00,-3300.00,-1100.00,-2200.00 --3400.00,-950.00,-2450.00,-3400.00,-1900.00,-1500.00 --3500.00,50.00,-3550.00,-3500.00,-2200.00,-1300.00 --3600.00,-2050.00,-1550.00,-3600.00,-600.00,-3000.00 --3700.00,-3900.00,200.00,-3700.00,-750.00,-2950.00 --3800.00,-3050.00,-750.00,-3800.00,-3050.00,-750.00 --3900.00,-2100.00,-1800.00,-3900.00,-3650.00,-250.00 --4000.00,-2300.00,-1700.00,-4000.00,-2550.00,-1450.00 --4100.00,-3300.00,-800.00,-4100.00,-1950.00,-2150.00 --4200.00,-3500.00,-700.00,-4200.00,-2450.00,-1750.00 --4300.00,-2800.00,-1500.00,-4300.00,-3350.00,-950.00 --4400.00,-2550.00,-1850.00,-4400.00,-3550.00,-850.00 --4500.00,-3600.00,-900.00,-4500.00,-2300.00,-2200.00 --4600.00,-4100.00,-500.00,-4600.00,-2100.00,-2500.00 --4700.00,-3250.00,-1450.00,-4700.00,-3400.00,-1300.00 --4800.00,-2900.00,-1900.00,-4800.00,-4450.00,-350.00 --4900.00,-4250.00,-650.00,-4900.00,-4450.00,-450.00 --5000.00,-4700.00,-300.00,-5000.00,-3100.00,-1900.00 --5100.00,-3800.00,-1300.00,-5100.00,-2700.00,-2400.00 --5200.00,-3700.00,-1500.00,-5200.00,-4150.00,-1050.00 --5300.00,-4450.00,-850.00,-5300.00,-5200.00,-100.00 --5400.00,-5350.00,-50.00,-5400.00,-4800.00,-600.00 --5500.00,-5500.00,0.00,-5500.00,-4300.00,-1200.00 --5600.00,-4450.00,-1150.00,-5600.00,-4200.00,-1400.00 --5700.00,-4300.00,-1400.00,-5700.00,-4750.00,-950.00 --5800.00,-5000.00,-800.00,-5800.00,-5150.00,-650.00 --5900.00,-6050.00,150.00,-5900.00,-5300.00,-600.00 --6000.00,-6000.00,0.00,-6000.00,-5500.00,-500.00 --6100.00,-5050.00,-1050.00,-6100.00,-5600.00,-500.00 --6200.00,-4750.00,-1450.00,-6200.00,-5400.00,-800.00 --6300.00,-5850.00,-450.00,-6300.00,-5850.00,-450.00 --6400.00,-6700.00,300.00,-6400.00,-6150.00,-250.00 --6500.00,-6950.00,450.00,-6500.00,-6700.00,200.00 --6600.00,-5550.00,-1050.00,-6600.00,-6600.00,0.00 --6700.00,-5450.00,-1250.00,-6700.00,-7000.00,300.00 --6800.00,-6450.00,-350.00,-6800.00,-6650.00,-150.00 --6900.00,-7350.00,450.00,-6900.00,-6050.00,-850.00 --7000.00,-7200.00,200.00,-7000.00,-6600.00,-400.00 --7100.00,-6200.00,-900.00,-7100.00,-7000.00,-100.00 --7200.00,-7150.00,-50.00,-7200.00,-7750.00,550.00 --7300.00,-7650.00,350.00,-7300.00,-7750.00,450.00 --7400.00,-7950.00,550.00,-7400.00,-7900.00,500.00 --7500.00,-7700.00,200.00,-7500.00,-7650.00,150.00 --7600.00,-7800.00,200.00,-7600.00,-7750.00,150.00 --7700.00,-8450.00,750.00,-7700.00,-8300.00,600.00 --7800.00,-8650.00,850.00,-7800.00,-8550.00,750.00 --7900.00,-8200.00,300.00,-7900.00,-8150.00,250.00 --8000.00,-8650.00,650.00,-8000.00,-8650.00,650.00 --8100.00,-10550.00,2450.00,-8100.00,-10450.00,2350.00 --8200.00,-8550.00,350.00,-8200.00,-8300.00,100.00 --8300.00,-7550.00,-750.00,-8300.00,-7450.00,-850.00 --8400.00,-8150.00,-250.00,-8400.00,-8300.00,-100.00 --8500.00,-9050.00,550.00,-8500.00,-9050.00,550.00 --8600.00,-9600.00,1000.00,-8600.00,-9450.00,850.00 --8700.00,-9850.00,1150.00,-8700.00,-9600.00,900.00 --8800.00,-9800.00,1000.00,-8800.00,-9600.00,800.00 --8900.00,-9750.00,850.00,-8900.00,-9600.00,700.00 --9000.00,-9800.00,800.00,-9000.00,-9650.00,650.00 --9100.00,-9900.00,800.00,-9100.00,-9950.00,850.00 --9200.00,-10150.00,950.00,-9200.00,-9950.00,750.00 --9300.00,-9850.00,550.00,-9300.00,-9750.00,450.00 --9400.00,-10500.00,1100.00,-9400.00,-10350.00,950.00 --9500.00,-10750.00,1250.00,-9500.00,-10550.00,1050.00 --9600.00,-10800.00,1200.00,-9600.00,-10550.00,950.00 --9700.00,-10550.00,850.00,-9700.00,-10250.00,550.00 --9800.00,-11000.00,1200.00,-9800.00,-10650.00,850.00 --9900.00,-11150.00,1250.00,-9900.00,-10950.00,1050.00 --10000.00,-11300.00,1300.00,-10000.00,-11050.00,1050.00 --10100.00,-11350.00,1250.00,-10100.00,-11150.00,1050.00 --10200.00,-11500.00,1300.00,-10200.00,-11200.00,1000.00 --10300.00,-11600.00,1300.00,-10300.00,-11350.00,1050.00 --10400.00,-11700.00,1300.00,-10400.00,-11450.00,1050.00 --10500.00,-11950.00,1450.00,-10500.00,-11600.00,1100.00 --10600.00,-12050.00,1450.00,-10600.00,-11650.00,1050.00 --10700.00,-11650.00,950.00,-10700.00,-11100.00,400.00 --10800.00,-12250.00,1450.00,-10800.00,-11650.00,850.00 --10900.00,-12500.00,1600.00,-10900.00,-11950.00,1050.00 --11000.00,-13050.00,2050.00,-11000.00,-12350.00,1350.00 --11100.00,-12550.00,1450.00,-11100.00,-11950.00,850.00 --11200.00,-13050.00,1850.00,-11200.00,-12400.00,1200.00 --11300.00,-12200.00,900.00,-11300.00,-11650.00,350.00 --11400.00,-12750.00,1350.00,-11400.00,-12250.00,850.00 --11500.00,-13150.00,1650.00,-11500.00,-12450.00,950.00 --11600.00,-13250.00,1650.00,-11600.00,-12350.00,750.00 --11700.00,-13850.00,2150.00,-11700.00,-13200.00,1500.00 --11800.00,-13400.00,1600.00,-11800.00,-12800.00,1000.00 --11900.00,-13250.00,1350.00,-11900.00,-12650.00,750.00 --12000.00,-12750.00,750.00,-12000.00,-12250.00,250.00 --12100.00,-13600.00,1500.00,-12100.00,-12950.00,850.00 --12200.00,-14050.00,1850.00,-12200.00,-13200.00,1000.00 --12300.00,-14200.00,1900.00,-12300.00,-13350.00,1050.00 --12400.00,-14100.00,1700.00,-12400.00,-13500.00,1100.00 --12500.00,-14200.00,1700.00,-12500.00,-13850.00,1350.00 --12600.00,-15000.00,2400.00,-12600.00,-14750.00,2150.00 --12700.00,-14950.00,2250.00,-12700.00,-14900.00,2200.00 --12800.00,-14750.00,1950.00,-12800.00,-14700.00,1900.00 --12900.00,-14050.00,1150.00,-12900.00,-14050.00,1150.00 --13000.00,-14350.00,1350.00,-13000.00,-14150.00,1150.00 --13100.00,-14900.00,1800.00,-13100.00,-14650.00,1550.00 --13200.00,-14950.00,1750.00,-13200.00,-14950.00,1750.00 --13300.00,-15250.00,1950.00,-13300.00,-15000.00,1700.00 --13400.00,-15400.00,2000.00,-13400.00,-15150.00,1750.00 --13500.00,-15500.00,2000.00,-13500.00,-15250.00,1750.00 --13600.00,-15600.00,2000.00,-13600.00,-15350.00,1750.00 --13700.00,-15700.00,2000.00,-13700.00,-15550.00,1850.00 --13800.00,-15850.00,2050.00,-13800.00,-15600.00,1800.00 --13900.00,-16100.00,2200.00,-13900.00,-15750.00,1850.00 --14000.00,-16150.00,2150.00,-14000.00,-15850.00,1850.00 --14100.00,-16200.00,2100.00,-14100.00,-16000.00,1900.00 --14200.00,-16350.00,2150.00,-14200.00,-16050.00,1850.00 --14300.00,-16450.00,2150.00,-14300.00,-16150.00,1850.00 --14400.00,-16650.00,2250.00,-14400.00,-16200.00,1800.00 --14500.00,-16850.00,2350.00,-14500.00,-16400.00,1900.00 --14600.00,-16950.00,2350.00,-14600.00,-16500.00,1900.00 --14700.00,-17050.00,2350.00,-14700.00,-16650.00,1950.00 --14800.00,-17200.00,2400.00,-14800.00,-16650.00,1850.00 --14900.00,-17250.00,2350.00,-14900.00,-16750.00,1850.00 --15000.00,-17150.00,2150.00,-15000.00,-16550.00,1550.00 --15100.00,-17600.00,2500.00,-15100.00,-16700.00,1600.00 --15200.00,-17600.00,2400.00,-15200.00,-16950.00,1750.00 --15300.00,-17650.00,2350.00,-15300.00,-17250.00,1950.00 --15400.00,-17950.00,2550.00,-15400.00,-17350.00,1950.00 --15500.00,-18600.00,3100.00,-15500.00,-18050.00,2550.00 --15600.00,-17900.00,2300.00,-15600.00,-17250.00,1650.00 --15700.00,-17800.00,2100.00,-15700.00,-17050.00,1350.00 --15800.00,-21450.00,5650.00,-15800.00,-20550.00,4750.00 --15900.00,-18550.00,2650.00,-15900.00,-17500.00,1600.00 --16000.00,-16900.00,900.00,-16000.00,-16250.00,250.00 --16100.00,-17600.00,1500.00,-16100.00,-16950.00,850.00 --16200.00,-18450.00,2250.00,-16200.00,-17700.00,1500.00 --16300.00,-19750.00,3450.00,-16300.00,-19650.00,3350.00 --16400.00,-19100.00,2700.00,-16400.00,-19400.00,3000.00 --16500.00,-19650.00,3150.00,-16500.00,-19700.00,3200.00 --16600.00,-18800.00,2200.00,-16600.00,-18550.00,1950.00 --16700.00,-18900.00,2200.00,-16700.00,-18650.00,1950.00 --16800.00,-19200.00,2400.00,-16800.00,-18950.00,2150.00 --16900.00,-19650.00,2750.00,-16900.00,-19300.00,2400.00 --17000.00,-19900.00,2900.00,-17000.00,-19350.00,2350.00 --17100.00,-20450.00,3350.00,-17100.00,-20400.00,3300.00 --17200.00,-20650.00,3450.00,-17200.00,-20450.00,3250.00 --17300.00,-19700.00,2400.00,-17300.00,-19400.00,2100.00 --17400.00,-19750.00,2350.00,-17400.00,-19350.00,1950.00 --17500.00,-21000.00,3500.00,-17500.00,-20750.00,3250.00 --17600.00,-21250.00,3650.00,-17600.00,-21050.00,3450.00 --17700.00,-20300.00,2600.00,-17700.00,-20150.00,2450.00 --17800.00,-21150.00,3350.00,-17800.00,-20700.00,2900.00 --17900.00,-20450.00,2550.00,-17743.79,-20200.00,2456.21 --17951.36,-21550.00,3598.64,-17643.79,-20750.00,3106.21 --17851.36,-20850.00,2998.64,-17543.79,-20100.00,2556.21 --17751.36,-21650.00,3898.64,-17443.79,-20700.00,3256.21 --17651.36,-20800.00,3148.64,-17343.79,-19650.00,2306.21 --17551.36,-21300.00,3748.64,-17243.79,-20350.00,3106.21 --17451.36,-21050.00,3598.64,-17143.79,-20300.00,3156.21 --17351.36,-20750.00,3398.64,-17043.79,-20000.00,2956.21 --17251.36,-20000.00,2748.64,-16943.79,-18450.00,1506.21 --17151.36,-19650.00,2498.64,-16843.79,-18850.00,2006.21 --17051.36,-20900.00,3848.64,-16743.79,-19650.00,2906.21 --16951.36,-20900.00,3948.64,-16643.79,-19550.00,2906.21 --16851.36,-19600.00,2748.64,-16543.79,-18600.00,2056.21 --16751.36,-19350.00,2598.64,-16443.79,-18350.00,1906.21 --16651.36,-19650.00,2998.64,-16343.79,-18750.00,2406.21 --16551.36,-19450.00,2898.64,-16243.79,-19200.00,2956.21 --16451.36,-19450.00,2998.64,-16143.79,-19250.00,3106.21 --16351.36,-19200.00,2848.64,-16043.79,-19000.00,2956.21 --16251.36,-19000.00,2748.64,-15943.79,-18850.00,2906.21 --16151.36,-18950.00,2798.64,-15843.79,-18400.00,2556.21 --16051.36,-18950.00,2898.64,-15743.79,-18200.00,2456.21 --15951.36,-18800.00,2848.64,-15643.79,-17600.00,1956.21 --15851.36,-19500.00,3648.64,-15543.79,-18550.00,3006.21 --15751.36,-18700.00,2948.64,-15443.79,-17900.00,2456.21 --15651.36,-18200.00,2548.64,-15343.79,-17550.00,2206.21 --15551.36,-18850.00,3298.64,-15243.79,-18150.00,2906.21 --15451.36,-18100.00,2648.64,-15143.79,-17450.00,2306.21 --15351.36,-18550.00,3198.64,-15043.79,-17800.00,2756.21 --15251.36,-17900.00,2648.64,-14943.79,-17050.00,2106.21 --15151.36,-17650.00,2498.64,-14843.79,-16950.00,2106.21 --15051.36,-16950.00,1898.64,-14743.79,-16250.00,1506.21 --14951.36,-17900.00,2948.64,-14643.79,-17000.00,2356.21 --14851.36,-17900.00,3048.64,-14543.79,-17200.00,2656.21 --14751.36,-17600.00,2848.64,-14443.79,-16950.00,2506.21 --14651.36,-17350.00,2698.64,-14343.79,-16450.00,2106.21 --14551.36,-17200.00,2648.64,-14243.79,-16050.00,1806.21 --14451.36,-16850.00,2398.64,-14143.79,-15800.00,1656.21 --14351.36,-17050.00,2698.64,-14043.79,-15750.00,1706.21 --14251.36,-16900.00,2648.64,-13943.79,-15750.00,1806.21 --14151.36,-17300.00,3148.64,-13843.79,-16500.00,2656.21 --14051.36,-16450.00,2398.64,-13743.79,-15500.00,1756.21 --13951.36,-16100.00,2148.64,-13643.79,-15300.00,1656.21 --13851.36,-16050.00,2198.64,-13543.79,-15150.00,1606.21 --13751.36,-15500.00,1748.64,-13443.79,-14400.00,956.21 --13651.36,-16050.00,2398.64,-13343.79,-14900.00,1556.21 --13551.36,-16150.00,2598.64,-13243.79,-14950.00,1706.21 --13451.36,-15950.00,2498.64,-13143.79,-14550.00,1406.21 --13351.36,-15800.00,2448.64,-13043.79,-14450.00,1406.21 --13251.36,-15500.00,2248.64,-12943.79,-14450.00,1506.21 --13151.36,-15400.00,2248.64,-12843.79,-14500.00,1656.21 --13051.36,-15200.00,2148.64,-12743.79,-14600.00,1856.21 --12951.36,-15100.00,2148.64,-12643.79,-14700.00,2056.21 --12851.36,-15050.00,2198.64,-12543.79,-14600.00,2056.21 --12751.36,-14850.00,2098.64,-12443.79,-14450.00,2006.21 --12651.36,-14650.00,1998.64,-12343.79,-14100.00,1756.21 --12551.36,-14750.00,2198.64,-12243.79,-14300.00,2056.21 --12451.36,-17350.00,4898.64,-12143.79,-16900.00,4756.21 --12351.36,-13450.00,1098.64,-12043.79,-13100.00,1056.21 --12251.36,-11750.00,-501.36,-11943.79,-11150.00,-793.79 --12151.36,-12500.00,348.64,-11843.79,-12400.00,556.21 --12051.36,-14000.00,1948.64,-11743.79,-13100.00,1356.21 --11951.36,-14750.00,2798.64,-11643.79,-13450.00,1806.21 --11851.36,-14500.00,2648.64,-11543.79,-13400.00,1856.21 --11751.36,-14100.00,2348.64,-11443.79,-13200.00,1756.21 --11651.36,-13900.00,2248.64,-11343.79,-13050.00,1706.21 --11551.36,-13550.00,1998.64,-11243.79,-12850.00,1606.21 --11451.36,-13400.00,1948.64,-11143.79,-12800.00,1656.21 --11351.36,-13500.00,2148.64,-11043.79,-12700.00,1656.21 --11251.36,-13250.00,1998.64,-10943.79,-12400.00,1456.21 --11151.36,-13150.00,1998.64,-10843.79,-12300.00,1456.21 --11051.36,-13050.00,1998.64,-10743.79,-12200.00,1456.21 --10951.36,-12900.00,1948.64,-10643.79,-12000.00,1356.21 --10851.36,-12800.00,1948.64,-10543.79,-12000.00,1456.21 --10751.36,-12700.00,1948.64,-10443.79,-11900.00,1456.21 --10651.36,-12600.00,1948.64,-10343.79,-11800.00,1456.21 --10551.36,-12500.00,1948.64,-10243.79,-11700.00,1456.21 --10451.36,-12300.00,1848.64,-10143.79,-11450.00,1306.21 --10351.36,-12100.00,1748.64,-10043.79,-11200.00,1156.21 --10251.36,-12050.00,1798.64,-9943.79,-10950.00,1006.21 --10151.36,-11950.00,1798.64,-9843.79,-10750.00,906.21 --10051.36,-11700.00,1648.64,-9743.79,-10550.00,806.21 --9951.36,-11650.00,1698.64,-9643.79,-10450.00,806.21 --9851.36,-11950.00,2098.64,-9543.79,-10750.00,1206.21 --9751.36,-11300.00,1548.64,-9443.79,-10300.00,856.21 --9651.36,-10950.00,1298.64,-9343.79,-10150.00,806.21 --9551.36,-10950.00,1398.64,-9243.79,-10150.00,906.21 --9451.36,-10950.00,1498.64,-9143.79,-10250.00,1106.21 --9351.36,-10850.00,1498.64,-9043.79,-10050.00,1006.21 --9251.36,-10800.00,1548.64,-8943.79,-9800.00,856.21 --9151.36,-10700.00,1548.64,-8843.79,-9700.00,856.21 --9051.36,-10500.00,1448.64,-8743.79,-9500.00,756.21 --8951.36,-10400.00,1448.64,-8643.79,-9250.00,606.21 --8851.36,-10200.00,1348.64,-8543.79,-9150.00,606.21 --8751.36,-10100.00,1348.64,-8443.79,-8950.00,506.21 --8651.36,-9950.00,1298.64,-8343.79,-8700.00,356.21 --8551.36,-10250.00,1698.64,-8243.79,-8950.00,706.21 --8451.36,-9200.00,748.64,-8143.79,-8300.00,156.21 --8351.36,-8000.00,-351.36,-8043.79,-8150.00,106.21 --8251.36,-8750.00,498.64,-7943.79,-8050.00,106.21 --8151.36,-9250.00,1098.64,-7843.79,-8100.00,256.21 --8051.36,-9450.00,1398.64,-7743.79,-8200.00,456.21 --7951.36,-8850.00,898.64,-7643.79,-8100.00,456.21 --7851.36,-7650.00,-201.36,-7543.79,-8100.00,556.21 --7751.36,-8700.00,948.64,-7443.79,-8600.00,1156.21 --7651.36,-8600.00,948.64,-7343.79,-7800.00,456.21 --7551.36,-8200.00,648.64,-7243.79,-7000.00,-243.79 --7451.36,-7250.00,-201.36,-7143.79,-7450.00,306.21 --7351.36,-7800.00,448.64,-7043.79,-7500.00,456.21 --7251.36,-8050.00,798.64,-6943.79,-7800.00,856.21 --7151.36,-7850.00,698.64,-6843.79,-7400.00,556.21 --7051.36,-6600.00,-451.36,-6743.79,-6300.00,-443.79 --6951.36,-6300.00,-651.36,-6643.79,-5850.00,-793.79 --6851.36,-6800.00,-51.36,-6543.79,-6350.00,-193.79 --6751.36,-7450.00,698.64,-6443.79,-7000.00,556.21 --6651.36,-7500.00,848.64,-6343.79,-6850.00,506.21 --6551.36,-6250.00,-301.36,-6243.79,-5800.00,-443.79 --6451.36,-6000.00,-451.36,-6143.79,-5350.00,-793.79 --6351.36,-6500.00,148.64,-6043.79,-5950.00,-93.79 --6251.36,-6550.00,298.64,-5943.79,-5850.00,-93.79 --6151.36,-5600.00,-551.36,-5843.79,-4950.00,-893.79 --6051.36,-5250.00,-801.36,-5743.79,-4750.00,-993.79 --5951.36,-6100.00,148.64,-5643.79,-5350.00,-293.79 --5851.36,-6350.00,498.64,-5543.79,-5500.00,-43.79 --5751.36,-5400.00,-351.36,-5443.79,-4600.00,-843.79 --5651.36,-4950.00,-701.36,-5343.79,-4300.00,-1043.79 --5551.36,-5700.00,148.64,-5243.79,-4850.00,-393.79 --5451.36,-5650.00,198.64,-5143.79,-4950.00,-193.79 --5351.36,-4700.00,-651.36,-5043.79,-3950.00,-1093.79 --5251.36,-4800.00,-451.36,-4943.79,-3900.00,-1043.79 --5151.36,-4850.00,-301.36,-4843.79,-4150.00,-693.79 --5051.36,-4100.00,-951.36,-4743.79,-4700.00,-43.79 --4951.36,-3800.00,-1151.36,-4643.79,-3800.00,-843.79 --4851.36,-4500.00,-351.36,-4543.79,-2950.00,-1593.79 --4751.36,-5900.00,1148.64,-4443.79,-3450.00,-993.79 --4651.36,-4200.00,-451.36,-4343.79,-3500.00,-843.79 --4551.36,-3350.00,-1201.36,-4243.79,-2350.00,-1893.79 --4451.36,-3050.00,-1401.36,-4143.79,-2450.00,-1693.79 --4351.36,-3900.00,-451.36,-4043.79,-3300.00,-743.79 --4251.36,-4300.00,48.64,-3943.79,-3600.00,-343.79 --4151.36,-3500.00,-651.36,-3843.79,-2700.00,-1143.79 --4051.36,-2900.00,-1151.36,-3743.79,-2300.00,-1443.79 --3951.36,-2450.00,-1501.36,-3643.79,-1050.00,-2593.79 --3851.36,-1850.00,-2001.36,-3543.79,-1650.00,-1893.79 --3751.36,-3150.00,-601.36,-3443.79,-3100.00,-343.79 --3651.36,-3800.00,148.64,-3343.79,-3300.00,-43.79 --3551.36,-3100.00,-451.36,-3243.79,-2300.00,-943.79 --3451.36,-2600.00,-851.36,-3143.79,-1900.00,-1243.79 --3351.36,-1950.00,-1401.36,-3043.79,-250.00,-2793.79 --3251.36,-850.00,-2401.36,-2943.79,100.00,-3043.79 --3151.36,-150.00,-3001.36,-2843.79,-1900.00,-943.79 --3051.36,-2100.00,-951.36,-2743.79,-2950.00,206.21 --2951.36,-3550.00,598.64,-2643.79,-2300.00,-343.79 --2851.36,-2850.00,-1.36,-2543.79,-1600.00,-943.79 --2751.36,-2150.00,-601.36,-2443.79,-700.00,-1743.79 --2651.36,-1850.00,-801.36,-2343.79,650.00,-2993.79 --2551.36,-500.00,-2051.36,-2243.79,-350.00,-1893.79 --2451.36,850.00,-3301.36,-2143.79,-1050.00,-1093.79 --2351.36,-400.00,-1951.36,-2043.79,300.00,-2343.79 --2251.36,-1200.00,-1051.36,-1943.79,850.00,-2793.79 --2151.36,-850.00,-1301.36,-1843.79,50.00,-1893.79 --2051.36,-1300.00,-751.36,-1743.79,-850.00,-893.79 --1951.36,300.00,-2251.36,-1643.79,600.00,-2243.79 --1851.36,400.00,-2251.36,-1543.79,850.00,-2393.79 --1751.36,-150.00,-1601.36,-1443.79,-350.00,-1093.79 --1651.36,0.00,-1651.36,-1343.79,-150.00,-1193.79 --1551.36,0.00,-1551.36,-1243.79,50.00,-1293.79 --1451.36,0.00,-1451.36,-1143.79,0.00,-1143.79 --1351.36,0.00,-1351.36,-1043.79,0.00,-1043.79 --1251.36,0.00,-1251.36,-943.79,0.00,-943.79 --1151.36,0.00,-1151.36,-843.79,0.00,-843.79 --1051.36,0.00,-1051.36,-743.79,0.00,-743.79 --951.36,0.00,-951.36,-643.79,0.00,-643.79 --851.36,0.00,-851.36,-543.79,0.00,-543.79 --751.36,0.00,-751.36,-443.79,0.00,-443.79 --651.36,0.00,-651.36,-343.79,0.00,-343.79 --551.36,0.00,-551.36,-243.79,0.00,-243.79 --451.36,0.00,-451.36,-143.79,0.00,-143.79 --351.36,0.00,-351.36,-43.79,0.00,-43.79 --251.36,0.00,-251.36,0.00,0.00,0.00 --151.36,0.00,-151.36,0.00,0.00,0.00 --51.36,0.00,-51.36,0.00,0.00,0.00 0.00,0.00,0.00,0.00,0.00,0.00 0.00,0.00,0.00,0.00,0.00,0.00 0.00,0.00,0.00,0.00,0.00,0.00 @@ -2100,6 +1741,358 @@ LeftSetpoint,LeftVelocity,LeftError,RightSetpoint,RightVelocity,RightError 0.00,0.00,0.00,0.00,0.00,0.00 0.00,0.00,0.00,0.00,0.00,0.00 0.00,0.00,0.00,0.00,0.00,0.00 +100.00,0.00,100.00,100.00,0.00,100.00 +200.00,0.00,200.00,200.00,0.00,200.00 +300.00,0.00,300.00,300.00,0.00,300.00 +400.00,0.00,400.00,400.00,0.00,400.00 +500.00,0.00,500.00,500.00,0.00,500.00 +600.00,0.00,600.00,600.00,0.00,600.00 +700.00,0.00,700.00,700.00,0.00,700.00 +800.00,0.00,800.00,800.00,0.00,800.00 +900.00,0.00,900.00,900.00,0.00,900.00 +1000.00,0.00,1000.00,1000.00,0.00,1000.00 +1100.00,0.00,1100.00,1100.00,0.00,1100.00 +1200.00,0.00,1200.00,1200.00,0.00,1200.00 +1300.00,0.00,1300.00,1300.00,0.00,1300.00 +1400.00,0.00,1400.00,1400.00,0.00,1400.00 +1500.00,0.00,1500.00,1500.00,0.00,1500.00 +1600.00,0.00,1600.00,1600.00,0.00,1600.00 +1700.00,0.00,1700.00,1700.00,0.00,1700.00 +1800.00,0.00,1800.00,1800.00,0.00,1800.00 +1900.00,0.00,1900.00,1900.00,0.00,1900.00 +2000.00,0.00,2000.00,2000.00,0.00,2000.00 +2100.00,0.00,2100.00,2100.00,0.00,2100.00 +2200.00,0.00,2200.00,2200.00,0.00,2200.00 +2300.00,0.00,2300.00,2300.00,0.00,2300.00 +2400.00,0.00,2400.00,2400.00,0.00,2400.00 +2500.00,450.00,2050.00,2500.00,400.00,2100.00 +2600.00,200.00,2400.00,2600.00,450.00,2150.00 +2700.00,-200.00,2900.00,2700.00,-800.00,3500.00 +2800.00,1150.00,1650.00,2800.00,350.00,2450.00 +2900.00,2200.00,700.00,2900.00,2500.00,400.00 +3000.00,1050.00,1950.00,3000.00,2500.00,500.00 +3100.00,100.00,3000.00,3100.00,1650.00,1450.00 +3200.00,850.00,2350.00,3200.00,-50.00,3250.00 +3300.00,2850.00,450.00,3300.00,150.00,3150.00 +3400.00,3550.00,-150.00,3400.00,1900.00,1500.00 +3500.00,3000.00,500.00,3500.00,2900.00,600.00 +3600.00,2400.00,1200.00,3600.00,2000.00,1600.00 +3700.00,1000.00,2700.00,3700.00,550.00,3150.00 +3800.00,1800.00,2000.00,3800.00,1500.00,2300.00 +3900.00,3400.00,500.00,3900.00,3500.00,400.00 +4000.00,4000.00,0.00,4000.00,3800.00,200.00 +4100.00,3150.00,950.00,4100.00,2450.00,1650.00 +4200.00,2500.00,1700.00,4200.00,2150.00,2050.00 +4300.00,2350.00,1950.00,4300.00,2950.00,1350.00 +4400.00,3350.00,1050.00,4400.00,3600.00,800.00 +4500.00,4050.00,450.00,4500.00,3550.00,950.00 +4600.00,3350.00,1250.00,4600.00,2500.00,2100.00 +4700.00,3100.00,1600.00,4700.00,1800.00,2900.00 +4800.00,3700.00,1100.00,4800.00,3650.00,1150.00 +4900.00,4600.00,300.00,4900.00,5050.00,-150.00 +5000.00,4850.00,150.00,5000.00,4800.00,200.00 +5100.00,4050.00,1050.00,5100.00,3750.00,1350.00 +5200.00,3700.00,1500.00,5200.00,2900.00,2300.00 +5300.00,4450.00,850.00,5300.00,3750.00,1550.00 +5400.00,5500.00,-100.00,5400.00,5100.00,300.00 +5500.00,5550.00,-50.00,5500.00,5050.00,450.00 +5600.00,4550.00,1050.00,5600.00,3850.00,1750.00 +5700.00,4300.00,1400.00,5700.00,3250.00,2450.00 +5800.00,5150.00,650.00,5800.00,4700.00,1100.00 +5900.00,6200.00,-300.00,5900.00,6150.00,-250.00 +6000.00,6250.00,-250.00,6000.00,5900.00,100.00 +6100.00,5400.00,700.00,6100.00,4550.00,1550.00 +6200.00,4900.00,1300.00,6200.00,3850.00,2350.00 +6300.00,5900.00,400.00,6300.00,5400.00,900.00 +6400.00,6700.00,-300.00,6400.00,6500.00,-100.00 +6500.00,6650.00,-150.00,6500.00,6700.00,-200.00 +6600.00,6050.00,550.00,6600.00,6000.00,600.00 +6700.00,6200.00,500.00,6700.00,4850.00,1850.00 +6800.00,7150.00,-350.00,6800.00,5650.00,1150.00 +6900.00,7500.00,-600.00,6900.00,6700.00,200.00 +7000.00,7300.00,-300.00,7000.00,7000.00,0.00 +7100.00,6500.00,600.00,7100.00,6800.00,300.00 +7200.00,7150.00,50.00,7200.00,6700.00,500.00 +7300.00,7650.00,-350.00,7300.00,6750.00,550.00 +7400.00,8050.00,-650.00,7400.00,6950.00,450.00 +7500.00,8350.00,-850.00,7500.00,7250.00,250.00 +7600.00,7900.00,-300.00,7600.00,7400.00,200.00 +7700.00,7200.00,500.00,7700.00,7500.00,200.00 +7800.00,7800.00,0.00,7800.00,7650.00,150.00 +7900.00,8500.00,-600.00,7900.00,7700.00,200.00 +8000.00,8950.00,-950.00,8000.00,8050.00,-50.00 +8100.00,9150.00,-1050.00,8100.00,8350.00,-250.00 +8200.00,9150.00,-950.00,8200.00,8400.00,-200.00 +8300.00,9200.00,-900.00,8300.00,8400.00,-100.00 +8400.00,9250.00,-850.00,8400.00,8600.00,-200.00 +8500.00,9400.00,-900.00,8500.00,8700.00,-200.00 +8600.00,11350.00,-2750.00,8600.00,10500.00,-1900.00 +8700.00,9150.00,-450.00,8700.00,8500.00,200.00 +8800.00,8250.00,550.00,8800.00,7400.00,1400.00 +8900.00,9250.00,-350.00,8900.00,8200.00,700.00 +9000.00,9900.00,-900.00,9000.00,9300.00,-300.00 +9100.00,10700.00,-1600.00,9100.00,10200.00,-1100.00 +9200.00,10850.00,-1650.00,9200.00,10150.00,-950.00 +9300.00,10500.00,-1200.00,9300.00,9400.00,-100.00 +9400.00,10450.00,-1050.00,9400.00,9300.00,100.00 +9500.00,10650.00,-1150.00,9500.00,9500.00,0.00 +9600.00,10700.00,-1100.00,9600.00,9800.00,-200.00 +9700.00,10850.00,-1150.00,9700.00,10150.00,-450.00 +9800.00,10950.00,-1150.00,9800.00,10400.00,-600.00 +9900.00,11200.00,-1300.00,9900.00,10500.00,-600.00 +10000.00,11800.00,-1800.00,10000.00,11000.00,-1000.00 +10100.00,11850.00,-1750.00,10100.00,11100.00,-1000.00 +10200.00,11700.00,-1500.00,10200.00,11100.00,-900.00 +10300.00,11700.00,-1400.00,10300.00,11100.00,-800.00 +10400.00,11800.00,-1400.00,10400.00,11150.00,-750.00 +10500.00,11900.00,-1400.00,10500.00,11350.00,-850.00 +10600.00,11650.00,-1050.00,10600.00,11050.00,-450.00 +10700.00,12250.00,-1550.00,10700.00,11800.00,-1100.00 +10800.00,12400.00,-1600.00,10800.00,12100.00,-1300.00 +10900.00,12500.00,-1600.00,10900.00,12100.00,-1200.00 +11000.00,12600.00,-1600.00,11000.00,12100.00,-1100.00 +11100.00,12600.00,-1500.00,11100.00,12050.00,-950.00 +11200.00,12700.00,-1500.00,11200.00,12150.00,-950.00 +11300.00,12400.00,-1100.00,11300.00,11800.00,-500.00 +11400.00,13150.00,-1750.00,11400.00,12650.00,-1250.00 +11500.00,13450.00,-1950.00,11500.00,12850.00,-1350.00 +11600.00,12950.00,-1350.00,11600.00,12450.00,-850.00 +11700.00,13050.00,-1350.00,11700.00,12500.00,-800.00 +11800.00,13350.00,-1550.00,11800.00,12800.00,-1000.00 +11900.00,13450.00,-1550.00,11900.00,13150.00,-1250.00 +12000.00,13550.00,-1550.00,12000.00,13200.00,-1200.00 +12100.00,13700.00,-1600.00,12100.00,13200.00,-1100.00 +12200.00,13850.00,-1650.00,12200.00,13200.00,-1000.00 +12300.00,14500.00,-2200.00,12300.00,13850.00,-1550.00 +12400.00,14050.00,-1650.00,12400.00,13400.00,-1000.00 +12500.00,13950.00,-1450.00,12500.00,13400.00,-900.00 +12600.00,14800.00,-2200.00,12600.00,14200.00,-1600.00 +12700.00,14950.00,-2250.00,12700.00,14300.00,-1600.00 +12800.00,14350.00,-1550.00,12800.00,13500.00,-700.00 +12900.00,14550.00,-1650.00,12900.00,13600.00,-700.00 +13000.00,15400.00,-2400.00,13000.00,14400.00,-1400.00 +13100.00,15550.00,-2450.00,13100.00,14700.00,-1600.00 +13200.00,15450.00,-2250.00,13200.00,14600.00,-1400.00 +13300.00,14850.00,-1550.00,13300.00,14100.00,-800.00 +13400.00,15500.00,-2100.00,13400.00,14800.00,-1400.00 +13500.00,15950.00,-2450.00,13500.00,15250.00,-1750.00 +13600.00,15450.00,-1850.00,13600.00,14950.00,-1350.00 +13700.00,16150.00,-2450.00,13700.00,15550.00,-1850.00 +13800.00,16450.00,-2650.00,13800.00,15750.00,-1950.00 +13900.00,15600.00,-1700.00,13900.00,15100.00,-1200.00 +14000.00,15600.00,-1600.00,14000.00,15200.00,-1200.00 +14100.00,16100.00,-2000.00,14100.00,15250.00,-1150.00 +14200.00,16250.00,-2050.00,14200.00,15750.00,-1550.00 +14300.00,16450.00,-2150.00,14300.00,16150.00,-1850.00 +14400.00,17250.00,-2850.00,14400.00,16850.00,-2450.00 +14500.00,16600.00,-2100.00,14500.00,16200.00,-1700.00 +14600.00,17150.00,-2550.00,14600.00,16750.00,-2150.00 +14700.00,16600.00,-1900.00,14700.00,16250.00,-1550.00 +14800.00,17400.00,-2600.00,14800.00,16900.00,-2100.00 +14900.00,17550.00,-2650.00,14900.00,17150.00,-2250.00 +15000.00,16800.00,-1800.00,15000.00,16500.00,-1500.00 +15100.00,17500.00,-2400.00,15100.00,17000.00,-1900.00 +15200.00,17750.00,-2550.00,15200.00,17450.00,-2250.00 +15300.00,17200.00,-1900.00,15300.00,16800.00,-1500.00 +15400.00,17900.00,-2500.00,15400.00,17500.00,-2100.00 +15500.00,18200.00,-2700.00,15500.00,17850.00,-2350.00 +15600.00,18300.00,-2700.00,15600.00,17750.00,-2150.00 +15700.00,18200.00,-2500.00,15700.00,17850.00,-2150.00 +15800.00,18150.00,-2350.00,15800.00,17900.00,-2100.00 +15900.00,18350.00,-2450.00,15900.00,17950.00,-2050.00 +16000.00,18500.00,-2500.00,16000.00,18050.00,-2050.00 +16100.00,18600.00,-2500.00,16100.00,18150.00,-2050.00 +16200.00,22300.00,-6100.00,16200.00,21500.00,-5300.00 +16300.00,17550.00,-1250.00,16300.00,17900.00,-1600.00 +16400.00,15200.00,1200.00,16400.00,17100.00,-700.00 +16500.00,16900.00,-400.00,16500.00,17650.00,-1150.00 +16600.00,19900.00,-3300.00,16600.00,18500.00,-1900.00 +16700.00,21050.00,-4350.00,16700.00,19050.00,-2350.00 +16800.00,20650.00,-3850.00,16800.00,19150.00,-2350.00 +16900.00,19850.00,-2950.00,16900.00,19250.00,-2350.00 +17000.00,19200.00,-2200.00,17000.00,18350.00,-1350.00 +17100.00,20300.00,-3200.00,17100.00,19550.00,-2450.00 +17200.00,20450.00,-3250.00,17033.32,19800.00,-2766.68 +17300.00,19650.00,-2350.00,16933.32,19150.00,-2216.68 +17400.00,20800.00,-3400.00,16833.32,19700.00,-2866.68 +17500.00,21200.00,-3700.00,16733.32,19650.00,-2916.68 +17600.00,20800.00,-3200.00,16633.32,19300.00,-2666.68 +17513.92,20800.00,-3286.08,16533.32,18950.00,-2416.68 +17413.92,21000.00,-3586.08,16433.32,18850.00,-2416.68 +17313.92,20800.00,-3486.08,16333.32,18900.00,-2566.68 +17213.92,20500.00,-3286.08,16233.32,18750.00,-2516.68 +17113.92,20300.00,-3186.08,16133.32,18650.00,-2516.68 +17013.92,20200.00,-3186.08,16033.32,18400.00,-2366.68 +16913.92,20100.00,-3186.08,15933.32,18200.00,-2266.68 +16813.92,20100.00,-3286.08,15833.32,18300.00,-2466.68 +16713.92,20000.00,-3286.08,15733.32,18200.00,-2466.68 +16613.92,19800.00,-3186.08,15633.32,17900.00,-2266.68 +16513.92,19750.00,-3236.08,15533.32,17800.00,-2266.68 +16413.92,19500.00,-3086.08,15433.32,17800.00,-2366.68 +16313.92,19350.00,-3036.08,15333.32,17700.00,-2366.68 +16213.92,19200.00,-2986.08,15233.32,17550.00,-2316.68 +16113.92,19150.00,-3036.08,15133.32,17250.00,-2116.68 +16013.92,19050.00,-3036.08,15033.32,17000.00,-1966.68 +15913.92,18950.00,-3036.08,14933.32,17000.00,-2066.68 +15813.92,18850.00,-3036.08,14833.32,16800.00,-1966.68 +15713.92,18700.00,-2986.08,14733.32,16750.00,-2016.68 +15613.92,18550.00,-2936.08,14633.32,16550.00,-1916.68 +15513.92,18450.00,-2936.08,14533.32,16350.00,-1816.68 +15413.92,18350.00,-2936.08,14433.32,16150.00,-1716.68 +15313.92,18200.00,-2886.08,14333.32,16050.00,-1716.68 +15213.92,18100.00,-2886.08,14233.32,15850.00,-1616.68 +15113.92,18000.00,-2886.08,14133.32,15700.00,-1566.68 +15013.92,17950.00,-2936.08,14033.32,15850.00,-1816.68 +14913.92,17750.00,-2836.08,13933.32,15800.00,-1866.68 +14813.92,17650.00,-2836.08,13833.32,15600.00,-1766.68 +14713.92,17500.00,-2786.08,13733.32,15450.00,-1716.68 +14613.92,17350.00,-2736.08,13633.32,15350.00,-1716.68 +14513.92,17250.00,-2736.08,13533.32,15150.00,-1616.68 +14413.92,17000.00,-2586.08,13433.32,15000.00,-1566.68 +14313.92,16900.00,-2586.08,13333.32,14750.00,-1416.68 +14213.92,16850.00,-2636.08,13233.32,14650.00,-1416.68 +14113.92,16650.00,-2536.08,13133.32,14650.00,-1516.68 +14013.92,16600.00,-2586.08,13033.32,14700.00,-1666.68 +13913.92,16400.00,-2486.08,12933.32,14650.00,-1716.68 +13813.92,16350.00,-2536.08,12833.32,14550.00,-1716.68 +13713.92,16100.00,-2386.08,12733.32,14350.00,-1616.68 +13613.92,15350.00,-1736.08,12633.32,13750.00,-1116.68 +13513.92,15950.00,-2436.08,12533.32,14250.00,-1716.68 +13413.92,16050.00,-2636.08,12433.32,14300.00,-1866.68 +13313.92,15700.00,-2386.08,12333.32,13900.00,-1566.68 +13213.92,15400.00,-2186.08,12233.32,13750.00,-1516.68 +13113.92,15300.00,-2186.08,12133.32,13550.00,-1416.68 +13013.92,15100.00,-2086.08,12033.32,13400.00,-1366.68 +12913.92,15000.00,-2086.08,11933.32,13200.00,-1266.68 +12813.92,14950.00,-2136.08,11833.32,13000.00,-1166.68 +12713.92,14850.00,-2136.08,11733.32,12950.00,-1216.68 +12613.92,14650.00,-2036.08,11633.32,12850.00,-1216.68 +12513.92,14600.00,-2086.08,11533.32,12800.00,-1266.68 +12413.92,14400.00,-1986.08,11433.32,12600.00,-1166.68 +12313.92,13850.00,-1536.08,11333.32,12100.00,-766.68 +12213.92,14450.00,-2236.08,11233.32,12550.00,-1316.68 +12113.92,14500.00,-2386.08,11133.32,12550.00,-1416.68 +12013.92,13650.00,-1636.08,11033.32,11750.00,-716.68 +11913.92,13500.00,-1586.08,10933.32,11550.00,-616.68 +11813.92,13550.00,-1736.08,10833.32,11500.00,-666.68 +11713.92,14050.00,-2336.08,10733.32,11950.00,-1216.68 +11613.92,13350.00,-1736.08,10633.32,11350.00,-716.68 +11513.92,16150.00,-4636.08,10533.32,13650.00,-3116.68 +11413.92,12650.00,-1236.08,10433.32,10700.00,-266.68 +11313.92,11050.00,263.92,10333.32,9150.00,1183.32 +11213.92,11050.00,163.92,10233.32,9300.00,933.32 +11113.92,12300.00,-1186.08,10133.32,10500.00,-366.68 +11013.92,13200.00,-2186.08,10033.32,11300.00,-1266.68 +10913.92,14000.00,-3086.08,9933.32,11850.00,-1916.68 +10813.92,12750.00,-1936.08,9833.32,11400.00,-1566.68 +10713.92,11000.00,-286.08,9733.32,10650.00,-916.68 +10613.92,11300.00,-686.08,9633.32,10400.00,-766.68 +10513.92,11750.00,-1236.08,9533.32,9900.00,-366.68 +10413.92,12700.00,-2286.08,9433.32,10500.00,-1066.68 +10313.92,12450.00,-2136.08,9333.32,10200.00,-866.68 +10213.92,12100.00,-1886.08,9233.32,10050.00,-816.68 +10113.92,12400.00,-2286.08,9133.32,10400.00,-1266.68 +10013.92,12200.00,-2186.08,9033.32,10250.00,-1216.68 +9913.92,11750.00,-1836.08,8933.32,9900.00,-966.68 +9813.92,11150.00,-1336.08,8833.32,9300.00,-466.68 +9713.92,11600.00,-1886.08,8733.32,9500.00,-766.68 +9613.92,11450.00,-1836.08,8633.32,9450.00,-816.68 +9513.92,11200.00,-1686.08,8533.32,9300.00,-766.68 +9413.92,10700.00,-1286.08,8433.32,8800.00,-366.68 +9313.92,10650.00,-1336.08,8333.32,8550.00,-216.68 +9213.92,10600.00,-1386.08,8233.32,8550.00,-316.68 +9113.92,10900.00,-1786.08,8133.32,8850.00,-716.68 +9013.92,9900.00,-886.08,8033.32,8450.00,-416.68 +8913.92,8650.00,263.92,7933.32,8200.00,-266.68 +8813.92,9350.00,-536.08,7833.32,8250.00,-416.68 +8713.92,9950.00,-1236.08,7733.32,8200.00,-466.68 +8613.92,10550.00,-1936.08,7633.32,8400.00,-766.68 +8513.92,9700.00,-1186.08,7533.32,8000.00,-466.68 +8413.92,8350.00,63.92,7433.32,7800.00,-366.68 +8313.92,8850.00,-536.08,7333.32,7700.00,-366.68 +8213.92,9200.00,-986.08,7233.32,7600.00,-366.68 +8113.92,9400.00,-1286.08,7133.32,7500.00,-366.68 +8013.92,8900.00,-886.08,7033.32,7500.00,-466.68 +7913.92,7850.00,63.92,6933.32,7000.00,-66.68 +7813.92,8650.00,-836.08,6833.32,6450.00,383.32 +7713.92,8700.00,-986.08,6733.32,6400.00,333.32 +7613.92,8300.00,-686.08,6633.32,6750.00,-116.68 +7513.92,7400.00,113.92,6533.32,6950.00,-416.68 +7413.92,7800.00,-386.08,6433.32,6750.00,-316.68 +7313.92,8200.00,-886.08,6333.32,5550.00,783.32 +7213.92,8350.00,-1136.08,6233.32,5100.00,1133.32 +7113.92,6700.00,413.92,6133.32,5650.00,483.32 +7013.92,6450.00,563.92,6033.32,6200.00,-166.68 +6913.92,7150.00,-236.08,5933.32,6200.00,-266.68 +6813.92,7900.00,-1086.08,5833.32,5100.00,733.32 +6713.92,7650.00,-936.08,5733.32,4300.00,1433.32 +6613.92,6500.00,113.92,5633.32,5000.00,633.32 +6513.92,6100.00,413.92,5533.32,5550.00,-16.68 +6413.92,6650.00,-236.08,5433.32,5550.00,-116.68 +6313.92,6700.00,-386.08,5333.32,4350.00,983.32 +6213.92,5750.00,463.92,5233.32,3850.00,1383.32 +6113.92,5500.00,613.92,5133.32,4200.00,933.32 +6013.92,6100.00,-86.08,5033.32,4700.00,333.32 +5913.92,6300.00,-386.08,4933.32,4650.00,283.32 +5813.92,5450.00,363.92,4833.32,3450.00,1383.32 +5713.92,5200.00,513.92,4733.32,3000.00,1733.32 +5613.92,5700.00,-86.08,4633.32,3800.00,833.32 +5513.92,5800.00,-286.08,4533.32,4150.00,383.32 +5413.92,4950.00,463.92,4433.32,3050.00,1383.32 +5313.92,4350.00,963.92,4333.32,2400.00,1933.32 +5213.92,4100.00,1113.92,4233.32,3300.00,933.32 +5113.92,5150.00,-36.08,4133.32,3800.00,333.32 +5013.92,5350.00,-336.08,4033.32,2650.00,1383.32 +4913.92,4650.00,263.92,3933.32,2050.00,1883.32 +4813.92,4000.00,813.92,3833.32,2800.00,1033.32 +4713.92,3300.00,1413.92,3733.32,3150.00,583.32 +4613.92,3100.00,1513.92,3633.32,2000.00,1633.32 +4513.92,4250.00,263.92,3533.32,1650.00,1883.32 +4413.92,4800.00,-386.08,3433.32,2350.00,1083.32 +4313.92,4050.00,263.92,3333.32,2450.00,883.32 +4213.92,3400.00,813.92,3233.32,1500.00,1733.32 +4113.92,2950.00,1163.92,3133.32,-250.00,3383.32 +4013.92,2000.00,2013.92,3033.32,-100.00,3133.32 +3913.92,2450.00,1463.92,2933.32,2200.00,733.32 +3813.92,3600.00,213.92,2833.32,3750.00,-916.68 +3713.92,2550.00,1163.92,2733.32,1950.00,783.32 +3613.92,1550.00,2063.92,2633.32,1200.00,1433.32 +3513.92,2300.00,1213.92,2533.32,750.00,1783.32 +3413.92,2800.00,613.92,2433.32,-350.00,2783.32 +3313.92,2000.00,1313.92,2333.32,300.00,2033.32 +3213.92,1800.00,1413.92,2233.32,450.00,1783.32 +3113.92,600.00,2513.92,2133.32,-800.00,2933.32 +3013.92,1450.00,1563.92,2033.32,300.00,1733.32 +2913.92,2300.00,613.92,1933.32,900.00,1033.32 +2813.92,2050.00,763.92,1833.32,-600.00,2433.32 +2713.92,1000.00,1713.92,1733.32,-1000.00,2733.32 +2613.92,1350.00,1263.92,1633.32,300.00,1333.32 +2513.92,500.00,2013.92,1533.32,250.00,1283.32 +2413.92,-800.00,3213.92,1433.32,-50.00,1483.32 +2313.92,800.00,1513.92,1333.32,0.00,1333.32 +2213.92,1700.00,513.92,1233.32,0.00,1233.32 +2113.92,1650.00,463.92,1133.32,0.00,1133.32 +2013.92,300.00,1713.92,1033.32,0.00,1033.32 +1913.92,-750.00,2663.92,933.32,0.00,933.32 +1813.92,-600.00,2413.92,833.32,0.00,833.32 +1713.92,300.00,1413.92,733.32,0.00,733.32 +1613.92,50.00,1563.92,633.32,0.00,633.32 +1513.92,0.00,1513.92,533.32,0.00,533.32 +1413.92,0.00,1413.92,433.32,0.00,433.32 +1313.92,0.00,1313.92,333.32,0.00,333.32 +1213.92,0.00,1213.92,233.32,0.00,233.32 +1113.92,0.00,1113.92,133.32,0.00,133.32 +1013.92,0.00,1013.92,33.32,0.00,33.32 +913.92,0.00,913.92,0.00,0.00,0.00 +813.92,0.00,813.92,0.00,0.00,0.00 +713.92,0.00,713.92,0.00,0.00,0.00 +613.92,0.00,613.92,0.00,0.00,0.00 +513.92,0.00,513.92,0.00,0.00,0.00 +413.92,0.00,413.92,0.00,0.00,0.00 +313.92,0.00,313.92,0.00,0.00,0.00 +213.92,0.00,213.92,0.00,0.00,0.00 +113.92,0.00,113.92,0.00,0.00,0.00 +13.92,0.00,13.92,0.00,0.00,0.00 0.00,0.00,0.00,0.00,0.00,0.00 0.00,0.00,0.00,0.00,0.00,0.00 0.00,0.00,0.00,0.00,0.00,0.00 @@ -2192,368 +2185,6 @@ LeftSetpoint,LeftVelocity,LeftError,RightSetpoint,RightVelocity,RightError 0.00,0.00,0.00,0.00,0.00,0.00 0.00,0.00,0.00,0.00,0.00,0.00 0.00,0.00,0.00,0.00,0.00,0.00 -100.00,0.00,100.00,100.00,0.00,100.00 -200.00,0.00,200.00,200.00,0.00,200.00 -300.00,0.00,300.00,300.00,0.00,300.00 -400.00,0.00,400.00,400.00,0.00,400.00 -500.00,0.00,500.00,500.00,0.00,500.00 -600.00,0.00,600.00,600.00,0.00,600.00 -700.00,0.00,700.00,700.00,0.00,700.00 -800.00,0.00,800.00,800.00,0.00,800.00 -900.00,0.00,900.00,900.00,0.00,900.00 -1000.00,0.00,1000.00,1000.00,0.00,1000.00 -1100.00,0.00,1100.00,1100.00,0.00,1100.00 -1200.00,0.00,1200.00,1200.00,0.00,1200.00 -1300.00,0.00,1300.00,1300.00,0.00,1300.00 -1400.00,0.00,1400.00,1400.00,0.00,1400.00 -1500.00,0.00,1500.00,1500.00,0.00,1500.00 -1600.00,0.00,1600.00,1600.00,0.00,1600.00 -1700.00,0.00,1700.00,1700.00,0.00,1700.00 -1800.00,0.00,1800.00,1800.00,0.00,1800.00 -1900.00,0.00,1900.00,1900.00,0.00,1900.00 -2000.00,0.00,2000.00,2000.00,0.00,2000.00 -2100.00,0.00,2100.00,2100.00,0.00,2100.00 -2200.00,0.00,2200.00,2200.00,0.00,2200.00 -2300.00,0.00,2300.00,2300.00,0.00,2300.00 -2400.00,0.00,2400.00,2400.00,0.00,2400.00 -2500.00,0.00,2500.00,2500.00,0.00,2500.00 -2600.00,450.00,2150.00,2600.00,450.00,2150.00 -2700.00,300.00,2400.00,2700.00,450.00,2250.00 -2800.00,-200.00,3000.00,2800.00,-800.00,3600.00 -2900.00,1050.00,1850.00,2900.00,500.00,2400.00 -3000.00,2400.00,600.00,3000.00,2450.00,550.00 -3100.00,1300.00,1800.00,3100.00,2650.00,450.00 -3200.00,1450.00,1750.00,3200.00,2100.00,1100.00 -3300.00,300.00,3000.00,3300.00,400.00,2900.00 -3400.00,300.00,3100.00,3400.00,700.00,2700.00 -3500.00,1950.00,1550.00,3500.00,2600.00,900.00 -3600.00,3100.00,500.00,3600.00,3300.00,300.00 -3700.00,2700.00,1000.00,3700.00,2400.00,1300.00 -3800.00,2200.00,1600.00,3800.00,1050.00,2750.00 -3900.00,1300.00,2600.00,3900.00,1150.00,2750.00 -4000.00,2850.00,1150.00,4000.00,3200.00,800.00 -4100.00,3800.00,300.00,4100.00,3900.00,200.00 -4200.00,3050.00,1150.00,4200.00,2900.00,1300.00 -4300.00,2500.00,1800.00,4300.00,2600.00,1700.00 -4400.00,2000.00,2400.00,4400.00,3100.00,1300.00 -4500.00,3550.00,950.00,4500.00,3950.00,550.00 -4600.00,4200.00,400.00,4600.00,3650.00,950.00 -4700.00,3550.00,1150.00,4700.00,2900.00,1800.00 -4800.00,3300.00,1500.00,4800.00,2900.00,1900.00 -4900.00,4050.00,850.00,4900.00,3950.00,950.00 -5000.00,4600.00,400.00,5000.00,4650.00,350.00 -5100.00,5000.00,100.00,5100.00,4750.00,350.00 -5200.00,4000.00,1200.00,5200.00,3850.00,1350.00 -5300.00,3750.00,1550.00,5300.00,3350.00,1950.00 -5400.00,4550.00,850.00,5400.00,4350.00,1050.00 -5500.00,5600.00,-100.00,5500.00,5500.00,0.00 -5600.00,5800.00,-200.00,5600.00,5500.00,100.00 -5700.00,4750.00,950.00,5700.00,4500.00,1200.00 -5800.00,4300.00,1500.00,5800.00,4150.00,1650.00 -5900.00,5150.00,750.00,5900.00,4850.00,1050.00 -6000.00,6250.00,-250.00,6000.00,6000.00,0.00 -6100.00,6000.00,100.00,6100.00,6000.00,100.00 -6200.00,5650.00,550.00,6200.00,5450.00,750.00 -6300.00,6100.00,200.00,6300.00,5800.00,500.00 -6400.00,6550.00,-150.00,6400.00,6250.00,150.00 -6500.00,6250.00,250.00,6500.00,6300.00,200.00 -6600.00,6000.00,600.00,6600.00,6800.00,-200.00 -6700.00,6600.00,100.00,6700.00,6800.00,-100.00 -6800.00,6850.00,-50.00,6800.00,6600.00,200.00 -6900.00,7550.00,-650.00,6900.00,7000.00,-100.00 -7000.00,7350.00,-350.00,7000.00,7200.00,-200.00 -7100.00,6600.00,500.00,7100.00,7250.00,-150.00 -7200.00,7300.00,-100.00,7200.00,7450.00,-250.00 -7300.00,7750.00,-450.00,7300.00,7500.00,-200.00 -7400.00,8100.00,-700.00,7400.00,7650.00,-250.00 -7500.00,8300.00,-800.00,7500.00,7750.00,-250.00 -7600.00,8350.00,-750.00,7600.00,7900.00,-300.00 -7700.00,8100.00,-400.00,7700.00,7700.00,0.00 -7800.00,8500.00,-700.00,7800.00,8200.00,-400.00 -7900.00,8800.00,-900.00,7900.00,8200.00,-300.00 -8000.00,8850.00,-850.00,8000.00,8200.00,-200.00 -8100.00,8950.00,-850.00,8100.00,8150.00,-50.00 -8200.00,9000.00,-800.00,8200.00,8150.00,50.00 -8300.00,9150.00,-850.00,8300.00,8300.00,0.00 -8400.00,11100.00,-2700.00,8400.00,10100.00,-1700.00 -8500.00,8900.00,-400.00,8500.00,8050.00,450.00 -8600.00,7850.00,750.00,8600.00,7050.00,1550.00 -8700.00,9000.00,-300.00,8700.00,8050.00,650.00 -8800.00,9650.00,-850.00,8800.00,9250.00,-450.00 -8900.00,10050.00,-1150.00,8900.00,9750.00,-850.00 -9000.00,10300.00,-1300.00,9000.00,9700.00,-700.00 -9100.00,10350.00,-1250.00,9100.00,9650.00,-550.00 -9200.00,10150.00,-950.00,9200.00,9600.00,-400.00 -9300.00,10250.00,-950.00,9300.00,9800.00,-500.00 -9400.00,10500.00,-1100.00,9400.00,10000.00,-600.00 -9500.00,10650.00,-1150.00,9500.00,10250.00,-750.00 -9600.00,10800.00,-1200.00,9600.00,10450.00,-850.00 -9700.00,10800.00,-1100.00,9700.00,10500.00,-800.00 -9800.00,10900.00,-1100.00,9800.00,10600.00,-800.00 -9900.00,11050.00,-1150.00,9900.00,10750.00,-850.00 -10000.00,11200.00,-1200.00,10000.00,10750.00,-750.00 -10100.00,11200.00,-1100.00,10100.00,10900.00,-800.00 -10200.00,11250.00,-1050.00,10200.00,11100.00,-900.00 -10300.00,11500.00,-1200.00,10300.00,11200.00,-900.00 -10400.00,11650.00,-1250.00,10400.00,11500.00,-1100.00 -10500.00,11650.00,-1150.00,10500.00,11750.00,-1250.00 -10600.00,11800.00,-1200.00,10600.00,11850.00,-1250.00 -10700.00,11900.00,-1200.00,10700.00,11900.00,-1200.00 -10800.00,12150.00,-1350.00,10800.00,12100.00,-1300.00 -10900.00,12350.00,-1450.00,10900.00,12200.00,-1300.00 -11000.00,12350.00,-1350.00,11000.00,12200.00,-1200.00 -11100.00,12350.00,-1250.00,11100.00,12450.00,-1350.00 -11200.00,12500.00,-1300.00,11200.00,12650.00,-1450.00 -11300.00,12750.00,-1450.00,11300.00,12750.00,-1450.00 -11400.00,12850.00,-1450.00,11400.00,12750.00,-1350.00 -11500.00,12950.00,-1450.00,11500.00,12800.00,-1300.00 -11600.00,13050.00,-1450.00,11600.00,12950.00,-1350.00 -11700.00,13200.00,-1500.00,11700.00,13050.00,-1350.00 -11800.00,13300.00,-1500.00,11800.00,13000.00,-1200.00 -11900.00,13550.00,-1650.00,11900.00,13400.00,-1500.00 -12000.00,13750.00,-1750.00,12000.00,13600.00,-1600.00 -12100.00,13750.00,-1650.00,12100.00,13750.00,-1650.00 -12200.00,13800.00,-1600.00,12200.00,13750.00,-1550.00 -12300.00,14000.00,-1700.00,12300.00,13900.00,-1600.00 -12400.00,14150.00,-1750.00,12400.00,14000.00,-1600.00 -12500.00,14200.00,-1700.00,12500.00,14050.00,-1550.00 -12600.00,14450.00,-1850.00,12600.00,14150.00,-1550.00 -12700.00,14600.00,-1900.00,12700.00,14400.00,-1700.00 -12800.00,14750.00,-1950.00,12800.00,14400.00,-1600.00 -12900.00,14850.00,-1950.00,12900.00,14600.00,-1700.00 -13000.00,14950.00,-1950.00,13000.00,14800.00,-1800.00 -13100.00,15150.00,-2050.00,13100.00,14600.00,-1500.00 -13200.00,15250.00,-2050.00,13200.00,14750.00,-1550.00 -13300.00,15250.00,-1950.00,13300.00,14750.00,-1450.00 -13400.00,15450.00,-2050.00,13400.00,14900.00,-1500.00 -13500.00,15600.00,-2100.00,13500.00,15000.00,-1500.00 -13600.00,15550.00,-1950.00,13600.00,15150.00,-1550.00 -13700.00,15800.00,-2100.00,13700.00,15300.00,-1600.00 -13800.00,15800.00,-2000.00,13800.00,15450.00,-1650.00 -13900.00,15700.00,-1800.00,13900.00,15600.00,-1700.00 -14000.00,16150.00,-2150.00,14000.00,15800.00,-1800.00 -14100.00,16350.00,-2250.00,14100.00,16000.00,-1900.00 -14200.00,16350.00,-2150.00,14200.00,16000.00,-1800.00 -14300.00,16350.00,-2050.00,14300.00,16050.00,-1750.00 -14400.00,16350.00,-1950.00,14400.00,16150.00,-1750.00 -14500.00,16650.00,-2150.00,14500.00,16150.00,-1650.00 -14600.00,16750.00,-2150.00,14600.00,16350.00,-1750.00 -14700.00,16850.00,-2150.00,14700.00,16800.00,-2100.00 -14800.00,17000.00,-2200.00,14800.00,17100.00,-2300.00 -14900.00,16500.00,-1600.00,14900.00,16550.00,-1650.00 -15000.00,17250.00,-2250.00,15000.00,17500.00,-2500.00 -15100.00,17350.00,-2250.00,15100.00,17700.00,-2600.00 -15200.00,17600.00,-2400.00,15200.00,17750.00,-2550.00 -15300.00,17650.00,-2350.00,15300.00,17600.00,-2300.00 -15400.00,17650.00,-2250.00,15400.00,17450.00,-2050.00 -15500.00,17750.00,-2250.00,15500.00,17600.00,-2100.00 -15600.00,17800.00,-2200.00,15600.00,17800.00,-2200.00 -15700.00,17600.00,-1900.00,15700.00,17950.00,-2250.00 -15800.00,18300.00,-2500.00,15800.00,18200.00,-2400.00 -15900.00,18500.00,-2600.00,15900.00,18200.00,-2300.00 -16000.00,18350.00,-2350.00,16000.00,18300.00,-2300.00 -16100.00,22200.00,-6100.00,16100.00,22100.00,-6000.00 -16200.00,18200.00,-2000.00,16200.00,18200.00,-2000.00 -16300.00,17450.00,-1150.00,16300.00,17350.00,-1050.00 -16400.00,17950.00,-1550.00,16400.00,17900.00,-1500.00 -16500.00,18900.00,-2400.00,16500.00,18950.00,-2450.00 -16600.00,19450.00,-2850.00,16600.00,19600.00,-3000.00 -16700.00,19700.00,-3000.00,16700.00,19400.00,-2700.00 -16800.00,19750.00,-2950.00,16800.00,19150.00,-2350.00 -16900.00,19800.00,-2900.00,16900.00,19100.00,-2200.00 -17000.00,19850.00,-2850.00,17000.00,19150.00,-2150.00 -17100.00,19550.00,-2450.00,17100.00,19300.00,-2200.00 -17200.00,19950.00,-2750.00,17200.00,19300.00,-2100.00 -17300.00,20200.00,-2900.00,17300.00,19800.00,-2500.00 -17400.00,20100.00,-2700.00,17400.00,20200.00,-2800.00 -17500.00,20300.00,-2800.00,17500.00,20000.00,-2500.00 -17600.00,20500.00,-2900.00,17600.00,20250.00,-2650.00 -17700.00,20450.00,-2750.00,17700.00,20400.00,-2700.00 -17800.00,19650.00,-1850.00,17800.00,19650.00,-1850.00 -17900.00,20650.00,-2750.00,17741.55,20550.00,-2808.45 -18000.00,20700.00,-2700.00,17641.55,21150.00,-3508.45 -18100.00,21300.00,-3200.00,17541.55,21100.00,-3558.45 -18060.72,21250.00,-3189.28,17441.55,20900.00,-3458.45 -17960.72,21300.00,-3339.28,17341.55,20600.00,-3258.45 -17860.72,21100.00,-3239.28,17241.55,20450.00,-3208.45 -17760.72,20900.00,-3139.28,17141.55,20150.00,-3008.45 -17660.72,20700.00,-3039.28,17041.55,20000.00,-2958.45 -17560.72,20650.00,-3089.28,16941.55,19800.00,-2858.45 -17460.72,20450.00,-2989.28,16841.55,19700.00,-2858.45 -17360.72,20550.00,-3189.28,16741.55,19700.00,-2958.45 -17260.72,20450.00,-3189.28,16641.55,19600.00,-2958.45 -17160.72,20300.00,-3139.28,16541.55,19400.00,-2858.45 -17060.72,20200.00,-3139.28,16441.55,19350.00,-2908.45 -16960.72,20050.00,-3089.28,16341.55,19300.00,-2958.45 -16860.72,19950.00,-3089.28,16241.55,19250.00,-3008.45 -16760.72,19650.00,-2889.28,16141.55,19000.00,-2858.45 -16660.72,19800.00,-3139.28,16041.55,18850.00,-2808.45 -16560.72,19750.00,-3189.28,15941.55,18550.00,-2608.45 -16460.72,19700.00,-3239.28,15841.55,18100.00,-2258.45 -16360.72,19300.00,-2939.28,15741.55,18050.00,-2308.45 -16260.72,18600.00,-2339.28,15641.55,17300.00,-1658.45 -16160.72,19350.00,-3189.28,15541.55,18000.00,-2458.45 -16060.72,19200.00,-3139.28,15441.55,18150.00,-2708.45 -15960.72,18900.00,-2939.28,15341.55,17900.00,-2558.45 -15860.72,18550.00,-2689.28,15241.55,17750.00,-2508.45 -15760.72,18450.00,-2689.28,15141.55,17350.00,-2208.45 -15660.72,17700.00,-2039.28,15041.55,16850.00,-1808.45 -15560.72,18400.00,-2839.28,14941.55,17550.00,-2608.45 -15460.72,17800.00,-2339.28,14841.55,16850.00,-2008.45 -15360.72,18250.00,-2889.28,14741.55,17250.00,-2508.45 -15260.72,17450.00,-2189.28,14641.55,16500.00,-1858.45 -15160.72,18100.00,-2939.28,14541.55,17200.00,-2658.45 -15060.72,17950.00,-2889.28,14441.55,17100.00,-2658.45 -14960.72,17650.00,-2689.28,14341.55,16950.00,-2608.45 -14860.72,17400.00,-2539.28,14241.55,16850.00,-2608.45 -14760.72,17200.00,-2439.28,14141.55,16550.00,-2408.45 -14660.72,16400.00,-1739.28,14041.55,15850.00,-1808.45 -14560.72,16400.00,-1839.28,13941.55,16000.00,-2058.45 -14460.72,17100.00,-2639.28,13841.55,16800.00,-2958.45 -14360.72,17200.00,-2839.28,13741.55,16500.00,-2758.45 -14260.72,17150.00,-2889.28,13641.55,16050.00,-2408.45 -14160.72,16550.00,-2389.28,13541.55,15650.00,-2108.45 -14060.72,16350.00,-2289.28,13441.55,15600.00,-2158.45 -13960.72,15650.00,-1689.28,13341.55,15000.00,-1658.45 -13860.72,16400.00,-2539.28,13241.55,15500.00,-2258.45 -13760.72,16300.00,-2539.28,13141.55,15500.00,-2358.45 -13660.72,16350.00,-2689.28,13041.55,15550.00,-2508.45 -13560.72,15450.00,-1889.28,12941.55,14600.00,-1658.45 -13460.72,15350.00,-1889.28,12841.55,14400.00,-1558.45 -13360.72,16100.00,-2739.28,12741.55,15050.00,-2308.45 -13260.72,16000.00,-2739.28,12641.55,15050.00,-2408.45 -13160.72,15550.00,-2389.28,12541.55,14750.00,-2208.45 -13060.72,15250.00,-2189.28,12441.55,14200.00,-1758.45 -12960.72,15200.00,-2239.28,12341.55,14200.00,-1858.45 -12860.72,15250.00,-2389.28,12241.55,13950.00,-1708.45 -12760.72,15050.00,-2289.28,12141.55,13650.00,-1508.45 -12660.72,14700.00,-2039.28,12041.55,13400.00,-1358.45 -12560.72,14000.00,-1439.28,11941.55,12800.00,-858.45 -12460.72,14650.00,-2189.28,11841.55,13200.00,-1358.45 -12360.72,17700.00,-5339.28,11741.55,16000.00,-4258.45 -12260.72,13650.00,-1389.28,11641.55,12500.00,-858.45 -12160.72,11500.00,660.72,11541.55,10300.00,1241.55 -12060.72,12200.00,-139.28,11441.55,11400.00,41.55 -11960.72,14000.00,-2039.28,11341.55,13150.00,-1808.45 -11860.72,14550.00,-2689.28,11241.55,13550.00,-2308.45 -11760.72,14150.00,-2389.28,11141.55,13400.00,-2258.45 -11660.72,13800.00,-2139.28,11041.55,12850.00,-1808.45 -11560.72,13500.00,-1939.28,10941.55,12450.00,-1508.45 -11460.72,13200.00,-1739.28,10841.55,12200.00,-1358.45 -11360.72,13150.00,-1789.28,10741.55,12150.00,-1408.45 -11260.72,13150.00,-1889.28,10641.55,12000.00,-1358.45 -11160.72,13000.00,-1839.28,10541.55,11900.00,-1358.45 -11060.72,12900.00,-1839.28,10441.55,11950.00,-1508.45 -10960.72,12800.00,-1839.28,10341.55,12000.00,-1658.45 -10860.72,12650.00,-1789.28,10241.55,11850.00,-1608.45 -10760.72,12500.00,-1739.28,10141.55,11700.00,-1558.45 -10660.72,12400.00,-1739.28,10041.55,11650.00,-1608.45 -10560.72,12250.00,-1689.28,9941.55,11400.00,-1458.45 -10460.72,12100.00,-1639.28,9841.55,11400.00,-1558.45 -10360.72,12050.00,-1689.28,9741.55,11200.00,-1458.45 -10260.72,11900.00,-1639.28,9641.55,11250.00,-1608.45 -10160.72,11800.00,-1639.28,9541.55,11150.00,-1608.45 -10060.72,11250.00,-1189.28,9441.55,10600.00,-1158.45 -9960.72,11600.00,-1639.28,9341.55,10900.00,-1558.45 -9860.72,11650.00,-1789.28,9241.55,10850.00,-1608.45 -9760.72,11450.00,-1689.28,9141.55,10750.00,-1608.45 -9660.72,11300.00,-1639.28,9041.55,10450.00,-1408.45 -9560.72,11150.00,-1589.28,8941.55,10250.00,-1308.45 -9460.72,11000.00,-1539.28,8841.55,10000.00,-1158.45 -9360.72,10900.00,-1539.28,8741.55,10000.00,-1258.45 -9260.72,10900.00,-1639.28,8641.55,9900.00,-1258.45 -9160.72,10750.00,-1589.28,8541.55,9800.00,-1258.45 -9060.72,10550.00,-1489.28,8441.55,9600.00,-1158.45 -8960.72,10450.00,-1489.28,8341.55,9400.00,-1058.45 -8860.72,9900.00,-1039.28,8241.55,9000.00,-758.45 -8760.72,10250.00,-1489.28,8141.55,9300.00,-1158.45 -8660.72,10250.00,-1589.28,8041.55,9300.00,-1258.45 -8560.72,9700.00,-1139.28,7941.55,8700.00,-758.45 -8460.72,8500.00,-39.28,7841.55,7700.00,141.55 -8360.72,8800.00,-439.28,7741.55,7600.00,141.55 -8260.72,9050.00,-789.28,7641.55,8000.00,-358.45 -8160.72,9700.00,-1539.28,7541.55,8700.00,-1158.45 -8060.72,9300.00,-1239.28,7441.55,8400.00,-958.45 -7960.72,7450.00,510.72,7341.55,6750.00,591.55 -7860.72,7200.00,660.72,7241.55,6300.00,941.55 -7760.72,8250.00,-489.28,7141.55,7450.00,-308.45 -7660.72,9000.00,-1339.28,7041.55,7900.00,-858.45 -7560.72,8300.00,-739.28,6941.55,7400.00,-458.45 -7460.72,7350.00,110.72,6841.55,6200.00,641.55 -7360.72,8350.00,-989.28,6741.55,5950.00,791.55 -7260.72,7850.00,-589.28,6641.55,6150.00,491.55 -7160.72,7150.00,10.72,6541.55,7000.00,-458.45 -7060.72,7750.00,-689.28,6441.55,6850.00,-408.45 -6960.72,7600.00,-639.28,6341.55,5600.00,741.55 -6860.72,6050.00,810.72,6241.55,4650.00,1591.55 -6760.72,6000.00,760.72,6141.55,5500.00,641.55 -6660.72,6850.00,-189.28,6041.55,6150.00,-108.45 -6560.72,7400.00,-839.28,5941.55,5900.00,41.55 -6460.72,7600.00,-1139.28,5841.55,5000.00,841.55 -6360.72,6250.00,110.72,5741.55,4200.00,1541.55 -6260.72,5600.00,660.72,5641.55,4750.00,891.55 -6160.72,6300.00,-139.28,5541.55,5300.00,241.55 -6060.72,6350.00,-289.28,5441.55,5550.00,-108.45 -5960.72,5450.00,510.72,5341.55,4350.00,991.55 -5860.72,5250.00,610.72,5241.55,3750.00,1491.55 -5760.72,5550.00,210.72,5141.55,4350.00,791.55 -5660.72,5500.00,160.72,5041.55,4800.00,241.55 -5560.72,4900.00,660.72,4941.55,4850.00,91.55 -5460.72,4250.00,1210.72,4841.55,3800.00,1041.55 -5360.72,5150.00,210.72,4741.55,3200.00,1541.55 -5260.72,5100.00,160.72,4641.55,3700.00,941.55 -5160.72,4650.00,510.72,4541.55,4150.00,391.55 -5060.72,3750.00,1310.72,4441.55,3200.00,1241.55 -4960.72,3750.00,1210.72,4341.55,2700.00,1641.55 -4860.72,4350.00,510.72,4241.55,3400.00,841.55 -4760.72,4550.00,210.72,4141.55,3700.00,441.55 -4660.72,3950.00,710.72,4041.55,2900.00,1141.55 -4560.72,3900.00,660.72,3941.55,1750.00,2191.55 -4460.72,2400.00,2060.72,3841.55,1950.00,1891.55 -4360.72,2350.00,2010.72,3741.55,3100.00,641.55 -4260.72,3850.00,410.72,3641.55,3300.00,341.55 -4160.72,4600.00,-439.28,3541.55,2650.00,891.55 -4060.72,3650.00,410.72,3441.55,1600.00,1841.55 -3960.72,3150.00,810.72,3341.55,1200.00,2141.55 -3860.72,2450.00,1410.72,3241.55,2450.00,791.55 -3760.72,1450.00,2310.72,3141.55,3000.00,141.55 -3660.72,1450.00,2210.72,3041.55,2000.00,1041.55 -3560.72,3100.00,460.72,2941.55,1200.00,1741.55 -3460.72,3800.00,-339.28,2841.55,-50.00,2891.55 -3360.72,3050.00,310.72,2741.55,300.00,2441.55 -3260.72,2450.00,810.72,2641.55,2550.00,91.55 -3160.72,2050.00,1110.72,2541.55,3000.00,-458.45 -3060.72,300.00,2760.72,2441.55,1800.00,641.55 -2960.72,-150.00,3110.72,2341.55,1600.00,741.55 -2860.72,1750.00,1110.72,2241.55,150.00,2091.55 -2760.72,3100.00,-339.28,2141.55,-650.00,2791.55 -2660.72,2450.00,210.72,2041.55,500.00,1541.55 -2560.72,1950.00,610.72,1941.55,1000.00,941.55 -2460.72,1000.00,1460.72,1841.55,-300.00,2141.55 -2360.72,-450.00,2810.72,1741.55,-1000.00,2741.55 -2260.72,-450.00,2710.72,1641.55,-400.00,2041.55 -2160.72,1150.00,1010.72,1541.55,350.00,1191.55 -2060.72,1700.00,360.72,1441.55,50.00,1391.55 -1960.72,1150.00,810.72,1341.55,0.00,1341.55 -1860.72,-450.00,2310.72,1241.55,0.00,1241.55 -1760.72,-850.00,2610.72,1141.55,0.00,1141.55 -1660.72,250.00,1410.72,1041.55,0.00,1041.55 -1560.72,150.00,1410.72,941.55,0.00,941.55 -1460.72,0.00,1460.72,841.55,0.00,841.55 -1360.72,0.00,1360.72,741.55,0.00,741.55 -1260.72,0.00,1260.72,641.55,0.00,641.55 -1160.72,0.00,1160.72,541.55,0.00,541.55 -1060.72,0.00,1060.72,441.55,0.00,441.55 -960.72,0.00,960.72,341.55,0.00,341.55 -860.72,0.00,860.72,241.55,0.00,241.55 -760.72,0.00,760.72,141.55,0.00,141.55 -660.72,0.00,660.72,41.55,0.00,41.55 -560.72,0.00,560.72,0.00,0.00,0.00 -460.72,0.00,460.72,0.00,0.00,0.00 -360.72,0.00,360.72,0.00,0.00,0.00 -260.72,0.00,260.72,0.00,0.00,0.00 -160.72,0.00,160.72,0.00,0.00,0.00 -60.72,0.00,60.72,0.00,0.00,0.00 0.00,0.00,0.00,0.00,0.00,0.00 0.00,0.00,0.00,0.00,0.00,0.00 0.00,0.00,0.00,0.00,0.00,0.00 @@ -2571,6 +2202,381 @@ LeftSetpoint,LeftVelocity,LeftError,RightSetpoint,RightVelocity,RightError 0.00,0.00,0.00,0.00,0.00,0.00 0.00,0.00,0.00,0.00,0.00,0.00 0.00,0.00,0.00,0.00,0.00,0.00 +-100.00,0.00,-100.00,-100.00,0.00,-100.00 +-200.00,0.00,-200.00,-200.00,0.00,-200.00 +-300.00,0.00,-300.00,-300.00,0.00,-300.00 +-400.00,0.00,-400.00,-400.00,0.00,-400.00 +-500.00,0.00,-500.00,-500.00,0.00,-500.00 +-600.00,0.00,-600.00,-600.00,0.00,-600.00 +-700.00,0.00,-700.00,-700.00,0.00,-700.00 +-800.00,0.00,-800.00,-800.00,0.00,-800.00 +-900.00,0.00,-900.00,-900.00,0.00,-900.00 +-1000.00,0.00,-1000.00,-1000.00,0.00,-1000.00 +-1100.00,0.00,-1100.00,-1100.00,0.00,-1100.00 +-1200.00,0.00,-1200.00,-1200.00,0.00,-1200.00 +-1300.00,0.00,-1300.00,-1300.00,0.00,-1300.00 +-1400.00,0.00,-1400.00,-1400.00,0.00,-1400.00 +-1500.00,0.00,-1500.00,-1500.00,0.00,-1500.00 +-1600.00,0.00,-1600.00,-1600.00,0.00,-1600.00 +-1700.00,0.00,-1700.00,-1700.00,0.00,-1700.00 +-1800.00,0.00,-1800.00,-1800.00,0.00,-1800.00 +-1900.00,0.00,-1900.00,-1900.00,0.00,-1900.00 +-2000.00,0.00,-2000.00,-2000.00,0.00,-2000.00 +-2100.00,0.00,-2100.00,-2100.00,0.00,-2100.00 +-2200.00,0.00,-2200.00,-2200.00,0.00,-2200.00 +-2300.00,0.00,-2300.00,-2300.00,0.00,-2300.00 +-2400.00,0.00,-2400.00,-2400.00,0.00,-2400.00 +-2500.00,-450.00,-2050.00,-2500.00,-500.00,-2000.00 +-2600.00,-350.00,-2250.00,-2600.00,-600.00,-2000.00 +-2700.00,300.00,-3000.00,-2700.00,800.00,-3500.00 +-2800.00,-950.00,-1850.00,-2800.00,-200.00,-2600.00 +-2900.00,-2000.00,-900.00,-2900.00,-2400.00,-500.00 +-3000.00,-850.00,-2150.00,-3000.00,-2800.00,-200.00 +-3100.00,-150.00,-2950.00,-3100.00,-1800.00,-1300.00 +-3200.00,-1850.00,-1350.00,-3200.00,150.00,-3350.00 +-3300.00,-3000.00,-300.00,-3300.00,50.00,-3350.00 +-3400.00,-2400.00,-1000.00,-3400.00,-2650.00,-750.00 +-3500.00,-1650.00,-1850.00,-3500.00,-3800.00,300.00 +-3600.00,-1450.00,-2150.00,-3600.00,-2400.00,-1200.00 +-3700.00,-2550.00,-1150.00,-3700.00,-1450.00,-2250.00 +-3800.00,-2900.00,-900.00,-3800.00,-200.00,-3600.00 +-3900.00,-2450.00,-1450.00,-3900.00,-1900.00,-2000.00 +-4000.00,-2300.00,-1700.00,-4000.00,-4000.00,0.00 +-4100.00,-2850.00,-1250.00,-4100.00,-4000.00,-100.00 +-4200.00,-3750.00,-450.00,-4200.00,-2800.00,-1400.00 +-4300.00,-4000.00,-300.00,-4300.00,-1800.00,-2500.00 +-4400.00,-3300.00,-1100.00,-4400.00,-2900.00,-1500.00 +-4500.00,-3000.00,-1500.00,-4500.00,-4150.00,-350.00 +-4600.00,-3650.00,-950.00,-4600.00,-4000.00,-600.00 +-4700.00,-4550.00,-150.00,-4700.00,-2550.00,-2150.00 +-4800.00,-4700.00,-100.00,-4800.00,-2400.00,-2400.00 +-4900.00,-3700.00,-1200.00,-4900.00,-3750.00,-1150.00 +-5000.00,-3450.00,-1550.00,-5000.00,-4700.00,-300.00 +-5100.00,-4300.00,-800.00,-5100.00,-4550.00,-550.00 +-5200.00,-5400.00,200.00,-5200.00,-3450.00,-1750.00 +-5300.00,-5600.00,300.00,-5300.00,-2850.00,-2450.00 +-5400.00,-4600.00,-800.00,-5400.00,-4300.00,-1100.00 +-5500.00,-4250.00,-1250.00,-5500.00,-5650.00,150.00 +-5600.00,-4900.00,-700.00,-5600.00,-5250.00,-350.00 +-5700.00,-5700.00,0.00,-5700.00,-4300.00,-1400.00 +-5800.00,-5800.00,0.00,-5800.00,-3600.00,-2200.00 +-5900.00,-4700.00,-1200.00,-5900.00,-4400.00,-1500.00 +-6000.00,-4650.00,-1350.00,-6000.00,-6200.00,200.00 +-6100.00,-5650.00,-450.00,-6100.00,-6400.00,300.00 +-6200.00,-6400.00,200.00,-6200.00,-4750.00,-1450.00 +-6300.00,-6700.00,400.00,-6300.00,-4450.00,-1850.00 +-6400.00,-5650.00,-750.00,-6400.00,-5650.00,-750.00 +-6500.00,-5350.00,-1150.00,-6500.00,-6850.00,350.00 +-6600.00,-6300.00,-300.00,-6600.00,-6700.00,100.00 +-6700.00,-6950.00,250.00,-6700.00,-5500.00,-1200.00 +-6800.00,-7300.00,500.00,-6800.00,-5700.00,-1100.00 +-6900.00,-7350.00,450.00,-6900.00,-6600.00,-300.00 +-7000.00,-6200.00,-800.00,-7000.00,-7100.00,100.00 +-7100.00,-6000.00,-1100.00,-7100.00,-7250.00,150.00 +-7200.00,-7000.00,-200.00,-7200.00,-7150.00,-50.00 +-7300.00,-7700.00,400.00,-7300.00,-6800.00,-500.00 +-7400.00,-8550.00,1150.00,-7400.00,-7250.00,-150.00 +-7500.00,-8300.00,800.00,-7500.00,-7450.00,-50.00 +-7600.00,-7150.00,-450.00,-7600.00,-7250.00,-350.00 +-7700.00,-7850.00,150.00,-7700.00,-7600.00,-100.00 +-7800.00,-8450.00,650.00,-7800.00,-7750.00,-50.00 +-7900.00,-8900.00,1000.00,-7900.00,-8000.00,100.00 +-8000.00,-9100.00,1100.00,-8000.00,-7900.00,-100.00 +-8100.00,-9100.00,1000.00,-8100.00,-7900.00,-200.00 +-8200.00,-9050.00,850.00,-8200.00,-8050.00,-150.00 +-8300.00,-9200.00,900.00,-8300.00,-8250.00,-50.00 +-8400.00,-9400.00,1000.00,-8400.00,-8500.00,100.00 +-8500.00,-9500.00,1000.00,-8500.00,-8600.00,100.00 +-8600.00,-9550.00,950.00,-8600.00,-8650.00,50.00 +-8700.00,-11200.00,2500.00,-8700.00,-10050.00,1350.00 +-8800.00,-9000.00,200.00,-8800.00,-8350.00,-450.00 +-8900.00,-8400.00,-500.00,-8900.00,-8550.00,-350.00 +-9000.00,-9450.00,450.00,-9000.00,-9100.00,100.00 +-9100.00,-10300.00,1200.00,-9100.00,-9600.00,500.00 +-9200.00,-10550.00,1350.00,-9200.00,-9700.00,500.00 +-9300.00,-10750.00,1450.00,-9300.00,-9800.00,500.00 +-9400.00,-10800.00,1400.00,-9400.00,-9800.00,400.00 +-9500.00,-10300.00,800.00,-9500.00,-9500.00,0.00 +-9600.00,-10800.00,1200.00,-9600.00,-10100.00,500.00 +-9700.00,-11150.00,1450.00,-9700.00,-10500.00,800.00 +-9800.00,-11250.00,1450.00,-9800.00,-10550.00,750.00 +-9900.00,-11250.00,1350.00,-9900.00,-10600.00,700.00 +-10000.00,-11250.00,1250.00,-10000.00,-10550.00,550.00 +-10100.00,-11300.00,1200.00,-10100.00,-10700.00,600.00 +-10200.00,-11500.00,1300.00,-10200.00,-10750.00,550.00 +-10300.00,-11700.00,1400.00,-10300.00,-10900.00,600.00 +-10400.00,-11800.00,1400.00,-10400.00,-11100.00,700.00 +-10500.00,-11850.00,1350.00,-10500.00,-11300.00,800.00 +-10600.00,-11900.00,1300.00,-10600.00,-11450.00,850.00 +-10700.00,-12150.00,1450.00,-10700.00,-11600.00,900.00 +-10800.00,-12300.00,1500.00,-10800.00,-11700.00,900.00 +-10900.00,-12350.00,1450.00,-10900.00,-11900.00,1000.00 +-11000.00,-12450.00,1450.00,-11000.00,-12000.00,1000.00 +-11100.00,-12550.00,1450.00,-11100.00,-12100.00,1000.00 +-11200.00,-12750.00,1550.00,-11200.00,-12200.00,1000.00 +-11300.00,-12850.00,1550.00,-11300.00,-12400.00,1100.00 +-11400.00,-13000.00,1600.00,-11400.00,-12500.00,1100.00 +-11500.00,-13200.00,1700.00,-11500.00,-12800.00,1300.00 +-11600.00,-13250.00,1650.00,-11600.00,-12900.00,1300.00 +-11700.00,-13250.00,1550.00,-11700.00,-12900.00,1200.00 +-11800.00,-13550.00,1750.00,-11800.00,-13050.00,1250.00 +-11900.00,-13700.00,1800.00,-11900.00,-13050.00,1150.00 +-12000.00,-13750.00,1750.00,-12000.00,-13000.00,1000.00 +-12100.00,-13850.00,1750.00,-12100.00,-13150.00,1050.00 +-12200.00,-14150.00,1950.00,-12200.00,-13350.00,1150.00 +-12300.00,-14200.00,1900.00,-12300.00,-13500.00,1200.00 +-12400.00,-14200.00,1800.00,-12400.00,-13650.00,1250.00 +-12500.00,-14400.00,1900.00,-12500.00,-13800.00,1300.00 +-12600.00,-14600.00,2000.00,-12600.00,-13800.00,1200.00 +-12700.00,-14700.00,2000.00,-12700.00,-14000.00,1300.00 +-12800.00,-14800.00,2000.00,-12800.00,-14100.00,1300.00 +-12900.00,-14950.00,2050.00,-12900.00,-14150.00,1250.00 +-13000.00,-15000.00,2000.00,-13000.00,-14200.00,1200.00 +-13100.00,-15100.00,2000.00,-13100.00,-14300.00,1200.00 +-13200.00,-15250.00,2050.00,-13200.00,-14450.00,1250.00 +-13300.00,-15500.00,2200.00,-13300.00,-14550.00,1250.00 +-13400.00,-15500.00,2100.00,-13400.00,-14650.00,1250.00 +-13500.00,-15600.00,2100.00,-13500.00,-14750.00,1250.00 +-13600.00,-15800.00,2200.00,-13600.00,-14900.00,1300.00 +-13700.00,-15850.00,2150.00,-13700.00,-15050.00,1350.00 +-13800.00,-15900.00,2100.00,-13800.00,-15250.00,1450.00 +-13900.00,-16100.00,2200.00,-13900.00,-15350.00,1450.00 +-14000.00,-16300.00,2300.00,-14000.00,-15550.00,1550.00 +-14100.00,-16500.00,2400.00,-14100.00,-15700.00,1600.00 +-14200.00,-16600.00,2400.00,-14200.00,-15750.00,1550.00 +-14300.00,-16600.00,2300.00,-14300.00,-15850.00,1550.00 +-14400.00,-16500.00,2100.00,-14400.00,-15950.00,1550.00 +-14500.00,-16750.00,2250.00,-14500.00,-16150.00,1650.00 +-14600.00,-16850.00,2250.00,-14600.00,-16200.00,1600.00 +-14700.00,-17050.00,2350.00,-14700.00,-16300.00,1600.00 +-14800.00,-17100.00,2300.00,-14800.00,-16650.00,1850.00 +-14900.00,-17250.00,2350.00,-14900.00,-16750.00,1850.00 +-15000.00,-17300.00,2300.00,-15000.00,-16900.00,1900.00 +-15100.00,-17450.00,2350.00,-15100.00,-17050.00,1950.00 +-15200.00,-17550.00,2350.00,-15200.00,-17100.00,1900.00 +-15300.00,-17700.00,2400.00,-15300.00,-17150.00,1850.00 +-15400.00,-17750.00,2350.00,-15400.00,-17400.00,2000.00 +-15500.00,-17950.00,2450.00,-15500.00,-17600.00,2100.00 +-15600.00,-18050.00,2450.00,-15600.00,-17700.00,2100.00 +-15700.00,-18300.00,2600.00,-15700.00,-17800.00,2100.00 +-15800.00,-18300.00,2500.00,-15800.00,-17600.00,1800.00 +-15900.00,-18600.00,2700.00,-15900.00,-17800.00,1900.00 +-16000.00,-18700.00,2700.00,-16000.00,-18000.00,2000.00 +-16100.00,-22150.00,6050.00,-16100.00,-21600.00,5500.00 +-16200.00,-17500.00,1300.00,-16200.00,-17900.00,1700.00 +-16300.00,-15200.00,-1100.00,-16300.00,-16900.00,600.00 +-16400.00,-16800.00,400.00,-16400.00,-17500.00,1100.00 +-16500.00,-20550.00,4050.00,-16500.00,-19100.00,2600.00 +-16600.00,-20900.00,4300.00,-16600.00,-18800.00,2200.00 +-16700.00,-20300.00,3600.00,-16700.00,-18600.00,1900.00 +-16800.00,-19950.00,3150.00,-16800.00,-18600.00,1800.00 +-16900.00,-19650.00,2750.00,-16900.00,-18850.00,1950.00 +-17000.00,-19800.00,2800.00,-17000.00,-19050.00,2050.00 +-17100.00,-20050.00,2950.00,-17100.00,-19200.00,2100.00 +-17200.00,-20550.00,3350.00,-17200.00,-19300.00,2100.00 +-17300.00,-20600.00,3300.00,-17300.00,-19600.00,2300.00 +-17400.00,-20600.00,3200.00,-17400.00,-19700.00,2300.00 +-17500.00,-20500.00,3000.00,-17500.00,-19900.00,2400.00 +-17600.00,-20800.00,3200.00,-17549.96,-19900.00,2350.04 +-17700.00,-20900.00,3200.00,-17449.96,-20000.00,2550.04 +-17800.00,-20950.00,3150.00,-17349.96,-19950.00,2600.04 +-17900.00,-19500.00,1600.00,-17249.96,-18350.00,1100.04 +-18000.00,-21500.00,3500.00,-17149.96,-19800.00,2650.04 +-18063.52,-22050.00,3986.48,-17049.96,-20300.00,3250.04 +-17963.52,-21800.00,3836.48,-16949.96,-19950.00,3000.04 +-17863.52,-22050.00,4186.48,-16849.96,-20250.00,3400.04 +-17763.52,-21850.00,4086.48,-16749.96,-19700.00,2950.04 +-17663.52,-20600.00,2936.48,-16649.96,-18450.00,1800.04 +-17563.52,-20400.00,2836.48,-16549.96,-18450.00,1900.04 +-17463.52,-20700.00,3236.48,-16449.96,-18800.00,2350.04 +-17363.52,-20700.00,3336.48,-16349.96,-18850.00,2500.04 +-17263.52,-21550.00,4286.48,-16249.96,-19350.00,3100.04 +-17163.52,-20600.00,3436.48,-16149.96,-18350.00,2200.04 +-17063.52,-20000.00,2936.48,-16049.96,-17950.00,1900.04 +-16963.52,-20000.00,3036.48,-15949.96,-17800.00,1850.04 +-16863.52,-20000.00,3136.48,-15849.96,-18000.00,2150.04 +-16763.52,-20000.00,3236.48,-15749.96,-18100.00,2350.04 +-16663.52,-20050.00,3386.48,-15649.96,-17950.00,2300.04 +-16563.52,-19850.00,3286.48,-15549.96,-17750.00,2200.04 +-16463.52,-19700.00,3236.48,-15449.96,-17400.00,1950.04 +-16363.52,-19500.00,3136.48,-15349.96,-17250.00,1900.04 +-16263.52,-19300.00,3036.48,-15249.96,-17150.00,1900.04 +-16163.52,-19300.00,3136.48,-15149.96,-16900.00,1750.04 +-16063.52,-19100.00,3036.48,-15049.96,-16700.00,1650.04 +-15963.52,-19000.00,3036.48,-14949.96,-16600.00,1650.04 +-15863.52,-18950.00,3086.48,-14849.96,-16500.00,1650.04 +-15763.52,-18750.00,2986.48,-14749.96,-16300.00,1550.04 +-15663.52,-18550.00,2886.48,-14649.96,-16300.00,1650.04 +-15563.52,-18350.00,2786.48,-14549.96,-16300.00,1750.04 +-15463.52,-18300.00,2836.48,-14449.96,-16300.00,1850.04 +-15363.52,-18150.00,2786.48,-14349.96,-16250.00,1900.04 +-15263.52,-18000.00,2736.48,-14249.96,-16150.00,1900.04 +-15163.52,-18000.00,2836.48,-14149.96,-16000.00,1850.04 +-15063.52,-17800.00,2736.48,-14049.96,-15850.00,1800.04 +-14963.52,-17650.00,2686.48,-13949.96,-15500.00,1550.04 +-14863.52,-17600.00,2736.48,-13849.96,-15300.00,1450.04 +-14763.52,-17350.00,2586.48,-13749.96,-15150.00,1400.04 +-14663.52,-17300.00,2636.48,-13649.96,-15300.00,1650.04 +-14563.52,-17250.00,2686.48,-13549.96,-15250.00,1700.04 +-14463.52,-17000.00,2536.48,-13449.96,-15050.00,1600.04 +-14363.52,-16850.00,2486.48,-13349.96,-15000.00,1650.04 +-14263.52,-16850.00,2586.48,-13249.96,-15000.00,1750.04 +-14163.52,-16700.00,2536.48,-13149.96,-14900.00,1750.04 +-14063.52,-16650.00,2586.48,-13049.96,-14750.00,1700.04 +-13963.52,-16500.00,2536.48,-12949.96,-14550.00,1600.04 +-13863.52,-16200.00,2336.48,-12849.96,-14400.00,1550.04 +-13763.52,-16100.00,2336.48,-12749.96,-14200.00,1450.04 +-13663.52,-16050.00,2386.48,-12649.96,-14050.00,1400.04 +-13563.52,-15950.00,2386.48,-12549.96,-13900.00,1350.04 +-13463.52,-15850.00,2386.48,-12449.96,-13750.00,1300.04 +-13363.52,-15750.00,2386.48,-12349.96,-13650.00,1300.04 +-13263.52,-15700.00,2436.48,-12249.96,-13550.00,1300.04 +-13163.52,-15450.00,2286.48,-12149.96,-13500.00,1350.04 +-13063.52,-15300.00,2236.48,-12049.96,-13350.00,1300.04 +-12963.52,-15250.00,2286.48,-11949.96,-13200.00,1250.04 +-12863.52,-15150.00,2286.48,-11849.96,-13050.00,1200.04 +-12763.52,-14950.00,2186.48,-11749.96,-12900.00,1150.04 +-12663.52,-17450.00,4786.48,-11649.96,-14950.00,3300.04 +-12563.52,-13700.00,1136.48,-11549.96,-11750.00,200.04 +-12463.52,-10900.00,-1563.52,-11449.96,-9150.00,-2299.96 +-12363.52,-13300.00,936.48,-11349.96,-11350.00,0.04 +-12263.52,-15300.00,3036.48,-11249.96,-13300.00,2050.04 +-12163.52,-15650.00,3486.48,-11149.96,-13550.00,2400.04 +-12063.52,-15000.00,2936.48,-11049.96,-12950.00,1900.04 +-11963.52,-14400.00,2436.48,-10949.96,-12050.00,1100.04 +-11863.52,-14100.00,2236.48,-10849.96,-11750.00,900.04 +-11763.52,-13850.00,2086.48,-10749.96,-11500.00,750.04 +-11663.52,-13650.00,1986.48,-10649.96,-11500.00,850.04 +-11563.52,-13700.00,2136.48,-10549.96,-11600.00,1050.04 +-11463.52,-13600.00,2136.48,-10449.96,-11400.00,950.04 +-11363.52,-13600.00,2236.48,-10349.96,-11300.00,950.04 +-11263.52,-13450.00,2186.48,-10249.96,-11300.00,1050.04 +-11163.52,-13150.00,1986.48,-10149.96,-11250.00,1100.04 +-11063.52,-13050.00,1986.48,-10049.96,-11250.00,1200.04 +-10963.52,-12900.00,1936.48,-9949.96,-11100.00,1150.04 +-10863.52,-12800.00,1936.48,-9849.96,-11050.00,1200.04 +-10763.52,-12250.00,1486.48,-9749.96,-10600.00,850.04 +-10663.52,-12650.00,1986.48,-9649.96,-10950.00,1300.04 +-10563.52,-12650.00,2086.48,-9549.96,-10800.00,1250.04 +-10463.52,-12500.00,2036.48,-9449.96,-10750.00,1300.04 +-10363.52,-12200.00,1836.48,-9349.96,-10450.00,1100.04 +-10263.52,-12050.00,1786.48,-9249.96,-10200.00,950.04 +-10163.52,-11900.00,1736.48,-9149.96,-9900.00,750.04 +-10063.52,-11750.00,1686.48,-9049.96,-9800.00,750.04 +-9963.52,-11650.00,1686.48,-8949.96,-9650.00,700.04 +-9863.52,-11250.00,1386.48,-8849.96,-9300.00,450.04 +-9763.52,-11600.00,1836.48,-8749.96,-9600.00,850.04 +-9663.52,-11550.00,1886.48,-8649.96,-9600.00,950.04 +-9563.52,-10950.00,1386.48,-8549.96,-8950.00,400.04 +-9463.52,-11200.00,1736.48,-8449.96,-9300.00,850.04 +-9363.52,-11100.00,1736.48,-8349.96,-9250.00,900.04 +-9263.52,-10950.00,1686.48,-8249.96,-9150.00,900.04 +-9163.52,-10700.00,1536.48,-8149.96,-8900.00,750.04 +-9063.52,-10550.00,1486.48,-8049.96,-8700.00,650.04 +-8963.52,-10400.00,1436.48,-7949.96,-8700.00,750.04 +-8863.52,-10350.00,1486.48,-7849.96,-8500.00,650.04 +-8763.52,-10350.00,1586.48,-7749.96,-8500.00,750.04 +-8663.52,-9650.00,986.48,-7649.96,-8400.00,750.04 +-8563.52,-8600.00,36.48,-7549.96,-8250.00,700.04 +-8463.52,-9050.00,586.48,-7449.96,-8050.00,600.04 +-8363.52,-9600.00,1236.48,-7349.96,-7950.00,600.04 +-8263.52,-9350.00,1086.48,-7249.96,-7750.00,500.04 +-8163.52,-8200.00,36.48,-7149.96,-7600.00,450.04 +-8063.52,-8650.00,586.48,-7049.96,-7500.00,450.04 +-7963.52,-9100.00,1136.48,-6949.96,-7000.00,50.04 +-7863.52,-8800.00,936.48,-6849.96,-5950.00,-899.96 +-7763.52,-7500.00,-263.52,-6749.96,-6250.00,-499.96 +-7663.52,-7000.00,-663.52,-6649.96,-6800.00,150.04 +-7563.52,-7800.00,236.48,-6549.96,-6900.00,350.04 +-7463.52,-8650.00,1186.48,-6449.96,-6500.00,50.04 +-7363.52,-8650.00,1286.48,-6349.96,-5500.00,-849.96 +-7263.52,-7450.00,186.48,-6249.96,-5650.00,-599.96 +-7163.52,-6750.00,-413.52,-6149.96,-6150.00,0.04 +-7063.52,-7350.00,286.48,-6049.96,-6000.00,-49.96 +-6963.52,-8000.00,1036.48,-5949.96,-4850.00,-1099.96 +-6863.52,-7800.00,936.48,-5849.96,-4150.00,-1699.96 +-6763.52,-6600.00,-163.52,-5749.96,-5050.00,-699.96 +-6663.52,-6300.00,-363.52,-5649.96,-6050.00,400.04 +-6563.52,-6850.00,286.48,-5549.96,-5950.00,400.04 +-6463.52,-6850.00,386.48,-5449.96,-4850.00,-599.96 +-6363.52,-5750.00,-613.52,-5349.96,-3900.00,-1449.96 +-6263.52,-5600.00,-663.52,-5249.96,-4400.00,-849.96 +-6163.52,-6250.00,86.48,-5149.96,-5200.00,50.04 +-6063.52,-6400.00,336.48,-5049.96,-4700.00,-349.96 +-5963.52,-5650.00,-313.52,-4949.96,-3900.00,-1049.96 +-5863.52,-4950.00,-913.52,-4849.96,-3200.00,-1649.96 +-5763.52,-6050.00,286.48,-4749.96,-3800.00,-949.96 +-5663.52,-6000.00,336.48,-4649.96,-4500.00,-149.96 +-5563.52,-5150.00,-413.52,-4549.96,-4200.00,-349.96 +-5463.52,-4400.00,-1063.52,-4449.96,-3200.00,-1249.96 +-5363.52,-4100.00,-1263.52,-4349.96,-2600.00,-1749.96 +-5263.52,-4800.00,-463.52,-4249.96,-3100.00,-1149.96 +-5163.52,-6400.00,1236.48,-4149.96,-3900.00,-249.96 +-5063.52,-4350.00,-713.52,-4049.96,-2200.00,-1849.96 +-4963.52,-3450.00,-1513.52,-3949.96,-1400.00,-2549.96 +-4863.52,-3350.00,-1513.52,-3849.96,-2500.00,-1349.96 +-4763.52,-4400.00,-363.52,-3749.96,-3500.00,-249.96 +-4663.52,-4950.00,286.48,-3649.96,-2200.00,-1449.96 +-4563.52,-4050.00,-513.52,-3549.96,-1200.00,-2349.96 +-4463.52,-3400.00,-1063.52,-3449.96,-100.00,-3349.96 +-4363.52,-2550.00,-1813.52,-3349.96,-1400.00,-1949.96 +-4263.52,-2300.00,-1963.52,-3249.96,-3500.00,250.04 +-4163.52,-3700.00,-463.52,-3149.96,-3500.00,350.04 +-4063.52,-4350.00,286.48,-3049.96,-2050.00,-999.96 +-3963.52,-3550.00,-413.52,-2949.96,-900.00,-2049.96 +-3863.52,-2850.00,-1013.52,-2849.96,-600.00,-2249.96 +-3763.52,-1800.00,-1963.52,-2749.96,-850.00,-1899.96 +-3663.52,-2350.00,-1313.52,-2649.96,-450.00,-2199.96 +-3563.52,-2750.00,-813.52,-2549.96,900.00,-3449.96 +-3463.52,-1800.00,-1663.52,-2449.96,-450.00,-1999.96 +-3363.52,-1600.00,-1763.52,-2349.96,-1500.00,-849.96 +-3263.52,200.00,-3463.52,-2249.96,-1000.00,-1249.96 +-3163.52,-50.00,-3113.52,-2149.96,-400.00,-1749.96 +-3063.52,-2300.00,-763.52,-2049.96,100.00,-2149.96 +-2963.52,-3600.00,636.48,-1949.96,50.00,-1999.96 +-2863.52,-2800.00,-63.52,-1849.96,0.00,-1849.96 +-2763.52,-2250.00,-513.52,-1749.96,0.00,-1749.96 +-2663.52,-1700.00,-963.52,-1649.96,0.00,-1649.96 +-2563.52,-900.00,-1663.52,-1549.96,0.00,-1549.96 +-2463.52,850.00,-3313.52,-1449.96,0.00,-1449.96 +-2363.52,-200.00,-2163.52,-1349.96,0.00,-1349.96 +-2263.52,-1700.00,-563.52,-1249.96,0.00,-1249.96 +-2163.52,-1200.00,-963.52,-1149.96,0.00,-1149.96 +-2063.52,-950.00,-1113.52,-1049.96,0.00,-1049.96 +-1963.52,550.00,-2513.52,-949.96,0.00,-949.96 +-1863.52,250.00,-2113.52,-849.96,0.00,-849.96 +-1763.52,-100.00,-1663.52,-749.96,0.00,-749.96 +-1663.52,0.00,-1663.52,-649.96,0.00,-649.96 +-1563.52,0.00,-1563.52,-549.96,0.00,-549.96 +-1463.52,0.00,-1463.52,-449.96,0.00,-449.96 +-1363.52,0.00,-1363.52,-349.96,0.00,-349.96 +-1263.52,0.00,-1263.52,-249.96,0.00,-249.96 +-1163.52,0.00,-1163.52,-149.96,0.00,-149.96 +-1063.52,0.00,-1063.52,-49.96,0.00,-49.96 +-963.52,0.00,-963.52,0.00,0.00,0.00 +-863.52,0.00,-863.52,0.00,0.00,0.00 +-763.52,0.00,-763.52,0.00,0.00,0.00 +-663.52,0.00,-663.52,0.00,0.00,0.00 +-563.52,0.00,-563.52,0.00,0.00,0.00 +-463.52,0.00,-463.52,0.00,0.00,0.00 +-363.52,0.00,-363.52,0.00,0.00,0.00 +-263.52,0.00,-263.52,0.00,0.00,0.00 +-163.52,0.00,-163.52,0.00,0.00,0.00 +-63.52,0.00,-63.52,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 +0.00,0.00,0.00,0.00,0.00,0.00 0.00,0.00,0.00,0.00,0.00,0.00 0.00,0.00,0.00,0.00,0.00,0.00 0.00,0.00,0.00,0.00,0.00,0.00 @@ -2652,334 +2658,334 @@ LeftSetpoint,LeftVelocity,LeftError,RightSetpoint,RightVelocity,RightError 2200.00,0.00,2200.00,2200.00,0.00,2200.00 2300.00,0.00,2300.00,2300.00,0.00,2300.00 2400.00,0.00,2400.00,2400.00,0.00,2400.00 -2500.00,400.00,2100.00,2500.00,350.00,2150.00 -2600.00,500.00,2100.00,2600.00,200.00,2400.00 -2700.00,-850.00,3550.00,2700.00,-150.00,2850.00 -2800.00,550.00,2250.00,2800.00,900.00,1900.00 -2900.00,2950.00,-50.00,2900.00,1950.00,950.00 -3000.00,2950.00,50.00,3000.00,550.00,2450.00 -3100.00,2200.00,900.00,3100.00,-200.00,3300.00 -3200.00,2100.00,1100.00,3200.00,1200.00,2000.00 -3300.00,850.00,2450.00,3300.00,2800.00,500.00 -3400.00,1750.00,1650.00,3400.00,2900.00,500.00 -3500.00,2100.00,1400.00,3500.00,1450.00,2050.00 -3600.00,1950.00,1650.00,3600.00,1500.00,2100.00 -3700.00,1400.00,2300.00,3700.00,2350.00,1350.00 -3800.00,2900.00,900.00,3800.00,2600.00,1200.00 -3900.00,3600.00,300.00,3900.00,1900.00,2000.00 -4000.00,2850.00,1150.00,4000.00,600.00,3400.00 -4100.00,2350.00,1750.00,4100.00,2300.00,1800.00 -4200.00,2200.00,2000.00,4200.00,4500.00,-300.00 -4300.00,3200.00,1100.00,4300.00,4200.00,100.00 -4400.00,4500.00,-100.00,4400.00,3050.00,1350.00 -4500.00,4550.00,-50.00,4500.00,2400.00,2100.00 -4600.00,3850.00,750.00,4600.00,2950.00,1650.00 -4700.00,3300.00,1400.00,4700.00,3900.00,800.00 -4800.00,3200.00,1600.00,4800.00,3900.00,900.00 -4900.00,4000.00,900.00,4900.00,2900.00,2000.00 -5000.00,4900.00,100.00,5000.00,2450.00,2550.00 -5100.00,5300.00,-200.00,5100.00,4050.00,1050.00 -5200.00,4450.00,750.00,5200.00,5600.00,-400.00 -5300.00,3800.00,1500.00,5300.00,5050.00,250.00 -5400.00,4900.00,500.00,5400.00,4000.00,1400.00 -5500.00,4900.00,600.00,5500.00,3300.00,2200.00 -5600.00,4600.00,1000.00,5600.00,4200.00,1400.00 -5700.00,5950.00,-250.00,5700.00,4150.00,1550.00 -5800.00,5600.00,200.00,5800.00,6600.00,-800.00 -5900.00,4400.00,1500.00,5900.00,6350.00,-450.00 -6000.00,4700.00,1300.00,6000.00,5200.00,800.00 -6100.00,5200.00,900.00,6100.00,4400.00,1700.00 -6200.00,6400.00,-200.00,6200.00,5100.00,1100.00 -6300.00,7100.00,-800.00,6300.00,5550.00,750.00 -6400.00,5650.00,750.00,6400.00,6800.00,-400.00 -6500.00,5550.00,950.00,6500.00,6750.00,-250.00 -6600.00,6100.00,500.00,6600.00,5550.00,1050.00 -6700.00,7000.00,-300.00,6700.00,5000.00,1700.00 -6800.00,6800.00,0.00,6800.00,5550.00,1250.00 -6900.00,6550.00,350.00,6900.00,7050.00,-150.00 -7000.00,7400.00,-400.00,7000.00,8200.00,-1200.00 -7100.00,7400.00,-300.00,7100.00,7450.00,-350.00 -7200.00,7850.00,-650.00,7200.00,6650.00,550.00 -7300.00,7550.00,-250.00,7300.00,6800.00,500.00 -7400.00,6600.00,800.00,7400.00,7000.00,400.00 -7500.00,7100.00,400.00,7500.00,7600.00,-100.00 -7600.00,8450.00,-850.00,7600.00,7400.00,200.00 -7700.00,8850.00,-1150.00,7700.00,8600.00,-900.00 -7800.00,8400.00,-600.00,7800.00,8700.00,-900.00 -7900.00,7450.00,450.00,7900.00,8800.00,-900.00 -8000.00,8100.00,-100.00,8000.00,8300.00,-300.00 -8100.00,8300.00,-200.00,8100.00,7000.00,1100.00 -8200.00,9350.00,-1150.00,8200.00,9300.00,-1100.00 -8300.00,9250.00,-950.00,8300.00,9200.00,-900.00 -8400.00,11300.00,-2900.00,8400.00,11600.00,-3200.00 -8500.00,9000.00,-500.00,8500.00,9150.00,-650.00 -8600.00,7800.00,800.00,8600.00,7850.00,750.00 -8700.00,8000.00,700.00,8700.00,8300.00,400.00 -8800.00,10000.00,-1200.00,8800.00,8650.00,150.00 -8900.00,10650.00,-1750.00,8900.00,9450.00,-550.00 -9000.00,9950.00,-950.00,9000.00,10600.00,-1600.00 -9100.00,8900.00,200.00,9100.00,10700.00,-1600.00 -9200.00,8900.00,300.00,9200.00,10050.00,-850.00 -9300.00,10150.00,-850.00,9300.00,9300.00,0.00 -9400.00,10300.00,-900.00,9400.00,10350.00,-950.00 -9500.00,11150.00,-1650.00,9500.00,10650.00,-1150.00 -9600.00,11200.00,-1600.00,9600.00,9450.00,150.00 -9700.00,11200.00,-1500.00,9700.00,10700.00,-1000.00 -9800.00,11800.00,-2000.00,9800.00,11350.00,-1550.00 -9900.00,11250.00,-1350.00,9900.00,11150.00,-1250.00 -10000.00,10800.00,-800.00,10000.00,10550.00,-550.00 -10100.00,11150.00,-1050.00,10100.00,10650.00,-550.00 -10200.00,11500.00,-1300.00,10200.00,11300.00,-1100.00 -10300.00,12000.00,-1700.00,10300.00,10200.00,100.00 -10296.86,11750.00,-1453.14,10400.00,11100.00,-700.00 -10196.86,11800.00,-1603.14,10500.00,11600.00,-1100.00 -10096.86,11650.00,-1553.14,10600.00,11600.00,-1000.00 -9996.86,12050.00,-2053.14,10700.00,12800.00,-2100.00 -9896.86,11900.00,-2003.14,10800.00,12500.00,-1700.00 -9796.86,11350.00,-1553.14,10900.00,12100.00,-1200.00 -9696.86,11150.00,-1453.14,11000.00,11300.00,-300.00 -9596.86,11450.00,-1853.14,11100.00,12100.00,-1000.00 -9496.86,11950.00,-2453.14,11200.00,13050.00,-1850.00 -9396.86,10700.00,-1303.14,11300.00,12650.00,-1350.00 -9296.86,9000.00,296.86,11400.00,11700.00,-300.00 -9196.86,9700.00,-503.14,11500.00,10700.00,800.00 -9096.86,10350.00,-1253.14,11600.00,10900.00,700.00 -8996.86,11600.00,-2603.14,11700.00,13600.00,-1900.00 -8896.86,10800.00,-1903.14,11800.00,15000.00,-3200.00 -8796.86,8200.00,596.86,11900.00,13600.00,-1700.00 -8696.86,7700.00,996.86,12000.00,12800.00,-800.00 -8596.86,9000.00,-403.14,12100.00,11150.00,950.00 -8496.86,10650.00,-2153.14,12200.00,13350.00,-1150.00 -8396.86,10450.00,-2053.14,12300.00,15000.00,-2700.00 -8296.86,8300.00,-3.14,12400.00,15250.00,-2850.00 -8196.86,7350.00,846.86,12500.00,14050.00,-1550.00 -8096.86,7850.00,246.86,12600.00,13200.00,-600.00 -7996.86,9400.00,-1403.14,12700.00,13000.00,-300.00 -7896.86,9400.00,-1503.14,12800.00,15700.00,-2900.00 -7796.86,7750.00,46.86,12900.00,15450.00,-2550.00 -7696.86,6900.00,796.86,13000.00,14650.00,-1650.00 -7596.86,7250.00,346.86,13100.00,14700.00,-1600.00 -7496.86,8500.00,-1003.14,13200.00,14650.00,-1450.00 -7396.86,9150.00,-1753.14,13300.00,16050.00,-2750.00 -7296.86,7300.00,-3.14,13400.00,15950.00,-2550.00 -7196.86,6400.00,796.86,13500.00,15250.00,-1750.00 -7096.86,6750.00,346.86,13600.00,14950.00,-1350.00 -6996.86,8000.00,-1003.14,13700.00,15650.00,-1950.00 -6896.86,8400.00,-1503.14,13800.00,14900.00,-1100.00 -6796.86,6550.00,246.86,13900.00,15700.00,-1800.00 -6696.86,6150.00,546.86,14000.00,16550.00,-2550.00 -6596.86,6800.00,-203.14,14100.00,16200.00,-2100.00 -6496.86,7500.00,-1003.14,14200.00,16350.00,-2150.00 -6396.86,7100.00,-703.14,14300.00,15550.00,-1250.00 -6296.86,5800.00,496.86,14400.00,16000.00,-1600.00 -6196.86,5500.00,696.86,14500.00,16850.00,-2350.00 -6096.86,6450.00,-353.14,14600.00,16700.00,-2100.00 -5996.86,6500.00,-503.14,14700.00,16800.00,-2100.00 -5896.86,5550.00,346.86,14740.48,17400.00,-2659.52 -5796.86,5100.00,696.86,14640.48,16950.00,-2309.52 -5696.86,5450.00,246.86,14540.48,16700.00,-2159.52 -5596.86,5900.00,-303.14,14440.48,17150.00,-2709.52 -5496.86,4750.00,746.86,14340.48,16200.00,-1859.52 -5396.86,4500.00,896.86,14240.48,15950.00,-1709.52 -5296.86,5000.00,296.86,14140.48,15950.00,-1809.52 -5196.86,5250.00,-53.14,14040.48,15900.00,-1859.52 -5096.86,4450.00,646.86,13940.48,15800.00,-1859.52 -4996.86,3650.00,1346.86,13840.48,15900.00,-2059.52 -4896.86,4050.00,846.86,13740.48,18850.00,-5109.52 -4796.86,4100.00,696.86,13640.48,15200.00,-1559.52 -4696.86,3250.00,1446.86,13540.48,12350.00,1190.48 -4596.86,3450.00,1146.86,13440.48,12300.00,1140.48 -4496.86,4850.00,-353.14,13340.48,15400.00,-2059.52 -4396.86,5150.00,-753.14,13240.48,19650.00,-6409.52 -4296.86,3950.00,346.86,13140.48,16550.00,-3409.52 -4196.86,2950.00,1246.86,13040.48,13200.00,-159.52 -4096.86,2150.00,1946.86,12940.48,13100.00,-159.52 -3996.86,2450.00,1546.86,12840.48,14700.00,-1859.52 -3896.86,4000.00,-103.14,12740.48,16500.00,-3759.52 -3796.86,4100.00,-303.14,12640.48,15250.00,-2609.52 -3696.86,3250.00,446.86,12540.48,14050.00,-1509.52 -3596.86,2700.00,896.86,12440.48,14000.00,-1559.52 -3496.86,1900.00,1596.86,12340.48,14250.00,-1909.52 -3396.86,1200.00,2196.86,12240.48,14300.00,-2059.52 -3296.86,400.00,2896.86,12140.48,14200.00,-2059.52 -3196.86,2800.00,396.86,12040.48,14950.00,-2909.52 -3096.86,3750.00,-653.14,11940.48,14150.00,-2209.52 -2996.86,3200.00,-203.14,11840.48,13250.00,-1409.52 -2896.86,2700.00,196.86,11740.48,13150.00,-1409.52 -2796.86,1800.00,996.86,11640.48,13350.00,-1709.52 -2696.86,1450.00,1246.86,11540.48,13900.00,-2359.52 -2596.86,-300.00,2896.86,11440.48,13100.00,-1659.52 -2496.86,-200.00,2696.86,11340.48,13100.00,-1759.52 -2396.86,1400.00,996.86,11240.48,13350.00,-2109.52 -2296.86,2650.00,-353.14,11140.48,13150.00,-2009.52 -2196.86,1650.00,546.86,11040.48,12000.00,-959.52 -2096.86,1450.00,646.86,10940.48,12300.00,-1359.52 -1996.86,-200.00,2196.86,10840.48,12500.00,-1659.52 -1896.86,-1000.00,2896.86,10740.48,12500.00,-1759.52 -1796.86,400.00,1396.86,10640.48,11850.00,-1209.52 -1696.86,900.00,796.86,10540.48,12200.00,-1659.52 -1596.86,-200.00,1796.86,10440.48,11550.00,-1109.52 -1496.86,-900.00,2396.86,10340.48,11900.00,-1559.52 -1396.86,-300.00,1696.86,10240.48,11800.00,-1559.52 -1296.86,250.00,1046.86,10140.48,10900.00,-759.52 -1196.86,0.00,1196.86,10040.48,11200.00,-1159.52 -1096.86,0.00,1096.86,9940.48,10700.00,-759.52 -996.86,0.00,996.86,9840.48,10650.00,-809.52 -896.86,0.00,896.86,9740.48,11150.00,-1409.52 -796.86,0.00,796.86,9640.48,10750.00,-1109.52 -696.86,0.00,696.86,9540.48,10600.00,-1059.52 -596.86,0.00,596.86,9440.48,10850.00,-1409.52 -496.86,0.00,496.86,9340.48,10400.00,-1059.52 -396.86,0.00,396.86,9240.48,10200.00,-959.52 -296.86,0.00,296.86,9140.48,10200.00,-1059.52 -196.86,0.00,196.86,9040.48,10150.00,-1109.52 -96.86,0.00,96.86,8940.48,9950.00,-1009.52 -0.00,0.00,0.00,8840.48,10200.00,-1359.52 -0.00,0.00,0.00,8740.48,9500.00,-759.52 -0.00,0.00,0.00,8640.48,9300.00,-659.52 -0.00,0.00,0.00,8540.48,9150.00,-609.52 -0.00,0.00,0.00,8440.48,9050.00,-609.52 -0.00,0.00,0.00,8340.48,8950.00,-609.52 -0.00,0.00,0.00,8240.48,8750.00,-509.52 -0.00,0.00,0.00,8140.48,9000.00,-859.52 -0.00,0.00,0.00,8040.48,8900.00,-859.52 -0.00,0.00,0.00,7940.48,8700.00,-759.52 -0.00,0.00,0.00,7840.48,8500.00,-659.52 -0.00,0.00,0.00,7740.48,8400.00,-659.52 -0.00,0.00,0.00,7640.48,8300.00,-659.52 -0.00,0.00,0.00,7540.48,8200.00,-659.52 -0.00,0.00,0.00,7440.48,7800.00,-359.52 -0.00,0.00,0.00,7340.48,6950.00,390.48 -0.00,0.00,0.00,7240.48,7050.00,190.48 -0.00,0.00,0.00,7140.48,7200.00,-59.52 -0.00,0.00,0.00,7040.48,7800.00,-759.52 -0.00,0.00,0.00,6940.48,7600.00,-659.52 -0.00,0.00,0.00,6840.48,6350.00,490.48 -0.00,0.00,0.00,6740.48,5650.00,1090.48 -0.00,0.00,0.00,6640.48,6550.00,90.48 -0.00,0.00,0.00,6540.48,7250.00,-709.52 -0.00,0.00,0.00,6440.48,7000.00,-559.52 -0.00,0.00,0.00,6340.48,5950.00,390.48 -0.00,0.00,0.00,6240.48,5500.00,740.48 -0.00,0.00,0.00,6140.48,6950.00,-809.52 -0.00,0.00,0.00,6040.48,6150.00,-109.52 -0.00,0.00,0.00,5940.48,4900.00,1040.48 -0.00,0.00,0.00,5840.48,4950.00,890.48 -0.00,0.00,0.00,5740.48,5550.00,190.48 -0.00,0.00,0.00,5640.48,5750.00,-109.52 -0.00,0.00,0.00,5540.48,4850.00,690.48 -0.00,0.00,0.00,5440.48,4250.00,1190.48 -0.00,0.00,0.00,5340.48,4650.00,690.48 -0.00,0.00,0.00,5240.48,5250.00,-9.52 -0.00,0.00,0.00,5140.48,5350.00,-209.52 -0.00,0.00,0.00,5040.48,4350.00,690.48 -0.00,0.00,0.00,4940.48,3600.00,1340.48 -0.00,0.00,0.00,4840.48,3350.00,1490.48 -0.00,0.00,0.00,4740.48,4050.00,690.48 -0.00,0.00,0.00,4640.48,4500.00,140.48 -0.00,0.00,0.00,4540.48,3600.00,940.48 -0.00,0.00,0.00,4440.48,2700.00,1740.48 -0.00,0.00,0.00,4340.48,2800.00,1540.48 -0.00,0.00,0.00,4240.48,3700.00,540.48 -0.00,0.00,0.00,4140.48,4150.00,-9.52 -0.00,0.00,0.00,4040.48,3350.00,690.48 -0.00,0.00,0.00,3940.48,2150.00,1790.48 -0.00,0.00,0.00,3840.48,2350.00,1490.48 -0.00,0.00,0.00,3740.48,2850.00,890.48 -0.00,0.00,0.00,3640.48,1550.00,2090.48 -0.00,0.00,0.00,3540.48,2250.00,1290.48 -0.00,0.00,0.00,3440.48,2650.00,790.48 -0.00,0.00,0.00,3340.48,1200.00,2140.48 -0.00,0.00,0.00,3240.48,1800.00,1440.48 -0.00,0.00,0.00,3140.48,2400.00,740.48 -0.00,0.00,0.00,3040.48,1650.00,1390.48 -0.00,0.00,0.00,2940.48,150.00,2790.48 -0.00,0.00,0.00,2840.48,350.00,2490.48 -0.00,0.00,0.00,2740.48,2450.00,290.48 -0.00,0.00,0.00,2640.48,2750.00,-109.52 -0.00,0.00,0.00,2540.48,1950.00,590.48 -0.00,0.00,0.00,2440.48,1650.00,790.48 -0.00,0.00,0.00,2340.48,650.00,1690.48 -0.00,0.00,0.00,2240.48,-850.00,3090.48 -0.00,0.00,0.00,2140.48,350.00,1790.48 -0.00,0.00,0.00,2040.48,1200.00,840.48 -0.00,0.00,0.00,1940.48,50.00,1890.48 -0.00,0.00,0.00,1840.48,0.00,1840.48 -0.00,0.00,0.00,1740.48,0.00,1740.48 -0.00,0.00,0.00,1640.48,0.00,1640.48 -0.00,0.00,0.00,1540.48,0.00,1540.48 -0.00,0.00,0.00,1440.48,0.00,1440.48 -0.00,0.00,0.00,1340.48,0.00,1340.48 -0.00,0.00,0.00,1240.48,0.00,1240.48 -0.00,0.00,0.00,1140.48,0.00,1140.48 -0.00,0.00,0.00,1040.48,0.00,1040.48 -0.00,0.00,0.00,940.48,0.00,940.48 -0.00,0.00,0.00,840.48,0.00,840.48 -0.00,0.00,0.00,740.48,0.00,740.48 -0.00,0.00,0.00,640.48,0.00,640.48 -0.00,0.00,0.00,540.48,0.00,540.48 -0.00,0.00,0.00,440.48,0.00,440.48 -0.00,0.00,0.00,340.48,0.00,340.48 -0.00,0.00,0.00,240.48,0.00,240.48 -0.00,0.00,0.00,140.48,0.00,140.48 -0.00,0.00,0.00,40.48,0.00,40.48 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 +2500.00,350.00,2150.00,2500.00,500.00,2000.00 +2600.00,250.00,2350.00,2600.00,600.00,2000.00 +2700.00,-250.00,2950.00,2700.00,-800.00,3500.00 +2800.00,850.00,1950.00,2800.00,50.00,2750.00 +2900.00,1000.00,1900.00,2900.00,1950.00,950.00 +3000.00,1050.00,1950.00,3000.00,1050.00,1950.00 +3100.00,-100.00,3200.00,3100.00,350.00,2750.00 +3200.00,850.00,2350.00,3200.00,450.00,2750.00 +3300.00,2400.00,900.00,3300.00,1150.00,2150.00 +3400.00,1300.00,2100.00,3400.00,1500.00,1900.00 +3500.00,350.00,3150.00,3500.00,1000.00,2500.00 +3600.00,2550.00,1050.00,3600.00,1300.00,2300.00 +3700.00,1850.00,1850.00,3700.00,1900.00,1800.00 +3800.00,2100.00,1700.00,3800.00,1450.00,2350.00 +3900.00,2200.00,1700.00,3900.00,1850.00,2050.00 +4000.00,2250.00,1750.00,4000.00,1950.00,2050.00 +4100.00,2500.00,1600.00,4100.00,2050.00,2050.00 +4200.00,2800.00,1400.00,4200.00,2200.00,2000.00 +4300.00,3100.00,1200.00,4300.00,2250.00,2050.00 +4400.00,3100.00,1300.00,4400.00,2400.00,2000.00 +4500.00,3200.00,1300.00,4500.00,2750.00,1750.00 +4600.00,3350.00,1250.00,4600.00,3000.00,1600.00 +4700.00,3450.00,1250.00,4700.00,3050.00,1650.00 +4800.00,3600.00,1200.00,4800.00,3150.00,1650.00 +4900.00,3700.00,1200.00,4900.00,3200.00,1700.00 +5000.00,3750.00,1250.00,5000.00,3350.00,1650.00 +5100.00,3850.00,1250.00,5100.00,3350.00,1750.00 +5200.00,4000.00,1200.00,5200.00,3400.00,1800.00 +5300.00,4350.00,950.00,5300.00,3500.00,1800.00 +5400.00,4350.00,1050.00,5400.00,3800.00,1600.00 +5500.00,4450.00,1050.00,5500.00,4000.00,1500.00 +5600.00,4800.00,800.00,5600.00,4400.00,1200.00 +5700.00,5100.00,600.00,5700.00,4550.00,1150.00 +5800.00,5300.00,500.00,5800.00,4750.00,1050.00 +5900.00,5450.00,450.00,5900.00,5000.00,900.00 +6000.00,5700.00,300.00,6000.00,5050.00,950.00 +6100.00,5850.00,250.00,6100.00,5350.00,750.00 +6200.00,6100.00,100.00,6200.00,5600.00,600.00 +6300.00,6200.00,100.00,6300.00,5500.00,800.00 +6400.00,6100.00,300.00,6400.00,5300.00,1100.00 +6500.00,6350.00,150.00,6500.00,5400.00,1100.00 +6600.00,6350.00,250.00,6600.00,5300.00,1300.00 +6700.00,6250.00,450.00,6700.00,5500.00,1200.00 +6800.00,6450.00,350.00,6800.00,5700.00,1100.00 +6900.00,6600.00,300.00,6900.00,6000.00,900.00 +7000.00,6750.00,250.00,7000.00,6100.00,900.00 +7100.00,6900.00,200.00,7100.00,6100.00,1000.00 +7200.00,6900.00,300.00,7200.00,6450.00,750.00 +7300.00,7050.00,250.00,7300.00,6850.00,450.00 +7400.00,7250.00,150.00,7400.00,7000.00,400.00 +7500.00,7200.00,300.00,7500.00,6950.00,550.00 +7600.00,7100.00,500.00,7600.00,6750.00,850.00 +7700.00,7300.00,400.00,7700.00,7000.00,700.00 +7800.00,7700.00,100.00,7800.00,6900.00,900.00 +7900.00,7850.00,50.00,7900.00,6900.00,1000.00 +8000.00,8100.00,-100.00,8000.00,6900.00,1100.00 +8100.00,8000.00,100.00,8100.00,7300.00,800.00 +8200.00,7900.00,300.00,8200.00,7200.00,1000.00 +8300.00,7750.00,550.00,8300.00,7600.00,700.00 +8400.00,8100.00,300.00,8400.00,7800.00,600.00 +8500.00,7950.00,550.00,8500.00,7750.00,750.00 +8600.00,8150.00,450.00,8600.00,7650.00,950.00 +8700.00,8450.00,250.00,8700.00,8350.00,350.00 +8800.00,9000.00,-200.00,8800.00,8750.00,50.00 +8900.00,8850.00,50.00,8900.00,8700.00,200.00 +9000.00,9300.00,-300.00,9000.00,8700.00,300.00 +9100.00,9500.00,-400.00,9100.00,8750.00,350.00 +9200.00,9050.00,150.00,9200.00,8150.00,1050.00 +9300.00,9350.00,-50.00,9300.00,8400.00,900.00 +9400.00,11000.00,-1600.00,9400.00,10300.00,-900.00 +9500.00,9200.00,300.00,9500.00,8500.00,1000.00 +9600.00,9450.00,150.00,9600.00,8750.00,850.00 +9700.00,9850.00,-150.00,9700.00,8850.00,850.00 +9800.00,9800.00,0.00,9800.00,8800.00,1000.00 +9900.00,10150.00,-250.00,9900.00,9400.00,500.00 +10000.00,10300.00,-300.00,10000.00,10100.00,-100.00 +10100.00,10500.00,-400.00,10100.00,10200.00,-100.00 +10200.00,10050.00,150.00,10200.00,9600.00,600.00 +10300.00,10500.00,-200.00,10300.00,9700.00,600.00 +10400.00,10700.00,-300.00,10400.00,10000.00,400.00 +10500.00,10700.00,-200.00,10500.00,9900.00,600.00 +10600.00,10600.00,0.00,10600.00,9650.00,950.00 +10700.00,10900.00,-200.00,10700.00,9950.00,750.00 +10800.00,11750.00,-950.00,10800.00,10950.00,-150.00 +10900.00,12000.00,-1100.00,10900.00,11150.00,-250.00 +11000.00,11250.00,-250.00,11000.00,10800.00,200.00 +11100.00,11150.00,-50.00,11100.00,10900.00,200.00 +11200.00,12050.00,-850.00,11200.00,11650.00,-450.00 +11300.00,12150.00,-850.00,11300.00,11700.00,-400.00 +11400.00,12150.00,-750.00,11400.00,11500.00,-100.00 +11500.00,12200.00,-700.00,11500.00,11500.00,0.00 +11600.00,11750.00,-150.00,11600.00,11050.00,550.00 +11700.00,12350.00,-650.00,11700.00,11550.00,150.00 +11800.00,12500.00,-700.00,11800.00,11700.00,100.00 +11900.00,12650.00,-750.00,11900.00,12100.00,-200.00 +12000.00,12150.00,-150.00,12000.00,11550.00,450.00 +12100.00,12950.00,-850.00,12100.00,12550.00,-450.00 +12200.00,13200.00,-1000.00,12200.00,12650.00,-450.00 +12300.00,12600.00,-300.00,12300.00,12100.00,200.00 +12400.00,13550.00,-1150.00,12400.00,13100.00,-700.00 +12500.00,14000.00,-1500.00,12500.00,13500.00,-1000.00 +12600.00,13650.00,-1050.00,12600.00,13000.00,-400.00 +12700.00,13300.00,-600.00,12700.00,12850.00,-150.00 +12800.00,13700.00,-900.00,12800.00,13300.00,-500.00 +12900.00,13900.00,-1000.00,12900.00,13350.00,-450.00 +13000.00,13800.00,-800.00,13000.00,13200.00,-200.00 +13100.00,13850.00,-750.00,13100.00,13350.00,-250.00 +13200.00,13400.00,-200.00,13200.00,13050.00,150.00 +13300.00,14150.00,-850.00,13300.00,13850.00,-550.00 +13400.00,14700.00,-1300.00,13400.00,14200.00,-800.00 +13500.00,14750.00,-1250.00,13500.00,14300.00,-800.00 +13600.00,14800.00,-1200.00,13600.00,14050.00,-450.00 +13700.00,14750.00,-1050.00,13700.00,13800.00,-100.00 +13800.00,14600.00,-800.00,13800.00,13800.00,0.00 +13900.00,14550.00,-650.00,13900.00,13800.00,100.00 +14000.00,15450.00,-1450.00,14000.00,14300.00,-300.00 +14100.00,15600.00,-1500.00,14100.00,14900.00,-800.00 +14200.00,15650.00,-1450.00,14200.00,15300.00,-1100.00 +14300.00,15300.00,-1000.00,14300.00,14800.00,-500.00 +14400.00,15250.00,-850.00,14400.00,14200.00,200.00 +14500.00,15800.00,-1300.00,14500.00,14600.00,-100.00 +14600.00,16350.00,-1750.00,14600.00,15300.00,-700.00 +14700.00,16050.00,-1350.00,14700.00,15150.00,-450.00 +14800.00,15800.00,-1000.00,14800.00,15450.00,-650.00 +14900.00,16350.00,-1450.00,14900.00,16000.00,-1100.00 +15000.00,17150.00,-2150.00,15000.00,16200.00,-1200.00 +15100.00,16450.00,-1350.00,15100.00,15200.00,-100.00 +15200.00,16550.00,-1350.00,15200.00,15500.00,-300.00 +15300.00,16950.00,-1650.00,15300.00,16150.00,-850.00 +15400.00,16900.00,-1500.00,15400.00,16750.00,-1350.00 +15500.00,16500.00,-1000.00,15500.00,16650.00,-1150.00 +15600.00,16800.00,-1200.00,15600.00,16550.00,-950.00 +15700.00,17000.00,-1300.00,15700.00,16350.00,-650.00 +15800.00,17350.00,-1550.00,15800.00,17000.00,-1200.00 +15900.00,17750.00,-1850.00,15900.00,16850.00,-950.00 +16000.00,18000.00,-2000.00,16000.00,17250.00,-1250.00 +16100.00,17950.00,-1850.00,16100.00,17150.00,-1050.00 +16200.00,17750.00,-1550.00,16200.00,17100.00,-900.00 +16300.00,18050.00,-1750.00,16300.00,17550.00,-1250.00 +16400.00,17750.00,-1350.00,16400.00,17350.00,-950.00 +16500.00,17850.00,-1350.00,16500.00,17350.00,-850.00 +16600.00,18650.00,-2050.00,16600.00,18250.00,-1650.00 +16700.00,18300.00,-1600.00,16700.00,17950.00,-1250.00 +16800.00,18100.00,-1300.00,16800.00,17650.00,-850.00 +16900.00,21450.00,-4550.00,16900.00,20700.00,-3800.00 +17000.00,18150.00,-1150.00,17000.00,17500.00,-500.00 +17100.00,18200.00,-1100.00,17100.00,18100.00,-1000.00 +17200.00,18950.00,-1750.00,17200.00,19150.00,-1950.00 +17300.00,18850.00,-1550.00,17195.22,18350.00,-1154.78 +17400.00,19200.00,-1800.00,17095.22,18350.00,-1254.78 +17500.00,19650.00,-2150.00,16995.22,18750.00,-1754.78 +17600.00,19550.00,-1950.00,16895.22,18500.00,-1604.78 +17549.96,19700.00,-2150.04,16795.22,18900.00,-2104.78 +17449.96,19500.00,-2050.04,16695.22,18200.00,-1504.78 +17349.96,19500.00,-2150.04,16595.22,18100.00,-1504.78 +17249.96,19950.00,-2700.04,16495.22,18550.00,-2054.78 +17149.96,20050.00,-2900.04,16395.22,18650.00,-2254.78 +17049.96,19000.00,-1950.04,16295.22,17800.00,-1504.78 +16949.96,19300.00,-2350.04,16195.22,18100.00,-1904.78 +16849.96,20200.00,-3350.04,16095.22,18050.00,-1954.78 +16749.96,19500.00,-2750.04,15995.22,17200.00,-1204.78 +16649.96,19000.00,-2350.04,15895.22,17450.00,-1554.78 +16549.96,18800.00,-2250.04,15795.22,17700.00,-1904.78 +16449.96,18900.00,-2450.04,15695.22,18000.00,-2304.78 +16349.96,18600.00,-2250.04,15595.22,17750.00,-2154.78 +16249.96,17850.00,-1600.04,15495.22,16600.00,-1104.78 +16149.96,18500.00,-2350.04,15395.22,17350.00,-1954.78 +16049.96,19200.00,-3150.04,15295.22,17400.00,-2104.78 +15949.96,18050.00,-2100.04,15195.22,16550.00,-1354.78 +15849.96,17950.00,-2100.04,15095.22,16600.00,-1504.78 +15749.96,17950.00,-2200.04,14995.22,16450.00,-1454.78 +15649.96,17950.00,-2300.04,14895.22,16150.00,-1254.78 +15549.96,17900.00,-2350.04,14795.22,16450.00,-1654.78 +15449.96,16700.00,-1250.04,14695.22,15600.00,-904.78 +15349.96,16700.00,-1350.04,14595.22,15800.00,-1204.78 +15249.96,16650.00,-1400.04,14495.22,15950.00,-1454.78 +15149.96,17300.00,-2150.04,14395.22,16500.00,-2104.78 +15049.96,17150.00,-2100.04,14295.22,15750.00,-1454.78 +14949.96,16550.00,-1600.04,14195.22,15100.00,-904.78 +14849.96,17200.00,-2350.04,14095.22,15800.00,-1704.78 +14749.96,17350.00,-2600.04,13995.22,16050.00,-2054.78 +14649.96,16350.00,-1700.04,13895.22,15400.00,-1504.78 +14549.96,16300.00,-1750.04,13795.22,15500.00,-1704.78 +14449.96,16800.00,-2350.04,13695.22,15450.00,-1754.78 +14349.96,16350.00,-2000.04,13595.22,14850.00,-1254.78 +14249.96,16000.00,-1750.04,13495.22,14650.00,-1154.78 +14149.96,16000.00,-1850.04,13395.22,14100.00,-704.78 +14049.96,15650.00,-1600.04,13295.22,14150.00,-854.78 +13949.96,14400.00,-450.04,13195.22,13550.00,-354.78 +13849.96,14900.00,-1050.04,13095.22,14100.00,-1004.78 +13749.96,15300.00,-1550.04,12995.22,13900.00,-904.78 +13649.96,14400.00,-750.04,12895.22,13000.00,-104.78 +13549.96,14900.00,-1350.04,12795.22,13500.00,-704.78 +13449.96,14800.00,-1350.04,12695.22,14400.00,-1704.78 +13349.96,13450.00,-100.04,12595.22,14000.00,-1404.78 +13249.96,12750.00,499.96,12495.22,13100.00,-604.78 +13149.96,13950.00,-800.04,12395.22,12900.00,-504.78 +13049.96,14700.00,-1650.04,12295.22,12600.00,-304.78 +12949.96,15100.00,-2150.04,12195.22,12700.00,-504.78 +12849.96,15100.00,-2250.04,12095.22,12950.00,-854.78 +12749.96,15000.00,-2250.04,11995.22,13050.00,-1054.78 +12649.96,14000.00,-1350.04,11895.22,12250.00,-354.78 +12549.96,13850.00,-1300.04,11795.22,12150.00,-354.78 +12449.96,14200.00,-1750.04,11695.22,12800.00,-1104.78 +12349.96,13950.00,-1600.04,11595.22,12600.00,-1004.78 +12249.96,13050.00,-800.04,11495.22,11500.00,-4.78 +12149.96,13900.00,-1750.04,11395.22,12400.00,-1004.78 +12049.96,13950.00,-1900.04,11295.22,12250.00,-954.78 +11949.96,13200.00,-1250.04,11195.22,11600.00,-404.78 +11849.96,13500.00,-1650.04,11095.22,11750.00,-654.78 +11749.96,13750.00,-2000.04,10995.22,12000.00,-1004.78 +11649.96,13300.00,-1650.04,10895.22,11650.00,-754.78 +11549.96,11850.00,-300.04,10795.22,10350.00,445.22 +11449.96,12300.00,-850.04,10695.22,11100.00,-404.78 +11349.96,12850.00,-1500.04,10595.22,11550.00,-954.78 +11249.96,12800.00,-1550.04,10495.22,11400.00,-904.78 +11149.96,11950.00,-800.04,10395.22,10450.00,-54.78 +11049.96,12000.00,-950.04,10295.22,10750.00,-454.78 +10949.96,12250.00,-1300.04,10195.22,10850.00,-654.78 +10849.96,14650.00,-3800.04,10095.22,13050.00,-2954.78 +10749.96,11350.00,-600.04,9995.22,9950.00,45.22 +10649.96,10100.00,549.96,9895.22,8800.00,1095.22 +10549.96,11300.00,-750.04,9795.22,10350.00,-554.78 +10449.96,11700.00,-1250.04,9695.22,11050.00,-1354.78 +10349.96,10750.00,-400.04,9595.22,9100.00,495.22 +10249.96,10550.00,-300.04,9495.22,8850.00,645.22 +10149.96,11200.00,-1050.04,9395.22,9550.00,-154.78 +10049.96,11350.00,-1300.04,9295.22,9700.00,-404.78 +9949.96,10650.00,-700.04,9195.22,9050.00,145.22 +9849.96,10950.00,-1100.04,9095.22,9550.00,-454.78 +9749.96,11200.00,-1450.04,8995.22,9900.00,-904.78 +9649.96,10100.00,-450.04,8895.22,8850.00,45.22 +9549.96,10450.00,-900.04,8795.22,9350.00,-554.78 +9449.96,11000.00,-1550.04,8695.22,9400.00,-704.78 +9349.96,10900.00,-1550.04,8595.22,8950.00,-354.78 +9249.96,10250.00,-1000.04,8495.22,8450.00,45.22 +9149.96,9750.00,-600.04,8395.22,7950.00,445.22 +9049.96,9550.00,-500.04,8295.22,8050.00,245.22 +8949.96,9100.00,-150.04,8195.22,7650.00,545.22 +8849.96,9150.00,-300.04,8095.22,7650.00,445.22 +8749.96,9350.00,-600.04,7995.22,8100.00,-104.78 +8649.96,9800.00,-1150.04,7895.22,8400.00,-504.78 +8549.96,9350.00,-800.04,7795.22,7950.00,-154.78 +8449.96,9050.00,-600.04,7695.22,7900.00,-204.78 +8349.96,9800.00,-1450.04,7595.22,8250.00,-654.78 +8249.96,8750.00,-500.04,7495.22,7300.00,195.22 +8149.96,7500.00,649.96,7395.22,6750.00,645.22 +8049.96,8500.00,-450.04,7295.22,6850.00,445.22 +7949.96,8050.00,-100.04,7195.22,6600.00,595.22 +7849.96,7400.00,449.96,7095.22,6150.00,945.22 +7749.96,7450.00,299.96,6995.22,6350.00,645.22 +7649.96,7500.00,149.96,6895.22,6450.00,445.22 +7549.96,7600.00,-50.04,6795.22,6350.00,445.22 +7449.96,7850.00,-400.04,6695.22,6400.00,295.22 +7349.96,7950.00,-600.04,6595.22,6400.00,195.22 +7249.96,7750.00,-500.04,6495.22,6150.00,345.22 +7149.96,7300.00,-150.04,6395.22,5900.00,495.22 +7049.96,7400.00,-350.04,6295.22,5950.00,345.22 +6949.96,7400.00,-450.04,6195.22,6150.00,45.22 +6849.96,6850.00,-0.04,6095.22,5450.00,645.22 +6749.96,6100.00,649.96,5995.22,4600.00,1395.22 +6649.96,6700.00,-50.04,5895.22,5500.00,395.22 +6549.96,6150.00,399.96,5795.22,4700.00,1095.22 +6449.96,5800.00,649.96,5695.22,4400.00,1295.22 +6349.96,6100.00,249.96,5595.22,4600.00,995.22 +6249.96,5950.00,299.96,5495.22,4600.00,895.22 +6149.96,5700.00,449.96,5395.22,4400.00,995.22 +6049.96,5650.00,399.96,5295.22,4300.00,995.22 +5949.96,5550.00,399.96,5195.22,4200.00,995.22 +5849.96,5350.00,499.96,5095.22,4000.00,1095.22 +5749.96,5150.00,599.96,4995.22,3900.00,1095.22 +5649.96,5250.00,399.96,4895.22,4000.00,895.22 +5549.96,5150.00,399.96,4795.22,3950.00,845.22 +5449.96,4800.00,649.96,4695.22,3350.00,1345.22 +5349.96,4250.00,1099.96,4595.22,3100.00,1495.22 +5249.96,4700.00,549.96,4495.22,3600.00,895.22 +5149.96,3950.00,1199.96,4395.22,2750.00,1645.22 +5049.96,3450.00,1599.96,4295.22,2250.00,2045.22 +4949.96,4200.00,749.96,4195.22,3500.00,695.22 +4849.96,3250.00,1599.96,4095.22,2100.00,1995.22 +4749.96,2800.00,1949.96,3995.22,2450.00,1545.22 +4649.96,4350.00,299.96,3895.22,2950.00,945.22 +4549.96,2900.00,1649.96,3795.22,2250.00,1545.22 +4449.96,2850.00,1599.96,3695.22,1450.00,2245.22 +4349.96,4000.00,349.96,3595.22,3100.00,495.22 +4249.96,2650.00,1599.96,3495.22,2000.00,1495.22 +4149.96,2200.00,1949.96,3395.22,550.00,2845.22 +4049.96,3250.00,799.96,3295.22,1650.00,1645.22 +3949.96,2600.00,1349.96,3195.22,2400.00,795.22 +3849.96,1900.00,1949.96,3095.22,-250.00,3345.22 +3749.96,1100.00,2649.96,2995.22,1200.00,1795.22 +3649.96,2350.00,1299.96,2895.22,2450.00,445.22 +3549.96,700.00,2849.96,2795.22,-200.00,2995.22 +3449.96,1350.00,2099.96,2695.22,200.00,2495.22 +3349.96,1950.00,1399.96,2595.22,2800.00,-204.78 +3249.96,1250.00,1999.96,2495.22,200.00,2295.22 +3149.96,1500.00,1649.96,2395.22,-250.00,2645.22 +3049.96,650.00,2399.96,2295.22,550.00,1745.22 +2949.96,700.00,2249.96,2195.22,1500.00,695.22 +2849.96,800.00,2049.96,2095.22,250.00,1845.22 +2749.96,800.00,1949.96,1995.22,50.00,1945.22 +2649.96,-300.00,2949.96,1895.22,0.00,1895.22 +2549.96,550.00,1999.96,1795.22,0.00,1795.22 +2449.96,-350.00,2799.96,1695.22,0.00,1695.22 +2349.96,50.00,2299.96,1595.22,0.00,1595.22 +2249.96,0.00,2249.96,1495.22,0.00,1495.22 +2149.96,-500.00,2649.96,1395.22,0.00,1395.22 +2049.96,600.00,1449.96,1295.22,0.00,1295.22 +1949.96,-250.00,2199.96,1195.22,-50.00,1245.22 +1849.96,-200.00,2049.96,1095.22,50.00,1045.22 +1749.96,50.00,1699.96,995.22,0.00,995.22 +1649.96,-50.00,1699.96,895.22,0.00,895.22 +1549.96,0.00,1549.96,795.22,0.00,795.22 +1449.96,0.00,1449.96,695.22,0.00,695.22 +1349.96,0.00,1349.96,595.22,0.00,595.22 +1249.96,0.00,1249.96,495.22,0.00,495.22 +1149.96,0.00,1149.96,395.22,0.00,395.22 +1049.96,0.00,1049.96,295.22,0.00,295.22 +949.96,0.00,949.96,195.22,0.00,195.22 +849.96,0.00,849.96,95.22,0.00,95.22 +749.96,0.00,749.96,0.00,0.00,0.00 +649.96,0.00,649.96,0.00,0.00,0.00 +549.96,0.00,549.96,0.00,0.00,0.00 +449.96,0.00,449.96,0.00,0.00,0.00 +349.96,0.00,349.96,0.00,0.00,0.00 +249.96,0.00,249.96,0.00,0.00,0.00 +149.96,0.00,149.96,0.00,0.00,0.00 +49.96,0.00,49.96,0.00,0.00,0.00 0.00,0.00,0.00,0.00,0.00,0.00 0.00,0.00,0.00,0.00,0.00,0.00 0.00,0.00,0.00,0.00,0.00,0.00 @@ -3112,345 +3118,331 @@ LeftSetpoint,LeftVelocity,LeftError,RightSetpoint,RightVelocity,RightError -2200.00,0.00,-2200.00,-2200.00,0.00,-2200.00 -2300.00,0.00,-2300.00,-2300.00,0.00,-2300.00 -2400.00,0.00,-2400.00,-2400.00,0.00,-2400.00 --2500.00,-450.00,-2050.00,-2500.00,-650.00,-1850.00 --2600.00,-500.00,-2100.00,-2600.00,-1800.00,-800.00 --2700.00,1050.00,-3750.00,-2700.00,150.00,-2850.00 --2800.00,-350.00,-2450.00,-2800.00,-50.00,-2750.00 --2900.00,-2950.00,50.00,-2900.00,-2000.00,-900.00 --3000.00,-3850.00,850.00,-3000.00,-3000.00,0.00 --3100.00,-2850.00,-250.00,-3100.00,-2100.00,-1000.00 --3200.00,-1750.00,-1450.00,-3200.00,-500.00,-2700.00 --3300.00,-1650.00,-1650.00,-3300.00,-950.00,-2350.00 --3400.00,-100.00,-3300.00,-3400.00,-3050.00,-350.00 --3500.00,-100.00,-3400.00,-3500.00,-3750.00,250.00 --3600.00,-2500.00,-1100.00,-3600.00,-2550.00,-1050.00 --3700.00,-4350.00,650.00,-3700.00,-3700.00,0.00 --3800.00,-3550.00,-250.00,-3800.00,-600.00,-3200.00 --3900.00,-3050.00,-850.00,-3900.00,-1400.00,-2500.00 --4000.00,-2200.00,-1800.00,-4000.00,-3600.00,-400.00 --4100.00,-1700.00,-2400.00,-4100.00,-4600.00,500.00 --4200.00,-2900.00,-1300.00,-4200.00,-3500.00,-700.00 --4300.00,-4600.00,300.00,-4300.00,-2800.00,-1500.00 --4400.00,-5000.00,600.00,-4400.00,-2500.00,-1900.00 --4500.00,-4050.00,-450.00,-4500.00,-3450.00,-1050.00 --4600.00,-3300.00,-1300.00,-4600.00,-4150.00,-450.00 --4700.00,-3100.00,-1600.00,-4700.00,-3150.00,-1550.00 --4800.00,-3700.00,-1100.00,-4800.00,-2800.00,-2000.00 --4900.00,-4600.00,-300.00,-4900.00,-4350.00,-550.00 --5000.00,-5700.00,700.00,-5000.00,-5300.00,300.00 --5100.00,-4150.00,-950.00,-5100.00,-3800.00,-1300.00 --5200.00,-3950.00,-1250.00,-5200.00,-3500.00,-1700.00 --5300.00,-4200.00,-1100.00,-5300.00,-4600.00,-700.00 --5400.00,-5550.00,150.00,-5400.00,-6350.00,950.00 --5500.00,-5700.00,200.00,-5500.00,-6450.00,950.00 --5600.00,-5200.00,-400.00,-5600.00,-4500.00,-1100.00 --5700.00,-4300.00,-1400.00,-5700.00,-4050.00,-1650.00 --5800.00,-4100.00,-1700.00,-5800.00,-4750.00,-1050.00 --5900.00,-4850.00,-1050.00,-5900.00,-5000.00,-900.00 --6000.00,-6600.00,600.00,-6000.00,-6500.00,500.00 --6100.00,-7100.00,1000.00,-6100.00,-6750.00,650.00 --6200.00,-5800.00,-400.00,-6200.00,-5350.00,-850.00 --6300.00,-5350.00,-950.00,-6300.00,-5000.00,-1300.00 --6400.00,-6350.00,-50.00,-6400.00,-6000.00,-400.00 --6500.00,-7050.00,550.00,-6500.00,-7400.00,900.00 --6600.00,-6750.00,150.00,-6600.00,-6750.00,150.00 --6700.00,-6450.00,-250.00,-6700.00,-5950.00,-750.00 --6800.00,-6700.00,-100.00,-6800.00,-6900.00,100.00 --6900.00,-7250.00,350.00,-6900.00,-6900.00,0.00 --7000.00,-7500.00,500.00,-7000.00,-6900.00,-100.00 --7100.00,-7050.00,-50.00,-7100.00,-7500.00,400.00 --7200.00,-7000.00,-200.00,-7200.00,-7600.00,400.00 --7300.00,-7450.00,150.00,-7300.00,-7700.00,400.00 --7400.00,-7850.00,450.00,-7400.00,-7600.00,200.00 --7500.00,-8200.00,700.00,-7500.00,-8400.00,900.00 --7600.00,-8350.00,750.00,-7600.00,-7450.00,-150.00 --7700.00,-8350.00,650.00,-7700.00,-6400.00,-1300.00 --7800.00,-8350.00,550.00,-7800.00,-7700.00,-100.00 --7900.00,-8500.00,600.00,-7900.00,-9250.00,1350.00 --8000.00,-9000.00,1000.00,-8000.00,-8150.00,150.00 --8100.00,-9250.00,1150.00,-8100.00,-7250.00,-850.00 --8200.00,-8750.00,550.00,-8200.00,-8300.00,100.00 --8300.00,-8450.00,150.00,-8300.00,-9950.00,1650.00 --8400.00,-9550.00,1150.00,-8400.00,-8850.00,450.00 --8500.00,-9850.00,1350.00,-8500.00,-7100.00,-1400.00 --8600.00,-9800.00,1200.00,-8600.00,-7700.00,-900.00 --8700.00,-11550.00,2850.00,-8700.00,-11500.00,2800.00 --8800.00,-8550.00,-250.00,-8800.00,-9200.00,400.00 --8900.00,-8150.00,-750.00,-8900.00,-7800.00,-1100.00 --9000.00,-8000.00,-1000.00,-9000.00,-8600.00,-400.00 --9100.00,-10700.00,1600.00,-9100.00,-10550.00,1450.00 --9200.00,-11550.00,2350.00,-9200.00,-10400.00,1200.00 --9300.00,-10200.00,900.00,-9300.00,-9700.00,400.00 --9400.00,-9400.00,0.00,-9400.00,-9600.00,200.00 --9500.00,-9250.00,-250.00,-9500.00,-10100.00,600.00 --9600.00,-9900.00,300.00,-9600.00,-10900.00,1300.00 --9700.00,-10950.00,1250.00,-9700.00,-10200.00,500.00 --9800.00,-12000.00,2200.00,-9800.00,-10350.00,550.00 --9900.00,-11600.00,1700.00,-9900.00,-10400.00,500.00 --10000.00,-10600.00,600.00,-10000.00,-10650.00,650.00 --10100.00,-11150.00,1050.00,-10100.00,-11200.00,1100.00 --10200.00,-11550.00,1350.00,-10200.00,-11000.00,800.00 --10300.00,-11500.00,1200.00,-10300.00,-10850.00,550.00 --10400.00,-11600.00,1200.00,-10400.00,-10250.00,-150.00 --10500.00,-11700.00,1200.00,-10500.00,-9950.00,-550.00 --10600.00,-12550.00,1950.00,-10600.00,-11000.00,400.00 --10700.00,-12450.00,1750.00,-10700.00,-12900.00,2200.00 --10800.00,-11600.00,800.00,-10800.00,-12800.00,2000.00 --10900.00,-11950.00,1050.00,-10900.00,-11800.00,900.00 --11000.00,-12250.00,1250.00,-11000.00,-12200.00,1200.00 --11100.00,-12750.00,1650.00,-11100.00,-13450.00,2350.00 --11200.00,-13250.00,2050.00,-11200.00,-12450.00,1250.00 --11300.00,-12900.00,1600.00,-11300.00,-12100.00,800.00 --11400.00,-13200.00,1800.00,-11400.00,-13400.00,2000.00 --11500.00,-13050.00,1550.00,-11500.00,-12650.00,1150.00 --11600.00,-13350.00,1750.00,-11600.00,-12600.00,1000.00 --11700.00,-12900.00,1200.00,-11700.00,-12700.00,1000.00 --11800.00,-13050.00,1250.00,-11800.00,-14150.00,2350.00 --11900.00,-13950.00,2050.00,-11900.00,-14000.00,2100.00 --12000.00,-14300.00,2300.00,-12000.00,-14200.00,2200.00 --12100.00,-14050.00,1950.00,-12100.00,-13850.00,1750.00 --12200.00,-13900.00,1700.00,-12200.00,-12800.00,600.00 --12300.00,-13550.00,1250.00,-12300.00,-12350.00,50.00 --12400.00,-14500.00,2100.00,-12400.00,-13900.00,1500.00 --12500.00,-14000.00,1500.00,-12500.00,-16000.00,3500.00 --12600.00,-14100.00,1500.00,-12600.00,-15600.00,3000.00 --12700.00,-15050.00,2350.00,-12700.00,-14750.00,2050.00 --12800.00,-15350.00,2550.00,-12800.00,-14050.00,1250.00 --12900.00,-15500.00,2600.00,-12900.00,-14200.00,1300.00 --13000.00,-14650.00,1650.00,-13000.00,-14500.00,1500.00 --13100.00,-14000.00,900.00,-13100.00,-14350.00,1250.00 --13200.00,-14600.00,1400.00,-13200.00,-15050.00,1850.00 --13300.00,-15400.00,2100.00,-13300.00,-16100.00,2800.00 --13400.00,-15950.00,2550.00,-13400.00,-17500.00,4100.00 --13500.00,-15900.00,2400.00,-13500.00,-15000.00,1500.00 --13600.00,-15550.00,1950.00,-13600.00,-13500.00,-100.00 --13700.00,-12650.00,-1050.00,-13700.00,-15300.00,1600.00 --13800.00,-10550.00,-3250.00,-13800.00,-19000.00,5200.00 --13900.00,-7850.00,-6050.00,-13900.00,-20500.00,6600.00 --14000.00,-5200.00,-8800.00,-14000.00,-14400.00,400.00 --14100.00,3200.00,-17300.00,-14100.00,-14000.00,-100.00 --14200.00,5000.00,-19200.00,-14200.00,-2000.00,-12200.00 --14300.00,0.00,-14300.00,-14300.00,-1200.00,-13100.00 --14400.00,200.00,-14600.00,-14400.00,-1600.00,-12800.00 --14500.00,-200.00,-14300.00,-14500.00,-400.00,-14100.00 --14600.00,-200.00,-14400.00,-14600.00,-200.00,-14400.00 --14700.00,400.00,-15100.00,-14700.00,-200.00,-14500.00 --14800.00,0.00,-14800.00,-14800.00,-600.00,-14200.00 --14900.00,200.00,-15100.00,-14900.00,-200.00,-14700.00 --15000.00,600.00,-15600.00,-15000.00,-400.00,-14600.00 --15100.00,1250.00,-16350.00,-15100.00,-800.00,-14300.00 --15200.00,3350.00,-18550.00,-15200.00,-1600.00,-13600.00 --15300.00,3600.00,-18900.00,-15300.00,-800.00,-14500.00 --15400.00,2400.00,-17800.00,-15400.00,-400.00,-15000.00 --15500.00,2800.00,-18300.00,-15500.00,-600.00,-14900.00 --15600.00,2400.00,-18000.00,-15600.00,-200.00,-15400.00 --15700.00,2600.00,-18300.00,-15700.00,0.00,-15700.00 --15800.00,2600.00,-18400.00,-15800.00,-400.00,-15400.00 --15900.00,2000.00,-17900.00,-15900.00,-800.00,-15100.00 --16000.00,1200.00,-17200.00,-16000.00,-1150.00,-14850.00 --16100.00,1200.00,-17300.00,-16100.00,-450.00,-15650.00 --16200.00,400.00,-16600.00,-16200.00,-600.00,-15600.00 --16300.00,600.00,-16900.00,-16300.00,-1400.00,-14900.00 --16400.00,1000.00,-17400.00,-16400.00,-1000.00,-15400.00 --16500.00,-200.00,-16300.00,-16500.00,-600.00,-15900.00 --16600.00,600.00,-17200.00,-16600.00,-600.00,-16000.00 --16700.00,450.00,-17150.00,-16700.00,-1600.00,-15100.00 --16800.00,400.00,-17200.00,-16800.00,-2200.00,-14600.00 --16900.00,150.00,-17050.00,-16900.00,-2400.00,-14500.00 --17000.00,400.00,-17400.00,-17000.00,-1800.00,-15200.00 --17100.00,0.00,-17100.00,-17100.00,-1600.00,-15500.00 --17048.50,0.00,-17048.50,-17200.00,-600.00,-16600.00 --16948.50,200.00,-17148.50,-17300.00,-1800.00,-15500.00 --16848.50,400.00,-17248.50,-17400.00,-2800.00,-14600.00 --16748.50,450.00,-17198.50,-17412.18,-2000.00,-15412.18 --16648.50,350.00,-16998.50,-17312.18,-2200.00,-15112.18 --16548.50,200.00,-16748.50,-17212.18,-2800.00,-14412.18 --16448.50,-200.00,-16248.50,-17112.18,-1200.00,-15912.18 --16348.50,200.00,-16548.50,-17012.18,-1600.00,-15412.18 --16248.50,400.00,-16648.50,-16912.18,-1600.00,-15312.18 --16148.50,800.00,-16948.50,-16812.18,-2400.00,-14412.18 --16048.50,0.00,-16048.50,-16712.18,-1800.00,-14912.18 --15948.50,400.00,-16348.50,-16612.18,-1400.00,-15212.18 --15848.50,200.00,-16048.50,-16512.18,-2200.00,-14312.18 --15748.50,400.00,-16148.50,-16412.18,-2200.00,-14212.18 --15648.50,200.00,-15848.50,-16312.18,-1800.00,-14512.18 --15548.50,0.00,-15548.50,-16212.18,-1800.00,-14412.18 --15448.50,200.00,-15648.50,-16112.18,-2800.00,-13312.18 --15348.50,0.00,-15348.50,-16012.18,-1800.00,-14212.18 --15248.50,200.00,-15448.50,-15912.18,-2000.00,-13912.18 --15148.50,200.00,-15348.50,-15812.18,-1400.00,-14412.18 --15048.50,0.00,-15048.50,-15712.18,-1200.00,-14512.18 --14948.50,400.00,-15348.50,-15612.18,-1600.00,-14012.18 --14848.50,400.00,-15248.50,-15512.18,-1800.00,-13712.18 --14748.50,200.00,-14948.50,-15412.18,-2800.00,-12612.18 --14648.50,800.00,-15448.50,-15312.18,-2600.00,-12712.18 --14548.50,0.00,-14548.50,-15212.18,-2600.00,-12612.18 --14448.50,-200.00,-14248.50,-15112.18,-3800.00,-11312.18 --14348.50,0.00,-14348.50,-15012.18,-4400.00,-10612.18 --14248.50,-400.00,-13848.50,-14912.18,-13200.00,-1712.18 --14148.50,-5800.00,-8348.50,-14812.18,-49500.00,34687.82 --14048.50,-6400.00,-7648.50,-14712.18,-31900.00,17187.82 --13948.50,0.00,-13948.50,-14612.18,0.00,-14612.18 --13848.50,0.00,-13848.50,-14512.18,0.00,-14512.18 --13748.50,0.00,-13748.50,-14412.18,0.00,-14412.18 --13648.50,0.00,-13648.50,-14312.18,0.00,-14312.18 --13548.50,0.00,-13548.50,-14212.18,0.00,-14212.18 --13448.50,0.00,-13448.50,-14112.18,0.00,-14112.18 --13348.50,0.00,-13348.50,-14012.18,0.00,-14012.18 --13248.50,0.00,-13248.50,-13912.18,200.00,-14112.18 --13148.50,0.00,-13148.50,-13812.18,0.00,-13812.18 --13048.50,400.00,-13448.50,-13712.18,0.00,-13712.18 --12948.50,0.00,-12948.50,-13612.18,0.00,-13612.18 --12848.50,400.00,-13248.50,-13512.18,0.00,-13512.18 --12748.50,800.00,-13548.50,-13412.18,0.00,-13412.18 --12648.50,4000.00,-16648.50,-13312.18,0.00,-13312.18 --12548.50,4250.00,-16798.50,-13212.18,0.00,-13212.18 --12448.50,3550.00,-15998.50,-13112.18,0.00,-13112.18 --12348.50,2600.00,-14948.50,-13012.18,0.00,-13012.18 --12248.50,3000.00,-15248.50,-12912.18,0.00,-12912.18 --12148.50,1200.00,-13348.50,-12812.18,0.00,-12812.18 --12048.50,800.00,-12848.50,-12712.18,0.00,-12712.18 --11948.50,200.00,-12148.50,-12612.18,-800.00,-11812.18 --11848.50,0.00,-11848.50,-12512.18,-2000.00,-10512.18 --11748.50,250.00,-11998.50,-12412.18,-10000.00,-2412.18 --11648.50,-9400.00,-2248.50,-12312.18,-37800.00,25487.82 --11548.50,-1850.00,-9698.50,-12212.18,-26600.00,14387.82 --11448.50,0.00,-11448.50,-12112.18,0.00,-12112.18 --11348.50,0.00,-11348.50,-12012.18,0.00,-12012.18 --11248.50,0.00,-11248.50,-11912.18,0.00,-11912.18 --11148.50,0.00,-11148.50,-11812.18,0.00,-11812.18 --11048.50,0.00,-11048.50,-11712.18,0.00,-11712.18 --10948.50,0.00,-10948.50,-11612.18,0.00,-11612.18 --10848.50,0.00,-10848.50,-11512.18,0.00,-11512.18 --10748.50,1000.00,-11748.50,-11412.18,0.00,-11412.18 --10648.50,600.00,-11248.50,-11312.18,0.00,-11312.18 --10548.50,1400.00,-11948.50,-11212.18,0.00,-11212.18 --10448.50,2200.00,-12648.50,-11112.18,0.00,-11112.18 --10348.50,1800.00,-12148.50,-11012.18,0.00,-11012.18 --10248.50,4000.00,-14248.50,-10912.18,-200.00,-10712.18 --10148.50,3600.00,-13748.50,-10812.18,0.00,-10812.18 --10048.50,2600.00,-12648.50,-10712.18,-400.00,-10312.18 --9948.50,400.00,-10348.50,-10612.18,-400.00,-10212.18 --9848.50,0.00,-9848.50,-10512.18,-4400.00,-6112.18 --9748.50,-1400.00,-8348.50,-10412.18,-25600.00,15187.82 --9648.50,-400.00,-9248.50,-10312.18,-23000.00,12687.82 --9548.50,200.00,-9748.50,-10212.18,-200.00,-10012.18 --9448.50,400.00,-9848.50,-10112.18,-200.00,-9912.18 --9348.50,0.00,-9348.50,-10012.18,0.00,-10012.18 --9248.50,0.00,-9248.50,-9912.18,0.00,-9912.18 --9148.50,1200.00,-10348.50,-9812.18,0.00,-9812.18 --9048.50,2000.00,-11048.50,-9712.18,0.00,-9712.18 --8948.50,1800.00,-10748.50,-9612.18,0.00,-9612.18 --8848.50,2400.00,-11248.50,-9512.18,0.00,-9512.18 --8748.50,2400.00,-11148.50,-9412.18,0.00,-9412.18 --8648.50,1200.00,-9848.50,-9312.18,0.00,-9312.18 --8548.50,400.00,-8948.50,-9212.18,-200.00,-9012.18 --8448.50,0.00,-8448.50,-9112.18,-4200.00,-4912.18 --8348.50,-2400.00,-5948.50,-9012.18,-24300.00,15287.82 --8248.50,-600.00,-7648.50,-8912.18,-18300.00,9387.82 --8148.50,-2900.00,-5248.50,-8812.18,-5400.00,-3412.18 --8048.50,-2300.00,-5748.50,-8712.18,-16300.00,7587.82 --7948.50,-13900.00,5951.50,-8612.18,-19700.00,11087.82 --7848.50,-7300.00,-548.50,-8512.18,-11200.00,2687.82 --7748.50,-18350.00,10601.50,-8412.18,-3500.00,-4912.18 --7648.50,-8450.00,801.50,-8312.18,-1300.00,-7012.18 --7548.50,200.00,-7748.50,-8212.18,0.00,-8212.18 --7448.50,600.00,-8048.50,-8112.18,0.00,-8112.18 --7348.50,0.00,-7348.50,-8012.18,0.00,-8012.18 --7248.50,0.00,-7248.50,-7912.18,0.00,-7912.18 --7148.50,1200.00,-8348.50,-7812.18,-200.00,-7612.18 --7048.50,600.00,-7648.50,-7712.18,-1200.00,-6512.18 --6948.50,0.00,-6948.50,-7612.18,-3600.00,-4012.18 --6848.50,-600.00,-6248.50,-7512.18,-26800.00,19287.82 --6748.50,0.00,-6748.50,-7412.18,-15200.00,7787.82 --6648.50,-750.00,-5898.50,-7312.18,-1000.00,-6312.18 --6548.50,-1850.00,-4698.50,-7212.18,-2800.00,-4412.18 --6448.50,850.00,-7298.50,-7112.18,-6200.00,-912.18 --6348.50,-200.00,-6148.50,-7012.18,-19400.00,12387.82 --6248.50,350.00,-6598.50,-6912.18,-8800.00,1887.82 --6148.50,-4300.00,-1848.50,-6812.18,100.00,-6912.18 --6048.50,-4300.00,-1748.50,-6712.18,-100.00,-6612.18 --5948.50,1600.00,-7548.50,-6612.18,-800.00,-5812.18 --5848.50,200.00,-6048.50,-6512.18,-4200.00,-2312.18 --5748.50,-2750.00,-2998.50,-6412.18,-11900.00,5487.82 --5648.50,-14950.00,9301.50,-6312.18,-19350.00,13037.82 --5548.50,-8100.00,2551.50,-6212.18,-5900.00,-312.18 --5448.50,-2100.00,-3348.50,-6112.18,-150.00,-5962.18 --5348.50,-700.00,-4648.50,-6012.18,-1100.00,-4912.18 --5248.50,1400.00,-6648.50,-5912.18,-1800.00,-4112.18 --5148.50,400.00,-5548.50,-5812.18,-4400.00,-1412.18 --5048.50,-1600.00,-3448.50,-5712.18,-10300.00,4587.82 --4948.50,-10400.00,5451.50,-5612.18,-13550.00,7937.82 --4848.50,-8400.00,3551.50,-5512.18,-8450.00,2937.82 --4748.50,-9850.00,5101.50,-5412.18,-2900.00,-2512.18 --4648.50,-5050.00,401.50,-5312.18,-1800.00,-3512.18 --4548.50,-800.00,-3748.50,-5212.18,-5400.00,187.82 --4448.50,-2300.00,-2148.50,-5112.18,-8000.00,2887.82 --4348.50,-7100.00,2751.50,-5012.18,-6200.00,1187.82 --4248.50,-8750.00,4501.50,-4912.18,-4650.00,-262.18 --4148.50,-7250.00,3101.50,-4812.18,-3250.00,-1562.18 --4048.50,-6100.00,2051.50,-4712.18,-2650.00,-2062.18 --3948.50,-5000.00,1051.50,-4612.18,-3750.00,-862.18 --3848.50,-4050.00,201.50,-4512.18,-4700.00,187.82 --3748.50,-3200.00,-548.50,-4412.18,-3400.00,-1012.18 --3648.50,-2450.00,-1198.50,-4312.18,-2300.00,-2012.18 --3548.50,-1200.00,-2348.50,-4212.18,-1600.00,-2612.18 --3448.50,-1050.00,-2398.50,-4112.18,-3500.00,-612.18 --3348.50,-2800.00,-548.50,-4012.18,-5900.00,1887.82 --3248.50,-4450.00,1201.50,-3912.18,-3550.00,-362.18 --3148.50,-3700.00,551.50,-3812.18,-2450.00,-1362.18 --3048.50,-3000.00,-48.50,-3712.18,-450.00,-3262.18 --2948.50,-1100.00,-1848.50,-3612.18,-1050.00,-2562.18 --2848.50,-750.00,-2098.50,-3512.18,-4200.00,687.82 --2748.50,450.00,-3198.50,-3412.18,-4100.00,687.82 --2648.50,300.00,-2948.50,-3312.18,-3300.00,-12.18 --2548.50,-1400.00,-1148.50,-3212.18,-2600.00,-612.18 --2448.50,-2950.00,501.50,-3112.18,-500.00,-2612.18 --2348.50,-2150.00,-198.50,-3012.18,0.00,-3012.18 --2248.50,-1800.00,-448.50,-2912.18,-2200.00,-712.18 --2148.50,-700.00,-1448.50,-2812.18,-3400.00,587.82 --2048.50,750.00,-2798.50,-2712.18,-2000.00,-712.18 --1948.50,-400.00,-1548.50,-2612.18,-1450.00,-1162.18 --1848.50,-750.00,-1098.50,-2512.18,-400.00,-2112.18 --1748.50,400.00,-2148.50,-2412.18,550.00,-2962.18 --1648.50,850.00,-2498.50,-2312.18,-700.00,-1612.18 --1548.50,-150.00,-1398.50,-2212.18,-1350.00,-862.18 --1448.50,-50.00,-1398.50,-2112.18,-1000.00,-1112.18 --1348.50,0.00,-1348.50,-2012.18,-450.00,-1562.18 --1248.50,0.00,-1248.50,-1912.18,100.00,-2012.18 --1148.50,0.00,-1148.50,-1812.18,50.00,-1862.18 --1048.50,0.00,-1048.50,-1712.18,0.00,-1712.18 --948.50,0.00,-948.50,-1612.18,0.00,-1612.18 --848.50,0.00,-848.50,-1512.18,0.00,-1512.18 --748.50,0.00,-748.50,-1412.18,0.00,-1412.18 --648.50,0.00,-648.50,-1312.18,0.00,-1312.18 --548.50,0.00,-548.50,-1212.18,0.00,-1212.18 --448.50,0.00,-448.50,-1112.18,0.00,-1112.18 --348.50,0.00,-348.50,-1012.18,0.00,-1012.18 --248.50,0.00,-248.50,-912.18,0.00,-912.18 --148.50,0.00,-148.50,-812.18,0.00,-812.18 --48.50,0.00,-48.50,-712.18,0.00,-712.18 -0.00,0.00,0.00,-612.18,0.00,-612.18 -0.00,0.00,0.00,-512.18,0.00,-512.18 -0.00,0.00,0.00,-412.18,0.00,-412.18 -0.00,0.00,0.00,-312.18,0.00,-312.18 -0.00,0.00,0.00,-212.18,0.00,-212.18 -0.00,0.00,0.00,-112.18,0.00,-112.18 -0.00,0.00,0.00,-12.18,0.00,-12.18 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 +-2500.00,-350.00,-2150.00,-2500.00,-350.00,-2150.00 +-2600.00,-300.00,-2300.00,-2600.00,-550.00,-2050.00 +-2700.00,350.00,-3050.00,-2700.00,800.00,-3500.00 +-2800.00,-950.00,-1850.00,-2800.00,-600.00,-2200.00 +-2900.00,-750.00,-2150.00,-2900.00,-1750.00,-1150.00 +-3000.00,-1000.00,-2000.00,-3000.00,-850.00,-2150.00 +-3100.00,-1400.00,-1700.00,-3100.00,-750.00,-2350.00 +-3200.00,-1350.00,-1850.00,-3200.00,-450.00,-2750.00 +-3300.00,-1350.00,-1950.00,-3300.00,-750.00,-2550.00 +-3400.00,-900.00,-2500.00,-3400.00,-1250.00,-2150.00 +-3500.00,-1300.00,-2200.00,-3500.00,-1300.00,-2200.00 +-3600.00,-1800.00,-1800.00,-3600.00,-1300.00,-2300.00 +-3700.00,-2100.00,-1600.00,-3700.00,-1550.00,-2150.00 +-3800.00,-1950.00,-1850.00,-3800.00,-1450.00,-2350.00 +-3900.00,-2500.00,-1400.00,-3900.00,-1900.00,-2000.00 +-4000.00,-2150.00,-1850.00,-4000.00,-1700.00,-2300.00 +-4100.00,-2350.00,-1750.00,-4100.00,-2000.00,-2100.00 +-4200.00,-2550.00,-1650.00,-4200.00,-2300.00,-1900.00 +-4300.00,-2850.00,-1450.00,-4300.00,-2200.00,-2100.00 +-4400.00,-2950.00,-1450.00,-4400.00,-2350.00,-2050.00 +-4500.00,-2900.00,-1600.00,-4500.00,-2650.00,-1850.00 +-4600.00,-3200.00,-1400.00,-4600.00,-2900.00,-1700.00 +-4700.00,-3250.00,-1450.00,-4700.00,-2800.00,-1900.00 +-4800.00,-3600.00,-1200.00,-4800.00,-2750.00,-2050.00 +-4900.00,-3700.00,-1200.00,-4900.00,-3050.00,-1850.00 +-5000.00,-3700.00,-1300.00,-5000.00,-3250.00,-1750.00 +-5100.00,-3800.00,-1300.00,-5100.00,-3400.00,-1700.00 +-5200.00,-4000.00,-1200.00,-5200.00,-3650.00,-1550.00 +-5300.00,-4200.00,-1100.00,-5300.00,-4000.00,-1300.00 +-5400.00,-4400.00,-1000.00,-5400.00,-4100.00,-1300.00 +-5500.00,-4350.00,-1150.00,-5500.00,-4050.00,-1450.00 +-5600.00,-4600.00,-1000.00,-5600.00,-4200.00,-1400.00 +-5700.00,-4700.00,-1000.00,-5700.00,-4450.00,-1250.00 +-5800.00,-4700.00,-1100.00,-5800.00,-4350.00,-1450.00 +-5900.00,-4950.00,-950.00,-5900.00,-4350.00,-1550.00 +-6000.00,-5150.00,-850.00,-6000.00,-4800.00,-1200.00 +-6100.00,-5350.00,-750.00,-6100.00,-4800.00,-1300.00 +-6200.00,-5400.00,-800.00,-6200.00,-5100.00,-1100.00 +-6300.00,-5650.00,-650.00,-6300.00,-5300.00,-1000.00 +-6400.00,-5950.00,-450.00,-6400.00,-5300.00,-1100.00 +-6500.00,-5950.00,-550.00,-6500.00,-5300.00,-1200.00 +-6600.00,-5950.00,-650.00,-6600.00,-5500.00,-1100.00 +-6700.00,-6100.00,-600.00,-6700.00,-5650.00,-1050.00 +-6800.00,-6100.00,-700.00,-6800.00,-5750.00,-1050.00 +-6900.00,-6150.00,-750.00,-6900.00,-5900.00,-1000.00 +-7000.00,-6200.00,-800.00,-7000.00,-6100.00,-900.00 +-7100.00,-6100.00,-1000.00,-7100.00,-5900.00,-1200.00 +-7200.00,-6700.00,-500.00,-7200.00,-6250.00,-950.00 +-7300.00,-6950.00,-350.00,-7300.00,-6500.00,-800.00 +-7400.00,-7050.00,-350.00,-7400.00,-6350.00,-1050.00 +-7500.00,-6950.00,-550.00,-7500.00,-6600.00,-900.00 +-7600.00,-7050.00,-550.00,-7600.00,-7050.00,-550.00 +-7700.00,-6950.00,-750.00,-7700.00,-7350.00,-350.00 +-7800.00,-7000.00,-800.00,-7800.00,-7350.00,-450.00 +-7900.00,-7300.00,-600.00,-7900.00,-7600.00,-300.00 +-8000.00,-7850.00,-150.00,-8000.00,-7950.00,-50.00 +-8100.00,-8100.00,0.00,-8100.00,-7850.00,-250.00 +-8200.00,-8300.00,100.00,-8200.00,-7200.00,-1000.00 +-8300.00,-8500.00,200.00,-8300.00,-7200.00,-1100.00 +-8400.00,-8650.00,250.00,-8400.00,-7600.00,-800.00 +-8500.00,-8050.00,-450.00,-8500.00,-7650.00,-850.00 +-8600.00,-7900.00,-700.00,-8600.00,-8150.00,-450.00 +-8700.00,-8100.00,-600.00,-8700.00,-8650.00,-50.00 +-8800.00,-8100.00,-700.00,-8800.00,-8300.00,-500.00 +-8900.00,-8300.00,-600.00,-8900.00,-8700.00,-200.00 +-9000.00,-8600.00,-400.00,-9000.00,-8800.00,-200.00 +-9100.00,-8600.00,-500.00,-9100.00,-8850.00,-250.00 +-9200.00,-8900.00,-300.00,-9200.00,-8900.00,-300.00 +-9300.00,-9350.00,50.00,-9300.00,-9150.00,-150.00 +-9400.00,-11250.00,1850.00,-9400.00,-11100.00,1700.00 +-9500.00,-9300.00,-200.00,-9500.00,-9050.00,-450.00 +-9600.00,-9600.00,0.00,-9600.00,-9300.00,-300.00 +-9700.00,-9750.00,50.00,-9700.00,-9250.00,-450.00 +-9800.00,-9500.00,-300.00,-9800.00,-9000.00,-800.00 +-9900.00,-9650.00,-250.00,-9900.00,-9450.00,-450.00 +-10000.00,-10650.00,650.00,-10000.00,-10250.00,250.00 +-10100.00,-10700.00,600.00,-10100.00,-10200.00,100.00 +-10200.00,-10800.00,600.00,-10200.00,-10250.00,50.00 +-10300.00,-10750.00,450.00,-10300.00,-10250.00,-50.00 +-10400.00,-10500.00,100.00,-10400.00,-10100.00,-300.00 +-10500.00,-10650.00,150.00,-10500.00,-10250.00,-250.00 +-10600.00,-10650.00,50.00,-10600.00,-10550.00,-50.00 +-10700.00,-10900.00,200.00,-10700.00,-10850.00,150.00 +-10800.00,-11150.00,350.00,-10800.00,-11100.00,300.00 +-10900.00,-11350.00,450.00,-10900.00,-10700.00,-200.00 +-11000.00,-11650.00,650.00,-11000.00,-11000.00,0.00 +-11100.00,-12050.00,950.00,-11100.00,-11600.00,500.00 +-11200.00,-12200.00,1000.00,-11200.00,-12050.00,850.00 +-11300.00,-11650.00,350.00,-11300.00,-11500.00,200.00 +-11400.00,-11950.00,550.00,-11400.00,-11450.00,50.00 +-11500.00,-12700.00,1200.00,-11500.00,-12250.00,750.00 +-11600.00,-12650.00,1050.00,-11600.00,-12200.00,600.00 +-11700.00,-12250.00,550.00,-11700.00,-11850.00,150.00 +-11800.00,-12950.00,1150.00,-11800.00,-12650.00,850.00 +-11900.00,-13600.00,1700.00,-11900.00,-13000.00,1100.00 +-12000.00,-12900.00,900.00,-12000.00,-12250.00,250.00 +-12100.00,-13250.00,1150.00,-12100.00,-12550.00,450.00 +-12200.00,-13600.00,1400.00,-12200.00,-12600.00,400.00 +-12300.00,-13400.00,1100.00,-12300.00,-12400.00,100.00 +-12400.00,-13650.00,1250.00,-12400.00,-12900.00,500.00 +-12500.00,-13600.00,1100.00,-12500.00,-13050.00,550.00 +-12600.00,-13000.00,400.00,-12600.00,-12600.00,0.00 +-12700.00,-13750.00,1050.00,-12700.00,-13250.00,550.00 +-12800.00,-14250.00,1450.00,-12800.00,-13150.00,350.00 +-12900.00,-12700.00,-200.00,-12900.00,-11350.00,-1550.00 +-13000.00,-11850.00,-1150.00,-13000.00,-10700.00,-2300.00 +-13100.00,-14400.00,1300.00,-13100.00,-13650.00,550.00 +-13200.00,-15500.00,2300.00,-13200.00,-15100.00,1900.00 +-13300.00,-13900.00,600.00,-13300.00,-13250.00,-50.00 +-13400.00,-14350.00,950.00,-13400.00,-13900.00,500.00 +-13500.00,-15800.00,2300.00,-13500.00,-15750.00,2250.00 +-13600.00,-16000.00,2400.00,-13600.00,-15150.00,1550.00 +-13700.00,-14800.00,1100.00,-13700.00,-14300.00,600.00 +-13800.00,-15000.00,1200.00,-13800.00,-14750.00,950.00 +-13900.00,-15500.00,1600.00,-13900.00,-15350.00,1450.00 +-14000.00,-15150.00,1150.00,-14000.00,-14500.00,500.00 +-14100.00,-15500.00,1400.00,-14100.00,-15150.00,1050.00 +-14200.00,-15550.00,1350.00,-14200.00,-15250.00,1050.00 +-14300.00,-15500.00,1200.00,-14300.00,-14800.00,500.00 +-14400.00,-16250.00,1850.00,-14400.00,-15000.00,600.00 +-14500.00,-16150.00,1650.00,-14500.00,-15400.00,900.00 +-14600.00,-16300.00,1700.00,-14600.00,-15550.00,950.00 +-14700.00,-15750.00,1050.00,-14700.00,-15150.00,450.00 +-14800.00,-15150.00,350.00,-14800.00,-15100.00,300.00 +-14900.00,-16950.00,2050.00,-14900.00,-17300.00,2400.00 +-15000.00,-17400.00,2400.00,-15000.00,-16600.00,1600.00 +-15100.00,-16700.00,1600.00,-15100.00,-15900.00,800.00 +-15200.00,-16400.00,1200.00,-15200.00,-15700.00,500.00 +-15300.00,-16750.00,1450.00,-15300.00,-15800.00,500.00 +-15400.00,-17300.00,1900.00,-15400.00,-16650.00,1250.00 +-15500.00,-17450.00,1950.00,-15500.00,-17050.00,1550.00 +-15600.00,-17300.00,1700.00,-15600.00,-16550.00,950.00 +-15700.00,-17350.00,1650.00,-15700.00,-16650.00,950.00 +-15800.00,-17950.00,2150.00,-15800.00,-17400.00,1600.00 +-15900.00,-17950.00,2050.00,-15900.00,-17600.00,1700.00 +-16000.00,-18250.00,2250.00,-16000.00,-17900.00,1900.00 +-16100.00,-18350.00,2250.00,-16100.00,-17800.00,1700.00 +-16200.00,-18350.00,2150.00,-16200.00,-17150.00,950.00 +-16300.00,-18250.00,1950.00,-16300.00,-17250.00,950.00 +-16400.00,-18400.00,2000.00,-16400.00,-17800.00,1400.00 +-16500.00,-18600.00,2100.00,-16500.00,-18200.00,1700.00 +-16600.00,-18850.00,2250.00,-16600.00,-18400.00,1800.00 +-16700.00,-18900.00,2200.00,-16700.00,-18200.00,1500.00 +-16800.00,-21850.00,5050.00,-16800.00,-21100.00,4300.00 +-16900.00,-18000.00,1100.00,-16900.00,-17450.00,550.00 +-17000.00,-18000.00,1000.00,-17000.00,-17750.00,750.00 +-17100.00,-19650.00,2550.00,-17035.03,-18700.00,1664.97 +-17200.00,-19200.00,2000.00,-16935.03,-18900.00,1964.97 +-17300.00,-18950.00,1650.00,-16835.03,-18350.00,1514.97 +-17400.00,-19200.00,1800.00,-16735.03,-18400.00,1664.97 +-17448.25,-19250.00,1801.75,-16635.03,-18050.00,1414.97 +-17348.25,-19750.00,2401.75,-16535.03,-18700.00,2164.97 +-17248.25,-20500.00,3251.75,-16435.03,-18850.00,2414.97 +-17148.25,-19500.00,2351.75,-16335.03,-17750.00,1414.97 +-17048.25,-19400.00,2351.75,-16235.03,-17500.00,1264.97 +-16948.25,-19550.00,2601.75,-16135.03,-17600.00,1464.97 +-16848.25,-19450.00,2601.75,-16035.03,-17900.00,1864.97 +-16748.25,-19250.00,2501.75,-15935.03,-18100.00,2164.97 +-16648.25,-19300.00,2651.75,-15835.03,-18100.00,2264.97 +-16548.25,-18750.00,2201.75,-15735.03,-17200.00,1464.97 +-16448.25,-19000.00,2551.75,-15635.03,-17150.00,1514.97 +-16348.25,-18700.00,2351.75,-15535.03,-17350.00,1814.97 +-16248.25,-18800.00,2551.75,-15435.03,-17300.00,1864.97 +-16148.25,-18750.00,2601.75,-15335.03,-17400.00,2064.97 +-16048.25,-18500.00,2451.75,-15235.03,-17400.00,2164.97 +-15948.25,-18500.00,2551.75,-15135.03,-17100.00,1964.97 +-15848.25,-17850.00,2001.75,-15035.03,-16900.00,1864.97 +-15748.25,-17900.00,2151.75,-14935.03,-17000.00,2064.97 +-15648.25,-18100.00,2451.75,-14835.03,-17100.00,2264.97 +-15548.25,-17800.00,2251.75,-14735.03,-16950.00,2214.97 +-15448.25,-17800.00,2351.75,-14635.03,-16600.00,1964.97 +-15348.25,-17450.00,2101.75,-14535.03,-16050.00,1514.97 +-15248.25,-17350.00,2101.75,-14435.03,-16000.00,1564.97 +-15148.25,-17250.00,2101.75,-14335.03,-15900.00,1564.97 +-15048.25,-17150.00,2101.75,-14235.03,-16100.00,1864.97 +-14948.25,-16700.00,1751.75,-14135.03,-15900.00,1764.97 +-14848.25,-16600.00,1751.75,-14035.03,-15450.00,1414.97 +-14748.25,-16950.00,2201.75,-13935.03,-15400.00,1464.97 +-14648.25,-16600.00,1951.75,-13835.03,-14850.00,1014.97 +-14548.25,-16500.00,1951.75,-13735.03,-14850.00,1114.97 +-14448.25,-16600.00,2151.75,-13635.03,-15350.00,1714.97 +-14348.25,-16200.00,1851.75,-13535.03,-15600.00,2064.97 +-14248.25,-15600.00,1351.75,-13435.03,-14850.00,1414.97 +-14148.25,-16200.00,2051.75,-13335.03,-14700.00,1364.97 +-14048.25,-15700.00,1651.75,-13235.03,-14250.00,1014.97 +-13948.25,-15350.00,1401.75,-13135.03,-13700.00,564.97 +-13848.25,-15650.00,1801.75,-13035.03,-14200.00,1164.97 +-13748.25,-16100.00,2351.75,-12935.03,-14800.00,1864.97 +-13648.25,-14600.00,951.75,-12835.03,-13200.00,364.97 +-13548.25,-14300.00,751.75,-12735.03,-13100.00,364.97 +-13448.25,-15850.00,2401.75,-12635.03,-14300.00,1664.97 +-13348.25,-15250.00,1901.75,-12535.03,-12550.00,14.97 +-13248.25,-14400.00,1151.75,-12435.03,-13200.00,764.97 +-13148.25,-14550.00,1401.75,-12335.03,-12850.00,514.97 +-13048.25,-14200.00,1151.75,-12235.03,-12950.00,714.97 +-12948.25,-14400.00,1451.75,-12135.03,-12950.00,814.97 +-12848.25,-14400.00,1551.75,-12035.03,-12850.00,814.97 +-12748.25,-14350.00,1601.75,-11935.03,-12750.00,814.97 +-12648.25,-13750.00,1101.75,-11835.03,-12100.00,264.97 +-12548.25,-13950.00,1401.75,-11735.03,-12200.00,464.97 +-12448.25,-14050.00,1601.75,-11635.03,-12350.00,714.97 +-12348.25,-13750.00,1401.75,-11535.03,-12100.00,564.97 +-12248.25,-13350.00,1101.75,-11435.03,-11550.00,114.97 +-12148.25,-13650.00,1501.75,-11335.03,-12200.00,864.97 +-12048.25,-13950.00,1901.75,-11235.03,-12300.00,1064.97 +-11948.25,-12800.00,851.75,-11135.03,-11200.00,64.97 +-11848.25,-12450.00,601.75,-11035.03,-10900.00,-135.03 +-11748.25,-13100.00,1351.75,-10935.03,-11600.00,664.97 +-11648.25,-12750.00,1101.75,-10835.03,-11950.00,1114.97 +-11548.25,-12600.00,1051.75,-10735.03,-11650.00,914.97 +-11448.25,-12450.00,1001.75,-10635.03,-11600.00,964.97 +-11348.25,-12350.00,1001.75,-10535.03,-11250.00,714.97 +-11248.25,-12100.00,851.75,-10435.03,-11150.00,714.97 +-11148.25,-12050.00,901.75,-10335.03,-11550.00,1214.97 +-11048.25,-12050.00,1001.75,-10235.03,-10850.00,614.97 +-10948.25,-11750.00,801.75,-10135.03,-10150.00,14.97 +-10848.25,-11650.00,801.75,-10035.03,-9950.00,-85.03 +-10748.25,-13700.00,2951.75,-9935.03,-11950.00,2014.97 +-10648.25,-10550.00,-98.25,-9835.03,-9850.00,14.97 +-10548.25,-9500.00,-1048.25,-9735.03,-9750.00,14.97 +-10448.25,-11650.00,1201.75,-9635.03,-10000.00,364.97 +-10348.25,-11550.00,1201.75,-9535.03,-10350.00,814.97 +-10248.25,-11100.00,851.75,-9435.03,-9350.00,-85.03 +-10148.25,-10950.00,801.75,-9335.03,-9500.00,164.97 +-10048.25,-10900.00,851.75,-9235.03,-9350.00,114.97 +-9948.25,-10250.00,301.75,-9135.03,-8750.00,-385.03 +-9848.25,-9850.00,1.75,-9035.03,-8750.00,-285.03 +-9748.25,-10300.00,551.75,-8935.03,-9100.00,164.97 +-9648.25,-10450.00,801.75,-8835.03,-8850.00,14.97 +-9548.25,-10350.00,801.75,-8735.03,-8850.00,114.97 +-9448.25,-10550.00,1101.75,-8635.03,-8900.00,264.97 +-9348.25,-10150.00,801.75,-8535.03,-8600.00,64.97 +-9248.25,-9750.00,501.75,-8435.03,-8500.00,64.97 +-9148.25,-10250.00,1101.75,-8335.03,-9150.00,814.97 +-9048.25,-9900.00,851.75,-8235.03,-8650.00,414.97 +-8948.25,-9400.00,451.75,-8135.03,-8300.00,164.97 +-8848.25,-9300.00,451.75,-8035.03,-8100.00,64.97 +-8748.25,-9250.00,501.75,-7935.03,-7650.00,-285.03 +-8648.25,-9250.00,601.75,-7835.03,-7500.00,-335.03 +-8548.25,-9400.00,851.75,-7735.03,-7500.00,-235.03 +-8448.25,-9050.00,601.75,-7635.03,-7400.00,-235.03 +-8348.25,-8800.00,451.75,-7535.03,-7550.00,14.97 +-8248.25,-8600.00,351.75,-7435.03,-7400.00,-35.03 +-8148.25,-8050.00,-98.25,-7335.03,-6900.00,-435.03 +-8048.25,-8250.00,201.75,-7235.03,-7000.00,-235.03 +-7948.25,-8000.00,51.75,-7135.03,-6800.00,-335.03 +-7848.25,-8000.00,151.75,-7035.03,-6650.00,-385.03 +-7748.25,-7800.00,51.75,-6935.03,-6750.00,-185.03 +-7648.25,-7650.00,1.75,-6835.03,-6400.00,-435.03 +-7548.25,-7450.00,-98.25,-6735.03,-6200.00,-535.03 +-7448.25,-7900.00,451.75,-6635.03,-6150.00,-485.03 +-7348.25,-7150.00,-198.25,-6535.03,-5450.00,-1085.03 +-7248.25,-6900.00,-348.25,-6435.03,-5400.00,-1035.03 +-7148.25,-6950.00,-198.25,-6335.03,-5200.00,-1135.03 +-7048.25,-6900.00,-148.25,-6235.03,-5250.00,-985.03 +-6948.25,-6850.00,-98.25,-6135.03,-5250.00,-885.03 +-6848.25,-6650.00,-198.25,-6035.03,-5050.00,-985.03 +-6748.25,-6450.00,-298.25,-5935.03,-5000.00,-935.03 +-6648.25,-6500.00,-148.25,-5835.03,-5250.00,-585.03 +-6548.25,-6300.00,-248.25,-5735.03,-5100.00,-635.03 +-6448.25,-6200.00,-248.25,-5635.03,-5050.00,-585.03 +-6348.25,-6000.00,-348.25,-5535.03,-4950.00,-585.03 +-6248.25,-5950.00,-298.25,-5435.03,-4850.00,-585.03 +-6148.25,-6050.00,-98.25,-5335.03,-4700.00,-635.03 +-6048.25,-5400.00,-648.25,-5235.03,-4450.00,-785.03 +-5948.25,-5100.00,-848.25,-5135.03,-4300.00,-835.03 +-5848.25,-5250.00,-598.25,-5035.03,-4300.00,-735.03 +-5748.25,-5300.00,-448.25,-4935.03,-4100.00,-835.03 +-5648.25,-5200.00,-448.25,-4835.03,-3900.00,-935.03 +-5548.25,-5250.00,-298.25,-4735.03,-3900.00,-835.03 +-5448.25,-4700.00,-748.25,-4635.03,-3400.00,-1235.03 +-5348.25,-4250.00,-1098.25,-4535.03,-3200.00,-1335.03 +-5248.25,-4250.00,-998.25,-4435.03,-3300.00,-1135.03 +-5148.25,-3900.00,-1248.25,-4335.03,-2800.00,-1535.03 +-5048.25,-3900.00,-1148.25,-4235.03,-2800.00,-1435.03 +-4948.25,-4050.00,-898.25,-4135.03,-2650.00,-1485.03 +-4848.25,-3950.00,-898.25,-4035.03,-2300.00,-1735.03 +-4748.25,-3700.00,-1048.25,-3935.03,-2500.00,-1435.03 +-4648.25,-3700.00,-948.25,-3835.03,-2600.00,-1235.03 +-4548.25,-3000.00,-1548.25,-3735.03,-1750.00,-1985.03 +-4448.25,-2450.00,-1998.25,-3635.03,-2100.00,-1535.03 +-4348.25,-3000.00,-1348.25,-3535.03,-1700.00,-1835.03 +-4248.25,-2800.00,-1448.25,-3435.03,-1700.00,-1735.03 +-4148.25,-2750.00,-1398.25,-3335.03,-1400.00,-1935.03 +-4048.25,-3000.00,-1048.25,-3235.03,-1800.00,-1435.03 +-3948.25,-2150.00,-1798.25,-3135.03,-1450.00,-1685.03 +-3848.25,-1850.00,-1998.25,-3035.03,-1200.00,-1835.03 +-3748.25,-2400.00,-1348.25,-2935.03,-250.00,-2685.03 +-3648.25,-2000.00,-1648.25,-2835.03,-200.00,-2635.03 +-3548.25,-1750.00,-1798.25,-2735.03,-1800.00,-935.03 +-3448.25,-2050.00,-1398.25,-2635.03,-1200.00,-1435.03 +-3348.25,-1000.00,-2348.25,-2535.03,50.00,-2585.03 +-3248.25,-700.00,-2548.25,-2435.03,-350.00,-2085.03 +-3148.25,-2300.00,-848.25,-2335.03,-1250.00,-1085.03 +-3048.25,-1150.00,-1898.25,-2235.03,-250.00,-1985.03 +-2948.25,-450.00,-2498.25,-2135.03,-50.00,-2085.03 +-2848.25,-950.00,-1898.25,-2035.03,-300.00,-1735.03 +-2748.25,-700.00,-2048.25,-1935.03,-250.00,-1685.03 +-2648.25,250.00,-2898.25,-1835.03,-200.00,-1635.03 +-2548.25,-650.00,-1898.25,-1735.03,-350.00,-1385.03 +-2448.25,50.00,-2498.25,-1635.03,-150.00,-1485.03 +-2348.25,350.00,-2698.25,-1535.03,100.00,-1635.03 +-2248.25,-1050.00,-1198.25,-1435.03,0.00,-1435.03 +-2148.25,-150.00,-1998.25,-1335.03,50.00,-1385.03 +-2048.25,50.00,-2098.25,-1235.03,-50.00,-1185.03 +-1948.25,0.00,-1948.25,-1135.03,0.00,-1135.03 +-1848.25,150.00,-1998.25,-1035.03,0.00,-1035.03 +-1748.25,550.00,-2298.25,-935.03,0.00,-935.03 +-1648.25,950.00,-2598.25,-835.03,0.00,-835.03 +-1548.25,-200.00,-1348.25,-735.03,0.00,-735.03 +-1448.25,-50.00,-1398.25,-635.03,0.00,-635.03 +-1348.25,0.00,-1348.25,-535.03,0.00,-535.03 +-1248.25,0.00,-1248.25,-435.03,0.00,-435.03 +-1148.25,0.00,-1148.25,-335.03,0.00,-335.03 +-1048.25,0.00,-1048.25,-235.03,0.00,-235.03 +-948.25,0.00,-948.25,-135.03,0.00,-135.03 +-848.25,0.00,-848.25,-35.03,0.00,-35.03 +-748.25,0.00,-748.25,0.00,0.00,0.00 +-648.25,0.00,-648.25,0.00,0.00,0.00 +-548.25,0.00,-548.25,0.00,0.00,0.00 +-448.25,0.00,-448.25,0.00,0.00,0.00 +-348.25,0.00,-348.25,0.00,0.00,0.00 +-248.25,0.00,-248.25,0.00,0.00,0.00 +-148.25,0.00,-148.25,0.00,0.00,0.00 +-48.25,0.00,-48.25,0.00,0.00,0.00 0.00,0.00,0.00,0.00,0.00,0.00 0.00,0.00,0.00,0.00,0.00,0.00 0.00,0.00,0.00,0.00,0.00,0.00 diff --git a/pid_vis.py b/pid_vis.py index 24a3218..fa3a18f 100644 --- a/pid_vis.py +++ b/pid_vis.py @@ -12,8 +12,8 @@ for row in reader: 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) # power_deadzone = [0.15] * len(lists["EncoderLeft"]) diff --git a/src/robot/control.cpp b/src/robot/control.cpp index 477c0a3..9e96419 100644 --- a/src/robot/control.cpp +++ b/src/robot/control.cpp @@ -31,8 +31,8 @@ TrapezoidProfile::Constraints profileConstraints(MAX_VELOCITY_TPS, MAX_ACCELERAT TrapezoidProfile leftProfile(profileConstraints); TrapezoidProfile rightProfile(profileConstraints); TrapezoidProfile::State leftSetpoint, rightSetpoint; -PIDController encoderAVelocityController(0.00004, 0.000001, 0.00000, -1, +1); // Blue -PIDController encoderBVelocityController(0.00004, 0.000001, 0.00000, -1, +1); //Red +PIDController encoderAVelocityController(0.00004, 0.000005, 0.00000, -1, +1); // Blue +PIDController encoderBVelocityController(0.00004, 0.000005, 0.00000, -1, +1); //Red //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; From f92ffcd31615d0ddc5ebffcb1d9ac06fcc76cb31 Mon Sep 17 00:00:00 2001 From: Mason Thomas Date: Mon, 15 Sep 2025 14:42:29 -0500 Subject: [PATCH 05/47] add magnetometer 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 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 ++ 38 files changed, 9476 insertions(+) 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 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 */ From 418b15d60b671c05b9640ec6e3a0df3e89310092 Mon Sep 17 00:00:00 2001 From: Mason Thomas Date: Mon, 15 Sep 2025 14:42:41 -0500 Subject: [PATCH 06/47] build magnet class for robot --- src/robot/magnet.cpp | 76 ++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 76 insertions(+) create mode 100644 src/robot/magnet.cpp diff --git a/src/robot/magnet.cpp b/src/robot/magnet.cpp new file mode 100644 index 0000000..c3a1895 --- /dev/null +++ b/src/robot/magnet.cpp @@ -0,0 +1,76 @@ +#include "DFRobot_BMM350.h" + +#define SDA_PIN 8 +#define SCL_PIN 9 + +struct MagnetReading { + float x; + float y; + float z; +}; + +class Magnet { + public: + Magnet() + : bmm350(&Wire, 0x14) + { + Wire.begin(SDA_PIN, SCL_PIN); + bmm350.begin(); + bmm350.setOperationMode(eBmm350NormalMode); + bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ); + bmm350.setMeasurementXYZ(); + } + + void 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 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 read_calibrated_data() { + sBmm350MagData_t sensor_mag_data = bmm350.getGeomagneticData(); + float mag_data[3]; + + mag_data[0] = sensor_mag_data.float_x + hard_iron_offset[0]; + mag_data[1] = sensor_mag_data.float_y + hard_iron_offset[1]; + mag_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] * mag_data[0]) + (soft_iron_matrix[i][1] * mag_data[1]) + (soft_iron_matrix[i][2] * mag_data[2]); + } + + MagnetReading calibrated_data = { mag_data[0], mag_data[1], mag_data[2] }; + return calibrated_data; + } + + float 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; + } + + private: + DFRobot_BMM350_I2C bmm350; + + float hard_iron_offset[3] = { 23.71, 5.45, 8.27 }; + float soft_iron_matrix[3][3] = { + { 1.017, -0.024, 0.023 }, + { -0.024, 0.994, 0.002 }, + { 0.023, 0.002, .991 } + }; + +}; From 29c6dfaee216aa7ca3b7310fe0d6ae40537268b0 Mon Sep 17 00:00:00 2001 From: Mason Thomas Date: Mon, 15 Sep 2025 18:34:58 -0500 Subject: [PATCH 07/47] erm this should work --- include/robot/magnet.h | 30 ++++++++++ include/utils/logging.h | 1 + src/main.cpp | 5 ++ src/robot/magnet.cpp | 121 +++++++++++++++++----------------------- src/utils/logging.cpp | 6 ++ 5 files changed, 93 insertions(+), 70 deletions(-) create mode 100644 include/robot/magnet.h diff --git a/include/robot/magnet.h b/include/robot/magnet.h new file mode 100644 index 0000000..c13a749 --- /dev/null +++ b/include/robot/magnet.h @@ -0,0 +1,30 @@ +#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); + private: + float hard_iron_offset[3] = { 23.71, 5.45, 8.27 }; + float soft_iron_matrix[3][3] = { + { 1.017, -0.024, 0.023 }, + { -0.024, 0.994, 0.002 }, + { 0.023, 0.002, .991 } + }; + DFRobot_BMM350_I2C bmm350; +}; + +#endif // MAGNET_H \ No newline at end of file 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/src/main.cpp b/src/main.cpp index 279268d..baf7e68 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; +Magnet magnet; // Setup gets run at startup void setup() { @@ -69,6 +71,9 @@ void loop() { // Run control loop controlLoop(loopDelayMilliseconds, framesUntilPrint); + MagnetReading mag_data = magnet.read_calibrated_data(); + float heading = magnet.getCompassDegree(mag_data); + serialLogln(heading, 1); // 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/magnet.cpp b/src/robot/magnet.cpp index c3a1895..deda628 100644 --- a/src/robot/magnet.cpp +++ b/src/robot/magnet.cpp @@ -1,76 +1,57 @@ #include "DFRobot_BMM350.h" +#include "robot/magnet.h" #define SDA_PIN 8 #define SCL_PIN 9 -struct MagnetReading { - float x; - float y; - float z; -}; - -class Magnet { - public: - Magnet() - : bmm350(&Wire, 0x14) - { - Wire.begin(SDA_PIN, SCL_PIN); - bmm350.begin(); - bmm350.setOperationMode(eBmm350NormalMode); - bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ); - bmm350.setMeasurementXYZ(); - } - - void 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 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]; - } - } +Magnet::Magnet() + : bmm350(&Wire, 0x14) +{ + Wire.begin(SDA_PIN, SCL_PIN); + bmm350.begin(); + bmm350.setOperationMode(eBmm350NormalMode); + bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY, BMM350_DATA_RATE_25HZ); + bmm350.setMeasurementXYZ(); +} + +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 read_calibrated_data() { - sBmm350MagData_t sensor_mag_data = bmm350.getGeomagneticData(); - float mag_data[3]; - - mag_data[0] = sensor_mag_data.float_x + hard_iron_offset[0]; - mag_data[1] = sensor_mag_data.float_y + hard_iron_offset[1]; - mag_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] * mag_data[0]) + (soft_iron_matrix[i][1] * mag_data[1]) + (soft_iron_matrix[i][2] * mag_data[2]); - } - - MagnetReading calibrated_data = { mag_data[0], mag_data[1], mag_data[2] }; - return calibrated_data; - } - - float 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; - } - - private: - DFRobot_BMM350_I2C bmm350; - - float hard_iron_offset[3] = { 23.71, 5.45, 8.27 }; - float soft_iron_matrix[3][3] = { - { 1.017, -0.024, 0.023 }, - { -0.024, 0.994, 0.002 }, - { 0.023, 0.002, .991 } - }; - -}; + } +} + +MagnetReading Magnet::read_calibrated_data() { + sBmm350MagData_t sensor_mag_data = bmm350.getGeomagneticData(); + float mag_data[3]; + + mag_data[0] = sensor_mag_data.float_x + hard_iron_offset[0]; + mag_data[1] = sensor_mag_data.float_y + hard_iron_offset[1]; + mag_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] * mag_data[0]) + (soft_iron_matrix[i][1] * mag_data[1]) + (soft_iron_matrix[i][2] * mag_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; +} 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); From 1ab2274843c2e4351b37d28d012d709b0232a072 Mon Sep 17 00:00:00 2001 From: Mason Thomas Date: Mon, 15 Sep 2025 18:52:30 -0500 Subject: [PATCH 08/47] haha fix magnet object now it works --- src/main.cpp | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/src/main.cpp b/src/main.cpp index baf7e68..00fdee2 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -21,7 +21,7 @@ //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; -Magnet magnet; +Magnet* magnet = nullptr; // Declare a pointer to Magnet // Setup gets run at startup void setup() { @@ -31,10 +31,12 @@ void setup() { delay(STARTUP_DELAY); serialLogln("Finished Delay!", 2); - // Any setup needed to get bot ready setupBot(); + // Initialize the Magnet object + magnet = new Magnet(); + // Create a WiFi network for the laptop to connect to if (!RUN_OFFLINE) connectWiFI(); @@ -71,8 +73,8 @@ void loop() { // Run control loop controlLoop(loopDelayMilliseconds, framesUntilPrint); - MagnetReading mag_data = magnet.read_calibrated_data(); - float heading = magnet.getCompassDegree(mag_data); + MagnetReading mag_data = magnet->read_calibrated_data(); + float heading = magnet->getCompassDegree(mag_data); serialLogln(heading, 1); // This delay determines how often the code in loop is run From 3fa77c4f6a51d851b464690ff74ffd4db6f9eec1 Mon Sep 17 00:00:00 2001 From: Mason Thomas Date: Mon, 15 Sep 2025 18:52:32 -0500 Subject: [PATCH 09/47] raise debug level --- src/main.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/main.cpp b/src/main.cpp index 00fdee2..4127120 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -73,9 +73,11 @@ void loop() { // Run control loop controlLoop(loopDelayMilliseconds, framesUntilPrint); + + // test magnet data MagnetReading mag_data = magnet->read_calibrated_data(); float heading = magnet->getCompassDegree(mag_data); - serialLogln(heading, 1); + serialLogln(heading, 3); // This delay determines how often the code in loop is run // (Forcefully pauses the thread for about the amount of milliseconds passed in) From d8fd4e7eea44739c0049a37f2b4498c303b1d642 Mon Sep 17 00:00:00 2001 From: democat Date: Tue, 16 Sep 2025 00:26:55 -0500 Subject: [PATCH 10/47] Move magnet into control, log heading --- include/robot/magnet.h | 4 + pid_test.csv | 4536 ++++++++++------------------------------ pid_vis.py | 75 +- src/main.cpp | 9 - src/robot/control.cpp | 15 +- 5 files changed, 1131 insertions(+), 3508 deletions(-) diff --git a/include/robot/magnet.h b/include/robot/magnet.h index c13a749..db4c45b 100644 --- a/include/robot/magnet.h +++ b/include/robot/magnet.h @@ -17,6 +17,10 @@ class Magnet { void set_soft_iron_matrix(float matrix[3][3]); struct MagnetReading read_calibrated_data(); float getCompassDegree(struct MagnetReading mag); + float readDegrees() { + MagnetReading mag = read_calibrated_data(); + return getCompassDegree(mag); + } private: float hard_iron_offset[3] = { 23.71, 5.45, 8.27 }; float soft_iron_matrix[3][3] = { diff --git a/pid_test.csv b/pid_test.csv index df3ec6a..217dadb 100644 --- a/pid_test.csv +++ b/pid_test.csv @@ -1,3471 +1,1065 @@ -LeftSetpoint,LeftVelocity,LeftError,RightSetpoint,RightVelocity,RightError -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 --100.00,0.00,-100.00,-100.00,0.00,-100.00 --200.00,0.00,-200.00,-200.00,0.00,-200.00 --300.00,0.00,-300.00,-300.00,0.00,-300.00 --400.00,0.00,-400.00,-400.00,0.00,-400.00 --500.00,0.00,-500.00,-500.00,0.00,-500.00 --600.00,0.00,-600.00,-600.00,0.00,-600.00 --700.00,0.00,-700.00,-700.00,0.00,-700.00 --800.00,0.00,-800.00,-800.00,0.00,-800.00 --900.00,0.00,-900.00,-900.00,0.00,-900.00 --1000.00,0.00,-1000.00,-1000.00,0.00,-1000.00 --1100.00,0.00,-1100.00,-1100.00,0.00,-1100.00 --1200.00,0.00,-1200.00,-1200.00,0.00,-1200.00 --1300.00,0.00,-1300.00,-1300.00,0.00,-1300.00 --1400.00,0.00,-1400.00,-1400.00,0.00,-1400.00 --1500.00,0.00,-1500.00,-1500.00,0.00,-1500.00 --1600.00,0.00,-1600.00,-1600.00,0.00,-1600.00 --1700.00,-400.00,-1300.00,-1700.00,-500.00,-1200.00 --1800.00,-600.00,-1200.00,-1800.00,-600.00,-1200.00 --1900.00,650.00,-2550.00,-1900.00,800.00,-2700.00 --2000.00,-450.00,-1550.00,-2000.00,-500.00,-1500.00 --2100.00,-3150.00,1050.00,-2100.00,-3350.00,1250.00 --2200.00,-4000.00,1800.00,-2200.00,-3600.00,1400.00 --2300.00,-3150.00,850.00,-2300.00,-2500.00,200.00 --2400.00,-2400.00,0.00,-2400.00,-1300.00,-1100.00 --2500.00,-1300.00,-1200.00,-2500.00,-350.00,-2150.00 --2600.00,-1200.00,-1400.00,-2600.00,-1100.00,-1500.00 --2700.00,-2750.00,50.00,-2700.00,-3750.00,1050.00 --2800.00,-3600.00,800.00,-2800.00,-4000.00,1200.00 --2900.00,-2650.00,-250.00,-2900.00,-2850.00,-50.00 --3000.00,-2150.00,-850.00,-3000.00,-1200.00,-1800.00 --3100.00,-650.00,-2450.00,-3100.00,-1200.00,-1900.00 --3200.00,-750.00,-2450.00,-3200.00,-3600.00,400.00 --3300.00,-5050.00,1750.00,-3300.00,-4800.00,1500.00 --3400.00,-6800.00,3400.00,-3400.00,-3500.00,100.00 --3500.00,-4900.00,1400.00,-3500.00,-2400.00,-1100.00 --3600.00,-1300.00,-2300.00,-3600.00,-1450.00,-2150.00 --3700.00,-1750.00,-1950.00,-3700.00,-3150.00,-550.00 --3800.00,-5300.00,1500.00,-3800.00,-4800.00,1000.00 --3900.00,-6850.00,2950.00,-3900.00,-3850.00,-50.00 --4000.00,-5750.00,1750.00,-4000.00,-2550.00,-1450.00 --4100.00,-4900.00,800.00,-4100.00,-2300.00,-1800.00 --4200.00,-3950.00,-250.00,-4200.00,-4200.00,0.00 --4300.00,-3050.00,-1250.00,-4300.00,-5350.00,1050.00 --4400.00,-3050.00,-1350.00,-4400.00,-4150.00,-250.00 --4500.00,-4900.00,400.00,-4500.00,-3200.00,-1300.00 --4600.00,-5900.00,1300.00,-4600.00,-2900.00,-1700.00 --4700.00,-4950.00,250.00,-4700.00,-4850.00,150.00 --4800.00,-4100.00,-700.00,-4800.00,-6050.00,1250.00 --4900.00,-3750.00,-1150.00,-4900.00,-5150.00,250.00 --5000.00,-4700.00,-300.00,-5000.00,-4050.00,-950.00 --5100.00,-5400.00,300.00,-5100.00,-3500.00,-1600.00 --5200.00,-4650.00,-550.00,-5200.00,-5250.00,50.00 --5300.00,-4450.00,-850.00,-5300.00,-6550.00,1250.00 --5400.00,-5100.00,-300.00,-5400.00,-5500.00,100.00 --5500.00,-6150.00,650.00,-5500.00,-4700.00,-800.00 --5600.00,-5800.00,200.00,-5600.00,-4300.00,-1300.00 --5700.00,-4850.00,-850.00,-5700.00,-5900.00,200.00 --5800.00,-4750.00,-1050.00,-5800.00,-6950.00,1150.00 --5900.00,-6300.00,400.00,-5900.00,-5650.00,-250.00 --6000.00,-7200.00,1200.00,-6000.00,-5350.00,-650.00 --6100.00,-5800.00,-300.00,-6100.00,-5850.00,-250.00 --6200.00,-5500.00,-700.00,-6200.00,-6600.00,400.00 --6300.00,-6300.00,0.00,-6300.00,-6200.00,-100.00 --6400.00,-7050.00,650.00,-6400.00,-5900.00,-500.00 --6500.00,-6850.00,350.00,-6500.00,-6650.00,150.00 --6600.00,-5750.00,-850.00,-6600.00,-6450.00,-150.00 --6700.00,-5650.00,-1050.00,-6700.00,-6000.00,-700.00 --6800.00,-7400.00,600.00,-6800.00,-6700.00,-100.00 --6900.00,-8100.00,1200.00,-6900.00,-7450.00,550.00 --7000.00,-6500.00,-500.00,-7000.00,-7050.00,50.00 --7100.00,-6350.00,-750.00,-7100.00,-6300.00,-800.00 --7200.00,-7450.00,250.00,-7200.00,-7200.00,0.00 --7300.00,-8400.00,1100.00,-7300.00,-8100.00,800.00 --7400.00,-8200.00,800.00,-7400.00,-7800.00,400.00 --7500.00,-6450.00,-1050.00,-7500.00,-6150.00,-1350.00 --7600.00,-6650.00,-950.00,-7600.00,-6700.00,-900.00 --7700.00,-8900.00,1200.00,-7700.00,-8650.00,950.00 --7800.00,-11050.00,3250.00,-7800.00,-10700.00,2900.00 --7900.00,-7500.00,-400.00,-7900.00,-7100.00,-800.00 --8000.00,-6850.00,-1150.00,-8000.00,-6800.00,-1200.00 --8100.00,-8600.00,500.00,-8100.00,-8600.00,500.00 --8200.00,-10100.00,1900.00,-8200.00,-9950.00,1750.00 --8300.00,-9600.00,1300.00,-8300.00,-9350.00,1050.00 --8400.00,-7750.00,-650.00,-8400.00,-7700.00,-700.00 --8500.00,-7550.00,-950.00,-8500.00,-7300.00,-1200.00 --8600.00,-9050.00,450.00,-8600.00,-8850.00,250.00 --8700.00,-10750.00,2050.00,-8700.00,-10500.00,1800.00 --8800.00,-10250.00,1450.00,-8800.00,-10250.00,1450.00 --8900.00,-8300.00,-600.00,-8900.00,-8300.00,-600.00 --9000.00,-7950.00,-1050.00,-9000.00,-7800.00,-1200.00 --9100.00,-9750.00,650.00,-9100.00,-9600.00,500.00 --9200.00,-11550.00,2350.00,-9200.00,-11250.00,2050.00 --9300.00,-10950.00,1650.00,-9300.00,-10550.00,1250.00 --9400.00,-8850.00,-550.00,-9400.00,-8400.00,-1000.00 --9500.00,-8300.00,-1200.00,-9500.00,-8250.00,-1250.00 --9600.00,-10000.00,400.00,-9600.00,-10200.00,600.00 --9700.00,-12600.00,2900.00,-9700.00,-12150.00,2450.00 --9800.00,-12050.00,2250.00,-9800.00,-11350.00,1550.00 --9900.00,-9400.00,-500.00,-9900.00,-8500.00,-1400.00 --10000.00,-9350.00,-650.00,-10000.00,-9000.00,-1000.00 --10100.00,-10850.00,750.00,-10100.00,-11350.00,1250.00 --10200.00,-12300.00,2100.00,-10200.00,-12000.00,1800.00 --10300.00,-11650.00,1350.00,-10300.00,-9550.00,-750.00 --10400.00,-9450.00,-950.00,-10400.00,-8800.00,-1600.00 --10500.00,-9050.00,-1450.00,-10500.00,-11100.00,600.00 --10600.00,-12200.00,1600.00,-10600.00,-13650.00,3050.00 --10700.00,-14000.00,3300.00,-10700.00,-12500.00,1800.00 --10800.00,-11150.00,350.00,-10800.00,-9750.00,-1050.00 --10900.00,-9700.00,-1200.00,-10900.00,-9350.00,-1550.00 --11000.00,-11300.00,300.00,-11000.00,-12050.00,1050.00 --11100.00,-13950.00,2850.00,-11100.00,-14250.00,3150.00 --11200.00,-13550.00,2350.00,-11200.00,-12900.00,1700.00 --11300.00,-10750.00,-550.00,-11300.00,-9900.00,-1400.00 --11400.00,-10000.00,-1400.00,-11400.00,-9700.00,-1700.00 --11500.00,-12650.00,1150.00,-11500.00,-12950.00,1450.00 --11600.00,-15100.00,3500.00,-11600.00,-15150.00,3550.00 --11700.00,-13950.00,2250.00,-11700.00,-13500.00,1800.00 --11800.00,-11000.00,-800.00,-11800.00,-10650.00,-1150.00 --11900.00,-10700.00,-1200.00,-11900.00,-10650.00,-1250.00 --12000.00,-13400.00,1400.00,-12000.00,-13350.00,1350.00 --12100.00,-15600.00,3500.00,-12100.00,-15400.00,3300.00 --12200.00,-14200.00,2000.00,-12200.00,-14100.00,1900.00 --12300.00,-11300.00,-1000.00,-12300.00,-11650.00,-650.00 --12400.00,-10450.00,-1950.00,-12400.00,-11950.00,-450.00 --12500.00,-14350.00,1850.00,-12500.00,-14050.00,1550.00 --12600.00,-17600.00,5000.00,-12600.00,-15000.00,2400.00 --12700.00,-15550.00,2850.00,-12700.00,-13700.00,1000.00 --12800.00,-12250.00,-550.00,-12800.00,-11450.00,-1350.00 --12900.00,-11450.00,-1450.00,-12900.00,-13550.00,650.00 --13000.00,-14300.00,1300.00,-13000.00,-15800.00,2800.00 --13100.00,-17200.00,4100.00,-13100.00,-14800.00,1700.00 --13200.00,-15750.00,2550.00,-13200.00,-12250.00,-950.00 --13300.00,-12400.00,-900.00,-13300.00,-12800.00,-500.00 --13400.00,-11500.00,-1900.00,-13400.00,-15550.00,2150.00 --13500.00,-15200.00,1700.00,-13500.00,-16500.00,3000.00 --13600.00,-18700.00,5100.00,-13600.00,-14700.00,1100.00 --13700.00,-17200.00,3500.00,-13700.00,-12100.00,-1600.00 --13800.00,-13150.00,-650.00,-13800.00,-13800.00,0.00 --13900.00,-12000.00,-1900.00,-13900.00,-17300.00,3400.00 --14000.00,-15800.00,1800.00,-14000.00,-16900.00,2900.00 --14100.00,-19250.00,5150.00,-14100.00,-13150.00,-950.00 --14200.00,-17550.00,3350.00,-14200.00,-12000.00,-2200.00 --14300.00,-13450.00,-850.00,-14300.00,-16050.00,1750.00 --14400.00,-12350.00,-2050.00,-14400.00,-19500.00,5100.00 --14500.00,-16650.00,2150.00,-14500.00,-17650.00,3150.00 --14600.00,-20450.00,5850.00,-14600.00,-13450.00,-1150.00 --14700.00,-18250.00,3550.00,-14700.00,-12150.00,-2550.00 --14800.00,-14450.00,-350.00,-14800.00,-17300.00,2500.00 --14900.00,-12850.00,-2050.00,-14900.00,-21250.00,6350.00 --15000.00,-16450.00,1450.00,-15000.00,-18150.00,3150.00 --15100.00,-20550.00,5450.00,-15100.00,-13550.00,-1550.00 --15200.00,-22900.00,7700.00,-15200.00,-15700.00,500.00 --15300.00,-12400.00,-2900.00,-15300.00,-17250.00,1950.00 --15400.00,-8150.00,-7250.00,-15400.00,-18200.00,2800.00 --15500.00,-15900.00,400.00,-15500.00,-16150.00,650.00 --15600.00,-22150.00,6550.00,-15600.00,-14500.00,-1100.00 --15700.00,-21050.00,5350.00,-15700.00,-16000.00,300.00 --15800.00,-16050.00,250.00,-15800.00,-18900.00,3100.00 --15900.00,-13850.00,-2050.00,-15900.00,-18250.00,2350.00 --16000.00,-16750.00,750.00,-16000.00,-15150.00,-850.00 --16100.00,-21250.00,5150.00,-16100.00,-15400.00,-700.00 --16200.00,-20800.00,4600.00,-16200.00,-19650.00,3450.00 --16300.00,-15300.00,-1000.00,-16300.00,-19600.00,3300.00 --16400.00,-13950.00,-2450.00,-16400.00,-15250.00,-1150.00 --16500.00,-19500.00,3000.00,-16500.00,-13800.00,-2700.00 --16600.00,-21600.00,5000.00,-16600.00,-16900.00,300.00 --16700.00,-18850.00,2150.00,-16700.00,-21400.00,4700.00 --16800.00,-15400.00,-1400.00,-16800.00,-20900.00,4100.00 --16900.00,-16700.00,-200.00,-16900.00,-15750.00,-1150.00 --17000.00,-21550.00,4550.00,-17000.00,-14700.00,-2300.00 --17100.00,-20700.00,3600.00,-17100.00,-18350.00,1250.00 --17200.00,-15950.00,-1250.00,-17200.00,-22350.00,5150.00 --17300.00,-14450.00,-2850.00,-17300.00,-20850.00,3550.00 --17400.00,-20700.00,3300.00,-17400.00,-16350.00,-1050.00 --17500.00,-25000.00,7500.00,-17332.74,-14450.00,-2882.74 --17404.00,-21150.00,3746.00,-17232.74,-18900.00,1667.26 --17304.00,-15900.00,-1404.00,-17132.74,-23000.00,5867.26 --17204.00,-14450.00,-2754.00,-17032.74,-21200.00,4167.26 --17104.00,-20800.00,3696.00,-16932.74,-16650.00,-282.74 --17004.00,-23300.00,6296.00,-16832.74,-13750.00,-3082.74 --16904.00,-17950.00,1046.00,-16732.74,-17800.00,1067.26 --16804.00,-14900.00,-1904.00,-16632.74,-22050.00,5417.26 --16704.00,-17750.00,1046.00,-16532.74,-21350.00,4817.26 --16604.00,-21400.00,4796.00,-16432.74,-15800.00,-632.74 --16504.00,-20400.00,3896.00,-16332.74,-13500.00,-2832.74 --16404.00,-16000.00,-404.00,-16232.74,-18700.00,2467.26 --16304.00,-14100.00,-2204.00,-16132.74,-22800.00,6667.26 --16204.00,-18100.00,1896.00,-16032.74,-19300.00,3267.26 --16104.00,-22000.00,5896.00,-15932.74,-14550.00,-1382.74 --16004.00,-20900.00,4896.00,-15832.74,-13600.00,-2232.74 --15904.00,-15700.00,-204.00,-15732.74,-18450.00,2717.26 --15804.00,-13700.00,-2104.00,-15632.74,-22000.00,6367.26 --15704.00,-17750.00,2046.00,-15532.74,-19100.00,3567.26 --15604.00,-21050.00,5446.00,-15432.74,-14200.00,-1232.74 --15504.00,-19100.00,3596.00,-15332.74,-12900.00,-2432.74 --15404.00,-15000.00,-404.00,-15232.74,-18400.00,3167.26 --15304.00,-13300.00,-2004.00,-15132.74,-20950.00,5817.26 --15204.00,-17650.00,2446.00,-15032.74,-16250.00,1217.26 --15104.00,-21550.00,6446.00,-14932.74,-13100.00,-1832.74 --15004.00,-19050.00,4046.00,-14832.74,-15200.00,367.26 --14904.00,-14400.00,-504.00,-14732.74,-19250.00,4517.26 --14804.00,-12900.00,-1904.00,-14632.74,-18500.00,3867.26 --14704.00,-17100.00,2396.00,-14532.74,-14050.00,-482.74 --14604.00,-20850.00,6246.00,-14432.74,-12500.00,-1932.74 --14504.00,-18600.00,4096.00,-14332.74,-16000.00,1667.26 --14404.00,-14050.00,-354.00,-14232.74,-19700.00,5467.26 --14304.00,-12400.00,-1904.00,-14132.74,-17900.00,3767.26 --14204.00,-16400.00,2196.00,-14032.74,-13350.00,-682.74 --14104.00,-20400.00,6296.00,-13932.74,-12150.00,-1782.74 --14004.00,-18200.00,4196.00,-13832.74,-15700.00,1867.26 --13904.00,-12950.00,-954.00,-13732.74,-17400.00,3667.26 --13804.00,-12750.00,-1054.00,-13632.74,-16700.00,3067.26 --13704.00,-16750.00,3046.00,-13532.74,-12750.00,-782.74 --13604.00,-18250.00,4646.00,-13432.74,-11700.00,-1732.74 --13504.00,-14100.00,596.00,-13332.74,-15150.00,1817.26 --13404.00,-11550.00,-1854.00,-13232.74,-17600.00,4367.26 --13304.00,-14150.00,846.00,-13132.74,-16450.00,3317.26 --13204.00,-18600.00,5396.00,-13032.74,-12250.00,-782.74 --13104.00,-17200.00,4096.00,-12932.74,-10900.00,-2032.74 --13004.00,-13700.00,696.00,-12832.74,-14800.00,1967.26 --12904.00,-11450.00,-1454.00,-12732.74,-18200.00,5467.26 --12804.00,-13550.00,746.00,-12632.74,-16200.00,3567.26 --12704.00,-17250.00,4546.00,-12532.74,-12400.00,-132.74 --12604.00,-16350.00,3746.00,-12432.74,-10600.00,-1832.74 --12504.00,-14600.00,2096.00,-12332.74,-15900.00,3567.26 --12404.00,-9100.00,-3304.00,-12232.74,-15700.00,3467.26 --12304.00,-10300.00,-2004.00,-12132.74,-12500.00,367.26 --12204.00,-17200.00,4996.00,-12032.74,-10550.00,-1482.74 --12104.00,-16150.00,4046.00,-11932.74,-10100.00,-1832.74 --12004.00,-14600.00,2596.00,-11832.74,-15650.00,3817.26 --11904.00,-10650.00,-1254.00,-11732.74,-16600.00,4867.26 --11804.00,-10350.00,-1454.00,-11632.74,-12900.00,1267.26 --11704.00,-14900.00,3196.00,-11532.74,-10900.00,-632.74 --11604.00,-16500.00,4896.00,-11432.74,-11600.00,167.26 --11504.00,-12600.00,1096.00,-11332.74,-12900.00,1567.26 --11404.00,-10350.00,-1054.00,-11232.74,-13350.00,2117.26 --11304.00,-12000.00,696.00,-11132.74,-12300.00,1167.26 --11204.00,-14100.00,2896.00,-11032.74,-9750.00,-1282.74 --11104.00,-13350.00,2246.00,-10932.74,-11200.00,267.26 --11004.00,-10650.00,-354.00,-10832.74,-13000.00,2167.26 --10904.00,-9550.00,-1354.00,-10732.74,-12950.00,2217.26 --10804.00,-12100.00,1296.00,-10632.74,-9800.00,-832.74 --10704.00,-14550.00,3846.00,-10532.74,-9550.00,-982.74 --10604.00,-13250.00,2646.00,-10432.74,-11800.00,1367.26 --10504.00,-10450.00,-54.00,-10332.74,-12600.00,2267.26 --10404.00,-9350.00,-1054.00,-10232.74,-10100.00,-132.74 --10304.00,-10900.00,596.00,-10132.74,-9000.00,-1132.74 --10204.00,-13100.00,2896.00,-10032.74,-10300.00,267.26 --10104.00,-12350.00,2246.00,-9932.74,-12300.00,2367.26 --10004.00,-9900.00,-104.00,-9832.74,-11950.00,2117.26 --9904.00,-8800.00,-1104.00,-9732.74,-9250.00,-482.74 --9804.00,-10700.00,896.00,-9632.74,-8700.00,-932.74 --9704.00,-12950.00,3246.00,-9532.74,-10300.00,767.26 --9604.00,-12000.00,2396.00,-9432.74,-11700.00,2267.26 --9504.00,-9650.00,146.00,-9332.74,-10800.00,1467.26 --9404.00,-8500.00,-904.00,-9232.74,-8400.00,-832.74 --9304.00,-9850.00,546.00,-9132.74,-8200.00,-932.74 --9204.00,-11750.00,2546.00,-9032.74,-10050.00,1017.26 --9104.00,-11150.00,2046.00,-8932.74,-10550.00,1617.26 --9004.00,-9000.00,-4.00,-8832.74,-8500.00,-332.74 --8904.00,-8450.00,-454.00,-8732.74,-8100.00,-632.74 --8804.00,-9500.00,696.00,-8632.74,-9000.00,367.26 --8704.00,-10350.00,1646.00,-8532.74,-9650.00,1117.26 --8604.00,-9750.00,1146.00,-8432.74,-9200.00,767.26 --8504.00,-8100.00,-404.00,-8332.74,-7350.00,-982.74 --8404.00,-7600.00,-804.00,-8232.74,-6750.00,-1482.74 --8304.00,-9600.00,1296.00,-8132.74,-9400.00,1267.26 --8204.00,-10300.00,2096.00,-8032.74,-10150.00,2117.26 --8104.00,-8450.00,346.00,-7932.74,-8150.00,217.26 --8004.00,-7500.00,-504.00,-7832.74,-6950.00,-882.74 --7904.00,-8400.00,496.00,-7732.74,-7200.00,-532.74 --7804.00,-9550.00,1746.00,-7632.74,-8850.00,1217.26 --7704.00,-8900.00,1196.00,-7532.74,-8600.00,1067.26 --7604.00,-7400.00,-204.00,-7432.74,-6950.00,-482.74 --7504.00,-7200.00,-304.00,-7332.74,-6250.00,-1082.74 --7404.00,-7800.00,396.00,-7232.74,-7350.00,117.26 --7304.00,-8250.00,946.00,-7132.74,-8650.00,1517.26 --7204.00,-6850.00,-354.00,-7032.74,-8350.00,1317.26 --7104.00,-6500.00,-604.00,-6932.74,-6800.00,-132.74 --7004.00,-7550.00,546.00,-6832.74,-5900.00,-932.74 --6904.00,-8200.00,1296.00,-6732.74,-6450.00,-282.74 --6804.00,-7000.00,196.00,-6632.74,-7950.00,1317.26 --6704.00,-5850.00,-854.00,-6532.74,-7550.00,1017.26 --6604.00,-5800.00,-804.00,-6432.74,-6250.00,-182.74 --6504.00,-7350.00,846.00,-6332.74,-5400.00,-932.74 --6404.00,-8050.00,1646.00,-6232.74,-5950.00,-282.74 --6304.00,-6750.00,446.00,-6132.74,-7050.00,917.26 --6204.00,-5800.00,-404.00,-6032.74,-6900.00,867.26 --6104.00,-5450.00,-654.00,-5932.74,-5550.00,-382.74 --6004.00,-6250.00,246.00,-5832.74,-4850.00,-982.74 --5904.00,-6750.00,846.00,-5732.74,-5450.00,-282.74 --5804.00,-5650.00,-154.00,-5632.74,-6450.00,817.26 --5704.00,-5350.00,-354.00,-5532.74,-6150.00,617.26 --5604.00,-5700.00,96.00,-5432.74,-4850.00,-582.74 --5504.00,-5850.00,346.00,-5332.74,-4100.00,-1232.74 --5404.00,-4800.00,-604.00,-5232.74,-5050.00,-182.74 --5304.00,-4450.00,-854.00,-5132.74,-5850.00,717.26 --5204.00,-5800.00,596.00,-5032.74,-4700.00,-332.74 --5104.00,-7150.00,2046.00,-4932.74,-4100.00,-832.74 --5004.00,-5150.00,146.00,-4832.74,-2900.00,-1932.74 --4904.00,-4250.00,-654.00,-4732.74,-4500.00,-232.74 --4804.00,-3950.00,-854.00,-4632.74,-6250.00,1617.26 --4704.00,-4900.00,196.00,-4532.74,-5150.00,617.26 --4604.00,-5450.00,846.00,-4432.74,-4400.00,-32.74 --4504.00,-4550.00,46.00,-4332.74,-3400.00,-932.74 --4404.00,-3600.00,-804.00,-4232.74,-2850.00,-1382.74 --4304.00,-3450.00,-854.00,-4132.74,-4250.00,117.26 --4204.00,-4300.00,96.00,-4032.74,-5200.00,1167.26 --4104.00,-4750.00,646.00,-3932.74,-4400.00,467.26 --4004.00,-4000.00,-4.00,-3832.74,-3400.00,-432.74 --3904.00,-3100.00,-804.00,-3732.74,-2650.00,-1082.74 --3804.00,-2750.00,-1054.00,-3632.74,-2350.00,-1282.74 --3704.00,-3900.00,196.00,-3532.74,-3700.00,167.26 --3604.00,-4350.00,746.00,-3432.74,-4500.00,1067.26 --3504.00,-3600.00,96.00,-3332.74,-3650.00,317.26 --3404.00,-2850.00,-554.00,-3232.74,-2650.00,-582.74 --3304.00,-1800.00,-1504.00,-3132.74,-1600.00,-1532.74 --3204.00,-2050.00,-1154.00,-3032.74,-2100.00,-932.74 --3104.00,-3800.00,696.00,-2932.74,-3100.00,167.26 --3004.00,-4350.00,1346.00,-2832.74,-2100.00,-732.74 --2904.00,-3500.00,596.00,-2732.74,-1650.00,-1082.74 --2804.00,-2650.00,-154.00,-2632.74,200.00,-2832.74 --2704.00,-1950.00,-754.00,-2532.74,-450.00,-2082.74 --2604.00,-800.00,-1804.00,-2432.74,-4450.00,2017.26 --2504.00,-1900.00,-604.00,-2332.74,-5950.00,3617.26 --2404.00,-3150.00,746.00,-2232.74,-3100.00,867.26 --2304.00,-2500.00,196.00,-2132.74,1200.00,-3332.74 --2204.00,-1700.00,-504.00,-2032.74,-650.00,-1382.74 --2104.00,-350.00,-1754.00,-1932.74,-4400.00,2467.26 --2004.00,-1300.00,-704.00,-1832.74,-4600.00,2767.26 --1904.00,-2450.00,546.00,-1732.74,-2650.00,917.26 --1804.00,-2200.00,396.00,-1632.74,-500.00,-1132.74 --1704.00,-750.00,-954.00,-1532.74,-300.00,-1232.74 --1604.00,-750.00,-854.00,-1432.74,50.00,-1482.74 --1504.00,-950.00,-554.00,-1332.74,0.00,-1332.74 --1404.00,300.00,-1704.00,-1232.74,0.00,-1232.74 --1304.00,-400.00,-904.00,-1132.74,0.00,-1132.74 --1204.00,-950.00,-254.00,-1032.74,0.00,-1032.74 --1104.00,450.00,-1554.00,-932.74,0.00,-932.74 --1004.00,1050.00,-2054.00,-832.74,0.00,-832.74 --904.00,-550.00,-354.00,-732.74,0.00,-732.74 --804.00,-1200.00,396.00,-632.74,0.00,-632.74 --704.00,-200.00,-504.00,-532.74,0.00,-532.74 --604.00,0.00,-604.00,-432.74,0.00,-432.74 --504.00,0.00,-504.00,-332.74,0.00,-332.74 --404.00,0.00,-404.00,-232.74,0.00,-232.74 --304.00,0.00,-304.00,-132.74,0.00,-132.74 --204.00,0.00,-204.00,-32.74,0.00,-32.74 --104.00,0.00,-104.00,0.00,0.00,0.00 --4.00,0.00,-4.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -100.00,0.00,100.00,100.00,0.00,100.00 -200.00,0.00,200.00,200.00,0.00,200.00 -300.00,0.00,300.00,300.00,0.00,300.00 -400.00,0.00,400.00,400.00,0.00,400.00 -500.00,0.00,500.00,500.00,0.00,500.00 -600.00,0.00,600.00,600.00,0.00,600.00 -700.00,0.00,700.00,700.00,0.00,700.00 -800.00,0.00,800.00,800.00,0.00,800.00 -900.00,0.00,900.00,900.00,0.00,900.00 -1000.00,0.00,1000.00,1000.00,0.00,1000.00 -1100.00,0.00,1100.00,1100.00,0.00,1100.00 -1200.00,0.00,1200.00,1200.00,0.00,1200.00 -1300.00,0.00,1300.00,1300.00,0.00,1300.00 -1400.00,0.00,1400.00,1400.00,0.00,1400.00 -1500.00,0.00,1500.00,1500.00,0.00,1500.00 -1600.00,0.00,1600.00,1600.00,0.00,1600.00 -1700.00,550.00,1150.00,1700.00,550.00,1150.00 -1800.00,1950.00,-150.00,1800.00,550.00,1250.00 -1900.00,300.00,1600.00,1900.00,-700.00,2600.00 -2000.00,0.00,2000.00,2000.00,250.00,1750.00 -2100.00,750.00,1350.00,2100.00,3100.00,-1000.00 -2200.00,2450.00,-250.00,2200.00,3600.00,-1400.00 -2300.00,2700.00,-400.00,2300.00,2200.00,100.00 -2400.00,1800.00,600.00,2400.00,1450.00,950.00 -2500.00,1750.00,750.00,2500.00,-350.00,2850.00 -2600.00,350.00,2250.00,2600.00,400.00,2200.00 -2700.00,550.00,2150.00,2700.00,4000.00,-1300.00 -2800.00,3350.00,-550.00,2800.00,5100.00,-2300.00 -2900.00,5200.00,-2300.00,2900.00,4300.00,-1400.00 -3000.00,4200.00,-1200.00,3000.00,3100.00,-100.00 -3100.00,3350.00,-250.00,3100.00,1700.00,1400.00 -3200.00,2900.00,300.00,3200.00,2000.00,1200.00 -3300.00,1850.00,1450.00,3300.00,2950.00,350.00 -3400.00,2450.00,950.00,3400.00,3400.00,0.00 -3500.00,3550.00,-50.00,3500.00,2400.00,1100.00 -3600.00,3750.00,-150.00,3600.00,2050.00,1550.00 -3700.00,3200.00,500.00,3700.00,3250.00,450.00 -3800.00,2650.00,1150.00,3800.00,4150.00,-350.00 -3900.00,2350.00,1550.00,3900.00,3300.00,600.00 -4000.00,3700.00,300.00,4000.00,2100.00,1900.00 -4100.00,4850.00,-750.00,4100.00,2400.00,1700.00 -4200.00,4250.00,-50.00,4200.00,5200.00,-1000.00 -4300.00,3200.00,1100.00,4300.00,6000.00,-1700.00 -4400.00,3400.00,1000.00,4400.00,5100.00,-700.00 -4500.00,4900.00,-400.00,4500.00,4100.00,400.00 -4600.00,4800.00,-200.00,4600.00,2900.00,1700.00 -4700.00,4100.00,600.00,4700.00,2700.00,2000.00 -4800.00,4000.00,800.00,4800.00,5350.00,-550.00 -4900.00,4850.00,50.00,4900.00,6950.00,-2050.00 -5000.00,4900.00,100.00,5000.00,5650.00,-650.00 -5100.00,4200.00,900.00,5100.00,4350.00,750.00 -5200.00,4150.00,1050.00,5200.00,3500.00,1700.00 -5300.00,5200.00,100.00,5300.00,4700.00,600.00 -5400.00,5950.00,-550.00,5400.00,6500.00,-1100.00 -5500.00,5100.00,400.00,5500.00,6300.00,-800.00 -5600.00,4600.00,1000.00,5600.00,5000.00,600.00 -5700.00,5450.00,250.00,5700.00,4250.00,1450.00 -5800.00,6400.00,-600.00,5800.00,5200.00,600.00 -5900.00,6400.00,-500.00,5900.00,6800.00,-900.00 -6000.00,5600.00,400.00,6000.00,6850.00,-850.00 -6100.00,4900.00,1200.00,6100.00,5500.00,600.00 -6200.00,6150.00,50.00,6200.00,4800.00,1400.00 -6300.00,6900.00,-600.00,6300.00,5800.00,500.00 -6400.00,5900.00,500.00,6400.00,7400.00,-1000.00 -6500.00,5400.00,1100.00,6500.00,7200.00,-700.00 -6600.00,6700.00,-100.00,6600.00,5900.00,700.00 -6700.00,7750.00,-1050.00,6700.00,5450.00,1250.00 -6800.00,7700.00,-900.00,6800.00,6850.00,-50.00 -6900.00,6250.00,650.00,6900.00,8050.00,-1150.00 -7000.00,6050.00,950.00,7000.00,7600.00,-600.00 -7100.00,7200.00,-100.00,7100.00,6250.00,850.00 -7200.00,8100.00,-900.00,7200.00,5700.00,1500.00 -7300.00,8350.00,-1050.00,7300.00,7950.00,-650.00 -7400.00,6850.00,550.00,7400.00,8900.00,-1500.00 -7500.00,6450.00,1050.00,7500.00,7250.00,250.00 -7600.00,7700.00,-100.00,7600.00,6600.00,1000.00 -7700.00,9050.00,-1350.00,7700.00,7300.00,400.00 -7800.00,8700.00,-900.00,7800.00,8600.00,-800.00 -7900.00,7250.00,650.00,7900.00,8600.00,-700.00 -8000.00,7000.00,1000.00,8000.00,6900.00,1100.00 -8100.00,8350.00,-250.00,8100.00,6550.00,1550.00 -8200.00,11600.00,-3400.00,8200.00,10850.00,-2650.00 -8300.00,9600.00,-1300.00,8300.00,10800.00,-2500.00 -8400.00,7950.00,450.00,8400.00,8650.00,-250.00 -8500.00,7200.00,1300.00,8500.00,7350.00,1150.00 -8600.00,8700.00,-100.00,8600.00,8200.00,400.00 -8700.00,10600.00,-1900.00,8700.00,9800.00,-1100.00 -8800.00,10150.00,-1350.00,8800.00,9700.00,-900.00 -8900.00,8750.00,150.00,8900.00,8100.00,800.00 -9000.00,7650.00,1350.00,9000.00,7600.00,1400.00 -9100.00,9100.00,0.00,9100.00,9600.00,-500.00 -9200.00,11700.00,-2500.00,9200.00,11850.00,-2650.00 -9300.00,11500.00,-2200.00,9300.00,11000.00,-1700.00 -9400.00,9350.00,50.00,9400.00,8750.00,650.00 -9500.00,8100.00,1400.00,9500.00,8150.00,1350.00 -9600.00,9550.00,50.00,9600.00,10050.00,-450.00 -9700.00,12500.00,-2800.00,9700.00,12350.00,-2650.00 -9800.00,12200.00,-2400.00,9800.00,11550.00,-1750.00 -9900.00,9900.00,0.00,9900.00,9100.00,800.00 -10000.00,8500.00,1500.00,10000.00,8500.00,1500.00 -10100.00,10700.00,-600.00,10100.00,11300.00,-1200.00 -10200.00,13200.00,-3000.00,10200.00,13200.00,-3000.00 -10300.00,12450.00,-2150.00,10300.00,12000.00,-1700.00 -10400.00,10100.00,300.00,10400.00,9400.00,1000.00 -10500.00,8850.00,1650.00,10500.00,8900.00,1600.00 -10600.00,11100.00,-500.00,10600.00,11400.00,-800.00 -10700.00,14200.00,-3500.00,10700.00,14050.00,-3350.00 -10800.00,13500.00,-2700.00,10800.00,13000.00,-2200.00 -10900.00,10900.00,0.00,10900.00,10100.00,800.00 -11000.00,9400.00,1600.00,11000.00,9450.00,1550.00 -11100.00,11400.00,-300.00,11100.00,11550.00,-450.00 -11200.00,14500.00,-3300.00,11200.00,14450.00,-3250.00 -11300.00,13950.00,-2650.00,11300.00,13600.00,-2300.00 -11400.00,11200.00,200.00,11400.00,10500.00,900.00 -11500.00,9750.00,1750.00,11500.00,9700.00,1800.00 -11600.00,12100.00,-500.00,11600.00,12300.00,-700.00 -11700.00,15200.00,-3500.00,11700.00,15400.00,-3700.00 -11800.00,14500.00,-2700.00,11800.00,14400.00,-2600.00 -11900.00,11650.00,250.00,11900.00,10900.00,1000.00 -12000.00,10150.00,1850.00,12000.00,9900.00,2100.00 -12100.00,12550.00,-450.00,12100.00,12700.00,-600.00 -12200.00,15750.00,-3550.00,12200.00,15950.00,-3750.00 -12300.00,15100.00,-2800.00,12300.00,14650.00,-2350.00 -12400.00,11500.00,900.00,12400.00,10900.00,1500.00 -12500.00,10600.00,1900.00,12500.00,10350.00,2150.00 -12600.00,13550.00,-950.00,12600.00,13850.00,-1250.00 -12700.00,16600.00,-3900.00,12700.00,16850.00,-4150.00 -12800.00,15450.00,-2650.00,12800.00,15400.00,-2600.00 -12900.00,12200.00,700.00,12900.00,11850.00,1050.00 -13000.00,11200.00,1800.00,13000.00,11200.00,1800.00 -13100.00,14000.00,-900.00,13100.00,13900.00,-800.00 -13200.00,17000.00,-3800.00,13200.00,17050.00,-3850.00 -13300.00,15950.00,-2650.00,13300.00,16050.00,-2750.00 -13400.00,12600.00,800.00,13400.00,12200.00,1200.00 -13500.00,11050.00,2450.00,13500.00,11200.00,2300.00 -13600.00,14200.00,-600.00,13600.00,14500.00,-900.00 -13700.00,17950.00,-4250.00,13700.00,17850.00,-4150.00 -13800.00,16400.00,-2600.00,13800.00,16200.00,-2400.00 -13900.00,13250.00,650.00,13900.00,13950.00,-50.00 -14000.00,11700.00,2300.00,14000.00,13000.00,1000.00 -14100.00,15100.00,-1000.00,14100.00,14700.00,-600.00 -14200.00,18250.00,-4050.00,14200.00,16500.00,-2300.00 -14300.00,17800.00,-3500.00,14300.00,17100.00,-2800.00 -14400.00,13800.00,600.00,14400.00,15250.00,-850.00 -14500.00,12550.00,1950.00,14500.00,12650.00,1850.00 -14600.00,15550.00,-950.00,14600.00,14250.00,350.00 -14700.00,19000.00,-4300.00,14700.00,17850.00,-3150.00 -14800.00,17200.00,-2400.00,14800.00,17050.00,-2250.00 -14900.00,14750.00,150.00,14900.00,14450.00,450.00 -15000.00,14400.00,600.00,15000.00,14300.00,700.00 -15100.00,16650.00,-1550.00,15100.00,16500.00,-1400.00 -15200.00,18950.00,-3750.00,15200.00,18800.00,-3600.00 -15300.00,16950.00,-1650.00,15300.00,16950.00,-1650.00 -15400.00,14950.00,450.00,15400.00,14200.00,1200.00 -15500.00,15000.00,500.00,15500.00,15150.00,350.00 -15600.00,18200.00,-2600.00,15600.00,18650.00,-3050.00 -15700.00,19550.00,-3850.00,15700.00,18450.00,-2750.00 -15800.00,20150.00,-4350.00,15800.00,18000.00,-2200.00 -15900.00,12950.00,2950.00,15900.00,13700.00,2200.00 -16000.00,12150.00,3850.00,16000.00,13950.00,2050.00 -16100.00,16950.00,-850.00,16100.00,16950.00,-850.00 -16200.00,21300.00,-5100.00,16200.00,19250.00,-3050.00 -16300.00,20000.00,-3700.00,16300.00,18850.00,-2550.00 -16400.00,14900.00,1500.00,16400.00,16650.00,-250.00 -16500.00,14000.00,2500.00,16500.00,16250.00,250.00 -16600.00,18250.00,-1650.00,16600.00,17300.00,-700.00 -16700.00,21450.00,-4750.00,16700.00,18350.00,-1650.00 -16800.00,20400.00,-3600.00,16800.00,19650.00,-2850.00 -16900.00,15550.00,1350.00,16900.00,18900.00,-2000.00 -17000.00,13850.00,3150.00,17000.00,17200.00,-200.00 -17100.00,18850.00,-1750.00,17100.00,16900.00,200.00 -17200.00,22400.00,-5200.00,17200.00,17950.00,-750.00 -17300.00,21400.00,-4100.00,17300.00,20750.00,-3450.00 -17400.00,15700.00,1700.00,17400.00,19700.00,-2300.00 -17500.00,14600.00,2900.00,17500.00,18400.00,-900.00 -17600.00,19750.00,-2150.00,17600.00,18200.00,-600.00 -17700.00,24150.00,-6450.00,17700.00,19450.00,-1750.00 -17800.00,21750.00,-3950.00,17658.43,20350.00,-2691.57 -17900.00,16050.00,1850.00,17558.43,19350.00,-1791.57 -17897.35,14850.00,3047.35,17458.43,18700.00,-1241.57 -17797.35,20200.00,-2402.65,17358.43,18350.00,-991.57 -17697.35,24550.00,-6852.65,17258.43,19100.00,-1841.57 -17597.35,22200.00,-4602.65,17158.43,19600.00,-2441.57 -17497.35,16900.00,597.35,17058.43,19200.00,-2141.57 -17397.35,15250.00,2147.35,16958.43,18550.00,-1591.57 -17297.35,18900.00,-1602.65,16858.43,17250.00,-391.57 -17197.35,23400.00,-6202.65,16758.43,18100.00,-1341.57 -17097.35,20950.00,-3852.65,16658.43,18600.00,-1941.57 -16997.35,16150.00,847.35,16558.43,18600.00,-2041.57 -16897.35,14700.00,2197.35,16458.43,18150.00,-1691.57 -16797.35,18800.00,-2002.65,16358.43,17700.00,-1341.57 -16697.35,22200.00,-5502.65,16258.43,17100.00,-841.57 -16597.35,21000.00,-4402.65,16158.43,18050.00,-1891.57 -16497.35,16150.00,347.35,16058.43,18400.00,-2341.57 -16397.35,13850.00,2547.35,15958.43,17000.00,-1041.57 -16297.35,18300.00,-2002.65,15858.43,17150.00,-1291.57 -16197.35,22000.00,-5802.65,15758.43,17150.00,-1391.57 -16097.35,19450.00,-3352.65,15658.43,16700.00,-1041.57 -15997.35,14950.00,1047.35,15558.43,16800.00,-1241.57 -15897.35,13750.00,2147.35,15458.43,17100.00,-1641.57 -15797.35,18650.00,-2852.65,15358.43,17650.00,-2291.57 -15697.35,21900.00,-6202.65,15258.43,17000.00,-1741.57 -15597.35,18650.00,-3052.65,15158.43,15650.00,-491.57 -15497.35,14750.00,747.35,15058.43,16100.00,-1041.57 -15397.35,13400.00,1997.35,14958.43,16900.00,-1941.57 -15297.35,17600.00,-2302.65,14858.43,16950.00,-2091.57 -15197.35,20950.00,-5752.65,14758.43,16250.00,-1491.57 -15097.35,18800.00,-3702.65,14658.43,15650.00,-991.57 -14997.35,14400.00,597.35,14558.43,15850.00,-1291.57 -14897.35,13000.00,1897.35,14458.43,16150.00,-1691.57 -14797.35,16900.00,-2102.65,14358.43,16100.00,-1741.57 -14697.35,20400.00,-5702.65,14258.43,15750.00,-1491.57 -14597.35,18400.00,-3802.65,14158.43,15450.00,-1291.57 -14497.35,14250.00,247.35,14058.43,15400.00,-1341.57 -14397.35,12900.00,1497.35,13958.43,15500.00,-1541.57 -14297.35,15450.00,-1152.65,13858.43,14800.00,-941.57 -14197.35,19200.00,-5002.65,13758.43,15150.00,-1391.57 -14097.35,17550.00,-3452.65,13658.43,14850.00,-1191.57 -13997.35,14200.00,-202.65,13558.43,15300.00,-1741.57 -13897.35,12300.00,1597.35,13458.43,15100.00,-1641.57 -13797.35,15150.00,-1352.65,13358.43,14650.00,-1291.57 -13697.35,17500.00,-3802.65,13258.43,13800.00,-541.57 -13597.35,17050.00,-3452.65,13158.43,14500.00,-1341.57 -13497.35,13350.00,147.35,13058.43,14850.00,-1791.57 -13397.35,11800.00,1597.35,12958.43,14550.00,-1591.57 -13297.35,14900.00,-1602.65,12858.43,14000.00,-1141.57 -13197.35,17950.00,-4752.65,12758.43,13600.00,-841.57 -13097.35,16550.00,-3452.65,12658.43,13600.00,-941.57 -12997.35,12850.00,147.35,12558.43,13900.00,-1341.57 -12897.35,11450.00,1447.35,12458.43,13750.00,-1291.57 -12797.35,14100.00,-1302.65,12358.43,13250.00,-891.57 -12697.35,16750.00,-4052.65,12258.43,12950.00,-691.57 -12597.35,18050.00,-5452.65,12158.43,15450.00,-3291.57 -12497.35,11650.00,847.35,12058.43,12350.00,-291.57 -12397.35,10950.00,1447.35,11958.43,10650.00,1308.43 -12297.35,13500.00,-1202.65,11858.43,11900.00,-41.57 -12197.35,16350.00,-4152.65,11758.43,14800.00,-3041.57 -12097.35,15100.00,-3002.65,11658.43,14450.00,-2791.57 -11997.35,11950.00,47.35,11558.43,11250.00,308.43 -11897.35,10150.00,1747.35,11458.43,9850.00,1608.43 -11797.35,13000.00,-1202.65,11358.43,12500.00,-1141.57 -11697.35,15700.00,-4002.65,11258.43,14950.00,-3691.57 -11597.35,14450.00,-2852.65,11158.43,13650.00,-2491.57 -11497.35,11400.00,97.35,11058.43,10450.00,608.43 -11397.35,9650.00,1747.35,10958.43,9500.00,1458.43 -11297.35,12350.00,-1052.65,10858.43,11950.00,-1091.57 -11197.35,15100.00,-3902.65,10758.43,14100.00,-3341.57 -11097.35,14050.00,-2952.65,10658.43,12850.00,-2191.57 -10997.35,11150.00,-152.65,10558.43,10100.00,458.43 -10897.35,9800.00,1097.35,10458.43,9500.00,958.43 -10797.35,11050.00,-252.65,10358.43,10900.00,-541.57 -10697.35,13850.00,-3152.65,10258.43,12950.00,-2691.57 -10597.35,13400.00,-2802.65,10158.43,12450.00,-2291.57 -10497.35,10400.00,97.35,10058.43,9300.00,758.43 -10397.35,9550.00,847.35,9958.43,9400.00,558.43 -10297.35,11250.00,-952.65,9858.43,11050.00,-1191.57 -10197.35,12750.00,-2552.65,9758.43,11650.00,-1891.57 -10097.35,11900.00,-1802.65,9658.43,9100.00,558.43 -9997.35,9800.00,197.35,9558.43,8900.00,658.43 -9897.35,8850.00,1047.35,9458.43,10300.00,-841.57 -9797.35,10350.00,-552.65,9358.43,11050.00,-1691.57 -9697.35,12750.00,-3052.65,9258.43,10550.00,-1291.57 -9597.35,11650.00,-2052.65,9158.43,8200.00,958.43 -9497.35,9650.00,-152.65,9058.43,8150.00,908.43 -9397.35,9000.00,397.35,8958.43,10400.00,-1441.57 -9297.35,9900.00,-602.65,8858.43,11100.00,-2241.57 -9197.35,11000.00,-1802.65,8758.43,8850.00,-91.57 -9097.35,10000.00,-902.65,8658.43,7900.00,758.43 -8997.35,9250.00,-252.65,8558.43,9200.00,-641.57 -8897.35,9350.00,-452.65,8458.43,10200.00,-1741.57 -8797.35,9800.00,-1002.65,8358.43,9500.00,-1141.57 -8697.35,9500.00,-802.65,8258.43,7700.00,558.43 -8597.35,7550.00,1047.35,8158.43,7100.00,1058.43 -8497.35,7800.00,697.35,8058.43,8700.00,-641.57 -8397.35,10100.00,-1702.65,7958.43,9800.00,-1841.57 -8297.35,10300.00,-2002.65,7858.43,7600.00,258.43 -8197.35,8850.00,-652.65,7758.43,7400.00,358.43 -8097.35,7400.00,697.35,7658.43,8300.00,-641.57 -7997.35,6900.00,1097.35,7558.43,8000.00,-441.57 -7897.35,9100.00,-1202.65,7458.43,6800.00,658.43 -7797.35,9850.00,-2052.65,7358.43,6400.00,958.43 -7697.35,8050.00,-352.65,7258.43,7700.00,-441.57 -7597.35,7400.00,197.35,7158.43,8150.00,-991.57 -7497.35,7600.00,-102.65,7058.43,6800.00,258.43 -7397.35,8150.00,-752.65,6958.43,6450.00,508.43 -7297.35,8050.00,-752.65,6858.43,7000.00,-141.57 -7197.35,6700.00,497.35,6758.43,7450.00,-691.57 -7097.35,6300.00,797.35,6658.43,7200.00,-541.57 -6997.35,7600.00,-602.65,6558.43,5950.00,608.43 -6897.35,8050.00,-1152.65,6458.43,5400.00,1058.43 -6797.35,6700.00,97.35,6358.43,6400.00,-41.57 -6697.35,6350.00,347.35,6258.43,7700.00,-1441.57 -6597.35,6850.00,-252.65,6158.43,7000.00,-841.57 -6497.35,7150.00,-652.65,6058.43,5850.00,208.43 -6397.35,5800.00,597.35,5958.43,4650.00,1308.43 -6297.35,5500.00,797.35,5858.43,5400.00,458.43 -6197.35,6600.00,-402.65,5758.43,6750.00,-991.57 -6097.35,7350.00,-1252.65,5658.43,6850.00,-1191.57 -5997.35,6300.00,-302.65,5558.43,5400.00,158.43 -5897.35,5250.00,647.35,5458.43,4150.00,1308.43 -5797.35,5000.00,797.35,5358.43,3750.00,1608.43 -5697.35,6100.00,-402.65,5258.43,6150.00,-891.57 -5597.35,6350.00,-752.65,5158.43,7100.00,-1941.57 -5497.35,5350.00,147.35,5058.43,5850.00,-791.57 -5397.35,4850.00,547.35,4958.43,4900.00,58.43 -5297.35,4300.00,997.35,4858.43,3600.00,1258.43 -5197.35,5200.00,-2.65,4758.43,3400.00,1358.43 -5097.35,5850.00,-752.65,4658.43,5200.00,-541.57 -4997.35,5850.00,-852.65,4558.43,6900.00,-2341.57 -4897.35,4050.00,847.35,4458.43,4800.00,-341.57 -4797.35,3900.00,897.35,4358.43,3700.00,658.43 -4697.35,4900.00,-202.65,4258.43,3200.00,1058.43 -4597.35,5600.00,-1002.65,4158.43,4100.00,58.43 -4497.35,4700.00,-202.65,4058.43,4600.00,-541.57 -4397.35,3850.00,547.35,3958.43,3700.00,258.43 -4297.35,2850.00,1447.35,3858.43,2650.00,1208.43 -4197.35,3100.00,1097.35,3758.43,2450.00,1308.43 -4097.35,4950.00,-852.65,3658.43,4000.00,-341.57 -3997.35,5650.00,-1652.65,3558.43,4900.00,-1341.57 -3897.35,4800.00,-902.65,3458.43,3950.00,-491.57 -3797.35,3900.00,-102.65,3358.43,2750.00,608.43 -3697.35,3050.00,647.35,3258.43,2200.00,1058.43 -3597.35,2150.00,1447.35,3158.43,1400.00,1758.43 -3497.35,2250.00,1247.35,3058.43,3150.00,-91.57 -3397.35,4100.00,-702.65,2958.43,4450.00,-1491.57 -3297.35,4750.00,-1452.65,2858.43,3400.00,-541.57 -3197.35,3850.00,-652.65,2758.43,2400.00,358.43 -3097.35,3100.00,-2.65,2658.43,1700.00,958.43 -2997.35,2400.00,597.35,2558.43,-50.00,2608.43 -2897.35,1200.00,1697.35,2458.43,350.00,2108.43 -2797.35,1650.00,1147.35,2358.43,3700.00,-1341.57 -2697.35,3550.00,-852.65,2258.43,4950.00,-2691.57 -2597.35,3950.00,-1352.65,2158.43,4150.00,-1991.57 -2497.35,3200.00,-702.65,2058.43,3000.00,-941.57 -2397.35,2400.00,-2.65,1958.43,1800.00,158.43 -2297.35,1700.00,597.35,1858.43,1200.00,658.43 -2197.35,750.00,1447.35,1758.43,600.00,1158.43 -2097.35,1600.00,497.35,1658.43,-450.00,2108.43 -1997.35,2050.00,-52.65,1558.43,750.00,808.43 -1897.35,1800.00,97.35,1458.43,1900.00,-441.57 -1797.35,50.00,1747.35,1358.43,1500.00,-141.57 -1697.35,-100.00,1797.35,1258.43,-300.00,1558.43 -1597.35,1800.00,-202.65,1158.43,-500.00,1658.43 -1497.35,2900.00,-1402.65,1058.43,650.00,408.43 -1397.35,2250.00,-852.65,958.43,950.00,8.43 -1297.35,1300.00,-2.65,858.43,-200.00,1058.43 -1197.35,1400.00,-202.65,758.43,-950.00,1708.43 -1097.35,-450.00,1547.35,658.43,-650.00,1308.43 -997.35,-550.00,1547.35,558.43,350.00,208.43 -897.35,200.00,697.35,458.43,100.00,358.43 -797.35,0.00,797.35,358.43,0.00,358.43 -697.35,0.00,697.35,258.43,0.00,258.43 -597.35,0.00,597.35,158.43,0.00,158.43 -497.35,0.00,497.35,58.43,0.00,58.43 -397.35,0.00,397.35,0.00,0.00,0.00 -297.35,0.00,297.35,0.00,0.00,0.00 -197.35,0.00,197.35,0.00,0.00,0.00 -97.35,0.00,97.35,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 --100.00,0.00,-100.00,-100.00,0.00,-100.00 --200.00,0.00,-200.00,-200.00,0.00,-200.00 --300.00,0.00,-300.00,-300.00,0.00,-300.00 --400.00,0.00,-400.00,-400.00,0.00,-400.00 --500.00,0.00,-500.00,-500.00,0.00,-500.00 --600.00,0.00,-600.00,-600.00,0.00,-600.00 --700.00,0.00,-700.00,-700.00,0.00,-700.00 --800.00,0.00,-800.00,-800.00,0.00,-800.00 --900.00,0.00,-900.00,-900.00,0.00,-900.00 --1000.00,0.00,-1000.00,-1000.00,0.00,-1000.00 --1100.00,0.00,-1100.00,-1100.00,0.00,-1100.00 --1200.00,0.00,-1200.00,-1200.00,0.00,-1200.00 --1300.00,0.00,-1300.00,-1300.00,0.00,-1300.00 --1400.00,0.00,-1400.00,-1400.00,0.00,-1400.00 --1500.00,0.00,-1500.00,-1500.00,0.00,-1500.00 --1600.00,0.00,-1600.00,-1600.00,0.00,-1600.00 --1700.00,0.00,-1700.00,-1700.00,0.00,-1700.00 --1800.00,0.00,-1800.00,-1800.00,0.00,-1800.00 --1900.00,0.00,-1900.00,-1900.00,0.00,-1900.00 --2000.00,0.00,-2000.00,-2000.00,0.00,-2000.00 --2100.00,0.00,-2100.00,-2100.00,0.00,-2100.00 --2200.00,0.00,-2200.00,-2200.00,0.00,-2200.00 --2300.00,0.00,-2300.00,-2300.00,0.00,-2300.00 --2400.00,0.00,-2400.00,-2400.00,0.00,-2400.00 --2500.00,0.00,-2500.00,-2500.00,0.00,-2500.00 --2600.00,-450.00,-2150.00,-2600.00,-450.00,-2150.00 --2700.00,-450.00,-2250.00,-2700.00,-500.00,-2200.00 --2800.00,800.00,-3600.00,-2800.00,800.00,-3600.00 --2900.00,-500.00,-2400.00,-2900.00,-450.00,-2450.00 --3000.00,-2600.00,-400.00,-3000.00,-2650.00,-350.00 --3100.00,-3200.00,100.00,-3100.00,-2800.00,-300.00 --3200.00,-2500.00,-700.00,-3200.00,-1800.00,-1400.00 --3300.00,-2050.00,-1250.00,-3300.00,100.00,-3400.00 --3400.00,-200.00,-3200.00,-3400.00,0.00,-3400.00 --3500.00,-350.00,-3150.00,-3500.00,-2700.00,-800.00 --3600.00,-3250.00,-350.00,-3600.00,-4150.00,550.00 --3700.00,-4200.00,500.00,-3700.00,-2950.00,-750.00 --3800.00,-3650.00,-150.00,-3800.00,-1600.00,-2200.00 --3900.00,-2900.00,-1000.00,-3900.00,-1850.00,-2050.00 --4000.00,-2250.00,-1750.00,-4000.00,-2750.00,-1250.00 --4100.00,-1550.00,-2550.00,-4100.00,-3400.00,-700.00 --4200.00,-3250.00,-950.00,-4200.00,-1900.00,-2300.00 --4300.00,-4450.00,150.00,-4300.00,-2100.00,-2200.00 --4400.00,-3550.00,-850.00,-4400.00,-3250.00,-1150.00 --4500.00,-2850.00,-1650.00,-4500.00,-3850.00,-650.00 --4600.00,-2700.00,-1900.00,-4600.00,-2700.00,-1900.00 --4700.00,-3800.00,-900.00,-4700.00,-1750.00,-2950.00 --4800.00,-4650.00,-150.00,-4800.00,-3350.00,-1450.00 --4900.00,-3600.00,-1300.00,-4900.00,-4800.00,-100.00 --5000.00,-3450.00,-1550.00,-5000.00,-4500.00,-500.00 --5100.00,-4500.00,-600.00,-5100.00,-3300.00,-1800.00 --5200.00,-5300.00,100.00,-5200.00,-2700.00,-2500.00 --5300.00,-4200.00,-1100.00,-5300.00,-4000.00,-1300.00 --5400.00,-3950.00,-1450.00,-5400.00,-5400.00,0.00 --5500.00,-4950.00,-550.00,-5500.00,-5100.00,-400.00 --5600.00,-5800.00,200.00,-5600.00,-3850.00,-1750.00 --5700.00,-5900.00,200.00,-5700.00,-3200.00,-2500.00 --5800.00,-5000.00,-800.00,-5800.00,-4750.00,-1050.00 --5900.00,-4600.00,-1300.00,-5900.00,-6100.00,200.00 --6000.00,-5450.00,-550.00,-6000.00,-6000.00,0.00 --6100.00,-6500.00,400.00,-6100.00,-4700.00,-1400.00 --6200.00,-6600.00,400.00,-6200.00,-4100.00,-2100.00 --6300.00,-5550.00,-750.00,-6300.00,-5600.00,-700.00 --6400.00,-5200.00,-1200.00,-6400.00,-6750.00,350.00 --6500.00,-6150.00,-350.00,-6500.00,-6650.00,150.00 --6600.00,-7200.00,600.00,-6600.00,-5800.00,-800.00 --6700.00,-7200.00,500.00,-6700.00,-5850.00,-850.00 --6800.00,-6100.00,-700.00,-6800.00,-6350.00,-450.00 --6900.00,-5850.00,-1050.00,-6900.00,-6750.00,-150.00 --7000.00,-6750.00,-250.00,-7000.00,-7050.00,50.00 --7100.00,-7800.00,700.00,-7100.00,-7100.00,0.00 --7200.00,-7900.00,700.00,-7200.00,-7200.00,0.00 --7300.00,-6550.00,-750.00,-7300.00,-7250.00,-50.00 --7400.00,-6300.00,-1100.00,-7400.00,-7350.00,-50.00 --7500.00,-7400.00,-100.00,-7500.00,-7500.00,0.00 --7600.00,-8450.00,850.00,-7600.00,-7600.00,0.00 --7700.00,-8950.00,1250.00,-7700.00,-7800.00,100.00 --7800.00,-9750.00,1950.00,-7800.00,-9400.00,1600.00 --7900.00,-6900.00,-1000.00,-7900.00,-7500.00,-400.00 --8000.00,-6600.00,-1400.00,-8000.00,-6700.00,-1300.00 --8100.00,-7950.00,-150.00,-8100.00,-7450.00,-650.00 --8200.00,-9800.00,1600.00,-8200.00,-9000.00,800.00 --8300.00,-9550.00,1250.00,-8300.00,-9300.00,1000.00 --8400.00,-8200.00,-200.00,-8400.00,-9100.00,700.00 --8500.00,-8700.00,200.00,-8500.00,-9000.00,500.00 --8600.00,-9150.00,550.00,-8600.00,-8950.00,350.00 --8700.00,-9650.00,950.00,-8700.00,-9300.00,600.00 --8800.00,-9950.00,1150.00,-8800.00,-9500.00,700.00 --8900.00,-9950.00,1050.00,-8900.00,-9700.00,800.00 --9000.00,-10000.00,1000.00,-9000.00,-9800.00,800.00 --9100.00,-10000.00,900.00,-9100.00,-9900.00,800.00 --9200.00,-10100.00,900.00,-9200.00,-10000.00,800.00 --9300.00,-10350.00,1050.00,-9300.00,-10200.00,900.00 --9400.00,-10450.00,1050.00,-9400.00,-10400.00,1000.00 --9500.00,-10600.00,1100.00,-9500.00,-10500.00,1000.00 --9600.00,-10700.00,1100.00,-9600.00,-10500.00,900.00 --9700.00,-10850.00,1150.00,-9700.00,-10700.00,1000.00 --9800.00,-11000.00,1200.00,-9800.00,-10900.00,1100.00 --9900.00,-11250.00,1350.00,-9900.00,-11050.00,1150.00 --10000.00,-11250.00,1250.00,-10000.00,-11150.00,1150.00 --10100.00,-11350.00,1250.00,-10100.00,-11200.00,1100.00 --10200.00,-11400.00,1200.00,-10200.00,-11350.00,1150.00 --10300.00,-11600.00,1300.00,-10300.00,-11450.00,1150.00 --10400.00,-11700.00,1300.00,-10400.00,-11600.00,1200.00 --10500.00,-11800.00,1300.00,-10500.00,-11600.00,1100.00 --10600.00,-11950.00,1350.00,-10600.00,-11900.00,1300.00 --10700.00,-12150.00,1450.00,-10700.00,-12050.00,1350.00 --10800.00,-12250.00,1450.00,-10800.00,-12100.00,1300.00 --10900.00,-12350.00,1450.00,-10900.00,-12200.00,1300.00 --11000.00,-12450.00,1450.00,-11000.00,-12250.00,1250.00 --11100.00,-12600.00,1500.00,-11100.00,-12350.00,1250.00 --11200.00,-12700.00,1500.00,-11200.00,-12400.00,1200.00 --11300.00,-12850.00,1550.00,-11300.00,-12550.00,1250.00 --11400.00,-13000.00,1600.00,-11400.00,-12600.00,1200.00 --11500.00,-13150.00,1650.00,-11500.00,-12650.00,1150.00 --11600.00,-13250.00,1650.00,-11600.00,-12850.00,1250.00 --11700.00,-13350.00,1650.00,-11700.00,-13000.00,1300.00 --11800.00,-13600.00,1800.00,-11800.00,-13000.00,1200.00 --11900.00,-13650.00,1750.00,-11900.00,-13100.00,1200.00 --12000.00,-13800.00,1800.00,-12000.00,-13100.00,1100.00 --12100.00,-13900.00,1800.00,-12100.00,-13200.00,1100.00 --12200.00,-14150.00,1950.00,-12200.00,-13400.00,1200.00 --12300.00,-14200.00,1900.00,-12300.00,-13700.00,1400.00 --12400.00,-14200.00,1800.00,-12400.00,-13900.00,1500.00 --12500.00,-14450.00,1950.00,-12500.00,-13950.00,1450.00 --12600.00,-14650.00,2050.00,-12600.00,-13950.00,1350.00 --12700.00,-14700.00,2000.00,-12700.00,-13900.00,1200.00 --12800.00,-14750.00,1950.00,-12800.00,-14050.00,1250.00 --12900.00,-14900.00,2000.00,-12900.00,-14200.00,1300.00 --13000.00,-15050.00,2050.00,-13000.00,-14300.00,1300.00 --13100.00,-15250.00,2150.00,-13100.00,-14400.00,1300.00 --13200.00,-15450.00,2250.00,-13200.00,-14600.00,1400.00 --13300.00,-15500.00,2200.00,-13300.00,-14800.00,1500.00 --13400.00,-15450.00,2050.00,-13400.00,-15050.00,1650.00 --13500.00,-15550.00,2050.00,-13500.00,-15400.00,1900.00 --13600.00,-15700.00,2100.00,-13600.00,-15700.00,2100.00 --13700.00,-15800.00,2100.00,-13700.00,-15800.00,2100.00 --13800.00,-16000.00,2200.00,-13800.00,-15750.00,1950.00 --13900.00,-15550.00,1650.00,-13900.00,-15150.00,1250.00 --14000.00,-16200.00,2200.00,-14000.00,-16000.00,2000.00 --14100.00,-15900.00,1800.00,-14100.00,-15700.00,1600.00 --14200.00,-16750.00,2550.00,-14200.00,-16500.00,2300.00 --14300.00,-16850.00,2550.00,-14300.00,-16800.00,2500.00 --14400.00,-16850.00,2450.00,-14400.00,-16750.00,2350.00 --14500.00,-16800.00,2300.00,-14500.00,-16650.00,2150.00 --14600.00,-16750.00,2150.00,-14600.00,-16750.00,2150.00 --14700.00,-17000.00,2300.00,-14700.00,-16750.00,2050.00 --14800.00,-17150.00,2350.00,-14800.00,-16950.00,2150.00 --14900.00,-17450.00,2550.00,-14900.00,-17150.00,2250.00 --15000.00,-17550.00,2550.00,-15000.00,-17300.00,2300.00 --15100.00,-17550.00,2450.00,-15100.00,-17450.00,2350.00 --15200.00,-20900.00,5700.00,-15200.00,-20900.00,5700.00 --15300.00,-17350.00,2050.00,-15300.00,-17250.00,1950.00 --15400.00,-16500.00,1100.00,-15400.00,-16400.00,1000.00 --15500.00,-17450.00,1950.00,-15500.00,-17050.00,1550.00 --15600.00,-17600.00,2000.00,-15600.00,-17200.00,1600.00 --15700.00,-18700.00,3000.00,-15700.00,-18300.00,2600.00 --15800.00,-19700.00,3900.00,-15800.00,-19000.00,3200.00 --15900.00,-18850.00,2950.00,-15900.00,-17950.00,2050.00 --16000.00,-18550.00,2550.00,-16000.00,-17800.00,1800.00 --16100.00,-19250.00,3150.00,-16100.00,-18850.00,2750.00 --16200.00,-18900.00,2700.00,-16200.00,-18450.00,2250.00 --16300.00,-19700.00,3400.00,-16300.00,-19200.00,2900.00 --16400.00,-19000.00,2600.00,-16400.00,-18450.00,2050.00 --16500.00,-19150.00,2650.00,-16500.00,-18400.00,1900.00 --16600.00,-19250.00,2650.00,-16600.00,-18550.00,1950.00 --16700.00,-19650.00,2950.00,-16700.00,-18700.00,2000.00 --16800.00,-20500.00,3700.00,-16800.00,-19800.00,3000.00 --16900.00,-20600.00,3700.00,-16900.00,-20150.00,3250.00 --17000.00,-19500.00,2500.00,-17000.00,-19500.00,2500.00 --17100.00,-20200.00,3100.00,-17100.00,-20350.00,3250.00 --17200.00,-19750.00,2550.00,-17200.00,-19800.00,2600.00 --17300.00,-19950.00,2650.00,-17300.00,-19800.00,2500.00 --17400.00,-20250.00,2850.00,-17400.00,-20100.00,2700.00 --17500.00,-21500.00,4000.00,-17500.00,-21100.00,3600.00 --17600.00,-21450.00,3850.00,-17600.00,-21150.00,3550.00 --17700.00,-21100.00,3400.00,-17700.00,-20850.00,3150.00 --17800.00,-20100.00,2300.00,-17800.00,-20100.00,2300.00 --17900.00,-20550.00,2650.00,-17900.00,-20250.00,2350.00 --18000.00,-21000.00,3000.00,-17952.47,-20750.00,2797.53 --18047.75,-21500.00,3452.25,-17852.47,-21200.00,3347.53 --17947.75,-21500.00,3552.25,-17752.47,-21300.00,3547.53 --17847.75,-21550.00,3702.25,-17652.47,-21200.00,3547.53 --17747.75,-21250.00,3502.25,-17552.47,-20900.00,3347.53 --17647.75,-21850.00,4202.25,-17452.47,-21400.00,3947.53 --17547.75,-21000.00,3452.25,-17352.47,-20350.00,2997.53 --17447.75,-21550.00,4102.25,-17252.47,-20550.00,3297.53 --17347.75,-21250.00,3902.25,-17152.47,-20300.00,3147.53 --17247.75,-20300.00,3052.25,-17052.47,-19250.00,2197.53 --17147.75,-19900.00,2752.25,-16952.47,-19300.00,2347.53 --17047.75,-21000.00,3952.25,-16852.47,-20450.00,3597.53 --16947.75,-20400.00,3452.25,-16752.47,-19700.00,2947.53 --16847.75,-20050.00,3202.25,-16652.47,-19350.00,2697.53 --16747.75,-20000.00,3252.25,-16552.47,-19150.00,2597.53 --16647.75,-19900.00,3252.25,-16452.47,-19050.00,2597.53 --16547.75,-19750.00,3202.25,-16352.47,-18800.00,2447.53 --16447.75,-19750.00,3302.25,-16252.47,-18700.00,2447.53 --16347.75,-19600.00,3252.25,-16152.47,-18750.00,2597.53 --16247.75,-20300.00,4052.25,-16052.47,-19550.00,3497.53 --16147.75,-19200.00,3052.25,-15952.47,-18900.00,2947.53 --16047.75,-18850.00,2802.25,-15852.47,-18650.00,2797.53 --15947.75,-18950.00,3002.25,-15752.47,-18650.00,2897.53 --15847.75,-18750.00,2902.25,-15652.47,-18650.00,2997.53 --15747.75,-18950.00,3202.25,-15552.47,-18600.00,3047.53 --15647.75,-19550.00,3902.25,-15452.47,-19150.00,3697.53 --15547.75,-18650.00,3102.25,-15352.47,-18250.00,2897.53 --15447.75,-18850.00,3402.25,-15252.47,-18250.00,2997.53 --15347.75,-18050.00,2702.25,-15152.47,-17300.00,2147.53 --15247.75,-18550.00,3302.25,-15052.47,-17850.00,2797.53 --15147.75,-17850.00,2702.25,-14952.47,-17300.00,2347.53 --15047.75,-17750.00,2702.25,-14852.47,-17200.00,2347.53 --14947.75,-18600.00,3652.25,-14752.47,-18000.00,3247.53 --14847.75,-17700.00,2852.25,-14652.47,-17200.00,2547.53 --14747.75,-17500.00,2752.25,-14552.47,-16950.00,2397.53 --14647.75,-18150.00,3502.25,-14452.47,-17500.00,3047.53 --14547.75,-17250.00,2702.25,-14352.47,-16800.00,2447.53 --14447.75,-17750.00,3302.25,-14252.47,-17150.00,2897.53 --14347.75,-17000.00,2652.25,-14152.47,-16600.00,2447.53 --14247.75,-17450.00,3202.25,-14052.47,-16800.00,2747.53 --14147.75,-17500.00,3352.25,-13952.47,-16500.00,2547.53 --14047.75,-17100.00,3052.25,-13852.47,-15950.00,2097.53 --13947.75,-16700.00,2752.25,-13752.47,-15700.00,1947.53 --13847.75,-16750.00,2902.25,-13652.47,-15650.00,1997.53 --13747.75,-16600.00,2852.25,-13552.47,-15850.00,2297.53 --13647.75,-18750.00,5102.25,-13452.47,-18050.00,4597.53 --13547.75,-14800.00,1252.25,-13352.47,-14700.00,1347.53 --13447.75,-12750.00,-697.75,-13252.47,-13800.00,547.53 --13347.75,-14000.00,652.25,-13152.47,-14300.00,1147.53 --13247.75,-16100.00,2852.25,-13052.47,-14850.00,1797.53 --13147.75,-17400.00,4252.25,-12952.47,-15550.00,2597.53 --13047.75,-16600.00,3552.25,-12852.47,-15150.00,2297.53 --12947.75,-15650.00,2702.25,-12752.47,-14700.00,1947.53 --12847.75,-14750.00,1902.25,-12652.47,-13900.00,1247.53 --12747.75,-14600.00,1852.25,-12552.47,-14050.00,1497.53 --12647.75,-15350.00,2702.25,-12452.47,-14950.00,2497.53 --12547.75,-15300.00,2752.25,-12352.47,-15150.00,2797.53 --12447.75,-15000.00,2552.25,-12252.47,-14950.00,2697.53 --12347.75,-14400.00,2052.25,-12152.47,-14000.00,1847.53 --12247.75,-14650.00,2402.25,-12052.47,-14300.00,2247.53 --12147.75,-14700.00,2552.25,-11952.47,-14350.00,2397.53 --12047.75,-14000.00,1952.25,-11852.47,-13750.00,1897.53 --11947.75,-13850.00,1902.25,-11752.47,-13550.00,1797.53 --11847.75,-13950.00,2102.25,-11652.47,-13500.00,1847.53 --11747.75,-13900.00,2152.25,-11552.47,-13600.00,2047.53 --11647.75,-13900.00,2252.25,-11452.47,-13450.00,1997.53 --11547.75,-13900.00,2352.25,-11352.47,-13350.00,1997.53 --11447.75,-13600.00,2152.25,-11252.47,-13200.00,1947.53 --11347.75,-13350.00,2002.25,-11152.47,-12900.00,1747.53 --11247.75,-13300.00,2052.25,-11052.47,-12650.00,1597.53 --11147.75,-13200.00,2052.25,-10952.47,-12400.00,1447.53 --11047.75,-13000.00,1952.25,-10852.47,-12450.00,1597.53 --10947.75,-12900.00,1952.25,-10752.47,-12400.00,1647.53 --10847.75,-12800.00,1952.25,-10652.47,-12200.00,1547.53 --10747.75,-12750.00,2002.25,-10552.47,-12050.00,1497.53 --10647.75,-12650.00,2002.25,-10452.47,-11950.00,1497.53 --10547.75,-12500.00,1952.25,-10352.47,-11900.00,1547.53 --10447.75,-12500.00,2052.25,-10252.47,-11800.00,1547.53 --10347.75,-12300.00,1952.25,-10152.47,-11650.00,1497.53 --10247.75,-12150.00,1902.25,-10052.47,-11550.00,1497.53 --10147.75,-12050.00,1902.25,-9952.47,-11400.00,1447.53 --10047.75,-11900.00,1852.25,-9852.47,-11350.00,1497.53 --9947.75,-11900.00,1952.25,-9752.47,-11150.00,1397.53 --9847.75,-11700.00,1852.25,-9652.47,-11000.00,1347.53 --9747.75,-11450.00,1702.25,-9552.47,-10700.00,1147.53 --9647.75,-11350.00,1702.25,-9452.47,-10450.00,997.53 --9547.75,-11400.00,1852.25,-9352.47,-10250.00,897.53 --9447.75,-11200.00,1752.25,-9252.47,-10200.00,947.53 --9347.75,-11050.00,1702.25,-9152.47,-10200.00,1047.53 --9247.75,-11000.00,1752.25,-9052.47,-10150.00,1097.53 --9147.75,-10750.00,1602.25,-8952.47,-10200.00,1247.53 --9047.75,-10650.00,1602.25,-8852.47,-10050.00,1197.53 --8947.75,-10550.00,1602.25,-8752.47,-9750.00,997.53 --8847.75,-10400.00,1552.25,-8652.47,-9500.00,847.53 --8747.75,-10250.00,1502.25,-8552.47,-9350.00,797.53 --8647.75,-9750.00,1102.25,-8452.47,-8800.00,347.53 --8547.75,-9700.00,1152.25,-8352.47,-8800.00,447.53 --8447.75,-9700.00,1252.25,-8252.47,-8800.00,547.53 --8347.75,-9700.00,1352.25,-8152.47,-8750.00,597.53 --8247.75,-9400.00,1152.25,-8052.47,-9050.00,997.53 --8147.75,-7800.00,-347.75,-7952.47,-8500.00,547.53 --8047.75,-8500.00,452.25,-7852.47,-8300.00,447.53 --7947.75,-8800.00,852.25,-7752.47,-8100.00,347.53 --7847.75,-9300.00,1452.25,-7652.47,-8000.00,347.53 --7747.75,-8650.00,902.25,-7552.47,-8000.00,447.53 --7647.75,-7900.00,252.25,-7452.47,-8200.00,747.53 --7547.75,-8300.00,752.25,-7352.47,-8200.00,847.53 --7447.75,-8500.00,1052.25,-7252.47,-7700.00,447.53 --7347.75,-8250.00,902.25,-7152.47,-6850.00,-302.47 --7247.75,-6600.00,-647.75,-7052.47,-6850.00,-202.47 --7147.75,-6550.00,-597.75,-6952.47,-7650.00,697.53 --7047.75,-7400.00,352.25,-6852.47,-7700.00,847.53 --6947.75,-8100.00,1152.25,-6752.47,-6500.00,-252.47 --6847.75,-7950.00,1102.25,-6652.47,-5950.00,-702.47 --6747.75,-6650.00,-97.75,-6552.47,-6950.00,397.53 --6647.75,-5900.00,-747.75,-6452.47,-6850.00,397.53 --6547.75,-6850.00,302.25,-6352.47,-5800.00,-552.47 --6447.75,-6850.00,402.25,-6252.47,-5500.00,-752.47 --6347.75,-5800.00,-547.75,-6152.47,-6200.00,47.53 --6247.75,-6550.00,302.25,-6052.47,-7300.00,1247.53 --6147.75,-5950.00,-197.75,-5952.47,-5200.00,-752.47 --6047.75,-5100.00,-947.75,-5852.47,-4750.00,-1102.47 --5947.75,-6100.00,152.25,-5752.47,-5450.00,-302.47 --5847.75,-6150.00,302.25,-5652.47,-5800.00,147.53 --5747.75,-5250.00,-497.75,-5552.47,-4900.00,-652.47 --5647.75,-4800.00,-847.75,-5452.47,-4400.00,-1052.47 --5547.75,-5450.00,-97.75,-5352.47,-4900.00,-452.47 --5447.75,-5700.00,252.25,-5252.47,-5150.00,-102.47 --5347.75,-4750.00,-597.75,-5152.47,-4400.00,-752.47 --5247.75,-4200.00,-1047.75,-5052.47,-3850.00,-1202.47 --5147.75,-5050.00,-97.75,-4952.47,-4300.00,-652.47 --5047.75,-5250.00,202.25,-4852.47,-4600.00,-252.47 --4947.75,-4450.00,-497.75,-4752.47,-3800.00,-952.47 --4847.75,-3450.00,-1397.75,-4652.47,-2700.00,-1952.47 --4747.75,-3100.00,-1647.75,-4552.47,-2850.00,-1702.47 --4647.75,-4400.00,-247.75,-4452.47,-4100.00,-352.47 --4547.75,-5050.00,502.25,-4352.47,-4650.00,297.53 --4447.75,-4300.00,-147.75,-4252.47,-3750.00,-502.47 --4347.75,-3350.00,-997.75,-4152.47,-2850.00,-1302.47 --4247.75,-2550.00,-1697.75,-4052.47,-1650.00,-2402.47 --4147.75,-2400.00,-1747.75,-3952.47,-2250.00,-1702.47 --4047.75,-3650.00,-397.75,-3852.47,-3500.00,-352.47 --3947.75,-4250.00,302.25,-3752.47,-3900.00,147.53 --3847.75,-3400.00,-447.75,-3652.47,-3000.00,-652.47 --3747.75,-2600.00,-1147.75,-3552.47,-2350.00,-1202.47 --3647.75,-1800.00,-1847.75,-3452.47,-650.00,-2802.47 --3547.75,-1300.00,-2247.75,-3352.47,-600.00,-2752.47 --3447.75,-2800.00,-647.75,-3252.47,-3000.00,-252.47 --3347.75,-3750.00,402.25,-3152.47,-4050.00,897.53 --3247.75,-2800.00,-447.75,-3052.47,-3050.00,-2.47 --3147.75,-2300.00,-847.75,-2952.47,-2400.00,-552.47 --3047.75,-900.00,-2147.75,-2852.47,-1200.00,-1652.47 --2947.75,-1600.00,-1347.75,-2752.47,-1200.00,-1552.47 --2847.75,-1550.00,-1297.75,-2652.47,100.00,-2752.47 --2747.75,-1450.00,-1297.75,-2552.47,-150.00,-2402.47 --2647.75,-700.00,-1947.75,-2452.47,-1450.00,-1002.47 --2547.75,600.00,-3147.75,-2352.47,-2050.00,-302.47 --2447.75,-600.00,-1847.75,-2252.47,-650.00,-1602.47 --2347.75,-1250.00,-1097.75,-2152.47,500.00,-2652.47 --2247.75,-1250.00,-997.75,-2052.47,400.00,-2452.47 --2147.75,-900.00,-1247.75,-1952.47,-600.00,-1352.47 --2047.75,750.00,-2797.75,-1852.47,800.00,-2652.47 --1947.75,-250.00,-1697.75,-1752.47,300.00,-2052.47 --1847.75,-900.00,-947.75,-1652.47,-400.00,-1252.47 --1747.75,350.00,-2097.75,-1552.47,50.00,-1602.47 --1647.75,900.00,-2547.75,-1452.47,0.00,-1452.47 --1547.75,50.00,-1597.75,-1352.47,0.00,-1352.47 --1447.75,-200.00,-1247.75,-1252.47,0.00,-1252.47 --1347.75,0.00,-1347.75,-1152.47,0.00,-1152.47 --1247.75,0.00,-1247.75,-1052.47,0.00,-1052.47 --1147.75,0.00,-1147.75,-952.47,0.00,-952.47 --1047.75,0.00,-1047.75,-852.47,0.00,-852.47 --947.75,0.00,-947.75,-752.47,0.00,-752.47 --847.75,0.00,-847.75,-652.47,0.00,-652.47 --747.75,0.00,-747.75,-552.47,0.00,-552.47 --647.75,0.00,-647.75,-452.47,0.00,-452.47 --547.75,0.00,-547.75,-352.47,0.00,-352.47 --447.75,0.00,-447.75,-252.47,0.00,-252.47 --347.75,0.00,-347.75,-152.47,0.00,-152.47 --247.75,0.00,-247.75,-52.47,0.00,-52.47 --147.75,0.00,-147.75,0.00,0.00,0.00 --47.75,0.00,-47.75,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -100.00,0.00,100.00,100.00,0.00,100.00 -200.00,0.00,200.00,200.00,0.00,200.00 -300.00,0.00,300.00,300.00,0.00,300.00 -400.00,0.00,400.00,400.00,0.00,400.00 -500.00,0.00,500.00,500.00,0.00,500.00 -600.00,0.00,600.00,600.00,0.00,600.00 -700.00,0.00,700.00,700.00,0.00,700.00 -800.00,0.00,800.00,800.00,0.00,800.00 -900.00,0.00,900.00,900.00,0.00,900.00 -1000.00,0.00,1000.00,1000.00,0.00,1000.00 -1100.00,0.00,1100.00,1100.00,0.00,1100.00 -1200.00,0.00,1200.00,1200.00,0.00,1200.00 -1300.00,0.00,1300.00,1300.00,0.00,1300.00 -1400.00,0.00,1400.00,1400.00,0.00,1400.00 -1500.00,0.00,1500.00,1500.00,0.00,1500.00 -1600.00,0.00,1600.00,1600.00,0.00,1600.00 -1700.00,0.00,1700.00,1700.00,0.00,1700.00 -1800.00,0.00,1800.00,1800.00,0.00,1800.00 -1900.00,0.00,1900.00,1900.00,0.00,1900.00 -2000.00,0.00,2000.00,2000.00,0.00,2000.00 -2100.00,0.00,2100.00,2100.00,0.00,2100.00 -2200.00,0.00,2200.00,2200.00,0.00,2200.00 -2300.00,0.00,2300.00,2300.00,0.00,2300.00 -2400.00,0.00,2400.00,2400.00,0.00,2400.00 -2500.00,0.00,2500.00,2500.00,0.00,2500.00 -2600.00,500.00,2100.00,2600.00,500.00,2100.00 -2700.00,550.00,2150.00,2700.00,400.00,2300.00 -2800.00,-900.00,3700.00,2800.00,-250.00,3050.00 -2900.00,450.00,2450.00,2900.00,1250.00,1650.00 -3000.00,2400.00,600.00,3000.00,2350.00,650.00 -3100.00,2900.00,200.00,3100.00,800.00,2300.00 -3200.00,2450.00,750.00,3200.00,700.00,2500.00 -3300.00,2000.00,1300.00,3300.00,2400.00,900.00 -3400.00,750.00,2650.00,3400.00,2950.00,450.00 -3500.00,250.00,3250.00,3500.00,1600.00,1900.00 -3600.00,2700.00,900.00,3600.00,1850.00,1750.00 -3700.00,4100.00,-400.00,3700.00,2350.00,1350.00 -3800.00,3150.00,650.00,3800.00,2550.00,1250.00 -3900.00,2650.00,1250.00,3900.00,1700.00,2200.00 -4000.00,1650.00,2350.00,4000.00,900.00,3100.00 -4100.00,2450.00,1650.00,4100.00,3000.00,1100.00 -4200.00,3500.00,700.00,4200.00,4100.00,100.00 -4300.00,3950.00,350.00,4300.00,3100.00,1200.00 -4400.00,3250.00,1150.00,4400.00,2350.00,2050.00 -4500.00,2750.00,1750.00,4500.00,1650.00,2850.00 -4600.00,2650.00,1950.00,4600.00,3550.00,1050.00 -4700.00,3800.00,900.00,4700.00,4650.00,50.00 -4800.00,4600.00,200.00,4800.00,3700.00,1100.00 -4900.00,3800.00,1100.00,4900.00,3150.00,1750.00 -5000.00,3800.00,1200.00,5000.00,3700.00,1300.00 -5100.00,4500.00,600.00,5100.00,4550.00,550.00 -5200.00,4600.00,600.00,5200.00,4700.00,500.00 -5300.00,3900.00,1400.00,5300.00,3600.00,1700.00 -5400.00,4000.00,1400.00,5400.00,3200.00,2200.00 -5500.00,4950.00,550.00,5500.00,4500.00,1000.00 -5600.00,5850.00,-250.00,5600.00,5700.00,-100.00 -5700.00,6100.00,-400.00,5700.00,6000.00,-300.00 -5800.00,5150.00,650.00,5800.00,4800.00,1000.00 -5900.00,4850.00,1050.00,5900.00,4150.00,1750.00 -6000.00,5400.00,600.00,6000.00,5000.00,1000.00 -6100.00,6150.00,-50.00,6100.00,6050.00,50.00 -6200.00,6650.00,-450.00,6200.00,6300.00,-100.00 -6300.00,5300.00,1000.00,6300.00,5000.00,1300.00 -6400.00,5100.00,1300.00,6400.00,4900.00,1500.00 -6500.00,6450.00,50.00,6500.00,5750.00,750.00 -6600.00,6950.00,-350.00,6600.00,6650.00,-50.00 -6700.00,7000.00,-300.00,6700.00,7000.00,-300.00 -6800.00,6050.00,750.00,6800.00,6950.00,-150.00 -6900.00,5800.00,1100.00,6900.00,6150.00,750.00 -7000.00,7100.00,-100.00,7000.00,6300.00,700.00 -7100.00,7450.00,-350.00,7100.00,6800.00,300.00 -7200.00,7950.00,-750.00,7200.00,7300.00,-100.00 -7300.00,7900.00,-600.00,7300.00,7950.00,-650.00 -7400.00,7100.00,300.00,7400.00,7950.00,-550.00 -7500.00,7700.00,-200.00,7500.00,7900.00,-400.00 -7600.00,8250.00,-650.00,7600.00,7700.00,-100.00 -7700.00,8500.00,-800.00,7700.00,7750.00,-50.00 -7800.00,8300.00,-500.00,7800.00,7550.00,250.00 -7900.00,8750.00,-850.00,7900.00,8100.00,-200.00 -8000.00,8850.00,-850.00,8000.00,8300.00,-300.00 -8100.00,10550.00,-2450.00,8100.00,9800.00,-1700.00 -8200.00,8550.00,-350.00,8200.00,7800.00,400.00 -8300.00,7300.00,1000.00,8300.00,6500.00,1800.00 -8400.00,7950.00,450.00,8400.00,7500.00,900.00 -8500.00,9050.00,-550.00,8500.00,8900.00,-400.00 -8600.00,10050.00,-1450.00,8600.00,9950.00,-1350.00 -8700.00,10250.00,-1550.00,8700.00,9800.00,-1100.00 -8800.00,9900.00,-1100.00,8800.00,9400.00,-600.00 -8900.00,9700.00,-800.00,8900.00,9250.00,-350.00 -9000.00,9800.00,-800.00,9000.00,9400.00,-400.00 -9100.00,10050.00,-950.00,9100.00,9700.00,-600.00 -9200.00,10200.00,-1000.00,9200.00,10000.00,-800.00 -9300.00,10400.00,-1100.00,9300.00,10200.00,-900.00 -9400.00,10500.00,-1100.00,9400.00,10300.00,-900.00 -9500.00,10550.00,-1050.00,9500.00,10300.00,-800.00 -9600.00,10650.00,-1050.00,9600.00,10300.00,-700.00 -9700.00,10850.00,-1150.00,9700.00,10550.00,-850.00 -9800.00,10850.00,-1050.00,9800.00,10650.00,-850.00 -9900.00,11050.00,-1150.00,9900.00,10650.00,-750.00 -10000.00,11150.00,-1150.00,10000.00,10850.00,-850.00 -10100.00,11350.00,-1250.00,10100.00,11150.00,-1050.00 -10200.00,11500.00,-1300.00,10200.00,11450.00,-1250.00 -10300.00,11550.00,-1250.00,10300.00,11500.00,-1200.00 -10400.00,11700.00,-1300.00,10400.00,11650.00,-1250.00 -10500.00,11800.00,-1300.00,10500.00,11750.00,-1250.00 -10600.00,12050.00,-1450.00,10600.00,12000.00,-1400.00 -10700.00,12150.00,-1450.00,10700.00,12050.00,-1350.00 -10800.00,12250.00,-1450.00,10800.00,12150.00,-1350.00 -10900.00,12500.00,-1600.00,10900.00,12350.00,-1450.00 -11000.00,12600.00,-1600.00,11000.00,12400.00,-1400.00 -11100.00,12650.00,-1550.00,11100.00,12450.00,-1350.00 -11200.00,12750.00,-1550.00,11200.00,12450.00,-1250.00 -11300.00,12900.00,-1600.00,11300.00,12550.00,-1250.00 -11400.00,13050.00,-1650.00,11400.00,12600.00,-1200.00 -11500.00,13250.00,-1750.00,11500.00,12800.00,-1300.00 -11600.00,13300.00,-1700.00,11600.00,12900.00,-1300.00 -11700.00,13450.00,-1750.00,11700.00,13050.00,-1350.00 -11800.00,13650.00,-1850.00,11800.00,13250.00,-1450.00 -11900.00,13800.00,-1900.00,11900.00,13500.00,-1600.00 -12000.00,13950.00,-1950.00,12000.00,13650.00,-1650.00 -12100.00,14100.00,-2000.00,12100.00,13750.00,-1650.00 -12200.00,14050.00,-1850.00,12200.00,13850.00,-1650.00 -12300.00,14200.00,-1900.00,12300.00,13900.00,-1600.00 -12400.00,14300.00,-1900.00,12400.00,14050.00,-1650.00 -12500.00,14500.00,-2000.00,12500.00,14200.00,-1700.00 -12600.00,14600.00,-2000.00,12600.00,14450.00,-1850.00 -12700.00,14800.00,-2100.00,12700.00,14650.00,-1950.00 -12800.00,14900.00,-2100.00,12800.00,14800.00,-2000.00 -12900.00,15000.00,-2100.00,12900.00,14800.00,-1900.00 -13000.00,15050.00,-2050.00,13000.00,14750.00,-1750.00 -13100.00,15200.00,-2100.00,13100.00,14650.00,-1550.00 -13200.00,15250.00,-2050.00,13200.00,14700.00,-1500.00 -13300.00,15250.00,-1950.00,13300.00,14800.00,-1500.00 -13400.00,15500.00,-2100.00,13400.00,15050.00,-1650.00 -13500.00,15650.00,-2150.00,13500.00,15350.00,-1850.00 -13600.00,15650.00,-2050.00,13600.00,15500.00,-1900.00 -13700.00,15800.00,-2100.00,13700.00,15500.00,-1800.00 -13800.00,16000.00,-2200.00,13800.00,15700.00,-1900.00 -13900.00,16100.00,-2200.00,13900.00,16050.00,-2150.00 -14000.00,16150.00,-2150.00,14000.00,16100.00,-2100.00 -14100.00,16300.00,-2200.00,14100.00,16100.00,-2000.00 -14200.00,16450.00,-2250.00,14200.00,16150.00,-1950.00 -14300.00,16600.00,-2300.00,14300.00,16300.00,-2000.00 -14400.00,16800.00,-2400.00,14400.00,16600.00,-2200.00 -14500.00,16800.00,-2300.00,14500.00,16900.00,-2400.00 -14600.00,16950.00,-2350.00,14600.00,17000.00,-2400.00 -14700.00,17050.00,-2350.00,14700.00,17100.00,-2400.00 -14800.00,17150.00,-2350.00,14800.00,17300.00,-2500.00 -14900.00,17300.00,-2400.00,14900.00,17350.00,-2450.00 -15000.00,17500.00,-2500.00,15000.00,17200.00,-2200.00 -15100.00,17600.00,-2500.00,15100.00,17550.00,-2450.00 -15200.00,17750.00,-2550.00,15200.00,17500.00,-2300.00 -15300.00,17850.00,-2550.00,15300.00,17550.00,-2250.00 -15400.00,18050.00,-2650.00,15400.00,17550.00,-2150.00 -15500.00,18100.00,-2600.00,15500.00,17700.00,-2200.00 -15600.00,21700.00,-6100.00,15600.00,21400.00,-5800.00 -15700.00,17000.00,-1300.00,15700.00,17750.00,-2050.00 -15800.00,14800.00,1000.00,15800.00,16800.00,-1000.00 -15900.00,16600.00,-700.00,15900.00,17650.00,-1750.00 -16000.00,19250.00,-3250.00,16000.00,18550.00,-2550.00 -16100.00,20350.00,-4250.00,16100.00,19000.00,-2900.00 -16200.00,19700.00,-3500.00,16200.00,18950.00,-2750.00 -16300.00,19200.00,-2900.00,16300.00,19100.00,-2800.00 -16400.00,19300.00,-2900.00,16400.00,19150.00,-2750.00 -16500.00,19050.00,-2550.00,16500.00,18850.00,-2350.00 -16600.00,19300.00,-2700.00,16600.00,18900.00,-2300.00 -16700.00,19450.00,-2750.00,16700.00,19300.00,-2600.00 -16800.00,19600.00,-2800.00,16800.00,19450.00,-2650.00 -16900.00,19750.00,-2850.00,16900.00,19650.00,-2750.00 -17000.00,19900.00,-2900.00,17000.00,19750.00,-2750.00 -17100.00,20100.00,-3000.00,17100.00,19850.00,-2750.00 -17200.00,20200.00,-3000.00,17200.00,19900.00,-2700.00 -17300.00,20200.00,-2900.00,17300.00,20000.00,-2700.00 -17400.00,20300.00,-2900.00,17400.00,20200.00,-2800.00 -17500.00,20350.00,-2850.00,17500.00,20200.00,-2700.00 -17600.00,20600.00,-3000.00,17600.00,20350.00,-2750.00 -17700.00,20750.00,-3050.00,17700.00,20800.00,-3100.00 -17800.00,20900.00,-3100.00,17800.00,20850.00,-3050.00 -17900.00,21000.00,-3100.00,17900.00,21050.00,-3150.00 -18000.00,21200.00,-3200.00,17956.36,21250.00,-3293.64 -18100.00,21400.00,-3300.00,17856.36,21150.00,-3293.64 -18200.00,21450.00,-3250.00,17756.36,21450.00,-3693.64 -18189.72,21600.00,-3410.28,17656.36,21000.00,-3343.64 -18089.72,21800.00,-3710.28,17556.36,21100.00,-3543.64 -17989.72,21750.00,-3760.28,17456.36,20850.00,-3393.64 -17889.72,21600.00,-3710.28,17356.36,20650.00,-3293.64 -17789.72,21550.00,-3760.28,17256.36,20550.00,-3293.64 -17689.72,21400.00,-3710.28,17156.36,20350.00,-3193.64 -17589.72,21200.00,-3610.28,17056.36,20350.00,-3293.64 -17489.72,21100.00,-3610.28,16956.36,20200.00,-3243.64 -17389.72,20900.00,-3510.28,16856.36,20100.00,-3243.64 -17289.72,20850.00,-3560.28,16756.36,19950.00,-3193.64 -17189.72,20800.00,-3610.28,16656.36,19700.00,-3043.64 -17089.72,20450.00,-3360.28,16556.36,19700.00,-3143.64 -16989.72,20250.00,-3260.28,16456.36,19450.00,-2993.64 -16889.72,20150.00,-3260.28,16356.36,19250.00,-2893.64 -16789.72,20100.00,-3310.28,16256.36,18900.00,-2643.64 -16689.72,19950.00,-3260.28,16156.36,18800.00,-2643.64 -16589.72,19850.00,-3260.28,16056.36,18850.00,-2793.64 -16489.72,19750.00,-3260.28,15956.36,18850.00,-2893.64 -16389.72,19750.00,-3360.28,15856.36,18700.00,-2843.64 -16289.72,19600.00,-3310.28,15756.36,18800.00,-3043.64 -16189.72,19450.00,-3260.28,15656.36,18600.00,-2943.64 -16089.72,19150.00,-3060.28,15556.36,18200.00,-2643.64 -15989.72,19050.00,-3060.28,15456.36,18150.00,-2693.64 -15889.72,18950.00,-3060.28,15356.36,18050.00,-2693.64 -15789.72,18850.00,-3060.28,15256.36,17900.00,-2643.64 -15689.72,18850.00,-3160.28,15156.36,18050.00,-2893.64 -15589.72,18650.00,-3060.28,15056.36,17950.00,-2893.64 -15489.72,18650.00,-3160.28,14956.36,17900.00,-2943.64 -15389.72,18550.00,-3160.28,14856.36,17700.00,-2843.64 -15289.72,18300.00,-3010.28,14756.36,17700.00,-2943.64 -15189.72,18250.00,-3060.28,14656.36,17550.00,-2893.64 -15089.72,18150.00,-3060.28,14556.36,17200.00,-2643.64 -14989.72,18000.00,-3010.28,14456.36,17050.00,-2593.64 -14889.72,17950.00,-3060.28,14356.36,17200.00,-2843.64 -14789.72,17950.00,-3160.28,14256.36,16950.00,-2693.64 -14689.72,17900.00,-3210.28,14156.36,16650.00,-2493.64 -14589.72,17650.00,-3060.28,14056.36,16750.00,-2693.64 -14489.72,17400.00,-2910.28,13956.36,16550.00,-2593.64 -14389.72,17300.00,-2910.28,13856.36,16450.00,-2593.64 -14289.72,17100.00,-2810.28,13756.36,16300.00,-2543.64 -14189.72,17000.00,-2810.28,13656.36,16100.00,-2443.64 -14089.72,16950.00,-2860.28,13556.36,16050.00,-2493.64 -13989.72,17000.00,-3010.28,13456.36,15750.00,-2293.64 -13889.72,16800.00,-2910.28,13356.36,15850.00,-2493.64 -13789.72,16550.00,-2760.28,13256.36,15800.00,-2543.64 -13689.72,16350.00,-2660.28,13156.36,15700.00,-2543.64 -13589.72,16150.00,-2560.28,13056.36,15350.00,-2293.64 -13489.72,14250.00,-760.28,12956.36,13400.00,-443.64 -13389.72,19200.00,-5810.28,12856.36,17900.00,-5043.64 -13289.72,15650.00,-2360.28,12756.36,14650.00,-1893.64 -13189.72,13350.00,-160.28,12656.36,12150.00,506.36 -13089.72,13750.00,-660.28,12556.36,13200.00,-643.64 -12989.72,15100.00,-2110.28,12456.36,14500.00,-2043.64 -12889.72,15700.00,-2810.28,12356.36,15000.00,-2643.64 -12789.72,15800.00,-3010.28,12256.36,14750.00,-2493.64 -12689.72,15250.00,-2560.28,12156.36,14500.00,-2343.64 -12589.72,14900.00,-2310.28,12056.36,14100.00,-2043.64 -12489.72,14700.00,-2210.28,11956.36,13900.00,-1943.64 -12389.72,14600.00,-2210.28,11856.36,13700.00,-1843.64 -12289.72,14600.00,-2310.28,11756.36,13700.00,-1943.64 -12189.72,14500.00,-2310.28,11656.36,13500.00,-1843.64 -12089.72,14400.00,-2310.28,11556.36,13350.00,-1793.64 -11989.72,14250.00,-2260.28,11456.36,13300.00,-1843.64 -11889.72,14150.00,-2260.28,11356.36,13300.00,-1943.64 -11789.72,14150.00,-2360.28,11256.36,13150.00,-1893.64 -11689.72,13950.00,-2260.28,11156.36,13050.00,-1893.64 -11589.72,13700.00,-2110.28,11056.36,12950.00,-1893.64 -11489.72,13650.00,-2160.28,10956.36,12800.00,-1843.64 -11389.72,13700.00,-2310.28,10856.36,12750.00,-1893.64 -11289.72,13500.00,-2210.28,10756.36,12700.00,-1943.64 -11189.72,13400.00,-2210.28,10656.36,12550.00,-1893.64 -11089.72,13200.00,-2110.28,10556.36,12450.00,-1893.64 -10989.72,13150.00,-2160.28,10456.36,12300.00,-1843.64 -10889.72,13050.00,-2160.28,10356.36,12100.00,-1743.64 -10789.72,12900.00,-2110.28,10256.36,12000.00,-1743.64 -10689.72,12750.00,-2060.28,10156.36,11800.00,-1643.64 -10589.72,12650.00,-2060.28,10056.36,11650.00,-1593.64 -10489.72,12550.00,-2060.28,9956.36,11550.00,-1593.64 -10389.72,12400.00,-2010.28,9856.36,11450.00,-1593.64 -10289.72,12200.00,-1910.28,9756.36,11300.00,-1543.64 -10189.72,12150.00,-1960.28,9656.36,11150.00,-1493.64 -10089.72,12000.00,-1910.28,9556.36,11050.00,-1493.64 -9989.72,11850.00,-1860.28,9456.36,10900.00,-1443.64 -9889.72,11800.00,-1910.28,9356.36,10850.00,-1493.64 -9789.72,11700.00,-1910.28,9256.36,10750.00,-1493.64 -9689.72,11500.00,-1810.28,9156.36,10400.00,-1243.64 -9589.72,11300.00,-1710.28,9056.36,10300.00,-1243.64 -9489.72,11100.00,-1610.28,8956.36,10300.00,-1343.64 -9389.72,11000.00,-1610.28,8856.36,10150.00,-1293.64 -9289.72,10900.00,-1610.28,8756.36,10000.00,-1243.64 -9189.72,10750.00,-1560.28,8656.36,9900.00,-1243.64 -9089.72,10550.00,-1460.28,8556.36,9750.00,-1193.64 -8989.72,10450.00,-1460.28,8456.36,9700.00,-1243.64 -8889.72,10400.00,-1510.28,8356.36,9500.00,-1143.64 -8789.72,10250.00,-1460.28,8256.36,9250.00,-993.64 -8689.72,10050.00,-1360.28,8156.36,9000.00,-843.64 -8589.72,9950.00,-1360.28,8056.36,8850.00,-793.64 -8489.72,9900.00,-1410.28,7956.36,8700.00,-743.64 -8389.72,9800.00,-1410.28,7856.36,8600.00,-743.64 -8289.72,8900.00,-610.28,7756.36,8250.00,-493.64 -8189.72,8100.00,89.72,7656.36,8500.00,-843.64 -8089.72,8800.00,-710.28,7556.36,8450.00,-893.64 -7989.72,9250.00,-1260.28,7456.36,7900.00,-443.64 -7889.72,8900.00,-1010.28,7356.36,6900.00,456.36 -7789.72,7950.00,-160.28,7256.36,7200.00,56.36 -7689.72,7900.00,-210.28,7156.36,7450.00,-293.64 -7589.72,8650.00,-1060.28,7056.36,8050.00,-993.64 -7489.72,8500.00,-1010.28,6956.36,7700.00,-743.64 -7389.72,7050.00,339.72,6856.36,6500.00,356.36 -7289.72,6450.00,839.72,6756.36,5650.00,1106.36 -7189.72,7400.00,-210.28,6656.36,6650.00,6.36 -7089.72,8250.00,-1160.28,6556.36,7400.00,-843.64 -6989.72,7850.00,-860.28,6456.36,7150.00,-693.64 -6889.72,6600.00,289.72,6356.36,6050.00,306.36 -6789.72,6450.00,339.72,6256.36,5600.00,656.36 -6689.72,6750.00,-60.28,6156.36,5850.00,306.36 -6589.72,7350.00,-760.28,6056.36,6350.00,-293.64 -6489.72,7600.00,-1110.28,5956.36,6550.00,-593.64 -6389.72,6350.00,39.72,5856.36,5300.00,556.36 -6289.72,5800.00,489.72,5756.36,4500.00,1256.36 -6189.72,6300.00,-110.28,5656.36,5300.00,356.36 -6089.72,6550.00,-460.28,5556.36,5550.00,6.36 -5989.72,5300.00,689.72,5456.36,4400.00,1056.36 -5889.72,6250.00,-360.28,5356.36,4600.00,756.36 -5789.72,5600.00,189.72,5256.36,4750.00,506.36 -5689.72,4650.00,1039.72,5156.36,4550.00,606.36 -5589.72,4700.00,889.72,5056.36,3850.00,1206.36 -5489.72,5500.00,-10.28,4956.36,3350.00,1606.36 -5389.72,5750.00,-360.28,4856.36,4100.00,756.36 -5289.72,4950.00,339.72,4756.36,4500.00,256.36 -5189.72,4150.00,1039.72,4656.36,3700.00,956.36 -5089.72,4000.00,1089.72,4556.36,2800.00,1756.36 -4989.72,4750.00,239.72,4456.36,2600.00,1856.36 -4889.72,5250.00,-360.28,4356.36,3800.00,556.36 -4789.72,4750.00,39.72,4256.36,4650.00,-393.64 -4689.72,3750.00,939.72,4156.36,3650.00,506.36 -4589.72,3050.00,1539.72,4056.36,2750.00,1306.36 -4489.72,3000.00,1489.72,3956.36,2200.00,1756.36 -4389.72,4250.00,139.72,3856.36,1550.00,2306.36 -4289.72,4650.00,-360.28,3756.36,2900.00,856.36 -4189.72,4150.00,39.72,3656.36,3800.00,-143.64 -4089.72,3100.00,989.72,3556.36,3000.00,556.36 -3989.72,2600.00,1389.72,3456.36,2200.00,1256.36 -3889.72,2200.00,1689.72,3356.36,600.00,2756.36 -3789.72,1700.00,2089.72,3256.36,950.00,2306.36 -3689.72,3200.00,489.72,3156.36,2900.00,256.36 -3589.72,3750.00,-160.28,3056.36,3400.00,-343.64 -3489.72,3300.00,189.72,2956.36,2650.00,306.36 -3389.72,2500.00,889.72,2856.36,1800.00,1056.36 -3289.72,2150.00,1139.72,2756.36,1150.00,1606.36 -3189.72,700.00,2489.72,2656.36,-550.00,3206.36 -3089.72,1600.00,1489.72,2556.36,-200.00,2756.36 -2989.72,2400.00,589.72,2456.36,2150.00,306.36 -2889.72,2000.00,889.72,2356.36,2650.00,-293.64 -2789.72,800.00,1989.72,2256.36,2000.00,256.36 -2689.72,1000.00,1689.72,2156.36,900.00,1256.36 -2589.72,1000.00,1589.72,2056.36,-100.00,2156.36 -2489.72,-500.00,2989.72,1956.36,-450.00,2406.36 -2389.72,400.00,1989.72,1856.36,-1050.00,2906.36 -2289.72,750.00,1539.72,1756.36,500.00,1256.36 -2189.72,-100.00,2289.72,1656.36,1200.00,456.36 -2089.72,-700.00,2789.72,1556.36,-100.00,1656.36 -1989.72,-150.00,2139.72,1456.36,-700.00,2156.36 -1889.72,650.00,1239.72,1356.36,-900.00,2256.36 -1789.72,-700.00,2489.72,1256.36,100.00,1156.36 -1689.72,-300.00,1989.72,1156.36,200.00,956.36 -1589.72,0.00,1589.72,1056.36,0.00,1056.36 -1489.72,0.00,1489.72,956.36,0.00,956.36 -1389.72,0.00,1389.72,856.36,0.00,856.36 -1289.72,0.00,1289.72,756.36,0.00,756.36 -1189.72,0.00,1189.72,656.36,0.00,656.36 -1089.72,0.00,1089.72,556.36,0.00,556.36 -989.72,0.00,989.72,456.36,0.00,456.36 -889.72,0.00,889.72,356.36,0.00,356.36 -789.72,0.00,789.72,256.36,0.00,256.36 -689.72,0.00,689.72,156.36,0.00,156.36 -589.72,0.00,589.72,56.36,0.00,56.36 -489.72,0.00,489.72,0.00,0.00,0.00 -389.72,0.00,389.72,0.00,0.00,0.00 -289.72,0.00,289.72,0.00,0.00,0.00 -189.72,0.00,189.72,0.00,0.00,0.00 -89.72,0.00,89.72,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -100.00,0.00,100.00,100.00,0.00,100.00 -200.00,0.00,200.00,200.00,0.00,200.00 -300.00,0.00,300.00,300.00,0.00,300.00 -400.00,0.00,400.00,400.00,0.00,400.00 -500.00,0.00,500.00,500.00,0.00,500.00 -600.00,0.00,600.00,600.00,0.00,600.00 -700.00,0.00,700.00,700.00,0.00,700.00 -800.00,0.00,800.00,800.00,0.00,800.00 -900.00,0.00,900.00,900.00,0.00,900.00 -1000.00,0.00,1000.00,1000.00,0.00,1000.00 -1100.00,0.00,1100.00,1100.00,0.00,1100.00 -1200.00,0.00,1200.00,1200.00,0.00,1200.00 -1300.00,0.00,1300.00,1300.00,0.00,1300.00 -1400.00,0.00,1400.00,1400.00,0.00,1400.00 -1500.00,0.00,1500.00,1500.00,0.00,1500.00 -1600.00,0.00,1600.00,1600.00,0.00,1600.00 -1700.00,0.00,1700.00,1700.00,0.00,1700.00 -1800.00,0.00,1800.00,1800.00,0.00,1800.00 -1900.00,0.00,1900.00,1900.00,0.00,1900.00 -2000.00,0.00,2000.00,2000.00,0.00,2000.00 -2100.00,0.00,2100.00,2100.00,0.00,2100.00 -2200.00,0.00,2200.00,2200.00,0.00,2200.00 -2300.00,0.00,2300.00,2300.00,0.00,2300.00 -2400.00,0.00,2400.00,2400.00,0.00,2400.00 -2500.00,450.00,2050.00,2500.00,400.00,2100.00 -2600.00,200.00,2400.00,2600.00,450.00,2150.00 -2700.00,-200.00,2900.00,2700.00,-800.00,3500.00 -2800.00,1150.00,1650.00,2800.00,350.00,2450.00 -2900.00,2200.00,700.00,2900.00,2500.00,400.00 -3000.00,1050.00,1950.00,3000.00,2500.00,500.00 -3100.00,100.00,3000.00,3100.00,1650.00,1450.00 -3200.00,850.00,2350.00,3200.00,-50.00,3250.00 -3300.00,2850.00,450.00,3300.00,150.00,3150.00 -3400.00,3550.00,-150.00,3400.00,1900.00,1500.00 -3500.00,3000.00,500.00,3500.00,2900.00,600.00 -3600.00,2400.00,1200.00,3600.00,2000.00,1600.00 -3700.00,1000.00,2700.00,3700.00,550.00,3150.00 -3800.00,1800.00,2000.00,3800.00,1500.00,2300.00 -3900.00,3400.00,500.00,3900.00,3500.00,400.00 -4000.00,4000.00,0.00,4000.00,3800.00,200.00 -4100.00,3150.00,950.00,4100.00,2450.00,1650.00 -4200.00,2500.00,1700.00,4200.00,2150.00,2050.00 -4300.00,2350.00,1950.00,4300.00,2950.00,1350.00 -4400.00,3350.00,1050.00,4400.00,3600.00,800.00 -4500.00,4050.00,450.00,4500.00,3550.00,950.00 -4600.00,3350.00,1250.00,4600.00,2500.00,2100.00 -4700.00,3100.00,1600.00,4700.00,1800.00,2900.00 -4800.00,3700.00,1100.00,4800.00,3650.00,1150.00 -4900.00,4600.00,300.00,4900.00,5050.00,-150.00 -5000.00,4850.00,150.00,5000.00,4800.00,200.00 -5100.00,4050.00,1050.00,5100.00,3750.00,1350.00 -5200.00,3700.00,1500.00,5200.00,2900.00,2300.00 -5300.00,4450.00,850.00,5300.00,3750.00,1550.00 -5400.00,5500.00,-100.00,5400.00,5100.00,300.00 -5500.00,5550.00,-50.00,5500.00,5050.00,450.00 -5600.00,4550.00,1050.00,5600.00,3850.00,1750.00 -5700.00,4300.00,1400.00,5700.00,3250.00,2450.00 -5800.00,5150.00,650.00,5800.00,4700.00,1100.00 -5900.00,6200.00,-300.00,5900.00,6150.00,-250.00 -6000.00,6250.00,-250.00,6000.00,5900.00,100.00 -6100.00,5400.00,700.00,6100.00,4550.00,1550.00 -6200.00,4900.00,1300.00,6200.00,3850.00,2350.00 -6300.00,5900.00,400.00,6300.00,5400.00,900.00 -6400.00,6700.00,-300.00,6400.00,6500.00,-100.00 -6500.00,6650.00,-150.00,6500.00,6700.00,-200.00 -6600.00,6050.00,550.00,6600.00,6000.00,600.00 -6700.00,6200.00,500.00,6700.00,4850.00,1850.00 -6800.00,7150.00,-350.00,6800.00,5650.00,1150.00 -6900.00,7500.00,-600.00,6900.00,6700.00,200.00 -7000.00,7300.00,-300.00,7000.00,7000.00,0.00 -7100.00,6500.00,600.00,7100.00,6800.00,300.00 -7200.00,7150.00,50.00,7200.00,6700.00,500.00 -7300.00,7650.00,-350.00,7300.00,6750.00,550.00 -7400.00,8050.00,-650.00,7400.00,6950.00,450.00 -7500.00,8350.00,-850.00,7500.00,7250.00,250.00 -7600.00,7900.00,-300.00,7600.00,7400.00,200.00 -7700.00,7200.00,500.00,7700.00,7500.00,200.00 -7800.00,7800.00,0.00,7800.00,7650.00,150.00 -7900.00,8500.00,-600.00,7900.00,7700.00,200.00 -8000.00,8950.00,-950.00,8000.00,8050.00,-50.00 -8100.00,9150.00,-1050.00,8100.00,8350.00,-250.00 -8200.00,9150.00,-950.00,8200.00,8400.00,-200.00 -8300.00,9200.00,-900.00,8300.00,8400.00,-100.00 -8400.00,9250.00,-850.00,8400.00,8600.00,-200.00 -8500.00,9400.00,-900.00,8500.00,8700.00,-200.00 -8600.00,11350.00,-2750.00,8600.00,10500.00,-1900.00 -8700.00,9150.00,-450.00,8700.00,8500.00,200.00 -8800.00,8250.00,550.00,8800.00,7400.00,1400.00 -8900.00,9250.00,-350.00,8900.00,8200.00,700.00 -9000.00,9900.00,-900.00,9000.00,9300.00,-300.00 -9100.00,10700.00,-1600.00,9100.00,10200.00,-1100.00 -9200.00,10850.00,-1650.00,9200.00,10150.00,-950.00 -9300.00,10500.00,-1200.00,9300.00,9400.00,-100.00 -9400.00,10450.00,-1050.00,9400.00,9300.00,100.00 -9500.00,10650.00,-1150.00,9500.00,9500.00,0.00 -9600.00,10700.00,-1100.00,9600.00,9800.00,-200.00 -9700.00,10850.00,-1150.00,9700.00,10150.00,-450.00 -9800.00,10950.00,-1150.00,9800.00,10400.00,-600.00 -9900.00,11200.00,-1300.00,9900.00,10500.00,-600.00 -10000.00,11800.00,-1800.00,10000.00,11000.00,-1000.00 -10100.00,11850.00,-1750.00,10100.00,11100.00,-1000.00 -10200.00,11700.00,-1500.00,10200.00,11100.00,-900.00 -10300.00,11700.00,-1400.00,10300.00,11100.00,-800.00 -10400.00,11800.00,-1400.00,10400.00,11150.00,-750.00 -10500.00,11900.00,-1400.00,10500.00,11350.00,-850.00 -10600.00,11650.00,-1050.00,10600.00,11050.00,-450.00 -10700.00,12250.00,-1550.00,10700.00,11800.00,-1100.00 -10800.00,12400.00,-1600.00,10800.00,12100.00,-1300.00 -10900.00,12500.00,-1600.00,10900.00,12100.00,-1200.00 -11000.00,12600.00,-1600.00,11000.00,12100.00,-1100.00 -11100.00,12600.00,-1500.00,11100.00,12050.00,-950.00 -11200.00,12700.00,-1500.00,11200.00,12150.00,-950.00 -11300.00,12400.00,-1100.00,11300.00,11800.00,-500.00 -11400.00,13150.00,-1750.00,11400.00,12650.00,-1250.00 -11500.00,13450.00,-1950.00,11500.00,12850.00,-1350.00 -11600.00,12950.00,-1350.00,11600.00,12450.00,-850.00 -11700.00,13050.00,-1350.00,11700.00,12500.00,-800.00 -11800.00,13350.00,-1550.00,11800.00,12800.00,-1000.00 -11900.00,13450.00,-1550.00,11900.00,13150.00,-1250.00 -12000.00,13550.00,-1550.00,12000.00,13200.00,-1200.00 -12100.00,13700.00,-1600.00,12100.00,13200.00,-1100.00 -12200.00,13850.00,-1650.00,12200.00,13200.00,-1000.00 -12300.00,14500.00,-2200.00,12300.00,13850.00,-1550.00 -12400.00,14050.00,-1650.00,12400.00,13400.00,-1000.00 -12500.00,13950.00,-1450.00,12500.00,13400.00,-900.00 -12600.00,14800.00,-2200.00,12600.00,14200.00,-1600.00 -12700.00,14950.00,-2250.00,12700.00,14300.00,-1600.00 -12800.00,14350.00,-1550.00,12800.00,13500.00,-700.00 -12900.00,14550.00,-1650.00,12900.00,13600.00,-700.00 -13000.00,15400.00,-2400.00,13000.00,14400.00,-1400.00 -13100.00,15550.00,-2450.00,13100.00,14700.00,-1600.00 -13200.00,15450.00,-2250.00,13200.00,14600.00,-1400.00 -13300.00,14850.00,-1550.00,13300.00,14100.00,-800.00 -13400.00,15500.00,-2100.00,13400.00,14800.00,-1400.00 -13500.00,15950.00,-2450.00,13500.00,15250.00,-1750.00 -13600.00,15450.00,-1850.00,13600.00,14950.00,-1350.00 -13700.00,16150.00,-2450.00,13700.00,15550.00,-1850.00 -13800.00,16450.00,-2650.00,13800.00,15750.00,-1950.00 -13900.00,15600.00,-1700.00,13900.00,15100.00,-1200.00 -14000.00,15600.00,-1600.00,14000.00,15200.00,-1200.00 -14100.00,16100.00,-2000.00,14100.00,15250.00,-1150.00 -14200.00,16250.00,-2050.00,14200.00,15750.00,-1550.00 -14300.00,16450.00,-2150.00,14300.00,16150.00,-1850.00 -14400.00,17250.00,-2850.00,14400.00,16850.00,-2450.00 -14500.00,16600.00,-2100.00,14500.00,16200.00,-1700.00 -14600.00,17150.00,-2550.00,14600.00,16750.00,-2150.00 -14700.00,16600.00,-1900.00,14700.00,16250.00,-1550.00 -14800.00,17400.00,-2600.00,14800.00,16900.00,-2100.00 -14900.00,17550.00,-2650.00,14900.00,17150.00,-2250.00 -15000.00,16800.00,-1800.00,15000.00,16500.00,-1500.00 -15100.00,17500.00,-2400.00,15100.00,17000.00,-1900.00 -15200.00,17750.00,-2550.00,15200.00,17450.00,-2250.00 -15300.00,17200.00,-1900.00,15300.00,16800.00,-1500.00 -15400.00,17900.00,-2500.00,15400.00,17500.00,-2100.00 -15500.00,18200.00,-2700.00,15500.00,17850.00,-2350.00 -15600.00,18300.00,-2700.00,15600.00,17750.00,-2150.00 -15700.00,18200.00,-2500.00,15700.00,17850.00,-2150.00 -15800.00,18150.00,-2350.00,15800.00,17900.00,-2100.00 -15900.00,18350.00,-2450.00,15900.00,17950.00,-2050.00 -16000.00,18500.00,-2500.00,16000.00,18050.00,-2050.00 -16100.00,18600.00,-2500.00,16100.00,18150.00,-2050.00 -16200.00,22300.00,-6100.00,16200.00,21500.00,-5300.00 -16300.00,17550.00,-1250.00,16300.00,17900.00,-1600.00 -16400.00,15200.00,1200.00,16400.00,17100.00,-700.00 -16500.00,16900.00,-400.00,16500.00,17650.00,-1150.00 -16600.00,19900.00,-3300.00,16600.00,18500.00,-1900.00 -16700.00,21050.00,-4350.00,16700.00,19050.00,-2350.00 -16800.00,20650.00,-3850.00,16800.00,19150.00,-2350.00 -16900.00,19850.00,-2950.00,16900.00,19250.00,-2350.00 -17000.00,19200.00,-2200.00,17000.00,18350.00,-1350.00 -17100.00,20300.00,-3200.00,17100.00,19550.00,-2450.00 -17200.00,20450.00,-3250.00,17033.32,19800.00,-2766.68 -17300.00,19650.00,-2350.00,16933.32,19150.00,-2216.68 -17400.00,20800.00,-3400.00,16833.32,19700.00,-2866.68 -17500.00,21200.00,-3700.00,16733.32,19650.00,-2916.68 -17600.00,20800.00,-3200.00,16633.32,19300.00,-2666.68 -17513.92,20800.00,-3286.08,16533.32,18950.00,-2416.68 -17413.92,21000.00,-3586.08,16433.32,18850.00,-2416.68 -17313.92,20800.00,-3486.08,16333.32,18900.00,-2566.68 -17213.92,20500.00,-3286.08,16233.32,18750.00,-2516.68 -17113.92,20300.00,-3186.08,16133.32,18650.00,-2516.68 -17013.92,20200.00,-3186.08,16033.32,18400.00,-2366.68 -16913.92,20100.00,-3186.08,15933.32,18200.00,-2266.68 -16813.92,20100.00,-3286.08,15833.32,18300.00,-2466.68 -16713.92,20000.00,-3286.08,15733.32,18200.00,-2466.68 -16613.92,19800.00,-3186.08,15633.32,17900.00,-2266.68 -16513.92,19750.00,-3236.08,15533.32,17800.00,-2266.68 -16413.92,19500.00,-3086.08,15433.32,17800.00,-2366.68 -16313.92,19350.00,-3036.08,15333.32,17700.00,-2366.68 -16213.92,19200.00,-2986.08,15233.32,17550.00,-2316.68 -16113.92,19150.00,-3036.08,15133.32,17250.00,-2116.68 -16013.92,19050.00,-3036.08,15033.32,17000.00,-1966.68 -15913.92,18950.00,-3036.08,14933.32,17000.00,-2066.68 -15813.92,18850.00,-3036.08,14833.32,16800.00,-1966.68 -15713.92,18700.00,-2986.08,14733.32,16750.00,-2016.68 -15613.92,18550.00,-2936.08,14633.32,16550.00,-1916.68 -15513.92,18450.00,-2936.08,14533.32,16350.00,-1816.68 -15413.92,18350.00,-2936.08,14433.32,16150.00,-1716.68 -15313.92,18200.00,-2886.08,14333.32,16050.00,-1716.68 -15213.92,18100.00,-2886.08,14233.32,15850.00,-1616.68 -15113.92,18000.00,-2886.08,14133.32,15700.00,-1566.68 -15013.92,17950.00,-2936.08,14033.32,15850.00,-1816.68 -14913.92,17750.00,-2836.08,13933.32,15800.00,-1866.68 -14813.92,17650.00,-2836.08,13833.32,15600.00,-1766.68 -14713.92,17500.00,-2786.08,13733.32,15450.00,-1716.68 -14613.92,17350.00,-2736.08,13633.32,15350.00,-1716.68 -14513.92,17250.00,-2736.08,13533.32,15150.00,-1616.68 -14413.92,17000.00,-2586.08,13433.32,15000.00,-1566.68 -14313.92,16900.00,-2586.08,13333.32,14750.00,-1416.68 -14213.92,16850.00,-2636.08,13233.32,14650.00,-1416.68 -14113.92,16650.00,-2536.08,13133.32,14650.00,-1516.68 -14013.92,16600.00,-2586.08,13033.32,14700.00,-1666.68 -13913.92,16400.00,-2486.08,12933.32,14650.00,-1716.68 -13813.92,16350.00,-2536.08,12833.32,14550.00,-1716.68 -13713.92,16100.00,-2386.08,12733.32,14350.00,-1616.68 -13613.92,15350.00,-1736.08,12633.32,13750.00,-1116.68 -13513.92,15950.00,-2436.08,12533.32,14250.00,-1716.68 -13413.92,16050.00,-2636.08,12433.32,14300.00,-1866.68 -13313.92,15700.00,-2386.08,12333.32,13900.00,-1566.68 -13213.92,15400.00,-2186.08,12233.32,13750.00,-1516.68 -13113.92,15300.00,-2186.08,12133.32,13550.00,-1416.68 -13013.92,15100.00,-2086.08,12033.32,13400.00,-1366.68 -12913.92,15000.00,-2086.08,11933.32,13200.00,-1266.68 -12813.92,14950.00,-2136.08,11833.32,13000.00,-1166.68 -12713.92,14850.00,-2136.08,11733.32,12950.00,-1216.68 -12613.92,14650.00,-2036.08,11633.32,12850.00,-1216.68 -12513.92,14600.00,-2086.08,11533.32,12800.00,-1266.68 -12413.92,14400.00,-1986.08,11433.32,12600.00,-1166.68 -12313.92,13850.00,-1536.08,11333.32,12100.00,-766.68 -12213.92,14450.00,-2236.08,11233.32,12550.00,-1316.68 -12113.92,14500.00,-2386.08,11133.32,12550.00,-1416.68 -12013.92,13650.00,-1636.08,11033.32,11750.00,-716.68 -11913.92,13500.00,-1586.08,10933.32,11550.00,-616.68 -11813.92,13550.00,-1736.08,10833.32,11500.00,-666.68 -11713.92,14050.00,-2336.08,10733.32,11950.00,-1216.68 -11613.92,13350.00,-1736.08,10633.32,11350.00,-716.68 -11513.92,16150.00,-4636.08,10533.32,13650.00,-3116.68 -11413.92,12650.00,-1236.08,10433.32,10700.00,-266.68 -11313.92,11050.00,263.92,10333.32,9150.00,1183.32 -11213.92,11050.00,163.92,10233.32,9300.00,933.32 -11113.92,12300.00,-1186.08,10133.32,10500.00,-366.68 -11013.92,13200.00,-2186.08,10033.32,11300.00,-1266.68 -10913.92,14000.00,-3086.08,9933.32,11850.00,-1916.68 -10813.92,12750.00,-1936.08,9833.32,11400.00,-1566.68 -10713.92,11000.00,-286.08,9733.32,10650.00,-916.68 -10613.92,11300.00,-686.08,9633.32,10400.00,-766.68 -10513.92,11750.00,-1236.08,9533.32,9900.00,-366.68 -10413.92,12700.00,-2286.08,9433.32,10500.00,-1066.68 -10313.92,12450.00,-2136.08,9333.32,10200.00,-866.68 -10213.92,12100.00,-1886.08,9233.32,10050.00,-816.68 -10113.92,12400.00,-2286.08,9133.32,10400.00,-1266.68 -10013.92,12200.00,-2186.08,9033.32,10250.00,-1216.68 -9913.92,11750.00,-1836.08,8933.32,9900.00,-966.68 -9813.92,11150.00,-1336.08,8833.32,9300.00,-466.68 -9713.92,11600.00,-1886.08,8733.32,9500.00,-766.68 -9613.92,11450.00,-1836.08,8633.32,9450.00,-816.68 -9513.92,11200.00,-1686.08,8533.32,9300.00,-766.68 -9413.92,10700.00,-1286.08,8433.32,8800.00,-366.68 -9313.92,10650.00,-1336.08,8333.32,8550.00,-216.68 -9213.92,10600.00,-1386.08,8233.32,8550.00,-316.68 -9113.92,10900.00,-1786.08,8133.32,8850.00,-716.68 -9013.92,9900.00,-886.08,8033.32,8450.00,-416.68 -8913.92,8650.00,263.92,7933.32,8200.00,-266.68 -8813.92,9350.00,-536.08,7833.32,8250.00,-416.68 -8713.92,9950.00,-1236.08,7733.32,8200.00,-466.68 -8613.92,10550.00,-1936.08,7633.32,8400.00,-766.68 -8513.92,9700.00,-1186.08,7533.32,8000.00,-466.68 -8413.92,8350.00,63.92,7433.32,7800.00,-366.68 -8313.92,8850.00,-536.08,7333.32,7700.00,-366.68 -8213.92,9200.00,-986.08,7233.32,7600.00,-366.68 -8113.92,9400.00,-1286.08,7133.32,7500.00,-366.68 -8013.92,8900.00,-886.08,7033.32,7500.00,-466.68 -7913.92,7850.00,63.92,6933.32,7000.00,-66.68 -7813.92,8650.00,-836.08,6833.32,6450.00,383.32 -7713.92,8700.00,-986.08,6733.32,6400.00,333.32 -7613.92,8300.00,-686.08,6633.32,6750.00,-116.68 -7513.92,7400.00,113.92,6533.32,6950.00,-416.68 -7413.92,7800.00,-386.08,6433.32,6750.00,-316.68 -7313.92,8200.00,-886.08,6333.32,5550.00,783.32 -7213.92,8350.00,-1136.08,6233.32,5100.00,1133.32 -7113.92,6700.00,413.92,6133.32,5650.00,483.32 -7013.92,6450.00,563.92,6033.32,6200.00,-166.68 -6913.92,7150.00,-236.08,5933.32,6200.00,-266.68 -6813.92,7900.00,-1086.08,5833.32,5100.00,733.32 -6713.92,7650.00,-936.08,5733.32,4300.00,1433.32 -6613.92,6500.00,113.92,5633.32,5000.00,633.32 -6513.92,6100.00,413.92,5533.32,5550.00,-16.68 -6413.92,6650.00,-236.08,5433.32,5550.00,-116.68 -6313.92,6700.00,-386.08,5333.32,4350.00,983.32 -6213.92,5750.00,463.92,5233.32,3850.00,1383.32 -6113.92,5500.00,613.92,5133.32,4200.00,933.32 -6013.92,6100.00,-86.08,5033.32,4700.00,333.32 -5913.92,6300.00,-386.08,4933.32,4650.00,283.32 -5813.92,5450.00,363.92,4833.32,3450.00,1383.32 -5713.92,5200.00,513.92,4733.32,3000.00,1733.32 -5613.92,5700.00,-86.08,4633.32,3800.00,833.32 -5513.92,5800.00,-286.08,4533.32,4150.00,383.32 -5413.92,4950.00,463.92,4433.32,3050.00,1383.32 -5313.92,4350.00,963.92,4333.32,2400.00,1933.32 -5213.92,4100.00,1113.92,4233.32,3300.00,933.32 -5113.92,5150.00,-36.08,4133.32,3800.00,333.32 -5013.92,5350.00,-336.08,4033.32,2650.00,1383.32 -4913.92,4650.00,263.92,3933.32,2050.00,1883.32 -4813.92,4000.00,813.92,3833.32,2800.00,1033.32 -4713.92,3300.00,1413.92,3733.32,3150.00,583.32 -4613.92,3100.00,1513.92,3633.32,2000.00,1633.32 -4513.92,4250.00,263.92,3533.32,1650.00,1883.32 -4413.92,4800.00,-386.08,3433.32,2350.00,1083.32 -4313.92,4050.00,263.92,3333.32,2450.00,883.32 -4213.92,3400.00,813.92,3233.32,1500.00,1733.32 -4113.92,2950.00,1163.92,3133.32,-250.00,3383.32 -4013.92,2000.00,2013.92,3033.32,-100.00,3133.32 -3913.92,2450.00,1463.92,2933.32,2200.00,733.32 -3813.92,3600.00,213.92,2833.32,3750.00,-916.68 -3713.92,2550.00,1163.92,2733.32,1950.00,783.32 -3613.92,1550.00,2063.92,2633.32,1200.00,1433.32 -3513.92,2300.00,1213.92,2533.32,750.00,1783.32 -3413.92,2800.00,613.92,2433.32,-350.00,2783.32 -3313.92,2000.00,1313.92,2333.32,300.00,2033.32 -3213.92,1800.00,1413.92,2233.32,450.00,1783.32 -3113.92,600.00,2513.92,2133.32,-800.00,2933.32 -3013.92,1450.00,1563.92,2033.32,300.00,1733.32 -2913.92,2300.00,613.92,1933.32,900.00,1033.32 -2813.92,2050.00,763.92,1833.32,-600.00,2433.32 -2713.92,1000.00,1713.92,1733.32,-1000.00,2733.32 -2613.92,1350.00,1263.92,1633.32,300.00,1333.32 -2513.92,500.00,2013.92,1533.32,250.00,1283.32 -2413.92,-800.00,3213.92,1433.32,-50.00,1483.32 -2313.92,800.00,1513.92,1333.32,0.00,1333.32 -2213.92,1700.00,513.92,1233.32,0.00,1233.32 -2113.92,1650.00,463.92,1133.32,0.00,1133.32 -2013.92,300.00,1713.92,1033.32,0.00,1033.32 -1913.92,-750.00,2663.92,933.32,0.00,933.32 -1813.92,-600.00,2413.92,833.32,0.00,833.32 -1713.92,300.00,1413.92,733.32,0.00,733.32 -1613.92,50.00,1563.92,633.32,0.00,633.32 -1513.92,0.00,1513.92,533.32,0.00,533.32 -1413.92,0.00,1413.92,433.32,0.00,433.32 -1313.92,0.00,1313.92,333.32,0.00,333.32 -1213.92,0.00,1213.92,233.32,0.00,233.32 -1113.92,0.00,1113.92,133.32,0.00,133.32 -1013.92,0.00,1013.92,33.32,0.00,33.32 -913.92,0.00,913.92,0.00,0.00,0.00 -813.92,0.00,813.92,0.00,0.00,0.00 -713.92,0.00,713.92,0.00,0.00,0.00 -613.92,0.00,613.92,0.00,0.00,0.00 -513.92,0.00,513.92,0.00,0.00,0.00 -413.92,0.00,413.92,0.00,0.00,0.00 -313.92,0.00,313.92,0.00,0.00,0.00 -213.92,0.00,213.92,0.00,0.00,0.00 -113.92,0.00,113.92,0.00,0.00,0.00 -13.92,0.00,13.92,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 --100.00,0.00,-100.00,-100.00,0.00,-100.00 --200.00,0.00,-200.00,-200.00,0.00,-200.00 --300.00,0.00,-300.00,-300.00,0.00,-300.00 --400.00,0.00,-400.00,-400.00,0.00,-400.00 --500.00,0.00,-500.00,-500.00,0.00,-500.00 --600.00,0.00,-600.00,-600.00,0.00,-600.00 --700.00,0.00,-700.00,-700.00,0.00,-700.00 --800.00,0.00,-800.00,-800.00,0.00,-800.00 --900.00,0.00,-900.00,-900.00,0.00,-900.00 --1000.00,0.00,-1000.00,-1000.00,0.00,-1000.00 --1100.00,0.00,-1100.00,-1100.00,0.00,-1100.00 --1200.00,0.00,-1200.00,-1200.00,0.00,-1200.00 --1300.00,0.00,-1300.00,-1300.00,0.00,-1300.00 --1400.00,0.00,-1400.00,-1400.00,0.00,-1400.00 --1500.00,0.00,-1500.00,-1500.00,0.00,-1500.00 --1600.00,0.00,-1600.00,-1600.00,0.00,-1600.00 --1700.00,0.00,-1700.00,-1700.00,0.00,-1700.00 --1800.00,0.00,-1800.00,-1800.00,0.00,-1800.00 --1900.00,0.00,-1900.00,-1900.00,0.00,-1900.00 --2000.00,0.00,-2000.00,-2000.00,0.00,-2000.00 --2100.00,0.00,-2100.00,-2100.00,0.00,-2100.00 --2200.00,0.00,-2200.00,-2200.00,0.00,-2200.00 --2300.00,0.00,-2300.00,-2300.00,0.00,-2300.00 --2400.00,0.00,-2400.00,-2400.00,0.00,-2400.00 --2500.00,-450.00,-2050.00,-2500.00,-500.00,-2000.00 --2600.00,-350.00,-2250.00,-2600.00,-600.00,-2000.00 --2700.00,300.00,-3000.00,-2700.00,800.00,-3500.00 --2800.00,-950.00,-1850.00,-2800.00,-200.00,-2600.00 --2900.00,-2000.00,-900.00,-2900.00,-2400.00,-500.00 --3000.00,-850.00,-2150.00,-3000.00,-2800.00,-200.00 --3100.00,-150.00,-2950.00,-3100.00,-1800.00,-1300.00 --3200.00,-1850.00,-1350.00,-3200.00,150.00,-3350.00 --3300.00,-3000.00,-300.00,-3300.00,50.00,-3350.00 --3400.00,-2400.00,-1000.00,-3400.00,-2650.00,-750.00 --3500.00,-1650.00,-1850.00,-3500.00,-3800.00,300.00 --3600.00,-1450.00,-2150.00,-3600.00,-2400.00,-1200.00 --3700.00,-2550.00,-1150.00,-3700.00,-1450.00,-2250.00 --3800.00,-2900.00,-900.00,-3800.00,-200.00,-3600.00 --3900.00,-2450.00,-1450.00,-3900.00,-1900.00,-2000.00 --4000.00,-2300.00,-1700.00,-4000.00,-4000.00,0.00 --4100.00,-2850.00,-1250.00,-4100.00,-4000.00,-100.00 --4200.00,-3750.00,-450.00,-4200.00,-2800.00,-1400.00 --4300.00,-4000.00,-300.00,-4300.00,-1800.00,-2500.00 --4400.00,-3300.00,-1100.00,-4400.00,-2900.00,-1500.00 --4500.00,-3000.00,-1500.00,-4500.00,-4150.00,-350.00 --4600.00,-3650.00,-950.00,-4600.00,-4000.00,-600.00 --4700.00,-4550.00,-150.00,-4700.00,-2550.00,-2150.00 --4800.00,-4700.00,-100.00,-4800.00,-2400.00,-2400.00 --4900.00,-3700.00,-1200.00,-4900.00,-3750.00,-1150.00 --5000.00,-3450.00,-1550.00,-5000.00,-4700.00,-300.00 --5100.00,-4300.00,-800.00,-5100.00,-4550.00,-550.00 --5200.00,-5400.00,200.00,-5200.00,-3450.00,-1750.00 --5300.00,-5600.00,300.00,-5300.00,-2850.00,-2450.00 --5400.00,-4600.00,-800.00,-5400.00,-4300.00,-1100.00 --5500.00,-4250.00,-1250.00,-5500.00,-5650.00,150.00 --5600.00,-4900.00,-700.00,-5600.00,-5250.00,-350.00 --5700.00,-5700.00,0.00,-5700.00,-4300.00,-1400.00 --5800.00,-5800.00,0.00,-5800.00,-3600.00,-2200.00 --5900.00,-4700.00,-1200.00,-5900.00,-4400.00,-1500.00 --6000.00,-4650.00,-1350.00,-6000.00,-6200.00,200.00 --6100.00,-5650.00,-450.00,-6100.00,-6400.00,300.00 --6200.00,-6400.00,200.00,-6200.00,-4750.00,-1450.00 --6300.00,-6700.00,400.00,-6300.00,-4450.00,-1850.00 --6400.00,-5650.00,-750.00,-6400.00,-5650.00,-750.00 --6500.00,-5350.00,-1150.00,-6500.00,-6850.00,350.00 --6600.00,-6300.00,-300.00,-6600.00,-6700.00,100.00 --6700.00,-6950.00,250.00,-6700.00,-5500.00,-1200.00 --6800.00,-7300.00,500.00,-6800.00,-5700.00,-1100.00 --6900.00,-7350.00,450.00,-6900.00,-6600.00,-300.00 --7000.00,-6200.00,-800.00,-7000.00,-7100.00,100.00 --7100.00,-6000.00,-1100.00,-7100.00,-7250.00,150.00 --7200.00,-7000.00,-200.00,-7200.00,-7150.00,-50.00 --7300.00,-7700.00,400.00,-7300.00,-6800.00,-500.00 --7400.00,-8550.00,1150.00,-7400.00,-7250.00,-150.00 --7500.00,-8300.00,800.00,-7500.00,-7450.00,-50.00 --7600.00,-7150.00,-450.00,-7600.00,-7250.00,-350.00 --7700.00,-7850.00,150.00,-7700.00,-7600.00,-100.00 --7800.00,-8450.00,650.00,-7800.00,-7750.00,-50.00 --7900.00,-8900.00,1000.00,-7900.00,-8000.00,100.00 --8000.00,-9100.00,1100.00,-8000.00,-7900.00,-100.00 --8100.00,-9100.00,1000.00,-8100.00,-7900.00,-200.00 --8200.00,-9050.00,850.00,-8200.00,-8050.00,-150.00 --8300.00,-9200.00,900.00,-8300.00,-8250.00,-50.00 --8400.00,-9400.00,1000.00,-8400.00,-8500.00,100.00 --8500.00,-9500.00,1000.00,-8500.00,-8600.00,100.00 --8600.00,-9550.00,950.00,-8600.00,-8650.00,50.00 --8700.00,-11200.00,2500.00,-8700.00,-10050.00,1350.00 --8800.00,-9000.00,200.00,-8800.00,-8350.00,-450.00 --8900.00,-8400.00,-500.00,-8900.00,-8550.00,-350.00 --9000.00,-9450.00,450.00,-9000.00,-9100.00,100.00 --9100.00,-10300.00,1200.00,-9100.00,-9600.00,500.00 --9200.00,-10550.00,1350.00,-9200.00,-9700.00,500.00 --9300.00,-10750.00,1450.00,-9300.00,-9800.00,500.00 --9400.00,-10800.00,1400.00,-9400.00,-9800.00,400.00 --9500.00,-10300.00,800.00,-9500.00,-9500.00,0.00 --9600.00,-10800.00,1200.00,-9600.00,-10100.00,500.00 --9700.00,-11150.00,1450.00,-9700.00,-10500.00,800.00 --9800.00,-11250.00,1450.00,-9800.00,-10550.00,750.00 --9900.00,-11250.00,1350.00,-9900.00,-10600.00,700.00 --10000.00,-11250.00,1250.00,-10000.00,-10550.00,550.00 --10100.00,-11300.00,1200.00,-10100.00,-10700.00,600.00 --10200.00,-11500.00,1300.00,-10200.00,-10750.00,550.00 --10300.00,-11700.00,1400.00,-10300.00,-10900.00,600.00 --10400.00,-11800.00,1400.00,-10400.00,-11100.00,700.00 --10500.00,-11850.00,1350.00,-10500.00,-11300.00,800.00 --10600.00,-11900.00,1300.00,-10600.00,-11450.00,850.00 --10700.00,-12150.00,1450.00,-10700.00,-11600.00,900.00 --10800.00,-12300.00,1500.00,-10800.00,-11700.00,900.00 --10900.00,-12350.00,1450.00,-10900.00,-11900.00,1000.00 --11000.00,-12450.00,1450.00,-11000.00,-12000.00,1000.00 --11100.00,-12550.00,1450.00,-11100.00,-12100.00,1000.00 --11200.00,-12750.00,1550.00,-11200.00,-12200.00,1000.00 --11300.00,-12850.00,1550.00,-11300.00,-12400.00,1100.00 --11400.00,-13000.00,1600.00,-11400.00,-12500.00,1100.00 --11500.00,-13200.00,1700.00,-11500.00,-12800.00,1300.00 --11600.00,-13250.00,1650.00,-11600.00,-12900.00,1300.00 --11700.00,-13250.00,1550.00,-11700.00,-12900.00,1200.00 --11800.00,-13550.00,1750.00,-11800.00,-13050.00,1250.00 --11900.00,-13700.00,1800.00,-11900.00,-13050.00,1150.00 --12000.00,-13750.00,1750.00,-12000.00,-13000.00,1000.00 --12100.00,-13850.00,1750.00,-12100.00,-13150.00,1050.00 --12200.00,-14150.00,1950.00,-12200.00,-13350.00,1150.00 --12300.00,-14200.00,1900.00,-12300.00,-13500.00,1200.00 --12400.00,-14200.00,1800.00,-12400.00,-13650.00,1250.00 --12500.00,-14400.00,1900.00,-12500.00,-13800.00,1300.00 --12600.00,-14600.00,2000.00,-12600.00,-13800.00,1200.00 --12700.00,-14700.00,2000.00,-12700.00,-14000.00,1300.00 --12800.00,-14800.00,2000.00,-12800.00,-14100.00,1300.00 --12900.00,-14950.00,2050.00,-12900.00,-14150.00,1250.00 --13000.00,-15000.00,2000.00,-13000.00,-14200.00,1200.00 --13100.00,-15100.00,2000.00,-13100.00,-14300.00,1200.00 --13200.00,-15250.00,2050.00,-13200.00,-14450.00,1250.00 --13300.00,-15500.00,2200.00,-13300.00,-14550.00,1250.00 --13400.00,-15500.00,2100.00,-13400.00,-14650.00,1250.00 --13500.00,-15600.00,2100.00,-13500.00,-14750.00,1250.00 --13600.00,-15800.00,2200.00,-13600.00,-14900.00,1300.00 --13700.00,-15850.00,2150.00,-13700.00,-15050.00,1350.00 --13800.00,-15900.00,2100.00,-13800.00,-15250.00,1450.00 --13900.00,-16100.00,2200.00,-13900.00,-15350.00,1450.00 --14000.00,-16300.00,2300.00,-14000.00,-15550.00,1550.00 --14100.00,-16500.00,2400.00,-14100.00,-15700.00,1600.00 --14200.00,-16600.00,2400.00,-14200.00,-15750.00,1550.00 --14300.00,-16600.00,2300.00,-14300.00,-15850.00,1550.00 --14400.00,-16500.00,2100.00,-14400.00,-15950.00,1550.00 --14500.00,-16750.00,2250.00,-14500.00,-16150.00,1650.00 --14600.00,-16850.00,2250.00,-14600.00,-16200.00,1600.00 --14700.00,-17050.00,2350.00,-14700.00,-16300.00,1600.00 --14800.00,-17100.00,2300.00,-14800.00,-16650.00,1850.00 --14900.00,-17250.00,2350.00,-14900.00,-16750.00,1850.00 --15000.00,-17300.00,2300.00,-15000.00,-16900.00,1900.00 --15100.00,-17450.00,2350.00,-15100.00,-17050.00,1950.00 --15200.00,-17550.00,2350.00,-15200.00,-17100.00,1900.00 --15300.00,-17700.00,2400.00,-15300.00,-17150.00,1850.00 --15400.00,-17750.00,2350.00,-15400.00,-17400.00,2000.00 --15500.00,-17950.00,2450.00,-15500.00,-17600.00,2100.00 --15600.00,-18050.00,2450.00,-15600.00,-17700.00,2100.00 --15700.00,-18300.00,2600.00,-15700.00,-17800.00,2100.00 --15800.00,-18300.00,2500.00,-15800.00,-17600.00,1800.00 --15900.00,-18600.00,2700.00,-15900.00,-17800.00,1900.00 --16000.00,-18700.00,2700.00,-16000.00,-18000.00,2000.00 --16100.00,-22150.00,6050.00,-16100.00,-21600.00,5500.00 --16200.00,-17500.00,1300.00,-16200.00,-17900.00,1700.00 --16300.00,-15200.00,-1100.00,-16300.00,-16900.00,600.00 --16400.00,-16800.00,400.00,-16400.00,-17500.00,1100.00 --16500.00,-20550.00,4050.00,-16500.00,-19100.00,2600.00 --16600.00,-20900.00,4300.00,-16600.00,-18800.00,2200.00 --16700.00,-20300.00,3600.00,-16700.00,-18600.00,1900.00 --16800.00,-19950.00,3150.00,-16800.00,-18600.00,1800.00 --16900.00,-19650.00,2750.00,-16900.00,-18850.00,1950.00 --17000.00,-19800.00,2800.00,-17000.00,-19050.00,2050.00 --17100.00,-20050.00,2950.00,-17100.00,-19200.00,2100.00 --17200.00,-20550.00,3350.00,-17200.00,-19300.00,2100.00 --17300.00,-20600.00,3300.00,-17300.00,-19600.00,2300.00 --17400.00,-20600.00,3200.00,-17400.00,-19700.00,2300.00 --17500.00,-20500.00,3000.00,-17500.00,-19900.00,2400.00 --17600.00,-20800.00,3200.00,-17549.96,-19900.00,2350.04 --17700.00,-20900.00,3200.00,-17449.96,-20000.00,2550.04 --17800.00,-20950.00,3150.00,-17349.96,-19950.00,2600.04 --17900.00,-19500.00,1600.00,-17249.96,-18350.00,1100.04 --18000.00,-21500.00,3500.00,-17149.96,-19800.00,2650.04 --18063.52,-22050.00,3986.48,-17049.96,-20300.00,3250.04 --17963.52,-21800.00,3836.48,-16949.96,-19950.00,3000.04 --17863.52,-22050.00,4186.48,-16849.96,-20250.00,3400.04 --17763.52,-21850.00,4086.48,-16749.96,-19700.00,2950.04 --17663.52,-20600.00,2936.48,-16649.96,-18450.00,1800.04 --17563.52,-20400.00,2836.48,-16549.96,-18450.00,1900.04 --17463.52,-20700.00,3236.48,-16449.96,-18800.00,2350.04 --17363.52,-20700.00,3336.48,-16349.96,-18850.00,2500.04 --17263.52,-21550.00,4286.48,-16249.96,-19350.00,3100.04 --17163.52,-20600.00,3436.48,-16149.96,-18350.00,2200.04 --17063.52,-20000.00,2936.48,-16049.96,-17950.00,1900.04 --16963.52,-20000.00,3036.48,-15949.96,-17800.00,1850.04 --16863.52,-20000.00,3136.48,-15849.96,-18000.00,2150.04 --16763.52,-20000.00,3236.48,-15749.96,-18100.00,2350.04 --16663.52,-20050.00,3386.48,-15649.96,-17950.00,2300.04 --16563.52,-19850.00,3286.48,-15549.96,-17750.00,2200.04 --16463.52,-19700.00,3236.48,-15449.96,-17400.00,1950.04 --16363.52,-19500.00,3136.48,-15349.96,-17250.00,1900.04 --16263.52,-19300.00,3036.48,-15249.96,-17150.00,1900.04 --16163.52,-19300.00,3136.48,-15149.96,-16900.00,1750.04 --16063.52,-19100.00,3036.48,-15049.96,-16700.00,1650.04 --15963.52,-19000.00,3036.48,-14949.96,-16600.00,1650.04 --15863.52,-18950.00,3086.48,-14849.96,-16500.00,1650.04 --15763.52,-18750.00,2986.48,-14749.96,-16300.00,1550.04 --15663.52,-18550.00,2886.48,-14649.96,-16300.00,1650.04 --15563.52,-18350.00,2786.48,-14549.96,-16300.00,1750.04 --15463.52,-18300.00,2836.48,-14449.96,-16300.00,1850.04 --15363.52,-18150.00,2786.48,-14349.96,-16250.00,1900.04 --15263.52,-18000.00,2736.48,-14249.96,-16150.00,1900.04 --15163.52,-18000.00,2836.48,-14149.96,-16000.00,1850.04 --15063.52,-17800.00,2736.48,-14049.96,-15850.00,1800.04 --14963.52,-17650.00,2686.48,-13949.96,-15500.00,1550.04 --14863.52,-17600.00,2736.48,-13849.96,-15300.00,1450.04 --14763.52,-17350.00,2586.48,-13749.96,-15150.00,1400.04 --14663.52,-17300.00,2636.48,-13649.96,-15300.00,1650.04 --14563.52,-17250.00,2686.48,-13549.96,-15250.00,1700.04 --14463.52,-17000.00,2536.48,-13449.96,-15050.00,1600.04 --14363.52,-16850.00,2486.48,-13349.96,-15000.00,1650.04 --14263.52,-16850.00,2586.48,-13249.96,-15000.00,1750.04 --14163.52,-16700.00,2536.48,-13149.96,-14900.00,1750.04 --14063.52,-16650.00,2586.48,-13049.96,-14750.00,1700.04 --13963.52,-16500.00,2536.48,-12949.96,-14550.00,1600.04 --13863.52,-16200.00,2336.48,-12849.96,-14400.00,1550.04 --13763.52,-16100.00,2336.48,-12749.96,-14200.00,1450.04 --13663.52,-16050.00,2386.48,-12649.96,-14050.00,1400.04 --13563.52,-15950.00,2386.48,-12549.96,-13900.00,1350.04 --13463.52,-15850.00,2386.48,-12449.96,-13750.00,1300.04 --13363.52,-15750.00,2386.48,-12349.96,-13650.00,1300.04 --13263.52,-15700.00,2436.48,-12249.96,-13550.00,1300.04 --13163.52,-15450.00,2286.48,-12149.96,-13500.00,1350.04 --13063.52,-15300.00,2236.48,-12049.96,-13350.00,1300.04 --12963.52,-15250.00,2286.48,-11949.96,-13200.00,1250.04 --12863.52,-15150.00,2286.48,-11849.96,-13050.00,1200.04 --12763.52,-14950.00,2186.48,-11749.96,-12900.00,1150.04 --12663.52,-17450.00,4786.48,-11649.96,-14950.00,3300.04 --12563.52,-13700.00,1136.48,-11549.96,-11750.00,200.04 --12463.52,-10900.00,-1563.52,-11449.96,-9150.00,-2299.96 --12363.52,-13300.00,936.48,-11349.96,-11350.00,0.04 --12263.52,-15300.00,3036.48,-11249.96,-13300.00,2050.04 --12163.52,-15650.00,3486.48,-11149.96,-13550.00,2400.04 --12063.52,-15000.00,2936.48,-11049.96,-12950.00,1900.04 --11963.52,-14400.00,2436.48,-10949.96,-12050.00,1100.04 --11863.52,-14100.00,2236.48,-10849.96,-11750.00,900.04 --11763.52,-13850.00,2086.48,-10749.96,-11500.00,750.04 --11663.52,-13650.00,1986.48,-10649.96,-11500.00,850.04 --11563.52,-13700.00,2136.48,-10549.96,-11600.00,1050.04 --11463.52,-13600.00,2136.48,-10449.96,-11400.00,950.04 --11363.52,-13600.00,2236.48,-10349.96,-11300.00,950.04 --11263.52,-13450.00,2186.48,-10249.96,-11300.00,1050.04 --11163.52,-13150.00,1986.48,-10149.96,-11250.00,1100.04 --11063.52,-13050.00,1986.48,-10049.96,-11250.00,1200.04 --10963.52,-12900.00,1936.48,-9949.96,-11100.00,1150.04 --10863.52,-12800.00,1936.48,-9849.96,-11050.00,1200.04 --10763.52,-12250.00,1486.48,-9749.96,-10600.00,850.04 --10663.52,-12650.00,1986.48,-9649.96,-10950.00,1300.04 --10563.52,-12650.00,2086.48,-9549.96,-10800.00,1250.04 --10463.52,-12500.00,2036.48,-9449.96,-10750.00,1300.04 --10363.52,-12200.00,1836.48,-9349.96,-10450.00,1100.04 --10263.52,-12050.00,1786.48,-9249.96,-10200.00,950.04 --10163.52,-11900.00,1736.48,-9149.96,-9900.00,750.04 --10063.52,-11750.00,1686.48,-9049.96,-9800.00,750.04 --9963.52,-11650.00,1686.48,-8949.96,-9650.00,700.04 --9863.52,-11250.00,1386.48,-8849.96,-9300.00,450.04 --9763.52,-11600.00,1836.48,-8749.96,-9600.00,850.04 --9663.52,-11550.00,1886.48,-8649.96,-9600.00,950.04 --9563.52,-10950.00,1386.48,-8549.96,-8950.00,400.04 --9463.52,-11200.00,1736.48,-8449.96,-9300.00,850.04 --9363.52,-11100.00,1736.48,-8349.96,-9250.00,900.04 --9263.52,-10950.00,1686.48,-8249.96,-9150.00,900.04 --9163.52,-10700.00,1536.48,-8149.96,-8900.00,750.04 --9063.52,-10550.00,1486.48,-8049.96,-8700.00,650.04 --8963.52,-10400.00,1436.48,-7949.96,-8700.00,750.04 --8863.52,-10350.00,1486.48,-7849.96,-8500.00,650.04 --8763.52,-10350.00,1586.48,-7749.96,-8500.00,750.04 --8663.52,-9650.00,986.48,-7649.96,-8400.00,750.04 --8563.52,-8600.00,36.48,-7549.96,-8250.00,700.04 --8463.52,-9050.00,586.48,-7449.96,-8050.00,600.04 --8363.52,-9600.00,1236.48,-7349.96,-7950.00,600.04 --8263.52,-9350.00,1086.48,-7249.96,-7750.00,500.04 --8163.52,-8200.00,36.48,-7149.96,-7600.00,450.04 --8063.52,-8650.00,586.48,-7049.96,-7500.00,450.04 --7963.52,-9100.00,1136.48,-6949.96,-7000.00,50.04 --7863.52,-8800.00,936.48,-6849.96,-5950.00,-899.96 --7763.52,-7500.00,-263.52,-6749.96,-6250.00,-499.96 --7663.52,-7000.00,-663.52,-6649.96,-6800.00,150.04 --7563.52,-7800.00,236.48,-6549.96,-6900.00,350.04 --7463.52,-8650.00,1186.48,-6449.96,-6500.00,50.04 --7363.52,-8650.00,1286.48,-6349.96,-5500.00,-849.96 --7263.52,-7450.00,186.48,-6249.96,-5650.00,-599.96 --7163.52,-6750.00,-413.52,-6149.96,-6150.00,0.04 --7063.52,-7350.00,286.48,-6049.96,-6000.00,-49.96 --6963.52,-8000.00,1036.48,-5949.96,-4850.00,-1099.96 --6863.52,-7800.00,936.48,-5849.96,-4150.00,-1699.96 --6763.52,-6600.00,-163.52,-5749.96,-5050.00,-699.96 --6663.52,-6300.00,-363.52,-5649.96,-6050.00,400.04 --6563.52,-6850.00,286.48,-5549.96,-5950.00,400.04 --6463.52,-6850.00,386.48,-5449.96,-4850.00,-599.96 --6363.52,-5750.00,-613.52,-5349.96,-3900.00,-1449.96 --6263.52,-5600.00,-663.52,-5249.96,-4400.00,-849.96 --6163.52,-6250.00,86.48,-5149.96,-5200.00,50.04 --6063.52,-6400.00,336.48,-5049.96,-4700.00,-349.96 --5963.52,-5650.00,-313.52,-4949.96,-3900.00,-1049.96 --5863.52,-4950.00,-913.52,-4849.96,-3200.00,-1649.96 --5763.52,-6050.00,286.48,-4749.96,-3800.00,-949.96 --5663.52,-6000.00,336.48,-4649.96,-4500.00,-149.96 --5563.52,-5150.00,-413.52,-4549.96,-4200.00,-349.96 --5463.52,-4400.00,-1063.52,-4449.96,-3200.00,-1249.96 --5363.52,-4100.00,-1263.52,-4349.96,-2600.00,-1749.96 --5263.52,-4800.00,-463.52,-4249.96,-3100.00,-1149.96 --5163.52,-6400.00,1236.48,-4149.96,-3900.00,-249.96 --5063.52,-4350.00,-713.52,-4049.96,-2200.00,-1849.96 --4963.52,-3450.00,-1513.52,-3949.96,-1400.00,-2549.96 --4863.52,-3350.00,-1513.52,-3849.96,-2500.00,-1349.96 --4763.52,-4400.00,-363.52,-3749.96,-3500.00,-249.96 --4663.52,-4950.00,286.48,-3649.96,-2200.00,-1449.96 --4563.52,-4050.00,-513.52,-3549.96,-1200.00,-2349.96 --4463.52,-3400.00,-1063.52,-3449.96,-100.00,-3349.96 --4363.52,-2550.00,-1813.52,-3349.96,-1400.00,-1949.96 --4263.52,-2300.00,-1963.52,-3249.96,-3500.00,250.04 --4163.52,-3700.00,-463.52,-3149.96,-3500.00,350.04 --4063.52,-4350.00,286.48,-3049.96,-2050.00,-999.96 --3963.52,-3550.00,-413.52,-2949.96,-900.00,-2049.96 --3863.52,-2850.00,-1013.52,-2849.96,-600.00,-2249.96 --3763.52,-1800.00,-1963.52,-2749.96,-850.00,-1899.96 --3663.52,-2350.00,-1313.52,-2649.96,-450.00,-2199.96 --3563.52,-2750.00,-813.52,-2549.96,900.00,-3449.96 --3463.52,-1800.00,-1663.52,-2449.96,-450.00,-1999.96 --3363.52,-1600.00,-1763.52,-2349.96,-1500.00,-849.96 --3263.52,200.00,-3463.52,-2249.96,-1000.00,-1249.96 --3163.52,-50.00,-3113.52,-2149.96,-400.00,-1749.96 --3063.52,-2300.00,-763.52,-2049.96,100.00,-2149.96 --2963.52,-3600.00,636.48,-1949.96,50.00,-1999.96 --2863.52,-2800.00,-63.52,-1849.96,0.00,-1849.96 --2763.52,-2250.00,-513.52,-1749.96,0.00,-1749.96 --2663.52,-1700.00,-963.52,-1649.96,0.00,-1649.96 --2563.52,-900.00,-1663.52,-1549.96,0.00,-1549.96 --2463.52,850.00,-3313.52,-1449.96,0.00,-1449.96 --2363.52,-200.00,-2163.52,-1349.96,0.00,-1349.96 --2263.52,-1700.00,-563.52,-1249.96,0.00,-1249.96 --2163.52,-1200.00,-963.52,-1149.96,0.00,-1149.96 --2063.52,-950.00,-1113.52,-1049.96,0.00,-1049.96 --1963.52,550.00,-2513.52,-949.96,0.00,-949.96 --1863.52,250.00,-2113.52,-849.96,0.00,-849.96 --1763.52,-100.00,-1663.52,-749.96,0.00,-749.96 --1663.52,0.00,-1663.52,-649.96,0.00,-649.96 --1563.52,0.00,-1563.52,-549.96,0.00,-549.96 --1463.52,0.00,-1463.52,-449.96,0.00,-449.96 --1363.52,0.00,-1363.52,-349.96,0.00,-349.96 --1263.52,0.00,-1263.52,-249.96,0.00,-249.96 --1163.52,0.00,-1163.52,-149.96,0.00,-149.96 --1063.52,0.00,-1063.52,-49.96,0.00,-49.96 --963.52,0.00,-963.52,0.00,0.00,0.00 --863.52,0.00,-863.52,0.00,0.00,0.00 --763.52,0.00,-763.52,0.00,0.00,0.00 --663.52,0.00,-663.52,0.00,0.00,0.00 --563.52,0.00,-563.52,0.00,0.00,0.00 --463.52,0.00,-463.52,0.00,0.00,0.00 --363.52,0.00,-363.52,0.00,0.00,0.00 --263.52,0.00,-263.52,0.00,0.00,0.00 --163.52,0.00,-163.52,0.00,0.00,0.00 --63.52,0.00,-63.52,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -100.00,0.00,100.00,100.00,0.00,100.00 -200.00,0.00,200.00,200.00,0.00,200.00 -300.00,0.00,300.00,300.00,0.00,300.00 -400.00,0.00,400.00,400.00,0.00,400.00 -500.00,0.00,500.00,500.00,0.00,500.00 -600.00,0.00,600.00,600.00,0.00,600.00 -700.00,0.00,700.00,700.00,0.00,700.00 -800.00,0.00,800.00,800.00,0.00,800.00 -900.00,0.00,900.00,900.00,0.00,900.00 -1000.00,0.00,1000.00,1000.00,0.00,1000.00 -1100.00,0.00,1100.00,1100.00,0.00,1100.00 -1200.00,0.00,1200.00,1200.00,0.00,1200.00 -1300.00,0.00,1300.00,1300.00,0.00,1300.00 -1400.00,0.00,1400.00,1400.00,0.00,1400.00 -1500.00,0.00,1500.00,1500.00,0.00,1500.00 -1600.00,0.00,1600.00,1600.00,0.00,1600.00 -1700.00,0.00,1700.00,1700.00,0.00,1700.00 -1800.00,0.00,1800.00,1800.00,0.00,1800.00 -1900.00,0.00,1900.00,1900.00,0.00,1900.00 -2000.00,0.00,2000.00,2000.00,0.00,2000.00 -2100.00,0.00,2100.00,2100.00,0.00,2100.00 -2200.00,0.00,2200.00,2200.00,0.00,2200.00 -2300.00,0.00,2300.00,2300.00,0.00,2300.00 -2400.00,0.00,2400.00,2400.00,0.00,2400.00 -2500.00,350.00,2150.00,2500.00,500.00,2000.00 -2600.00,250.00,2350.00,2600.00,600.00,2000.00 -2700.00,-250.00,2950.00,2700.00,-800.00,3500.00 -2800.00,850.00,1950.00,2800.00,50.00,2750.00 -2900.00,1000.00,1900.00,2900.00,1950.00,950.00 -3000.00,1050.00,1950.00,3000.00,1050.00,1950.00 -3100.00,-100.00,3200.00,3100.00,350.00,2750.00 -3200.00,850.00,2350.00,3200.00,450.00,2750.00 -3300.00,2400.00,900.00,3300.00,1150.00,2150.00 -3400.00,1300.00,2100.00,3400.00,1500.00,1900.00 -3500.00,350.00,3150.00,3500.00,1000.00,2500.00 -3600.00,2550.00,1050.00,3600.00,1300.00,2300.00 -3700.00,1850.00,1850.00,3700.00,1900.00,1800.00 -3800.00,2100.00,1700.00,3800.00,1450.00,2350.00 -3900.00,2200.00,1700.00,3900.00,1850.00,2050.00 -4000.00,2250.00,1750.00,4000.00,1950.00,2050.00 -4100.00,2500.00,1600.00,4100.00,2050.00,2050.00 -4200.00,2800.00,1400.00,4200.00,2200.00,2000.00 -4300.00,3100.00,1200.00,4300.00,2250.00,2050.00 -4400.00,3100.00,1300.00,4400.00,2400.00,2000.00 -4500.00,3200.00,1300.00,4500.00,2750.00,1750.00 -4600.00,3350.00,1250.00,4600.00,3000.00,1600.00 -4700.00,3450.00,1250.00,4700.00,3050.00,1650.00 -4800.00,3600.00,1200.00,4800.00,3150.00,1650.00 -4900.00,3700.00,1200.00,4900.00,3200.00,1700.00 -5000.00,3750.00,1250.00,5000.00,3350.00,1650.00 -5100.00,3850.00,1250.00,5100.00,3350.00,1750.00 -5200.00,4000.00,1200.00,5200.00,3400.00,1800.00 -5300.00,4350.00,950.00,5300.00,3500.00,1800.00 -5400.00,4350.00,1050.00,5400.00,3800.00,1600.00 -5500.00,4450.00,1050.00,5500.00,4000.00,1500.00 -5600.00,4800.00,800.00,5600.00,4400.00,1200.00 -5700.00,5100.00,600.00,5700.00,4550.00,1150.00 -5800.00,5300.00,500.00,5800.00,4750.00,1050.00 -5900.00,5450.00,450.00,5900.00,5000.00,900.00 -6000.00,5700.00,300.00,6000.00,5050.00,950.00 -6100.00,5850.00,250.00,6100.00,5350.00,750.00 -6200.00,6100.00,100.00,6200.00,5600.00,600.00 -6300.00,6200.00,100.00,6300.00,5500.00,800.00 -6400.00,6100.00,300.00,6400.00,5300.00,1100.00 -6500.00,6350.00,150.00,6500.00,5400.00,1100.00 -6600.00,6350.00,250.00,6600.00,5300.00,1300.00 -6700.00,6250.00,450.00,6700.00,5500.00,1200.00 -6800.00,6450.00,350.00,6800.00,5700.00,1100.00 -6900.00,6600.00,300.00,6900.00,6000.00,900.00 -7000.00,6750.00,250.00,7000.00,6100.00,900.00 -7100.00,6900.00,200.00,7100.00,6100.00,1000.00 -7200.00,6900.00,300.00,7200.00,6450.00,750.00 -7300.00,7050.00,250.00,7300.00,6850.00,450.00 -7400.00,7250.00,150.00,7400.00,7000.00,400.00 -7500.00,7200.00,300.00,7500.00,6950.00,550.00 -7600.00,7100.00,500.00,7600.00,6750.00,850.00 -7700.00,7300.00,400.00,7700.00,7000.00,700.00 -7800.00,7700.00,100.00,7800.00,6900.00,900.00 -7900.00,7850.00,50.00,7900.00,6900.00,1000.00 -8000.00,8100.00,-100.00,8000.00,6900.00,1100.00 -8100.00,8000.00,100.00,8100.00,7300.00,800.00 -8200.00,7900.00,300.00,8200.00,7200.00,1000.00 -8300.00,7750.00,550.00,8300.00,7600.00,700.00 -8400.00,8100.00,300.00,8400.00,7800.00,600.00 -8500.00,7950.00,550.00,8500.00,7750.00,750.00 -8600.00,8150.00,450.00,8600.00,7650.00,950.00 -8700.00,8450.00,250.00,8700.00,8350.00,350.00 -8800.00,9000.00,-200.00,8800.00,8750.00,50.00 -8900.00,8850.00,50.00,8900.00,8700.00,200.00 -9000.00,9300.00,-300.00,9000.00,8700.00,300.00 -9100.00,9500.00,-400.00,9100.00,8750.00,350.00 -9200.00,9050.00,150.00,9200.00,8150.00,1050.00 -9300.00,9350.00,-50.00,9300.00,8400.00,900.00 -9400.00,11000.00,-1600.00,9400.00,10300.00,-900.00 -9500.00,9200.00,300.00,9500.00,8500.00,1000.00 -9600.00,9450.00,150.00,9600.00,8750.00,850.00 -9700.00,9850.00,-150.00,9700.00,8850.00,850.00 -9800.00,9800.00,0.00,9800.00,8800.00,1000.00 -9900.00,10150.00,-250.00,9900.00,9400.00,500.00 -10000.00,10300.00,-300.00,10000.00,10100.00,-100.00 -10100.00,10500.00,-400.00,10100.00,10200.00,-100.00 -10200.00,10050.00,150.00,10200.00,9600.00,600.00 -10300.00,10500.00,-200.00,10300.00,9700.00,600.00 -10400.00,10700.00,-300.00,10400.00,10000.00,400.00 -10500.00,10700.00,-200.00,10500.00,9900.00,600.00 -10600.00,10600.00,0.00,10600.00,9650.00,950.00 -10700.00,10900.00,-200.00,10700.00,9950.00,750.00 -10800.00,11750.00,-950.00,10800.00,10950.00,-150.00 -10900.00,12000.00,-1100.00,10900.00,11150.00,-250.00 -11000.00,11250.00,-250.00,11000.00,10800.00,200.00 -11100.00,11150.00,-50.00,11100.00,10900.00,200.00 -11200.00,12050.00,-850.00,11200.00,11650.00,-450.00 -11300.00,12150.00,-850.00,11300.00,11700.00,-400.00 -11400.00,12150.00,-750.00,11400.00,11500.00,-100.00 -11500.00,12200.00,-700.00,11500.00,11500.00,0.00 -11600.00,11750.00,-150.00,11600.00,11050.00,550.00 -11700.00,12350.00,-650.00,11700.00,11550.00,150.00 -11800.00,12500.00,-700.00,11800.00,11700.00,100.00 -11900.00,12650.00,-750.00,11900.00,12100.00,-200.00 -12000.00,12150.00,-150.00,12000.00,11550.00,450.00 -12100.00,12950.00,-850.00,12100.00,12550.00,-450.00 -12200.00,13200.00,-1000.00,12200.00,12650.00,-450.00 -12300.00,12600.00,-300.00,12300.00,12100.00,200.00 -12400.00,13550.00,-1150.00,12400.00,13100.00,-700.00 -12500.00,14000.00,-1500.00,12500.00,13500.00,-1000.00 -12600.00,13650.00,-1050.00,12600.00,13000.00,-400.00 -12700.00,13300.00,-600.00,12700.00,12850.00,-150.00 -12800.00,13700.00,-900.00,12800.00,13300.00,-500.00 -12900.00,13900.00,-1000.00,12900.00,13350.00,-450.00 -13000.00,13800.00,-800.00,13000.00,13200.00,-200.00 -13100.00,13850.00,-750.00,13100.00,13350.00,-250.00 -13200.00,13400.00,-200.00,13200.00,13050.00,150.00 -13300.00,14150.00,-850.00,13300.00,13850.00,-550.00 -13400.00,14700.00,-1300.00,13400.00,14200.00,-800.00 -13500.00,14750.00,-1250.00,13500.00,14300.00,-800.00 -13600.00,14800.00,-1200.00,13600.00,14050.00,-450.00 -13700.00,14750.00,-1050.00,13700.00,13800.00,-100.00 -13800.00,14600.00,-800.00,13800.00,13800.00,0.00 -13900.00,14550.00,-650.00,13900.00,13800.00,100.00 -14000.00,15450.00,-1450.00,14000.00,14300.00,-300.00 -14100.00,15600.00,-1500.00,14100.00,14900.00,-800.00 -14200.00,15650.00,-1450.00,14200.00,15300.00,-1100.00 -14300.00,15300.00,-1000.00,14300.00,14800.00,-500.00 -14400.00,15250.00,-850.00,14400.00,14200.00,200.00 -14500.00,15800.00,-1300.00,14500.00,14600.00,-100.00 -14600.00,16350.00,-1750.00,14600.00,15300.00,-700.00 -14700.00,16050.00,-1350.00,14700.00,15150.00,-450.00 -14800.00,15800.00,-1000.00,14800.00,15450.00,-650.00 -14900.00,16350.00,-1450.00,14900.00,16000.00,-1100.00 -15000.00,17150.00,-2150.00,15000.00,16200.00,-1200.00 -15100.00,16450.00,-1350.00,15100.00,15200.00,-100.00 -15200.00,16550.00,-1350.00,15200.00,15500.00,-300.00 -15300.00,16950.00,-1650.00,15300.00,16150.00,-850.00 -15400.00,16900.00,-1500.00,15400.00,16750.00,-1350.00 -15500.00,16500.00,-1000.00,15500.00,16650.00,-1150.00 -15600.00,16800.00,-1200.00,15600.00,16550.00,-950.00 -15700.00,17000.00,-1300.00,15700.00,16350.00,-650.00 -15800.00,17350.00,-1550.00,15800.00,17000.00,-1200.00 -15900.00,17750.00,-1850.00,15900.00,16850.00,-950.00 -16000.00,18000.00,-2000.00,16000.00,17250.00,-1250.00 -16100.00,17950.00,-1850.00,16100.00,17150.00,-1050.00 -16200.00,17750.00,-1550.00,16200.00,17100.00,-900.00 -16300.00,18050.00,-1750.00,16300.00,17550.00,-1250.00 -16400.00,17750.00,-1350.00,16400.00,17350.00,-950.00 -16500.00,17850.00,-1350.00,16500.00,17350.00,-850.00 -16600.00,18650.00,-2050.00,16600.00,18250.00,-1650.00 -16700.00,18300.00,-1600.00,16700.00,17950.00,-1250.00 -16800.00,18100.00,-1300.00,16800.00,17650.00,-850.00 -16900.00,21450.00,-4550.00,16900.00,20700.00,-3800.00 -17000.00,18150.00,-1150.00,17000.00,17500.00,-500.00 -17100.00,18200.00,-1100.00,17100.00,18100.00,-1000.00 -17200.00,18950.00,-1750.00,17200.00,19150.00,-1950.00 -17300.00,18850.00,-1550.00,17195.22,18350.00,-1154.78 -17400.00,19200.00,-1800.00,17095.22,18350.00,-1254.78 -17500.00,19650.00,-2150.00,16995.22,18750.00,-1754.78 -17600.00,19550.00,-1950.00,16895.22,18500.00,-1604.78 -17549.96,19700.00,-2150.04,16795.22,18900.00,-2104.78 -17449.96,19500.00,-2050.04,16695.22,18200.00,-1504.78 -17349.96,19500.00,-2150.04,16595.22,18100.00,-1504.78 -17249.96,19950.00,-2700.04,16495.22,18550.00,-2054.78 -17149.96,20050.00,-2900.04,16395.22,18650.00,-2254.78 -17049.96,19000.00,-1950.04,16295.22,17800.00,-1504.78 -16949.96,19300.00,-2350.04,16195.22,18100.00,-1904.78 -16849.96,20200.00,-3350.04,16095.22,18050.00,-1954.78 -16749.96,19500.00,-2750.04,15995.22,17200.00,-1204.78 -16649.96,19000.00,-2350.04,15895.22,17450.00,-1554.78 -16549.96,18800.00,-2250.04,15795.22,17700.00,-1904.78 -16449.96,18900.00,-2450.04,15695.22,18000.00,-2304.78 -16349.96,18600.00,-2250.04,15595.22,17750.00,-2154.78 -16249.96,17850.00,-1600.04,15495.22,16600.00,-1104.78 -16149.96,18500.00,-2350.04,15395.22,17350.00,-1954.78 -16049.96,19200.00,-3150.04,15295.22,17400.00,-2104.78 -15949.96,18050.00,-2100.04,15195.22,16550.00,-1354.78 -15849.96,17950.00,-2100.04,15095.22,16600.00,-1504.78 -15749.96,17950.00,-2200.04,14995.22,16450.00,-1454.78 -15649.96,17950.00,-2300.04,14895.22,16150.00,-1254.78 -15549.96,17900.00,-2350.04,14795.22,16450.00,-1654.78 -15449.96,16700.00,-1250.04,14695.22,15600.00,-904.78 -15349.96,16700.00,-1350.04,14595.22,15800.00,-1204.78 -15249.96,16650.00,-1400.04,14495.22,15950.00,-1454.78 -15149.96,17300.00,-2150.04,14395.22,16500.00,-2104.78 -15049.96,17150.00,-2100.04,14295.22,15750.00,-1454.78 -14949.96,16550.00,-1600.04,14195.22,15100.00,-904.78 -14849.96,17200.00,-2350.04,14095.22,15800.00,-1704.78 -14749.96,17350.00,-2600.04,13995.22,16050.00,-2054.78 -14649.96,16350.00,-1700.04,13895.22,15400.00,-1504.78 -14549.96,16300.00,-1750.04,13795.22,15500.00,-1704.78 -14449.96,16800.00,-2350.04,13695.22,15450.00,-1754.78 -14349.96,16350.00,-2000.04,13595.22,14850.00,-1254.78 -14249.96,16000.00,-1750.04,13495.22,14650.00,-1154.78 -14149.96,16000.00,-1850.04,13395.22,14100.00,-704.78 -14049.96,15650.00,-1600.04,13295.22,14150.00,-854.78 -13949.96,14400.00,-450.04,13195.22,13550.00,-354.78 -13849.96,14900.00,-1050.04,13095.22,14100.00,-1004.78 -13749.96,15300.00,-1550.04,12995.22,13900.00,-904.78 -13649.96,14400.00,-750.04,12895.22,13000.00,-104.78 -13549.96,14900.00,-1350.04,12795.22,13500.00,-704.78 -13449.96,14800.00,-1350.04,12695.22,14400.00,-1704.78 -13349.96,13450.00,-100.04,12595.22,14000.00,-1404.78 -13249.96,12750.00,499.96,12495.22,13100.00,-604.78 -13149.96,13950.00,-800.04,12395.22,12900.00,-504.78 -13049.96,14700.00,-1650.04,12295.22,12600.00,-304.78 -12949.96,15100.00,-2150.04,12195.22,12700.00,-504.78 -12849.96,15100.00,-2250.04,12095.22,12950.00,-854.78 -12749.96,15000.00,-2250.04,11995.22,13050.00,-1054.78 -12649.96,14000.00,-1350.04,11895.22,12250.00,-354.78 -12549.96,13850.00,-1300.04,11795.22,12150.00,-354.78 -12449.96,14200.00,-1750.04,11695.22,12800.00,-1104.78 -12349.96,13950.00,-1600.04,11595.22,12600.00,-1004.78 -12249.96,13050.00,-800.04,11495.22,11500.00,-4.78 -12149.96,13900.00,-1750.04,11395.22,12400.00,-1004.78 -12049.96,13950.00,-1900.04,11295.22,12250.00,-954.78 -11949.96,13200.00,-1250.04,11195.22,11600.00,-404.78 -11849.96,13500.00,-1650.04,11095.22,11750.00,-654.78 -11749.96,13750.00,-2000.04,10995.22,12000.00,-1004.78 -11649.96,13300.00,-1650.04,10895.22,11650.00,-754.78 -11549.96,11850.00,-300.04,10795.22,10350.00,445.22 -11449.96,12300.00,-850.04,10695.22,11100.00,-404.78 -11349.96,12850.00,-1500.04,10595.22,11550.00,-954.78 -11249.96,12800.00,-1550.04,10495.22,11400.00,-904.78 -11149.96,11950.00,-800.04,10395.22,10450.00,-54.78 -11049.96,12000.00,-950.04,10295.22,10750.00,-454.78 -10949.96,12250.00,-1300.04,10195.22,10850.00,-654.78 -10849.96,14650.00,-3800.04,10095.22,13050.00,-2954.78 -10749.96,11350.00,-600.04,9995.22,9950.00,45.22 -10649.96,10100.00,549.96,9895.22,8800.00,1095.22 -10549.96,11300.00,-750.04,9795.22,10350.00,-554.78 -10449.96,11700.00,-1250.04,9695.22,11050.00,-1354.78 -10349.96,10750.00,-400.04,9595.22,9100.00,495.22 -10249.96,10550.00,-300.04,9495.22,8850.00,645.22 -10149.96,11200.00,-1050.04,9395.22,9550.00,-154.78 -10049.96,11350.00,-1300.04,9295.22,9700.00,-404.78 -9949.96,10650.00,-700.04,9195.22,9050.00,145.22 -9849.96,10950.00,-1100.04,9095.22,9550.00,-454.78 -9749.96,11200.00,-1450.04,8995.22,9900.00,-904.78 -9649.96,10100.00,-450.04,8895.22,8850.00,45.22 -9549.96,10450.00,-900.04,8795.22,9350.00,-554.78 -9449.96,11000.00,-1550.04,8695.22,9400.00,-704.78 -9349.96,10900.00,-1550.04,8595.22,8950.00,-354.78 -9249.96,10250.00,-1000.04,8495.22,8450.00,45.22 -9149.96,9750.00,-600.04,8395.22,7950.00,445.22 -9049.96,9550.00,-500.04,8295.22,8050.00,245.22 -8949.96,9100.00,-150.04,8195.22,7650.00,545.22 -8849.96,9150.00,-300.04,8095.22,7650.00,445.22 -8749.96,9350.00,-600.04,7995.22,8100.00,-104.78 -8649.96,9800.00,-1150.04,7895.22,8400.00,-504.78 -8549.96,9350.00,-800.04,7795.22,7950.00,-154.78 -8449.96,9050.00,-600.04,7695.22,7900.00,-204.78 -8349.96,9800.00,-1450.04,7595.22,8250.00,-654.78 -8249.96,8750.00,-500.04,7495.22,7300.00,195.22 -8149.96,7500.00,649.96,7395.22,6750.00,645.22 -8049.96,8500.00,-450.04,7295.22,6850.00,445.22 -7949.96,8050.00,-100.04,7195.22,6600.00,595.22 -7849.96,7400.00,449.96,7095.22,6150.00,945.22 -7749.96,7450.00,299.96,6995.22,6350.00,645.22 -7649.96,7500.00,149.96,6895.22,6450.00,445.22 -7549.96,7600.00,-50.04,6795.22,6350.00,445.22 -7449.96,7850.00,-400.04,6695.22,6400.00,295.22 -7349.96,7950.00,-600.04,6595.22,6400.00,195.22 -7249.96,7750.00,-500.04,6495.22,6150.00,345.22 -7149.96,7300.00,-150.04,6395.22,5900.00,495.22 -7049.96,7400.00,-350.04,6295.22,5950.00,345.22 -6949.96,7400.00,-450.04,6195.22,6150.00,45.22 -6849.96,6850.00,-0.04,6095.22,5450.00,645.22 -6749.96,6100.00,649.96,5995.22,4600.00,1395.22 -6649.96,6700.00,-50.04,5895.22,5500.00,395.22 -6549.96,6150.00,399.96,5795.22,4700.00,1095.22 -6449.96,5800.00,649.96,5695.22,4400.00,1295.22 -6349.96,6100.00,249.96,5595.22,4600.00,995.22 -6249.96,5950.00,299.96,5495.22,4600.00,895.22 -6149.96,5700.00,449.96,5395.22,4400.00,995.22 -6049.96,5650.00,399.96,5295.22,4300.00,995.22 -5949.96,5550.00,399.96,5195.22,4200.00,995.22 -5849.96,5350.00,499.96,5095.22,4000.00,1095.22 -5749.96,5150.00,599.96,4995.22,3900.00,1095.22 -5649.96,5250.00,399.96,4895.22,4000.00,895.22 -5549.96,5150.00,399.96,4795.22,3950.00,845.22 -5449.96,4800.00,649.96,4695.22,3350.00,1345.22 -5349.96,4250.00,1099.96,4595.22,3100.00,1495.22 -5249.96,4700.00,549.96,4495.22,3600.00,895.22 -5149.96,3950.00,1199.96,4395.22,2750.00,1645.22 -5049.96,3450.00,1599.96,4295.22,2250.00,2045.22 -4949.96,4200.00,749.96,4195.22,3500.00,695.22 -4849.96,3250.00,1599.96,4095.22,2100.00,1995.22 -4749.96,2800.00,1949.96,3995.22,2450.00,1545.22 -4649.96,4350.00,299.96,3895.22,2950.00,945.22 -4549.96,2900.00,1649.96,3795.22,2250.00,1545.22 -4449.96,2850.00,1599.96,3695.22,1450.00,2245.22 -4349.96,4000.00,349.96,3595.22,3100.00,495.22 -4249.96,2650.00,1599.96,3495.22,2000.00,1495.22 -4149.96,2200.00,1949.96,3395.22,550.00,2845.22 -4049.96,3250.00,799.96,3295.22,1650.00,1645.22 -3949.96,2600.00,1349.96,3195.22,2400.00,795.22 -3849.96,1900.00,1949.96,3095.22,-250.00,3345.22 -3749.96,1100.00,2649.96,2995.22,1200.00,1795.22 -3649.96,2350.00,1299.96,2895.22,2450.00,445.22 -3549.96,700.00,2849.96,2795.22,-200.00,2995.22 -3449.96,1350.00,2099.96,2695.22,200.00,2495.22 -3349.96,1950.00,1399.96,2595.22,2800.00,-204.78 -3249.96,1250.00,1999.96,2495.22,200.00,2295.22 -3149.96,1500.00,1649.96,2395.22,-250.00,2645.22 -3049.96,650.00,2399.96,2295.22,550.00,1745.22 -2949.96,700.00,2249.96,2195.22,1500.00,695.22 -2849.96,800.00,2049.96,2095.22,250.00,1845.22 -2749.96,800.00,1949.96,1995.22,50.00,1945.22 -2649.96,-300.00,2949.96,1895.22,0.00,1895.22 -2549.96,550.00,1999.96,1795.22,0.00,1795.22 -2449.96,-350.00,2799.96,1695.22,0.00,1695.22 -2349.96,50.00,2299.96,1595.22,0.00,1595.22 -2249.96,0.00,2249.96,1495.22,0.00,1495.22 -2149.96,-500.00,2649.96,1395.22,0.00,1395.22 -2049.96,600.00,1449.96,1295.22,0.00,1295.22 -1949.96,-250.00,2199.96,1195.22,-50.00,1245.22 -1849.96,-200.00,2049.96,1095.22,50.00,1045.22 -1749.96,50.00,1699.96,995.22,0.00,995.22 -1649.96,-50.00,1699.96,895.22,0.00,895.22 -1549.96,0.00,1549.96,795.22,0.00,795.22 -1449.96,0.00,1449.96,695.22,0.00,695.22 -1349.96,0.00,1349.96,595.22,0.00,595.22 -1249.96,0.00,1249.96,495.22,0.00,495.22 -1149.96,0.00,1149.96,395.22,0.00,395.22 -1049.96,0.00,1049.96,295.22,0.00,295.22 -949.96,0.00,949.96,195.22,0.00,195.22 -849.96,0.00,849.96,95.22,0.00,95.22 -749.96,0.00,749.96,0.00,0.00,0.00 -649.96,0.00,649.96,0.00,0.00,0.00 -549.96,0.00,549.96,0.00,0.00,0.00 -449.96,0.00,449.96,0.00,0.00,0.00 -349.96,0.00,349.96,0.00,0.00,0.00 -249.96,0.00,249.96,0.00,0.00,0.00 -149.96,0.00,149.96,0.00,0.00,0.00 -49.96,0.00,49.96,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 --100.00,0.00,-100.00,-100.00,0.00,-100.00 --200.00,0.00,-200.00,-200.00,0.00,-200.00 --300.00,0.00,-300.00,-300.00,0.00,-300.00 --400.00,0.00,-400.00,-400.00,0.00,-400.00 --500.00,0.00,-500.00,-500.00,0.00,-500.00 --600.00,0.00,-600.00,-600.00,0.00,-600.00 --700.00,0.00,-700.00,-700.00,0.00,-700.00 --800.00,0.00,-800.00,-800.00,0.00,-800.00 --900.00,0.00,-900.00,-900.00,0.00,-900.00 --1000.00,0.00,-1000.00,-1000.00,0.00,-1000.00 --1100.00,0.00,-1100.00,-1100.00,0.00,-1100.00 --1200.00,0.00,-1200.00,-1200.00,0.00,-1200.00 --1300.00,0.00,-1300.00,-1300.00,0.00,-1300.00 --1400.00,0.00,-1400.00,-1400.00,0.00,-1400.00 --1500.00,0.00,-1500.00,-1500.00,0.00,-1500.00 --1600.00,0.00,-1600.00,-1600.00,0.00,-1600.00 --1700.00,0.00,-1700.00,-1700.00,0.00,-1700.00 --1800.00,0.00,-1800.00,-1800.00,0.00,-1800.00 --1900.00,0.00,-1900.00,-1900.00,0.00,-1900.00 --2000.00,0.00,-2000.00,-2000.00,0.00,-2000.00 --2100.00,0.00,-2100.00,-2100.00,0.00,-2100.00 --2200.00,0.00,-2200.00,-2200.00,0.00,-2200.00 --2300.00,0.00,-2300.00,-2300.00,0.00,-2300.00 --2400.00,0.00,-2400.00,-2400.00,0.00,-2400.00 --2500.00,-350.00,-2150.00,-2500.00,-350.00,-2150.00 --2600.00,-300.00,-2300.00,-2600.00,-550.00,-2050.00 --2700.00,350.00,-3050.00,-2700.00,800.00,-3500.00 --2800.00,-950.00,-1850.00,-2800.00,-600.00,-2200.00 --2900.00,-750.00,-2150.00,-2900.00,-1750.00,-1150.00 --3000.00,-1000.00,-2000.00,-3000.00,-850.00,-2150.00 --3100.00,-1400.00,-1700.00,-3100.00,-750.00,-2350.00 --3200.00,-1350.00,-1850.00,-3200.00,-450.00,-2750.00 --3300.00,-1350.00,-1950.00,-3300.00,-750.00,-2550.00 --3400.00,-900.00,-2500.00,-3400.00,-1250.00,-2150.00 --3500.00,-1300.00,-2200.00,-3500.00,-1300.00,-2200.00 --3600.00,-1800.00,-1800.00,-3600.00,-1300.00,-2300.00 --3700.00,-2100.00,-1600.00,-3700.00,-1550.00,-2150.00 --3800.00,-1950.00,-1850.00,-3800.00,-1450.00,-2350.00 --3900.00,-2500.00,-1400.00,-3900.00,-1900.00,-2000.00 --4000.00,-2150.00,-1850.00,-4000.00,-1700.00,-2300.00 --4100.00,-2350.00,-1750.00,-4100.00,-2000.00,-2100.00 --4200.00,-2550.00,-1650.00,-4200.00,-2300.00,-1900.00 --4300.00,-2850.00,-1450.00,-4300.00,-2200.00,-2100.00 --4400.00,-2950.00,-1450.00,-4400.00,-2350.00,-2050.00 --4500.00,-2900.00,-1600.00,-4500.00,-2650.00,-1850.00 --4600.00,-3200.00,-1400.00,-4600.00,-2900.00,-1700.00 --4700.00,-3250.00,-1450.00,-4700.00,-2800.00,-1900.00 --4800.00,-3600.00,-1200.00,-4800.00,-2750.00,-2050.00 --4900.00,-3700.00,-1200.00,-4900.00,-3050.00,-1850.00 --5000.00,-3700.00,-1300.00,-5000.00,-3250.00,-1750.00 --5100.00,-3800.00,-1300.00,-5100.00,-3400.00,-1700.00 --5200.00,-4000.00,-1200.00,-5200.00,-3650.00,-1550.00 --5300.00,-4200.00,-1100.00,-5300.00,-4000.00,-1300.00 --5400.00,-4400.00,-1000.00,-5400.00,-4100.00,-1300.00 --5500.00,-4350.00,-1150.00,-5500.00,-4050.00,-1450.00 --5600.00,-4600.00,-1000.00,-5600.00,-4200.00,-1400.00 --5700.00,-4700.00,-1000.00,-5700.00,-4450.00,-1250.00 --5800.00,-4700.00,-1100.00,-5800.00,-4350.00,-1450.00 --5900.00,-4950.00,-950.00,-5900.00,-4350.00,-1550.00 --6000.00,-5150.00,-850.00,-6000.00,-4800.00,-1200.00 --6100.00,-5350.00,-750.00,-6100.00,-4800.00,-1300.00 --6200.00,-5400.00,-800.00,-6200.00,-5100.00,-1100.00 --6300.00,-5650.00,-650.00,-6300.00,-5300.00,-1000.00 --6400.00,-5950.00,-450.00,-6400.00,-5300.00,-1100.00 --6500.00,-5950.00,-550.00,-6500.00,-5300.00,-1200.00 --6600.00,-5950.00,-650.00,-6600.00,-5500.00,-1100.00 --6700.00,-6100.00,-600.00,-6700.00,-5650.00,-1050.00 --6800.00,-6100.00,-700.00,-6800.00,-5750.00,-1050.00 --6900.00,-6150.00,-750.00,-6900.00,-5900.00,-1000.00 --7000.00,-6200.00,-800.00,-7000.00,-6100.00,-900.00 --7100.00,-6100.00,-1000.00,-7100.00,-5900.00,-1200.00 --7200.00,-6700.00,-500.00,-7200.00,-6250.00,-950.00 --7300.00,-6950.00,-350.00,-7300.00,-6500.00,-800.00 --7400.00,-7050.00,-350.00,-7400.00,-6350.00,-1050.00 --7500.00,-6950.00,-550.00,-7500.00,-6600.00,-900.00 --7600.00,-7050.00,-550.00,-7600.00,-7050.00,-550.00 --7700.00,-6950.00,-750.00,-7700.00,-7350.00,-350.00 --7800.00,-7000.00,-800.00,-7800.00,-7350.00,-450.00 --7900.00,-7300.00,-600.00,-7900.00,-7600.00,-300.00 --8000.00,-7850.00,-150.00,-8000.00,-7950.00,-50.00 --8100.00,-8100.00,0.00,-8100.00,-7850.00,-250.00 --8200.00,-8300.00,100.00,-8200.00,-7200.00,-1000.00 --8300.00,-8500.00,200.00,-8300.00,-7200.00,-1100.00 --8400.00,-8650.00,250.00,-8400.00,-7600.00,-800.00 --8500.00,-8050.00,-450.00,-8500.00,-7650.00,-850.00 --8600.00,-7900.00,-700.00,-8600.00,-8150.00,-450.00 --8700.00,-8100.00,-600.00,-8700.00,-8650.00,-50.00 --8800.00,-8100.00,-700.00,-8800.00,-8300.00,-500.00 --8900.00,-8300.00,-600.00,-8900.00,-8700.00,-200.00 --9000.00,-8600.00,-400.00,-9000.00,-8800.00,-200.00 --9100.00,-8600.00,-500.00,-9100.00,-8850.00,-250.00 --9200.00,-8900.00,-300.00,-9200.00,-8900.00,-300.00 --9300.00,-9350.00,50.00,-9300.00,-9150.00,-150.00 --9400.00,-11250.00,1850.00,-9400.00,-11100.00,1700.00 --9500.00,-9300.00,-200.00,-9500.00,-9050.00,-450.00 --9600.00,-9600.00,0.00,-9600.00,-9300.00,-300.00 --9700.00,-9750.00,50.00,-9700.00,-9250.00,-450.00 --9800.00,-9500.00,-300.00,-9800.00,-9000.00,-800.00 --9900.00,-9650.00,-250.00,-9900.00,-9450.00,-450.00 --10000.00,-10650.00,650.00,-10000.00,-10250.00,250.00 --10100.00,-10700.00,600.00,-10100.00,-10200.00,100.00 --10200.00,-10800.00,600.00,-10200.00,-10250.00,50.00 --10300.00,-10750.00,450.00,-10300.00,-10250.00,-50.00 --10400.00,-10500.00,100.00,-10400.00,-10100.00,-300.00 --10500.00,-10650.00,150.00,-10500.00,-10250.00,-250.00 --10600.00,-10650.00,50.00,-10600.00,-10550.00,-50.00 --10700.00,-10900.00,200.00,-10700.00,-10850.00,150.00 --10800.00,-11150.00,350.00,-10800.00,-11100.00,300.00 --10900.00,-11350.00,450.00,-10900.00,-10700.00,-200.00 --11000.00,-11650.00,650.00,-11000.00,-11000.00,0.00 --11100.00,-12050.00,950.00,-11100.00,-11600.00,500.00 --11200.00,-12200.00,1000.00,-11200.00,-12050.00,850.00 --11300.00,-11650.00,350.00,-11300.00,-11500.00,200.00 --11400.00,-11950.00,550.00,-11400.00,-11450.00,50.00 --11500.00,-12700.00,1200.00,-11500.00,-12250.00,750.00 --11600.00,-12650.00,1050.00,-11600.00,-12200.00,600.00 --11700.00,-12250.00,550.00,-11700.00,-11850.00,150.00 --11800.00,-12950.00,1150.00,-11800.00,-12650.00,850.00 --11900.00,-13600.00,1700.00,-11900.00,-13000.00,1100.00 --12000.00,-12900.00,900.00,-12000.00,-12250.00,250.00 --12100.00,-13250.00,1150.00,-12100.00,-12550.00,450.00 --12200.00,-13600.00,1400.00,-12200.00,-12600.00,400.00 --12300.00,-13400.00,1100.00,-12300.00,-12400.00,100.00 --12400.00,-13650.00,1250.00,-12400.00,-12900.00,500.00 --12500.00,-13600.00,1100.00,-12500.00,-13050.00,550.00 --12600.00,-13000.00,400.00,-12600.00,-12600.00,0.00 --12700.00,-13750.00,1050.00,-12700.00,-13250.00,550.00 --12800.00,-14250.00,1450.00,-12800.00,-13150.00,350.00 --12900.00,-12700.00,-200.00,-12900.00,-11350.00,-1550.00 --13000.00,-11850.00,-1150.00,-13000.00,-10700.00,-2300.00 --13100.00,-14400.00,1300.00,-13100.00,-13650.00,550.00 --13200.00,-15500.00,2300.00,-13200.00,-15100.00,1900.00 --13300.00,-13900.00,600.00,-13300.00,-13250.00,-50.00 --13400.00,-14350.00,950.00,-13400.00,-13900.00,500.00 --13500.00,-15800.00,2300.00,-13500.00,-15750.00,2250.00 --13600.00,-16000.00,2400.00,-13600.00,-15150.00,1550.00 --13700.00,-14800.00,1100.00,-13700.00,-14300.00,600.00 --13800.00,-15000.00,1200.00,-13800.00,-14750.00,950.00 --13900.00,-15500.00,1600.00,-13900.00,-15350.00,1450.00 --14000.00,-15150.00,1150.00,-14000.00,-14500.00,500.00 --14100.00,-15500.00,1400.00,-14100.00,-15150.00,1050.00 --14200.00,-15550.00,1350.00,-14200.00,-15250.00,1050.00 --14300.00,-15500.00,1200.00,-14300.00,-14800.00,500.00 --14400.00,-16250.00,1850.00,-14400.00,-15000.00,600.00 --14500.00,-16150.00,1650.00,-14500.00,-15400.00,900.00 --14600.00,-16300.00,1700.00,-14600.00,-15550.00,950.00 --14700.00,-15750.00,1050.00,-14700.00,-15150.00,450.00 --14800.00,-15150.00,350.00,-14800.00,-15100.00,300.00 --14900.00,-16950.00,2050.00,-14900.00,-17300.00,2400.00 --15000.00,-17400.00,2400.00,-15000.00,-16600.00,1600.00 --15100.00,-16700.00,1600.00,-15100.00,-15900.00,800.00 --15200.00,-16400.00,1200.00,-15200.00,-15700.00,500.00 --15300.00,-16750.00,1450.00,-15300.00,-15800.00,500.00 --15400.00,-17300.00,1900.00,-15400.00,-16650.00,1250.00 --15500.00,-17450.00,1950.00,-15500.00,-17050.00,1550.00 --15600.00,-17300.00,1700.00,-15600.00,-16550.00,950.00 --15700.00,-17350.00,1650.00,-15700.00,-16650.00,950.00 --15800.00,-17950.00,2150.00,-15800.00,-17400.00,1600.00 --15900.00,-17950.00,2050.00,-15900.00,-17600.00,1700.00 --16000.00,-18250.00,2250.00,-16000.00,-17900.00,1900.00 --16100.00,-18350.00,2250.00,-16100.00,-17800.00,1700.00 --16200.00,-18350.00,2150.00,-16200.00,-17150.00,950.00 --16300.00,-18250.00,1950.00,-16300.00,-17250.00,950.00 --16400.00,-18400.00,2000.00,-16400.00,-17800.00,1400.00 --16500.00,-18600.00,2100.00,-16500.00,-18200.00,1700.00 --16600.00,-18850.00,2250.00,-16600.00,-18400.00,1800.00 --16700.00,-18900.00,2200.00,-16700.00,-18200.00,1500.00 --16800.00,-21850.00,5050.00,-16800.00,-21100.00,4300.00 --16900.00,-18000.00,1100.00,-16900.00,-17450.00,550.00 --17000.00,-18000.00,1000.00,-17000.00,-17750.00,750.00 --17100.00,-19650.00,2550.00,-17035.03,-18700.00,1664.97 --17200.00,-19200.00,2000.00,-16935.03,-18900.00,1964.97 --17300.00,-18950.00,1650.00,-16835.03,-18350.00,1514.97 --17400.00,-19200.00,1800.00,-16735.03,-18400.00,1664.97 --17448.25,-19250.00,1801.75,-16635.03,-18050.00,1414.97 --17348.25,-19750.00,2401.75,-16535.03,-18700.00,2164.97 --17248.25,-20500.00,3251.75,-16435.03,-18850.00,2414.97 --17148.25,-19500.00,2351.75,-16335.03,-17750.00,1414.97 --17048.25,-19400.00,2351.75,-16235.03,-17500.00,1264.97 --16948.25,-19550.00,2601.75,-16135.03,-17600.00,1464.97 --16848.25,-19450.00,2601.75,-16035.03,-17900.00,1864.97 --16748.25,-19250.00,2501.75,-15935.03,-18100.00,2164.97 --16648.25,-19300.00,2651.75,-15835.03,-18100.00,2264.97 --16548.25,-18750.00,2201.75,-15735.03,-17200.00,1464.97 --16448.25,-19000.00,2551.75,-15635.03,-17150.00,1514.97 --16348.25,-18700.00,2351.75,-15535.03,-17350.00,1814.97 --16248.25,-18800.00,2551.75,-15435.03,-17300.00,1864.97 --16148.25,-18750.00,2601.75,-15335.03,-17400.00,2064.97 --16048.25,-18500.00,2451.75,-15235.03,-17400.00,2164.97 --15948.25,-18500.00,2551.75,-15135.03,-17100.00,1964.97 --15848.25,-17850.00,2001.75,-15035.03,-16900.00,1864.97 --15748.25,-17900.00,2151.75,-14935.03,-17000.00,2064.97 --15648.25,-18100.00,2451.75,-14835.03,-17100.00,2264.97 --15548.25,-17800.00,2251.75,-14735.03,-16950.00,2214.97 --15448.25,-17800.00,2351.75,-14635.03,-16600.00,1964.97 --15348.25,-17450.00,2101.75,-14535.03,-16050.00,1514.97 --15248.25,-17350.00,2101.75,-14435.03,-16000.00,1564.97 --15148.25,-17250.00,2101.75,-14335.03,-15900.00,1564.97 --15048.25,-17150.00,2101.75,-14235.03,-16100.00,1864.97 --14948.25,-16700.00,1751.75,-14135.03,-15900.00,1764.97 --14848.25,-16600.00,1751.75,-14035.03,-15450.00,1414.97 --14748.25,-16950.00,2201.75,-13935.03,-15400.00,1464.97 --14648.25,-16600.00,1951.75,-13835.03,-14850.00,1014.97 --14548.25,-16500.00,1951.75,-13735.03,-14850.00,1114.97 --14448.25,-16600.00,2151.75,-13635.03,-15350.00,1714.97 --14348.25,-16200.00,1851.75,-13535.03,-15600.00,2064.97 --14248.25,-15600.00,1351.75,-13435.03,-14850.00,1414.97 --14148.25,-16200.00,2051.75,-13335.03,-14700.00,1364.97 --14048.25,-15700.00,1651.75,-13235.03,-14250.00,1014.97 --13948.25,-15350.00,1401.75,-13135.03,-13700.00,564.97 --13848.25,-15650.00,1801.75,-13035.03,-14200.00,1164.97 --13748.25,-16100.00,2351.75,-12935.03,-14800.00,1864.97 --13648.25,-14600.00,951.75,-12835.03,-13200.00,364.97 --13548.25,-14300.00,751.75,-12735.03,-13100.00,364.97 --13448.25,-15850.00,2401.75,-12635.03,-14300.00,1664.97 --13348.25,-15250.00,1901.75,-12535.03,-12550.00,14.97 --13248.25,-14400.00,1151.75,-12435.03,-13200.00,764.97 --13148.25,-14550.00,1401.75,-12335.03,-12850.00,514.97 --13048.25,-14200.00,1151.75,-12235.03,-12950.00,714.97 --12948.25,-14400.00,1451.75,-12135.03,-12950.00,814.97 --12848.25,-14400.00,1551.75,-12035.03,-12850.00,814.97 --12748.25,-14350.00,1601.75,-11935.03,-12750.00,814.97 --12648.25,-13750.00,1101.75,-11835.03,-12100.00,264.97 --12548.25,-13950.00,1401.75,-11735.03,-12200.00,464.97 --12448.25,-14050.00,1601.75,-11635.03,-12350.00,714.97 --12348.25,-13750.00,1401.75,-11535.03,-12100.00,564.97 --12248.25,-13350.00,1101.75,-11435.03,-11550.00,114.97 --12148.25,-13650.00,1501.75,-11335.03,-12200.00,864.97 --12048.25,-13950.00,1901.75,-11235.03,-12300.00,1064.97 --11948.25,-12800.00,851.75,-11135.03,-11200.00,64.97 --11848.25,-12450.00,601.75,-11035.03,-10900.00,-135.03 --11748.25,-13100.00,1351.75,-10935.03,-11600.00,664.97 --11648.25,-12750.00,1101.75,-10835.03,-11950.00,1114.97 --11548.25,-12600.00,1051.75,-10735.03,-11650.00,914.97 --11448.25,-12450.00,1001.75,-10635.03,-11600.00,964.97 --11348.25,-12350.00,1001.75,-10535.03,-11250.00,714.97 --11248.25,-12100.00,851.75,-10435.03,-11150.00,714.97 --11148.25,-12050.00,901.75,-10335.03,-11550.00,1214.97 --11048.25,-12050.00,1001.75,-10235.03,-10850.00,614.97 --10948.25,-11750.00,801.75,-10135.03,-10150.00,14.97 --10848.25,-11650.00,801.75,-10035.03,-9950.00,-85.03 --10748.25,-13700.00,2951.75,-9935.03,-11950.00,2014.97 --10648.25,-10550.00,-98.25,-9835.03,-9850.00,14.97 --10548.25,-9500.00,-1048.25,-9735.03,-9750.00,14.97 --10448.25,-11650.00,1201.75,-9635.03,-10000.00,364.97 --10348.25,-11550.00,1201.75,-9535.03,-10350.00,814.97 --10248.25,-11100.00,851.75,-9435.03,-9350.00,-85.03 --10148.25,-10950.00,801.75,-9335.03,-9500.00,164.97 --10048.25,-10900.00,851.75,-9235.03,-9350.00,114.97 --9948.25,-10250.00,301.75,-9135.03,-8750.00,-385.03 --9848.25,-9850.00,1.75,-9035.03,-8750.00,-285.03 --9748.25,-10300.00,551.75,-8935.03,-9100.00,164.97 --9648.25,-10450.00,801.75,-8835.03,-8850.00,14.97 --9548.25,-10350.00,801.75,-8735.03,-8850.00,114.97 --9448.25,-10550.00,1101.75,-8635.03,-8900.00,264.97 --9348.25,-10150.00,801.75,-8535.03,-8600.00,64.97 --9248.25,-9750.00,501.75,-8435.03,-8500.00,64.97 --9148.25,-10250.00,1101.75,-8335.03,-9150.00,814.97 --9048.25,-9900.00,851.75,-8235.03,-8650.00,414.97 --8948.25,-9400.00,451.75,-8135.03,-8300.00,164.97 --8848.25,-9300.00,451.75,-8035.03,-8100.00,64.97 --8748.25,-9250.00,501.75,-7935.03,-7650.00,-285.03 --8648.25,-9250.00,601.75,-7835.03,-7500.00,-335.03 --8548.25,-9400.00,851.75,-7735.03,-7500.00,-235.03 --8448.25,-9050.00,601.75,-7635.03,-7400.00,-235.03 --8348.25,-8800.00,451.75,-7535.03,-7550.00,14.97 --8248.25,-8600.00,351.75,-7435.03,-7400.00,-35.03 --8148.25,-8050.00,-98.25,-7335.03,-6900.00,-435.03 --8048.25,-8250.00,201.75,-7235.03,-7000.00,-235.03 --7948.25,-8000.00,51.75,-7135.03,-6800.00,-335.03 --7848.25,-8000.00,151.75,-7035.03,-6650.00,-385.03 --7748.25,-7800.00,51.75,-6935.03,-6750.00,-185.03 --7648.25,-7650.00,1.75,-6835.03,-6400.00,-435.03 --7548.25,-7450.00,-98.25,-6735.03,-6200.00,-535.03 --7448.25,-7900.00,451.75,-6635.03,-6150.00,-485.03 --7348.25,-7150.00,-198.25,-6535.03,-5450.00,-1085.03 --7248.25,-6900.00,-348.25,-6435.03,-5400.00,-1035.03 --7148.25,-6950.00,-198.25,-6335.03,-5200.00,-1135.03 --7048.25,-6900.00,-148.25,-6235.03,-5250.00,-985.03 --6948.25,-6850.00,-98.25,-6135.03,-5250.00,-885.03 --6848.25,-6650.00,-198.25,-6035.03,-5050.00,-985.03 --6748.25,-6450.00,-298.25,-5935.03,-5000.00,-935.03 --6648.25,-6500.00,-148.25,-5835.03,-5250.00,-585.03 --6548.25,-6300.00,-248.25,-5735.03,-5100.00,-635.03 --6448.25,-6200.00,-248.25,-5635.03,-5050.00,-585.03 --6348.25,-6000.00,-348.25,-5535.03,-4950.00,-585.03 --6248.25,-5950.00,-298.25,-5435.03,-4850.00,-585.03 --6148.25,-6050.00,-98.25,-5335.03,-4700.00,-635.03 --6048.25,-5400.00,-648.25,-5235.03,-4450.00,-785.03 --5948.25,-5100.00,-848.25,-5135.03,-4300.00,-835.03 --5848.25,-5250.00,-598.25,-5035.03,-4300.00,-735.03 --5748.25,-5300.00,-448.25,-4935.03,-4100.00,-835.03 --5648.25,-5200.00,-448.25,-4835.03,-3900.00,-935.03 --5548.25,-5250.00,-298.25,-4735.03,-3900.00,-835.03 --5448.25,-4700.00,-748.25,-4635.03,-3400.00,-1235.03 --5348.25,-4250.00,-1098.25,-4535.03,-3200.00,-1335.03 --5248.25,-4250.00,-998.25,-4435.03,-3300.00,-1135.03 --5148.25,-3900.00,-1248.25,-4335.03,-2800.00,-1535.03 --5048.25,-3900.00,-1148.25,-4235.03,-2800.00,-1435.03 --4948.25,-4050.00,-898.25,-4135.03,-2650.00,-1485.03 --4848.25,-3950.00,-898.25,-4035.03,-2300.00,-1735.03 --4748.25,-3700.00,-1048.25,-3935.03,-2500.00,-1435.03 --4648.25,-3700.00,-948.25,-3835.03,-2600.00,-1235.03 --4548.25,-3000.00,-1548.25,-3735.03,-1750.00,-1985.03 --4448.25,-2450.00,-1998.25,-3635.03,-2100.00,-1535.03 --4348.25,-3000.00,-1348.25,-3535.03,-1700.00,-1835.03 --4248.25,-2800.00,-1448.25,-3435.03,-1700.00,-1735.03 --4148.25,-2750.00,-1398.25,-3335.03,-1400.00,-1935.03 --4048.25,-3000.00,-1048.25,-3235.03,-1800.00,-1435.03 --3948.25,-2150.00,-1798.25,-3135.03,-1450.00,-1685.03 --3848.25,-1850.00,-1998.25,-3035.03,-1200.00,-1835.03 --3748.25,-2400.00,-1348.25,-2935.03,-250.00,-2685.03 --3648.25,-2000.00,-1648.25,-2835.03,-200.00,-2635.03 --3548.25,-1750.00,-1798.25,-2735.03,-1800.00,-935.03 --3448.25,-2050.00,-1398.25,-2635.03,-1200.00,-1435.03 --3348.25,-1000.00,-2348.25,-2535.03,50.00,-2585.03 --3248.25,-700.00,-2548.25,-2435.03,-350.00,-2085.03 --3148.25,-2300.00,-848.25,-2335.03,-1250.00,-1085.03 --3048.25,-1150.00,-1898.25,-2235.03,-250.00,-1985.03 --2948.25,-450.00,-2498.25,-2135.03,-50.00,-2085.03 --2848.25,-950.00,-1898.25,-2035.03,-300.00,-1735.03 --2748.25,-700.00,-2048.25,-1935.03,-250.00,-1685.03 --2648.25,250.00,-2898.25,-1835.03,-200.00,-1635.03 --2548.25,-650.00,-1898.25,-1735.03,-350.00,-1385.03 --2448.25,50.00,-2498.25,-1635.03,-150.00,-1485.03 --2348.25,350.00,-2698.25,-1535.03,100.00,-1635.03 --2248.25,-1050.00,-1198.25,-1435.03,0.00,-1435.03 --2148.25,-150.00,-1998.25,-1335.03,50.00,-1385.03 --2048.25,50.00,-2098.25,-1235.03,-50.00,-1185.03 --1948.25,0.00,-1948.25,-1135.03,0.00,-1135.03 --1848.25,150.00,-1998.25,-1035.03,0.00,-1035.03 --1748.25,550.00,-2298.25,-935.03,0.00,-935.03 --1648.25,950.00,-2598.25,-835.03,0.00,-835.03 --1548.25,-200.00,-1348.25,-735.03,0.00,-735.03 --1448.25,-50.00,-1398.25,-635.03,0.00,-635.03 --1348.25,0.00,-1348.25,-535.03,0.00,-535.03 --1248.25,0.00,-1248.25,-435.03,0.00,-435.03 --1148.25,0.00,-1148.25,-335.03,0.00,-335.03 --1048.25,0.00,-1048.25,-235.03,0.00,-235.03 --948.25,0.00,-948.25,-135.03,0.00,-135.03 --848.25,0.00,-848.25,-35.03,0.00,-35.03 --748.25,0.00,-748.25,0.00,0.00,0.00 --648.25,0.00,-648.25,0.00,0.00,0.00 --548.25,0.00,-548.25,0.00,0.00,0.00 --448.25,0.00,-448.25,0.00,0.00,0.00 --348.25,0.00,-348.25,0.00,0.00,0.00 --248.25,0.00,-248.25,0.00,0.00,0.00 --148.25,0.00,-148.25,0.00,0.00,0.00 --48.25,0.00,-48.25,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 \ No newline at end of file +LeftSetpoint,LeftVelocity,LeftError,RightSetpoint,RightVelocity,RightError,Heading +-15300.00,-18050.00,2750.00,-15300.00,-17550.00,2250.00,62.64 +-15400.00,-17050.00,1650.00,-15400.00,-16650.00,1250.00,66.25 +-15500.00,-17150.00,1650.00,-15500.00,-16800.00,1300.00,68.92 +-15600.00,-17750.00,2150.00,-15600.00,-17100.00,1500.00,68.92 +-15700.00,-18900.00,3200.00,-15700.00,-17900.00,2200.00,72.08 +-15800.00,-18150.00,2350.00,-15800.00,-17400.00,1600.00,75.90 +-15900.00,-17600.00,1700.00,-15900.00,-16900.00,1000.00,75.90 +-16000.00,-17500.00,1500.00,-16000.00,-16950.00,950.00,78.43 +-16100.00,-18250.00,2150.00,-16100.00,-17750.00,1650.00,80.81 +-16200.00,-18650.00,2450.00,-16200.00,-18150.00,1950.00,83.73 +-16300.00,-22150.00,5850.00,-16300.00,-21350.00,5050.00,86.48 +-16400.00,-18200.00,1800.00,-16400.00,-17800.00,1400.00,86.48 +-16500.00,-18000.00,1500.00,-16500.00,-17900.00,1400.00,88.49 +-16600.00,-18550.00,1950.00,-16600.00,-18300.00,1700.00,90.02 +-16700.00,-19200.00,2500.00,-16700.00,-18600.00,1900.00,90.02 +-16800.00,-19150.00,2350.00,-16800.00,-18100.00,1300.00,92.08 +-16900.00,-19050.00,2150.00,-16900.00,-18450.00,1550.00,94.08 +-17000.00,-18700.00,1700.00,-17000.00,-18300.00,1300.00,95.82 +-17100.00,-19000.00,1900.00,-17100.00,-18300.00,1200.00,95.82 +-17200.00,-19500.00,2300.00,-17200.00,-18750.00,1550.00,96.45 +-17300.00,-20050.00,2750.00,-17207.97,-19100.00,1892.03,97.55 +-17400.00,-19800.00,2400.00,-17107.97,-18800.00,1692.03,97.94 +-17500.00,-20500.00,3000.00,-17007.97,-19900.00,2892.03,97.94 +-17553.09,-20050.00,2496.91,-16907.97,-19300.00,2392.03,98.88 +-17453.09,-19550.00,2096.91,-16807.97,-19000.00,2192.03,99.44 +-17353.09,-20200.00,2846.91,-16707.97,-19150.00,2442.03,99.44 +-17253.09,-20350.00,3096.91,-16607.97,-18900.00,2292.03,100.38 +-17153.09,-19950.00,2796.91,-16507.97,-18400.00,1892.03,100.92 +-17053.09,-21050.00,3996.91,-16407.97,-19050.00,2642.03,100.69 +-16953.09,-19800.00,2846.91,-16307.97,-18600.00,2292.03,100.69 +-16853.09,-19650.00,2796.91,-16207.97,-18250.00,2042.03,101.10 +-16753.09,-19850.00,3096.91,-16107.97,-17900.00,1792.03,101.09 +-16653.09,-19400.00,2746.91,-16007.97,-17800.00,1792.03,101.43 +-16553.09,-19050.00,2496.91,-15907.97,-17250.00,1342.03,101.43 +-16453.09,-18950.00,2496.91,-15807.97,-17500.00,1692.03,101.32 +-16353.09,-19150.00,2796.91,-15707.97,-17850.00,2142.03,100.92 +-16253.09,-19050.00,2796.91,-15607.97,-17650.00,2042.03,100.92 +-16153.09,-18850.00,2696.91,-15507.97,-17500.00,1992.03,101.07 +-16053.09,-18450.00,2396.91,-15407.97,-17300.00,1892.03,101.28 +-15953.09,-18150.00,2196.91,-15307.97,-16900.00,1592.03,100.11 +-15853.09,-18100.00,2246.91,-15207.97,-17200.00,1992.03,100.11 +-15753.09,-18350.00,2596.91,-15107.97,-17450.00,2342.03,99.67 +-15653.09,-17900.00,2246.91,-15007.97,-16950.00,1942.03,99.24 +-15553.09,-18050.00,2496.91,-14907.97,-17050.00,2142.03,98.27 +-15453.09,-18000.00,2546.91,-14807.97,-17100.00,2292.03,98.27 +-15353.09,-17900.00,2546.91,-14707.97,-16850.00,2142.03,97.29 +-15253.09,-17650.00,2396.91,-14607.97,-16700.00,2092.03,95.89 +-15153.09,-17350.00,2196.91,-14507.97,-16300.00,1792.03,95.89 +-15053.09,-17150.00,2096.91,-14407.97,-16000.00,1592.03,94.66 +-14953.09,-17100.00,2146.91,-14307.97,-15900.00,1592.03,93.90 +-14853.09,-16850.00,1996.91,-14207.97,-15800.00,1592.03,92.57 +-14753.09,-16650.00,1896.91,-14107.97,-15500.00,1392.03,92.57 +-14653.09,-16650.00,1996.91,-14007.97,-15100.00,1092.03,91.45 +-14553.09,-16850.00,2296.91,-13907.97,-15200.00,1292.03,89.73 +-14453.09,-16650.00,2196.91,-13807.97,-15050.00,1242.03,89.73 +-14353.09,-16300.00,1946.91,-13707.97,-14650.00,942.03,87.93 +-14253.09,-16000.00,1746.91,-13607.97,-14500.00,892.03,86.35 +-14153.09,-16350.00,2196.91,-13507.97,-15250.00,1742.03,84.98 +-14053.09,-15350.00,1296.91,-13407.97,-14450.00,1042.03,84.98 +-13953.09,-14850.00,896.91,-13307.97,-14100.00,792.03,83.67 +-13853.09,-16250.00,2396.91,-13207.97,-15300.00,2092.03,82.27 +-13753.09,-15500.00,1746.91,-13107.97,-13800.00,692.03,80.71 +-13653.09,-15050.00,1396.91,-13007.97,-13650.00,642.03,80.71 +-13553.09,-15400.00,1846.91,-12907.97,-14250.00,1342.03,79.48 +-13453.09,-14750.00,1296.91,-12807.97,-13850.00,1042.03,78.68 +-13353.09,-14350.00,996.91,-12707.97,-13250.00,542.03,78.68 +-13253.09,-14900.00,1646.91,-12607.97,-13800.00,1192.03,77.04 +-13153.09,-14550.00,1396.91,-12507.97,-13350.00,842.03,76.07 +-13053.09,-14200.00,1146.91,-12407.97,-12800.00,392.03,74.69 +-12953.09,-14850.00,1896.91,-12307.97,-13050.00,742.03,74.69 +-12853.09,-14450.00,1596.91,-12207.97,-12800.00,592.03,73.98 +-12753.09,-13750.00,996.91,-12107.97,-12600.00,492.03,73.28 +-12653.09,-13600.00,946.91,-12007.97,-12600.00,592.03,72.72 +-12553.09,-13400.00,846.91,-11907.97,-12700.00,792.03,72.72 +-12453.09,-13750.00,1296.91,-11807.97,-13200.00,1392.03,71.66 +-12353.09,-13500.00,1146.91,-11707.97,-12700.00,992.03,71.77 +-12253.09,-13400.00,1146.91,-11607.97,-12100.00,492.03,71.77 +-12153.09,-13300.00,1146.91,-11507.97,-12100.00,592.03,71.05 +-12053.09,-13100.00,1046.91,-11407.97,-12200.00,792.03,70.63 +-11953.09,-15000.00,3046.91,-11307.97,-14000.00,2692.03,70.52 +-11853.09,-12600.00,746.91,-11207.97,-11900.00,692.03,70.52 +-11753.09,-12050.00,296.91,-11107.97,-11250.00,142.03,70.38 +-11653.09,-12250.00,596.91,-11007.97,-11250.00,242.03,70.38 +-11553.09,-12550.00,996.91,-10907.97,-11550.00,642.03,70.49 +-11453.09,-12750.00,1296.91,-10807.97,-11650.00,842.03,70.49 +-11353.09,-12700.00,1346.91,-10707.97,-11200.00,492.03,70.85 +-11253.09,-12450.00,1196.91,-10607.97,-11150.00,542.03,70.58 +-11153.09,-12000.00,846.91,-10507.97,-11100.00,592.03,70.68 +-11053.09,-11850.00,796.91,-10407.97,-11350.00,942.03,70.68 +-10953.09,-11300.00,346.91,-10307.97,-10800.00,492.03,70.82 +-10853.09,-11000.00,146.91,-10207.97,-10650.00,442.03,70.76 +-10753.09,-11100.00,346.91,-10107.97,-10850.00,742.03,70.76 +-10653.09,-11400.00,746.91,-10007.97,-10400.00,392.03,71.20 +-10553.09,-11500.00,946.91,-9907.97,-10100.00,192.03,71.18 +-10453.09,-11350.00,896.91,-9807.97,-9750.00,-57.97,71.47 +-10353.09,-11000.00,646.91,-9707.97,-9500.00,-207.97,71.47 +-10253.09,-10950.00,696.91,-9607.97,-9500.00,-107.97,70.98 +-10153.09,-11150.00,996.91,-9507.97,-9850.00,342.03,70.91 +-10053.09,-10900.00,846.91,-9407.97,-9950.00,542.03,70.92 +-9953.09,-10600.00,646.91,-9307.97,-9850.00,542.03,70.92 +-9853.09,-10000.00,146.91,-9207.97,-9400.00,192.03,71.04 +-9753.09,-10050.00,296.91,-9107.97,-9050.00,-57.97,70.73 +-9653.09,-10600.00,946.91,-9007.97,-9650.00,642.03,70.73 +-9553.09,-9850.00,296.91,-8907.97,-9000.00,92.03,70.83 +-9453.09,-9450.00,-3.09,-8807.97,-8750.00,-57.97,70.24 +-9353.09,-9600.00,246.91,-8707.97,-9250.00,542.03,70.20 +-9253.09,-9100.00,-153.09,-8607.97,-8400.00,-207.97,70.20 +-9153.09,-9250.00,96.91,-8507.97,-8300.00,-207.97,70.34 +-9053.09,-9350.00,296.91,-8407.97,-8600.00,192.03,69.85 +-8953.09,-9000.00,46.91,-8307.97,-8050.00,-257.97,70.05 +-8853.09,-9000.00,146.91,-8207.97,-8350.00,142.03,70.05 +-8753.09,-9300.00,546.91,-8107.97,-8500.00,392.03,69.22 +-8653.09,-9150.00,496.91,-8007.97,-8450.00,442.03,69.22 +-8553.09,-9200.00,646.91,-7907.97,-8500.00,592.03,69.22 +-8453.09,-8900.00,446.91,-7807.97,-8150.00,342.03,68.54 +-8353.09,-8900.00,546.91,-7707.97,-7900.00,192.03,68.26 +-8253.09,-8650.00,396.91,-7607.97,-7350.00,-257.97,67.64 +-8153.09,-8400.00,246.91,-7507.97,-7000.00,-507.97,67.64 +-8053.09,-8450.00,396.91,-7407.97,-7450.00,42.03,67.08 +-7953.09,-8150.00,196.91,-7307.97,-7300.00,-7.97,67.32 +-7853.09,-7900.00,46.91,-7207.97,-7200.00,-7.97,67.32 +-7753.09,-7850.00,96.91,-7107.97,-7200.00,92.03,66.74 +-7653.09,-7700.00,46.91,-7007.97,-6900.00,-107.97,66.08 +-7553.09,-8050.00,496.91,-6907.97,-7100.00,192.03,65.57 +-7453.09,-8050.00,596.91,-6807.97,-7050.00,242.03,65.57 +-7353.09,-7400.00,46.91,-6707.97,-6450.00,-257.97,65.20 +-7253.09,-7450.00,196.91,-6607.97,-6800.00,192.03,64.82 +-7153.09,-7350.00,196.91,-6507.97,-6800.00,292.03,64.15 +-7053.09,-6550.00,-503.09,-6407.97,-5750.00,-657.97,64.15 +-6953.09,-6750.00,-203.09,-6307.97,-5350.00,-957.97,63.84 +-6853.09,-6950.00,96.91,-6207.97,-5900.00,-307.97,63.56 +-6753.09,-6800.00,46.91,-6107.97,-5900.00,-207.97,63.56 +-6653.09,-6250.00,-403.09,-6007.97,-5300.00,-707.97,63.06 +-6553.09,-6200.00,-353.09,-5907.97,-5400.00,-507.97,62.43 +-6453.09,-6000.00,-453.09,-5807.97,-5300.00,-507.97,62.12 +-6353.09,-5900.00,-453.09,-5707.97,-4850.00,-857.97,62.12 +-6253.09,-5400.00,-853.09,-5607.97,-4650.00,-957.97,61.76 +-6153.09,-5800.00,-353.09,-5507.97,-5000.00,-507.97,61.20 +-6053.09,-6000.00,-53.09,-5407.97,-5000.00,-407.97,61.20 +-5953.09,-5600.00,-353.09,-5307.97,-4500.00,-807.97,60.76 +-5853.09,-4900.00,-953.09,-5207.97,-4000.00,-1207.97,60.56 +-5753.09,-5200.00,-553.09,-5107.97,-4900.00,-207.97,60.16 +-5653.09,-5150.00,-503.09,-5007.97,-4500.00,-507.97,60.16 +-5553.09,-4800.00,-753.09,-4907.97,-3500.00,-1407.97,60.09 +-5453.09,-4950.00,-503.09,-4807.97,-3250.00,-1557.97,59.71 +-5353.09,-4950.00,-403.09,-4707.97,-4950.00,242.03,58.79 +-5253.09,-4300.00,-953.09,-4607.97,-3800.00,-807.97,58.79 +-5153.09,-3450.00,-1703.09,-4507.97,-2900.00,-1607.97,58.55 +-5053.09,-5350.00,296.91,-4407.97,-3400.00,-1007.97,58.44 +-4953.09,-4450.00,-503.09,-4307.97,-4500.00,192.03,58.03 +-4853.09,-3200.00,-1653.09,-4207.97,-2200.00,-2007.97,58.03 +-4753.09,-3100.00,-1653.09,-4107.97,-1800.00,-2307.97,57.82 +-4653.09,-3500.00,-1153.09,-4007.97,-3350.00,-657.97,57.31 +-4553.09,-3350.00,-1203.09,-3907.97,-2700.00,-1207.97,57.31 +-4453.09,-3100.00,-1353.09,-3807.97,-1350.00,-2457.97,57.29 +-4353.09,-3100.00,-1253.09,-3707.97,-1850.00,-1857.97,56.42 +-4253.09,-3300.00,-953.09,-3607.97,-2500.00,-1107.97,55.85 +-4153.09,-2600.00,-1553.09,-3507.97,-1900.00,-1607.97,55.85 +-4053.09,-1700.00,-2353.09,-3407.97,-1350.00,-2057.97,55.76 +-3953.09,-2150.00,-1803.09,-3307.97,0.00,-3307.97,55.79 +-3853.09,-2450.00,-1403.09,-3207.97,-1900.00,-1307.97,55.52 +-3753.09,-2200.00,-1553.09,-3107.97,-1300.00,-1807.97,55.52 +-3653.09,-1350.00,-2303.09,-3007.97,200.00,-3207.97,55.22 +-3553.09,-1450.00,-2103.09,-2907.97,-650.00,-2257.97,54.64 +-3453.09,-1950.00,-1503.09,-2807.97,-1850.00,-957.97,54.64 +-3353.09,-1350.00,-2003.09,-2707.97,-1300.00,-1407.97,54.95 +-3253.09,150.00,-3403.09,-2607.97,700.00,-3307.97,54.87 +-3153.09,-1500.00,-1653.09,-2507.97,-500.00,-2007.97,54.59 +-3053.09,-1600.00,-1453.09,-2407.97,-1150.00,-1257.97,54.59 +-2953.09,-50.00,-2903.09,-2307.97,0.00,-2307.97,53.92 +-2853.09,-250.00,-2603.09,-2207.97,0.00,-2207.97,53.36 +-2753.09,-1700.00,-1053.09,-2107.97,0.00,-2107.97,53.36 +-2653.09,-1550.00,-1103.09,-2007.97,0.00,-2007.97,53.58 +-2553.09,550.00,-3103.09,-1907.97,150.00,-2057.97,53.64 +-2453.09,-350.00,-2103.09,-1807.97,350.00,-2157.97,53.29 +-2353.09,-550.00,-1803.09,-1707.97,950.00,-2657.97,53.29 +-2253.09,1150.00,-3403.09,-1607.97,450.00,-2057.97,53.87 +-2153.09,-650.00,-1503.09,-1507.97,-250.00,-1257.97,53.53 +-2053.09,-300.00,-1753.09,-1407.97,0.00,-1407.97,53.53 +-1953.09,900.00,-2853.09,-1307.97,0.00,-1307.97,53.89 +-1853.09,-500.00,-1353.09,-1207.97,0.00,-1207.97,53.76 +-1753.09,150.00,-1903.09,-1107.97,0.00,-1107.97,53.76 +-1653.09,700.00,-2353.09,-1007.97,0.00,-1007.97,53.87 +-1553.09,-350.00,-1203.09,-907.97,0.00,-907.97,53.73 +-1453.09,0.00,-1453.09,-807.97,0.00,-807.97,53.53 +-1353.09,0.00,-1353.09,-707.97,0.00,-707.97,53.53 +-1253.09,0.00,-1253.09,-607.97,0.00,-607.97,53.93 +-1153.09,0.00,-1153.09,-507.97,0.00,-507.97,53.82 +-1053.09,0.00,-1053.09,-407.97,0.00,-407.97,53.82 +-953.09,0.00,-953.09,-307.97,0.00,-307.97,54.02 +-853.09,0.00,-853.09,-207.97,0.00,-207.97,53.34 +-753.09,0.00,-753.09,-107.97,0.00,-107.97,53.34 +-653.09,0.00,-653.09,-7.97,0.00,-7.97,53.53 +-553.09,0.00,-553.09,0.00,0.00,0.00,53.55 +-453.09,0.00,-453.09,0.00,0.00,0.00,53.67 +-353.09,0.00,-353.09,0.00,0.00,0.00,53.67 +-253.09,0.00,-253.09,0.00,0.00,0.00,53.67 +-153.09,0.00,-153.09,0.00,0.00,0.00,53.67 +-53.09,0.00,-53.09,0.00,0.00,0.00,53.67 +0.00,0.00,0.00,0.00,0.00,0.00,53.53 +0.00,0.00,0.00,0.00,0.00,0.00,53.77 +0.00,0.00,0.00,0.00,0.00,0.00,53.77 +0.00,0.00,0.00,0.00,0.00,0.00,53.63 +0.00,0.00,0.00,0.00,0.00,0.00,53.34 +0.00,0.00,0.00,0.00,0.00,0.00,53.34 +0.00,0.00,0.00,0.00,0.00,0.00,53.45 +0.00,0.00,0.00,0.00,0.00,0.00,53.34 +0.00,0.00,0.00,0.00,0.00,0.00,53.43 +0.00,0.00,0.00,0.00,0.00,0.00,53.43 +0.00,0.00,0.00,0.00,0.00,0.00,53.79 +0.00,0.00,0.00,0.00,0.00,0.00,53.61 +0.00,0.00,0.00,0.00,0.00,0.00,53.61 +0.00,0.00,0.00,0.00,0.00,0.00,53.50 +0.00,0.00,0.00,0.00,0.00,0.00,53.41 +0.00,0.00,0.00,0.00,0.00,0.00,53.41 +0.00,0.00,0.00,0.00,0.00,0.00,53.69 +0.00,0.00,0.00,0.00,0.00,0.00,53.58 +0.00,0.00,0.00,0.00,0.00,0.00,53.58 +0.00,0.00,0.00,0.00,0.00,0.00,53.72 +0.00,0.00,0.00,0.00,0.00,0.00,53.89 +0.00,0.00,0.00,0.00,0.00,0.00,53.70 +0.00,0.00,0.00,0.00,0.00,0.00,53.70 +0.00,0.00,0.00,0.00,0.00,0.00,53.48 +0.00,0.00,0.00,0.00,0.00,0.00,53.73 +0.00,0.00,0.00,0.00,0.00,0.00,53.73 +0.00,0.00,0.00,0.00,0.00,0.00,53.19 +0.00,0.00,0.00,0.00,0.00,0.00,53.55 +0.00,0.00,0.00,0.00,0.00,0.00,53.55 +0.00,0.00,0.00,0.00,0.00,0.00,53.52 +0.00,0.00,0.00,0.00,0.00,0.00,53.62 +0.00,0.00,0.00,0.00,0.00,0.00,53.62 +0.00,0.00,0.00,0.00,0.00,0.00,53.67 +0.00,0.00,0.00,0.00,0.00,0.00,53.54 +0.00,0.00,0.00,0.00,0.00,0.00,53.67 +0.00,0.00,0.00,0.00,0.00,0.00,53.67 +0.00,0.00,0.00,0.00,0.00,0.00,53.57 +0.00,0.00,0.00,0.00,0.00,0.00,53.62 +0.00,0.00,0.00,0.00,0.00,0.00,53.62 +0.00,0.00,0.00,0.00,0.00,0.00,53.47 +0.00,0.00,0.00,0.00,0.00,0.00,54.00 +0.00,0.00,0.00,0.00,0.00,0.00,54.00 +0.00,0.00,0.00,0.00,0.00,0.00,53.78 +0.00,0.00,0.00,0.00,0.00,0.00,53.72 +0.00,0.00,0.00,0.00,0.00,0.00,53.72 +0.00,0.00,0.00,0.00,0.00,0.00,53.34 +0.00,0.00,0.00,0.00,0.00,0.00,53.79 +0.00,0.00,0.00,0.00,0.00,0.00,53.79 +0.00,0.00,0.00,0.00,0.00,0.00,53.59 +0.00,0.00,0.00,0.00,0.00,0.00,53.55 +0.00,0.00,0.00,0.00,0.00,0.00,53.59 +0.00,0.00,0.00,0.00,0.00,0.00,53.59 +0.00,0.00,0.00,0.00,0.00,0.00,53.87 +0.00,0.00,0.00,0.00,0.00,0.00,53.86 +0.00,0.00,0.00,0.00,0.00,0.00,53.86 +0.00,0.00,0.00,0.00,0.00,0.00,53.96 +0.00,0.00,0.00,0.00,0.00,0.00,53.83 +0.00,0.00,0.00,0.00,0.00,0.00,53.83 +0.00,0.00,0.00,0.00,0.00,0.00,53.97 +0.00,0.00,0.00,0.00,0.00,0.00,53.51 +0.00,0.00,0.00,0.00,0.00,0.00,53.51 +0.00,0.00,0.00,0.00,0.00,0.00,53.89 +0.00,0.00,0.00,0.00,0.00,0.00,53.62 +0.00,0.00,0.00,0.00,0.00,0.00,53.62 +0.00,0.00,0.00,0.00,0.00,0.00,53.74 +0.00,0.00,0.00,0.00,0.00,0.00,53.54 +0.00,0.00,0.00,0.00,0.00,0.00,53.59 +0.00,0.00,0.00,0.00,0.00,0.00,53.59 +100.00,0.00,100.00,100.00,0.00,100.00,54.05 +200.00,0.00,200.00,200.00,0.00,200.00,53.88 +300.00,0.00,300.00,300.00,0.00,300.00,53.88 +400.00,0.00,400.00,400.00,0.00,400.00,53.79 +500.00,0.00,500.00,500.00,0.00,500.00,53.82 +600.00,0.00,600.00,600.00,0.00,600.00,53.82 +700.00,0.00,700.00,700.00,0.00,700.00,53.75 +800.00,0.00,800.00,800.00,0.00,800.00,53.61 +900.00,0.00,900.00,900.00,0.00,900.00,53.37 +1000.00,0.00,1000.00,1000.00,0.00,1000.00,53.37 +1100.00,0.00,1100.00,1100.00,0.00,1100.00,53.60 +1200.00,0.00,1200.00,1200.00,0.00,1200.00,53.80 +1300.00,0.00,1300.00,1300.00,0.00,1300.00,53.80 +1400.00,0.00,1400.00,1400.00,0.00,1400.00,53.66 +1500.00,0.00,1500.00,1500.00,0.00,1500.00,53.44 +1600.00,0.00,1600.00,1600.00,0.00,1600.00,53.44 +1700.00,0.00,1700.00,1700.00,0.00,1700.00,53.57 +1800.00,0.00,1800.00,1800.00,0.00,1800.00,53.72 +1900.00,0.00,1900.00,1900.00,0.00,1900.00,53.59 +2000.00,0.00,2000.00,2000.00,0.00,2000.00,53.59 +2100.00,0.00,2100.00,2100.00,0.00,2100.00,53.65 +2200.00,0.00,2200.00,2200.00,0.00,2200.00,53.55 +2300.00,0.00,2300.00,2300.00,0.00,2300.00,53.55 +2400.00,0.00,2400.00,2400.00,0.00,2400.00,53.66 +2500.00,500.00,2000.00,2500.00,450.00,2050.00,53.59 +2600.00,150.00,2450.00,2600.00,450.00,2150.00,53.33 +2700.00,-350.00,3050.00,2700.00,-1050.00,3750.00,53.33 +2800.00,1350.00,1450.00,2800.00,800.00,2000.00,53.67 +2900.00,1450.00,1450.00,2900.00,1950.00,950.00,53.36 +3000.00,550.00,2450.00,3000.00,800.00,2200.00,53.36 +3100.00,250.00,2850.00,3100.00,350.00,2750.00,53.92 +3200.00,1350.00,1850.00,3200.00,900.00,2300.00,54.30 +3300.00,2200.00,1100.00,3300.00,1950.00,1350.00,54.30 +3400.00,1650.00,1750.00,3400.00,1050.00,2350.00,53.56 +3500.00,1300.00,2200.00,3500.00,-100.00,3600.00,54.11 +3600.00,1700.00,1900.00,3600.00,2350.00,1250.00,54.11 +3700.00,2550.00,1150.00,3700.00,1100.00,2600.00,54.78 +3800.00,2100.00,1700.00,3800.00,700.00,3100.00,54.54 +3900.00,1200.00,2700.00,3900.00,2950.00,950.00,55.02 +4000.00,2650.00,1350.00,4000.00,2150.00,1850.00,55.02 +4100.00,2350.00,1750.00,4100.00,1900.00,2200.00,55.33 +4200.00,2500.00,1700.00,4200.00,2100.00,2100.00,55.13 +4300.00,2550.00,1750.00,4300.00,2700.00,1600.00,55.13 +4400.00,2900.00,1500.00,4400.00,2750.00,1650.00,55.48 +4500.00,3000.00,1500.00,4500.00,3050.00,1450.00,55.64 +4600.00,3250.00,1350.00,4600.00,3150.00,1450.00,55.56 +4700.00,3550.00,1150.00,4700.00,2900.00,1800.00,55.56 +4800.00,3600.00,1200.00,4800.00,3050.00,1750.00,55.54 +4900.00,3600.00,1300.00,4900.00,3100.00,1800.00,55.70 +5000.00,3450.00,1550.00,5000.00,3100.00,1900.00,55.70 +5100.00,3700.00,1400.00,5100.00,3350.00,1750.00,55.86 +5200.00,3900.00,1300.00,5200.00,3300.00,1900.00,56.43 +5300.00,4150.00,1150.00,5300.00,3450.00,1850.00,56.43 +5400.00,4350.00,1050.00,5400.00,3700.00,1700.00,56.48 +5500.00,4300.00,1200.00,5500.00,4100.00,1400.00,56.92 +5600.00,4500.00,1100.00,5600.00,4300.00,1300.00,57.37 +5700.00,4700.00,1000.00,5700.00,4400.00,1300.00,57.37 +5800.00,4850.00,950.00,5800.00,4500.00,1300.00,57.65 +5900.00,5050.00,850.00,5900.00,4800.00,1100.00,58.00 +6000.00,5000.00,1000.00,6000.00,4650.00,1350.00,58.00 +6100.00,5050.00,1050.00,6100.00,4800.00,1300.00,58.43 +6200.00,5100.00,1100.00,6200.00,4950.00,1250.00,58.91 +6300.00,5400.00,900.00,6300.00,5100.00,1200.00,58.91 +6400.00,5500.00,900.00,6400.00,5150.00,1250.00,59.12 +6500.00,5650.00,850.00,6500.00,5400.00,1100.00,59.18 +6600.00,5950.00,650.00,6600.00,5500.00,1100.00,60.11 +6700.00,6050.00,650.00,6700.00,5700.00,1000.00,60.11 +6800.00,6350.00,450.00,6800.00,5650.00,1150.00,60.08 +6900.00,6000.00,900.00,6900.00,5350.00,1550.00,60.74 +7000.00,5950.00,1050.00,7000.00,5300.00,1700.00,60.74 +7100.00,6300.00,800.00,7100.00,5550.00,1550.00,60.79 +7200.00,6500.00,700.00,7200.00,6000.00,1200.00,61.01 +7300.00,6450.00,850.00,7300.00,6200.00,1100.00,61.01 +7400.00,6600.00,800.00,7400.00,6550.00,850.00,61.63 +7500.00,6700.00,800.00,7500.00,6850.00,650.00,61.98 +7600.00,6700.00,900.00,7600.00,6950.00,650.00,62.20 +7700.00,6800.00,900.00,7700.00,7000.00,700.00,62.20 +7800.00,7200.00,600.00,7800.00,6900.00,900.00,62.19 +7900.00,7050.00,850.00,7900.00,6950.00,950.00,62.29 +8000.00,7250.00,750.00,8000.00,7200.00,800.00,62.29 +8100.00,7400.00,700.00,8100.00,7650.00,450.00,63.16 +8200.00,7450.00,750.00,8200.00,7750.00,450.00,63.26 +8300.00,7850.00,450.00,8300.00,8200.00,100.00,63.26 +8400.00,7950.00,450.00,8400.00,7950.00,450.00,63.59 +8500.00,7900.00,600.00,8500.00,7850.00,650.00,63.77 +8600.00,8400.00,200.00,8600.00,7950.00,650.00,63.70 +8700.00,8500.00,200.00,8700.00,8150.00,550.00,63.70 +8800.00,8700.00,100.00,8800.00,8100.00,700.00,64.15 +8900.00,8850.00,50.00,8900.00,8750.00,150.00,64.45 +9000.00,9200.00,-200.00,9000.00,9250.00,-250.00,64.45 +9100.00,9350.00,-250.00,9100.00,9400.00,-300.00,64.99 +9200.00,8950.00,250.00,9200.00,8800.00,400.00,64.88 +9300.00,9150.00,150.00,9300.00,8800.00,500.00,64.88 +9400.00,9550.00,-150.00,9400.00,9300.00,100.00,64.89 +9500.00,9550.00,-50.00,9500.00,9250.00,250.00,64.63 +9600.00,9800.00,-200.00,9600.00,9000.00,600.00,65.01 +9700.00,10100.00,-400.00,9700.00,9150.00,550.00,65.01 +9800.00,12350.00,-2550.00,9800.00,10950.00,-1150.00,65.09 +9900.00,10500.00,-600.00,9900.00,9750.00,150.00,65.34 +10000.00,8650.00,1350.00,10000.00,9350.00,650.00,65.36 +10100.00,10300.00,-200.00,10100.00,9650.00,450.00,65.36 +10200.00,9700.00,500.00,10200.00,9850.00,350.00,64.95 +10300.00,10100.00,200.00,10300.00,9750.00,550.00,64.73 +10400.00,10750.00,-350.00,10400.00,10500.00,-100.00,64.73 +10500.00,11250.00,-750.00,10500.00,11000.00,-500.00,64.66 +10600.00,11800.00,-1200.00,10600.00,11250.00,-650.00,65.14 +10700.00,11500.00,-800.00,10700.00,10950.00,-250.00,65.14 +10800.00,11500.00,-700.00,10800.00,10800.00,0.00,64.85 +10900.00,11300.00,-400.00,10900.00,10950.00,-50.00,64.33 +11000.00,11700.00,-700.00,11000.00,11250.00,-250.00,64.05 +11100.00,11800.00,-700.00,11100.00,11300.00,-200.00,64.05 +11200.00,11700.00,-500.00,11200.00,11300.00,-100.00,63.84 +11300.00,12450.00,-1150.00,11300.00,12200.00,-900.00,63.56 +11400.00,12450.00,-1050.00,11400.00,11900.00,-500.00,63.48 +11500.00,12550.00,-1050.00,11500.00,11700.00,-200.00,63.48 +11600.00,12850.00,-1250.00,11600.00,11900.00,-300.00,63.03 +11700.00,13150.00,-1450.00,11700.00,12550.00,-850.00,63.07 +11800.00,12650.00,-850.00,11800.00,12650.00,-850.00,63.07 +11900.00,12500.00,-600.00,11900.00,12550.00,-650.00,62.59 +12000.00,13100.00,-1100.00,12000.00,12900.00,-900.00,62.46 +12100.00,12650.00,-550.00,12100.00,12450.00,-350.00,62.11 +12200.00,13050.00,-850.00,12200.00,12700.00,-500.00,62.11 +12300.00,13300.00,-1000.00,12300.00,12750.00,-450.00,63.11 +12400.00,14050.00,-1650.00,12400.00,12700.00,-300.00,62.69 +12500.00,13650.00,-1150.00,12500.00,11950.00,550.00,62.69 +12600.00,13650.00,-1050.00,12600.00,12000.00,600.00,62.59 +12700.00,13100.00,-400.00,12700.00,12400.00,300.00,62.64 +12800.00,13400.00,-600.00,12800.00,14100.00,-1300.00,62.99 +12900.00,13350.00,-450.00,12900.00,14900.00,-2000.00,62.99 +13000.00,13800.00,-800.00,13000.00,15250.00,-2250.00,64.03 +13100.00,14900.00,-1800.00,13100.00,15350.00,-2250.00,64.26 +13200.00,15250.00,-2050.00,13200.00,14650.00,-1450.00,64.91 +13300.00,14600.00,-1300.00,13300.00,14150.00,-850.00,64.91 +13400.00,14700.00,-1300.00,13400.00,14500.00,-1100.00,65.59 +13500.00,14800.00,-1300.00,13500.00,14650.00,-1150.00,66.15 +13600.00,14250.00,-650.00,13600.00,14500.00,-900.00,66.15 +13700.00,14900.00,-1200.00,13700.00,14650.00,-950.00,66.96 +13800.00,15400.00,-1600.00,13800.00,14450.00,-650.00,67.76 +13900.00,15300.00,-1400.00,13900.00,14300.00,-400.00,68.76 +14000.00,15750.00,-1750.00,14000.00,15450.00,-1450.00,68.76 +14100.00,16000.00,-1900.00,14100.00,15500.00,-1400.00,69.69 +14200.00,15400.00,-1200.00,14200.00,14600.00,-400.00,70.52 +14300.00,15700.00,-1400.00,14300.00,14900.00,-600.00,70.52 +14400.00,16350.00,-1950.00,14400.00,15650.00,-1250.00,71.62 +14500.00,16000.00,-1500.00,14500.00,15050.00,-550.00,72.80 +14600.00,16250.00,-1650.00,14600.00,15350.00,-750.00,73.67 +14700.00,16900.00,-2200.00,14700.00,15650.00,-950.00,73.67 +14800.00,17100.00,-2300.00,14800.00,16000.00,-1200.00,74.41 +14900.00,16300.00,-1400.00,14900.00,15800.00,-900.00,75.67 +15000.00,16150.00,-1150.00,15000.00,16050.00,-1050.00,77.18 +15100.00,16400.00,-1300.00,15100.00,16150.00,-1050.00,77.18 +15200.00,17100.00,-1900.00,15200.00,16500.00,-1300.00,78.24 +15300.00,17450.00,-2150.00,15300.00,16800.00,-1500.00,78.13 +15400.00,17350.00,-1950.00,15400.00,16200.00,-800.00,78.13 +15500.00,17550.00,-2050.00,15500.00,16850.00,-1350.00,79.48 +15600.00,17750.00,-2150.00,15600.00,17150.00,-1550.00,79.88 +15700.00,17550.00,-1850.00,15700.00,17000.00,-1300.00,80.67 +15800.00,17500.00,-1700.00,15800.00,17100.00,-1300.00,80.67 +15900.00,17750.00,-1850.00,15900.00,17100.00,-1200.00,81.19 +16000.00,18100.00,-2100.00,16000.00,17600.00,-1600.00,81.80 +16100.00,17750.00,-1650.00,16100.00,17700.00,-1600.00,82.41 +16200.00,18200.00,-2000.00,16200.00,17850.00,-1650.00,82.41 +16300.00,18450.00,-2150.00,16300.00,17800.00,-1500.00,83.55 +16400.00,18800.00,-2400.00,16400.00,18150.00,-1750.00,83.72 +16500.00,18700.00,-2200.00,16500.00,18200.00,-1700.00,83.72 +16600.00,18650.00,-2050.00,16600.00,18400.00,-1800.00,84.19 +16700.00,18700.00,-2000.00,16700.00,18650.00,-1950.00,84.36 +16800.00,22000.00,-5200.00,16800.00,21500.00,-4700.00,84.82 +16900.00,18550.00,-1650.00,16900.00,18050.00,-1150.00,84.82 +17000.00,18250.00,-1250.00,17000.00,17900.00,-900.00,85.02 +17100.00,18600.00,-1500.00,17100.00,18400.00,-1300.00,84.85 +17200.00,18750.00,-1550.00,17200.00,18500.00,-1300.00,84.73 +17300.00,19350.00,-2050.00,17166.22,18600.00,-1433.78,84.73 +17400.00,19450.00,-2050.00,17066.22,18750.00,-1683.78,85.59 +17500.00,19950.00,-2450.00,16966.22,19350.00,-2383.78,85.52 +17428.56,19850.00,-2421.44,16866.22,19300.00,-2433.78,85.89 +17328.56,19500.00,-2171.44,16766.22,18800.00,-2033.78,85.89 +17228.56,20550.00,-3321.44,16666.22,19100.00,-2433.78,86.99 +17128.56,20400.00,-3271.44,16566.22,18900.00,-2333.78,86.71 +17028.56,19750.00,-2721.44,16466.22,18200.00,-1733.78,86.71 +16928.56,19600.00,-2671.44,16366.22,18050.00,-1683.78,87.00 +16828.56,19150.00,-2321.44,16266.22,18200.00,-1933.78,87.18 +16728.56,19000.00,-2271.44,16166.22,18350.00,-2183.78,87.97 +16628.56,19000.00,-2371.44,16066.22,18300.00,-2233.78,87.97 +16528.56,18950.00,-2421.44,15966.22,17850.00,-1883.78,88.39 +16428.56,19350.00,-2921.44,15866.22,17900.00,-2033.78,88.62 +16328.56,19450.00,-3121.44,15766.22,17650.00,-1883.78,88.69 +16228.56,18600.00,-2371.44,15666.22,17450.00,-1783.78,88.69 +16128.56,18300.00,-2171.44,15566.22,17650.00,-2083.78,88.62 +16028.56,18700.00,-2671.44,15466.22,17750.00,-2283.78,88.44 +15928.56,18100.00,-2171.44,15366.22,17200.00,-1833.78,88.44 +15828.56,17750.00,-1921.44,15266.22,16900.00,-1633.78,88.42 +15728.56,17750.00,-2021.44,15166.22,17100.00,-1933.78,88.49 +15628.56,17750.00,-2121.44,15066.22,17300.00,-2233.78,88.47 +15528.56,17100.00,-1571.44,14966.22,16850.00,-1883.78,88.47 +15428.56,17650.00,-2221.44,14866.22,16950.00,-2083.78,87.75 +15328.56,17700.00,-2371.44,14766.22,16400.00,-1633.78,86.54 +15228.56,17200.00,-1971.44,14666.22,16050.00,-1383.78,86.80 +15128.56,17050.00,-1921.44,14566.22,16200.00,-1633.78,86.80 +15028.56,17050.00,-2021.44,14466.22,16750.00,-2283.78,85.78 +14928.56,16700.00,-1771.44,14366.22,16300.00,-1933.78,84.67 +14828.56,16700.00,-1871.44,14266.22,16100.00,-1833.78,84.67 +14728.56,16750.00,-2021.44,14166.22,15850.00,-1683.78,83.27 +14628.56,16400.00,-1771.44,14066.22,15200.00,-1133.78,81.73 +14528.56,15550.00,-1021.44,13966.22,14350.00,-383.78,80.47 +14428.56,16650.00,-2221.44,13866.22,15750.00,-1883.78,80.47 +14328.56,16750.00,-2421.44,13766.22,16000.00,-2233.78,78.46 +14228.56,15350.00,-1121.44,13666.22,14200.00,-533.78,76.36 +14128.56,15250.00,-1121.44,13566.22,14000.00,-433.78,76.36 +14028.56,16300.00,-2271.44,13466.22,15000.00,-1533.78,75.75 +13928.56,16250.00,-2321.44,13366.22,14600.00,-1233.78,74.13 +13828.56,16050.00,-2221.44,13266.22,14900.00,-1633.78,72.85 +13728.56,15900.00,-2171.44,13166.22,15100.00,-1933.78,72.85 +13628.56,15400.00,-1771.44,13066.22,14400.00,-1333.78,70.28 +13528.56,15550.00,-2021.44,12966.22,14000.00,-1033.78,67.94 +13428.56,15250.00,-1821.44,12866.22,13900.00,-1033.78,67.94 +13328.56,14900.00,-1571.44,12766.22,14000.00,-1233.78,65.69 +13228.56,14600.00,-1371.44,12666.22,13500.00,-833.78,63.24 +13128.56,14400.00,-1271.44,12566.22,13200.00,-633.78,61.64 +13028.56,14750.00,-1721.44,12466.22,13900.00,-1433.78,61.64 +12928.56,14700.00,-1771.44,12366.22,13900.00,-1533.78,59.51 +12828.56,14600.00,-1771.44,12266.22,13400.00,-1133.78,57.52 +12728.56,14550.00,-1821.44,12166.22,13200.00,-1033.78,54.77 +12628.56,14250.00,-1621.44,12066.22,12900.00,-833.78,54.77 +12528.56,14250.00,-1721.44,11966.22,13050.00,-1083.78,53.75 +12428.56,14100.00,-1671.44,11866.22,13300.00,-1433.78,51.44 +12328.56,13300.00,-971.44,11766.22,12550.00,-783.78,51.44 +12228.56,13350.00,-1121.44,11666.22,12400.00,-733.78,48.68 +12128.56,13750.00,-1621.44,11566.22,12700.00,-1133.78,47.52 +12028.56,13550.00,-1521.44,11466.22,12750.00,-1283.78,45.24 +11928.56,13000.00,-1071.44,11366.22,12150.00,-783.78,45.24 +11828.56,12750.00,-921.44,11266.22,12150.00,-883.78,43.98 +11728.56,12850.00,-1121.44,11166.22,12250.00,-1083.78,42.92 +11628.56,12850.00,-1221.44,11066.22,12300.00,-1233.78,41.14 +11528.56,12500.00,-971.44,10966.22,12050.00,-1083.78,41.14 +11428.56,12450.00,-1021.44,10866.22,11950.00,-1083.78,40.38 +11328.56,14750.00,-3421.44,10766.22,14000.00,-3233.78,39.85 +11228.56,11450.00,-221.44,10666.22,10600.00,66.22,38.62 +11128.56,10100.00,1028.56,10566.22,9000.00,1566.22,38.62 +11028.56,11900.00,-871.44,10466.22,11450.00,-983.78,39.36 +10928.56,11550.00,-621.44,10366.22,10800.00,-433.78,37.97 +10828.56,10950.00,-121.44,10266.22,10200.00,66.22,37.97 +10728.56,11600.00,-871.44,10166.22,11200.00,-1033.78,38.29 +10628.56,11300.00,-671.44,10066.22,11000.00,-933.78,37.68 +10528.56,11550.00,-1021.44,9966.22,11200.00,-1233.78,37.95 +10428.56,11500.00,-1071.44,9866.22,10850.00,-983.78,37.95 +10328.56,10650.00,-321.44,9766.22,9600.00,166.22,38.12 +10228.56,11100.00,-871.44,9666.22,10100.00,-433.78,38.65 +10128.56,11550.00,-1421.44,9566.22,9800.00,-233.78,38.65 +10028.56,11500.00,-1471.44,9466.22,9700.00,-233.78,38.33 +9928.56,11100.00,-1171.44,9366.22,9700.00,-333.78,38.85 +9828.56,10500.00,-671.44,9266.22,9550.00,-283.78,39.29 +9728.56,10200.00,-471.44,9166.22,9450.00,-283.78,39.29 +9628.56,9800.00,-171.44,9066.22,9000.00,66.22,40.22 +9528.56,10250.00,-721.44,8966.22,9600.00,-633.78,41.02 +9428.56,10100.00,-671.44,8866.22,9250.00,-383.78,41.35 +9328.56,10300.00,-971.44,8766.22,8800.00,-33.78,41.35 +9228.56,10200.00,-971.44,8666.22,8400.00,266.22,41.98 +9128.56,9850.00,-721.44,8566.22,8150.00,416.22,43.08 +9028.56,9700.00,-671.44,8466.22,8100.00,366.22,43.08 +8928.56,9500.00,-571.44,8366.22,8800.00,-433.78,43.89 +8828.56,9150.00,-321.44,8266.22,8600.00,-333.78,44.46 +8728.56,8800.00,-71.44,8166.22,8100.00,66.22,45.22 +8628.56,8950.00,-321.44,8066.22,8050.00,16.22,45.22 +8528.56,9100.00,-571.44,7966.22,8050.00,-83.78,45.58 +8428.56,8750.00,-321.44,7866.22,8000.00,-133.78,46.88 +8328.56,8900.00,-571.44,7766.22,8150.00,-383.78,46.88 +8228.56,8550.00,-321.44,7666.22,7950.00,-283.78,47.06 +8128.56,8500.00,-371.44,7566.22,7500.00,66.22,48.03 +8028.56,8300.00,-271.44,7466.22,6900.00,566.22,48.03 +7928.56,8050.00,-121.44,7366.22,6600.00,766.22,48.68 +7828.56,7900.00,-71.44,7266.22,6500.00,766.22,49.68 +7728.56,7650.00,78.56,7166.22,6850.00,316.22,50.01 +7628.56,7500.00,128.56,7066.22,6650.00,416.22,50.01 +7528.56,7300.00,228.56,6966.22,6600.00,366.22,50.05 +7428.56,7450.00,-21.44,6866.22,6400.00,466.22,50.73 +7328.56,7750.00,-421.44,6766.22,6500.00,266.22,50.73 +7228.56,7650.00,-421.44,6666.22,6350.00,316.22,51.86 +7128.56,7600.00,-471.44,6566.22,6600.00,-33.78,52.04 +7028.56,7250.00,-221.44,6466.22,6450.00,16.22,52.58 +6928.56,6750.00,178.56,6366.22,6100.00,266.22,52.58 +6828.56,6900.00,-71.44,6266.22,6300.00,-33.78,53.36 +6728.56,6550.00,178.56,6166.22,6150.00,16.22,53.50 +6628.56,6050.00,578.56,6066.22,5450.00,616.22,53.50 +6528.56,6100.00,428.56,5966.22,5000.00,966.22,54.23 +6428.56,6250.00,178.56,5866.22,5800.00,66.22,54.79 +6328.56,5900.00,428.56,5766.22,4800.00,966.22,54.79 +6228.56,5700.00,528.56,5666.22,4300.00,1366.22,54.75 +6128.56,5850.00,278.56,5566.22,4700.00,866.22,55.42 +6028.56,5600.00,428.56,5466.22,4700.00,766.22,55.33 +5928.56,5350.00,578.56,5366.22,4600.00,766.22,55.33 +5828.56,5450.00,378.56,5266.22,4800.00,466.22,55.78 +5728.56,5400.00,328.56,5166.22,4450.00,716.22,56.19 +5628.56,5050.00,578.56,5066.22,4050.00,1016.22,56.19 +5528.56,5050.00,478.56,4966.22,3900.00,1066.22,56.50 +5428.56,4750.00,678.56,4866.22,4000.00,866.22,56.56 +5328.56,4650.00,678.56,4766.22,3950.00,816.22,56.56 +5228.56,4500.00,728.56,4666.22,3550.00,1116.22,56.55 +5128.56,4350.00,778.56,4566.22,3200.00,1366.22,56.94 +5028.56,4350.00,678.56,4466.22,3300.00,1166.22,57.56 +4928.56,3850.00,1078.56,4366.22,3450.00,916.22,57.56 +4828.56,3400.00,1428.56,4266.22,3250.00,1016.22,57.16 +4728.56,3550.00,1178.56,4166.22,2200.00,1966.22,57.63 +4628.56,3650.00,978.56,4066.22,2200.00,1866.22,57.63 +4528.56,3400.00,1128.56,3966.22,3200.00,766.22,57.65 +4428.56,2650.00,1778.56,3866.22,2400.00,1466.22,58.10 +4328.56,2500.00,1828.56,3766.22,800.00,2966.22,58.10 +4228.56,3600.00,628.56,3666.22,3900.00,-233.78,58.17 +4128.56,2500.00,1628.56,3566.22,1900.00,1666.22,58.27 +4028.56,2250.00,1778.56,3466.22,-200.00,3666.22,58.35 +3928.56,2650.00,1278.56,3366.22,1600.00,1766.22,58.35 +3828.56,2600.00,1228.56,3266.22,2100.00,1166.22,59.05 +3728.56,900.00,2828.56,3166.22,-800.00,3966.22,59.07 +3628.56,750.00,2878.56,3066.22,800.00,2266.22,59.07 +3528.56,2700.00,828.56,2966.22,2800.00,166.22,59.59 +3428.56,1000.00,2428.56,2866.22,350.00,2516.22,59.16 +3328.56,1150.00,2178.56,2766.22,-300.00,3066.22,59.61 +3228.56,2350.00,878.56,2666.22,1700.00,966.22,59.61 +3128.56,1800.00,1328.56,2566.22,1150.00,1416.22,59.58 +3028.56,50.00,2978.56,2466.22,-450.00,2916.22,60.33 +2928.56,650.00,2278.56,2366.22,1150.00,1216.22,60.33 +2828.56,1600.00,1228.56,2266.22,2050.00,216.22,59.87 +2728.56,900.00,1828.56,2166.22,150.00,2016.22,59.61 +2628.56,-100.00,2728.56,2066.22,50.00,2016.22,59.61 +2528.56,550.00,1978.56,1966.22,100.00,1866.22,60.21 +2428.56,350.00,2078.56,1866.22,0.00,1866.22,59.85 +2328.56,-950.00,3278.56,1766.22,0.00,1766.22,59.76 +2228.56,600.00,1628.56,1666.22,0.00,1666.22,59.76 +2128.56,-200.00,2328.56,1566.22,0.00,1566.22,59.91 +2028.56,-550.00,2578.56,1466.22,-50.00,1516.22,60.26 +1928.56,650.00,1278.56,1366.22,0.00,1366.22,60.26 +1828.56,-50.00,1878.56,1266.22,0.00,1266.22,59.81 +1728.56,-650.00,2378.56,1166.22,0.00,1166.22,60.03 +1628.56,200.00,1428.56,1066.22,0.00,1066.22,60.03 +1528.56,0.00,1528.56,966.22,0.00,966.22,59.92 +1428.56,0.00,1428.56,866.22,0.00,866.22,59.96 +1328.56,0.00,1328.56,766.22,0.00,766.22,59.96 +1228.56,0.00,1228.56,666.22,0.00,666.22,60.00 +1128.56,0.00,1128.56,566.22,0.00,566.22,60.07 +1028.56,0.00,1028.56,466.22,0.00,466.22,59.51 +928.56,0.00,928.56,366.22,0.00,366.22,59.51 +828.56,0.00,828.56,266.22,0.00,266.22,59.66 +728.56,0.00,728.56,166.22,0.00,166.22,59.46 +628.56,0.00,628.56,66.22,0.00,66.22,59.46 +528.56,0.00,528.56,0.00,0.00,0.00,59.94 +428.56,0.00,428.56,0.00,0.00,0.00,60.11 +328.56,0.00,328.56,0.00,0.00,0.00,60.11 +228.56,0.00,228.56,0.00,0.00,0.00,60.04 +128.56,0.00,128.56,0.00,0.00,0.00,59.64 +28.56,0.00,28.56,0.00,0.00,0.00,59.59 +0.00,0.00,0.00,0.00,0.00,0.00,59.59 +0.00,0.00,0.00,0.00,0.00,0.00,59.65 +0.00,0.00,0.00,0.00,0.00,0.00,59.44 +0.00,0.00,0.00,0.00,0.00,0.00,59.44 +0.00,0.00,0.00,0.00,0.00,0.00,59.25 +0.00,0.00,0.00,0.00,0.00,0.00,59.37 +0.00,0.00,0.00,0.00,0.00,0.00,59.37 +0.00,0.00,0.00,0.00,0.00,0.00,59.43 +0.00,0.00,0.00,0.00,0.00,0.00,59.65 +0.00,0.00,0.00,0.00,0.00,0.00,59.65 +0.00,0.00,0.00,0.00,0.00,0.00,59.70 +0.00,0.00,0.00,0.00,0.00,0.00,59.66 +0.00,0.00,0.00,0.00,0.00,0.00,59.37 +0.00,0.00,0.00,0.00,0.00,0.00,59.37 +0.00,0.00,0.00,0.00,0.00,0.00,59.84 +0.00,0.00,0.00,0.00,0.00,0.00,59.57 +0.00,0.00,0.00,0.00,0.00,0.00,59.57 +0.00,0.00,0.00,0.00,0.00,0.00,59.37 +0.00,0.00,0.00,0.00,0.00,0.00,59.15 +0.00,0.00,0.00,0.00,0.00,0.00,59.15 +0.00,0.00,0.00,0.00,0.00,0.00,59.52 +0.00,0.00,0.00,0.00,0.00,0.00,59.57 +0.00,0.00,0.00,0.00,0.00,0.00,59.57 +0.00,0.00,0.00,0.00,0.00,0.00,59.48 +0.00,0.00,0.00,0.00,0.00,0.00,59.46 +0.00,0.00,0.00,0.00,0.00,0.00,59.24 +0.00,0.00,0.00,0.00,0.00,0.00,59.24 +0.00,0.00,0.00,0.00,0.00,0.00,59.62 +0.00,0.00,0.00,0.00,0.00,0.00,59.45 +0.00,0.00,0.00,0.00,0.00,0.00,59.45 +0.00,0.00,0.00,0.00,0.00,0.00,59.69 +0.00,0.00,0.00,0.00,0.00,0.00,59.52 +0.00,0.00,0.00,0.00,0.00,0.00,59.82 +0.00,0.00,0.00,0.00,0.00,0.00,59.82 +0.00,0.00,0.00,0.00,0.00,0.00,59.96 +0.00,0.00,0.00,0.00,0.00,0.00,59.96 +0.00,0.00,0.00,0.00,0.00,0.00,59.96 +0.00,0.00,0.00,0.00,0.00,0.00,59.97 +0.00,0.00,0.00,0.00,0.00,0.00,59.35 +0.00,0.00,0.00,0.00,0.00,0.00,59.35 +0.00,0.00,0.00,0.00,0.00,0.00,59.66 +0.00,0.00,0.00,0.00,0.00,0.00,59.91 +0.00,0.00,0.00,0.00,0.00,0.00,59.91 +0.00,0.00,0.00,0.00,0.00,0.00,59.77 +0.00,0.00,0.00,0.00,0.00,0.00,59.64 +0.00,0.00,0.00,0.00,0.00,0.00,59.64 +0.00,0.00,0.00,0.00,0.00,0.00,59.84 +0.00,0.00,0.00,0.00,0.00,0.00,59.73 +0.00,0.00,0.00,0.00,0.00,0.00,60.11 +0.00,0.00,0.00,0.00,0.00,0.00,60.11 +0.00,0.00,0.00,0.00,0.00,0.00,59.67 +0.00,0.00,0.00,0.00,0.00,0.00,59.77 +0.00,0.00,0.00,0.00,0.00,0.00,59.77 +0.00,0.00,0.00,0.00,0.00,0.00,59.64 +0.00,0.00,0.00,0.00,0.00,0.00,59.82 +0.00,0.00,0.00,0.00,0.00,0.00,59.82 +0.00,0.00,0.00,0.00,0.00,0.00,59.65 +0.00,0.00,0.00,0.00,0.00,0.00,59.81 +0.00,0.00,0.00,0.00,0.00,0.00,59.81 +0.00,0.00,0.00,0.00,0.00,0.00,59.81 +0.00,0.00,0.00,0.00,0.00,0.00,59.95 +0.00,0.00,0.00,0.00,0.00,0.00,59.94 +0.00,0.00,0.00,0.00,0.00,0.00,59.94 +0.00,0.00,0.00,0.00,0.00,0.00,59.79 +0.00,0.00,0.00,0.00,0.00,0.00,59.82 +0.00,0.00,0.00,0.00,0.00,0.00,59.82 +0.00,0.00,0.00,0.00,0.00,0.00,59.56 +0.00,0.00,0.00,0.00,0.00,0.00,59.86 +0.00,0.00,0.00,0.00,0.00,0.00,60.13 +0.00,0.00,0.00,0.00,0.00,0.00,60.13 +0.00,0.00,0.00,0.00,0.00,0.00,59.79 +0.00,0.00,0.00,0.00,0.00,0.00,60.21 +0.00,0.00,0.00,0.00,0.00,0.00,60.21 +0.00,0.00,0.00,0.00,0.00,0.00,59.72 +-100.00,0.00,-100.00,-100.00,0.00,-100.00,59.67 +-200.00,0.00,-200.00,-200.00,0.00,-200.00,59.67 +-300.00,0.00,-300.00,-300.00,0.00,-300.00,59.74 +-400.00,0.00,-400.00,-400.00,0.00,-400.00,59.88 +-500.00,0.00,-500.00,-500.00,0.00,-500.00,59.85 +-600.00,0.00,-600.00,-600.00,0.00,-600.00,59.85 +-700.00,0.00,-700.00,-700.00,0.00,-700.00,59.97 +-800.00,0.00,-800.00,-800.00,0.00,-800.00,60.03 +-900.00,0.00,-900.00,-900.00,0.00,-900.00,60.03 +-1000.00,0.00,-1000.00,-1000.00,0.00,-1000.00,59.86 +-1100.00,0.00,-1100.00,-1100.00,0.00,-1100.00,59.83 +-1200.00,0.00,-1200.00,-1200.00,0.00,-1200.00,59.83 +-1300.00,0.00,-1300.00,-1300.00,0.00,-1300.00,59.68 +-1400.00,0.00,-1400.00,-1400.00,0.00,-1400.00,59.44 +-1500.00,0.00,-1500.00,-1500.00,0.00,-1500.00,59.76 +-1600.00,0.00,-1600.00,-1600.00,0.00,-1600.00,59.76 +-1700.00,0.00,-1700.00,-1700.00,0.00,-1700.00,59.56 +-1800.00,0.00,-1800.00,-1800.00,0.00,-1800.00,60.00 +-1900.00,0.00,-1900.00,-1900.00,0.00,-1900.00,60.00 +-2000.00,0.00,-2000.00,-2000.00,0.00,-2000.00,59.97 +-2100.00,0.00,-2100.00,-2100.00,0.00,-2100.00,59.72 +-2200.00,0.00,-2200.00,-2200.00,0.00,-2200.00,59.72 +-2300.00,0.00,-2300.00,-2300.00,0.00,-2300.00,59.88 +-2400.00,0.00,-2400.00,-2400.00,0.00,-2400.00,59.83 +-2500.00,-400.00,-2100.00,-2500.00,-300.00,-2200.00,60.05 +-2600.00,-150.00,-2450.00,-2600.00,-750.00,-1850.00,60.05 +-2700.00,200.00,-2900.00,-2700.00,600.00,-3300.00,59.72 +-2800.00,-1350.00,-1450.00,-2800.00,-450.00,-2350.00,60.47 +-2900.00,-1500.00,-1400.00,-2900.00,-2200.00,-700.00,60.31 +-3000.00,-350.00,-2650.00,-3000.00,-1000.00,-2000.00,60.31 +-3100.00,-350.00,-2750.00,-3100.00,200.00,-3300.00,59.55 +-3200.00,-1950.00,-1250.00,-3200.00,-1800.00,-1400.00,59.90 +-3300.00,-1800.00,-1500.00,-3300.00,-1300.00,-2000.00,59.90 +-3400.00,250.00,-3650.00,-3400.00,200.00,-3600.00,59.76 +-3500.00,-750.00,-2750.00,-3500.00,-2000.00,-1500.00,59.91 +-3600.00,-2150.00,-1450.00,-3600.00,-1850.00,-1750.00,59.65 +-3700.00,-1400.00,-2300.00,-3700.00,250.00,-3950.00,59.65 +-3800.00,-1800.00,-2000.00,-3800.00,-2100.00,-1700.00,59.57 +-3900.00,-2200.00,-1700.00,-3900.00,-2500.00,-1400.00,60.22 +-4000.00,-1850.00,-2150.00,-4000.00,-2200.00,-1800.00,60.22 +-4100.00,-2300.00,-1800.00,-4100.00,-1900.00,-2200.00,59.91 +-4200.00,-2900.00,-1300.00,-4200.00,-2900.00,-1300.00,59.48 +-4300.00,-2850.00,-1450.00,-4300.00,-2650.00,-1650.00,59.61 +-4400.00,-2900.00,-1500.00,-4400.00,-2850.00,-1550.00,59.61 +-4500.00,-3500.00,-1000.00,-4500.00,-3100.00,-1400.00,59.55 +-4600.00,-3400.00,-1200.00,-4600.00,-3000.00,-1600.00,59.45 +-4700.00,-3050.00,-1650.00,-4700.00,-2700.00,-2000.00,59.54 +-4800.00,-3400.00,-1400.00,-4800.00,-3100.00,-1700.00,59.54 +-4900.00,-3850.00,-1050.00,-4900.00,-3600.00,-1300.00,59.95 +-5000.00,-3950.00,-1050.00,-5000.00,-3800.00,-1200.00,59.50 +-5100.00,-4050.00,-1050.00,-5100.00,-3750.00,-1350.00,59.50 +-5200.00,-4200.00,-1000.00,-5200.00,-3850.00,-1350.00,59.36 +-5300.00,-4250.00,-1050.00,-5300.00,-4000.00,-1300.00,59.19 +-5400.00,-4450.00,-950.00,-5400.00,-4400.00,-1000.00,59.28 +-5500.00,-4350.00,-1150.00,-5500.00,-4400.00,-1100.00,59.28 +-5600.00,-4500.00,-1100.00,-5600.00,-4400.00,-1200.00,59.46 +-5700.00,-4850.00,-850.00,-5700.00,-4700.00,-1000.00,58.82 +-5800.00,-4850.00,-950.00,-5800.00,-4700.00,-1100.00,58.82 +-5900.00,-5050.00,-850.00,-5900.00,-4750.00,-1150.00,58.99 +-6000.00,-5000.00,-1000.00,-6000.00,-5100.00,-900.00,58.86 +-6100.00,-5100.00,-1000.00,-6100.00,-5050.00,-1050.00,58.78 +-6200.00,-5150.00,-1050.00,-6200.00,-5350.00,-850.00,58.78 +-6300.00,-5250.00,-1050.00,-6300.00,-5550.00,-750.00,58.99 +-6400.00,-5150.00,-1250.00,-6400.00,-5300.00,-1100.00,58.78 +-6500.00,-5550.00,-950.00,-6500.00,-5350.00,-1150.00,58.19 +-6600.00,-5900.00,-700.00,-6600.00,-5500.00,-1100.00,58.19 +-6700.00,-6250.00,-450.00,-6700.00,-5450.00,-1250.00,57.95 +-6800.00,-6450.00,-350.00,-6800.00,-5600.00,-1200.00,56.80 +-6900.00,-6850.00,-50.00,-6900.00,-5750.00,-1150.00,56.80 +-7000.00,-6600.00,-400.00,-7000.00,-5850.00,-1150.00,56.56 +-7100.00,-6200.00,-900.00,-7100.00,-6000.00,-1100.00,56.06 +-7200.00,-6350.00,-850.00,-7200.00,-6150.00,-1050.00,55.88 +-7300.00,-6450.00,-850.00,-7300.00,-6350.00,-950.00,55.88 +-7400.00,-6600.00,-800.00,-7400.00,-6550.00,-850.00,55.28 +-7500.00,-6600.00,-900.00,-7500.00,-6550.00,-950.00,54.90 +-7600.00,-6650.00,-950.00,-7600.00,-6700.00,-900.00,54.91 +-7700.00,-6650.00,-1050.00,-7700.00,-7100.00,-600.00,54.91 +-7800.00,-6700.00,-1100.00,-7800.00,-7250.00,-550.00,54.44 +-7900.00,-7150.00,-750.00,-7900.00,-7450.00,-450.00,54.23 +-8000.00,-7650.00,-350.00,-8000.00,-7600.00,-400.00,54.23 +-8100.00,-8100.00,0.00,-8100.00,-7450.00,-650.00,53.95 +-8200.00,-8050.00,-150.00,-8200.00,-7650.00,-550.00,53.36 +-8300.00,-8000.00,-300.00,-8300.00,-7700.00,-600.00,52.59 +-8400.00,-8150.00,-250.00,-8400.00,-8050.00,-350.00,52.59 +-8500.00,-8450.00,-50.00,-8500.00,-8250.00,-250.00,52.05 +-8600.00,-8700.00,100.00,-8600.00,-8300.00,-300.00,52.26 +-8700.00,-8650.00,-50.00,-8700.00,-8450.00,-250.00,51.48 +-8800.00,-8700.00,-100.00,-8800.00,-8500.00,-300.00,51.48 +-8900.00,-8550.00,-350.00,-8900.00,-8950.00,50.00,50.77 +-9000.00,-8650.00,-350.00,-9000.00,-9250.00,250.00,50.37 +-9100.00,-9050.00,-50.00,-9100.00,-9650.00,550.00,50.37 +-9200.00,-9300.00,100.00,-9200.00,-9700.00,500.00,50.20 +-9300.00,-9400.00,100.00,-9300.00,-9100.00,-200.00,50.00 +-9400.00,-9750.00,350.00,-9400.00,-9300.00,-100.00,49.74 +-9500.00,-9500.00,0.00,-9500.00,-9000.00,-500.00,49.74 +-9600.00,-9150.00,-450.00,-9600.00,-9000.00,-600.00,49.73 +-9700.00,-11150.00,1450.00,-9700.00,-11150.00,1450.00,49.48 +-9800.00,-9700.00,-100.00,-9800.00,-9750.00,-50.00,49.74 +-9900.00,-9700.00,-200.00,-9900.00,-9700.00,-200.00,49.74 +-10000.00,-9800.00,-200.00,-10000.00,-10400.00,400.00,49.89 +-10100.00,-9900.00,-200.00,-10100.00,-10000.00,-100.00,50.57 +-10200.00,-10000.00,-200.00,-10200.00,-10200.00,0.00,49.90 +-10300.00,-11050.00,750.00,-10300.00,-10800.00,500.00,49.90 +-10400.00,-11050.00,650.00,-10400.00,-10400.00,0.00,51.11 +-10500.00,-10400.00,-100.00,-10500.00,-9800.00,-700.00,51.47 +-10600.00,-10750.00,150.00,-10600.00,-10700.00,100.00,51.47 +-10700.00,-11200.00,500.00,-10700.00,-11300.00,600.00,51.90 +-10800.00,-11650.00,850.00,-10800.00,-11300.00,500.00,53.17 +-10900.00,-11250.00,350.00,-10900.00,-10850.00,-50.00,54.61 +-11000.00,-11300.00,300.00,-11000.00,-10900.00,-100.00,54.61 +-11100.00,-11900.00,800.00,-11100.00,-11750.00,650.00,55.48 +-11200.00,-12100.00,900.00,-11200.00,-11600.00,400.00,56.95 +-11300.00,-12050.00,750.00,-11300.00,-11700.00,400.00,59.28 +-11400.00,-12450.00,1050.00,-11400.00,-11950.00,550.00,59.28 +-11500.00,-11300.00,-200.00,-11500.00,-10650.00,-850.00,60.95 +-11600.00,-12250.00,650.00,-11600.00,-11550.00,-50.00,62.04 +-11700.00,-12850.00,1150.00,-11700.00,-12650.00,950.00,62.04 +-11800.00,-12650.00,850.00,-11800.00,-12700.00,900.00,64.63 +-11900.00,-12450.00,550.00,-11900.00,-12400.00,500.00,66.89 +-12000.00,-12900.00,900.00,-12000.00,-12750.00,750.00,68.83 +-12100.00,-13250.00,1150.00,-12100.00,-12850.00,750.00,68.83 +-12200.00,-13150.00,950.00,-12200.00,-12800.00,600.00,71.94 +-12300.00,-13050.00,750.00,-12300.00,-13000.00,700.00,74.78 +-12400.00,-13450.00,1050.00,-12400.00,-13350.00,950.00,74.78 +-12500.00,-13450.00,950.00,-12500.00,-13250.00,750.00,77.45 +-12600.00,-13650.00,1050.00,-12600.00,-13450.00,850.00,79.87 +-12700.00,-13750.00,1050.00,-12700.00,-13700.00,1000.00,82.89 +-12800.00,-13900.00,1100.00,-12800.00,-13250.00,450.00,82.89 +-12900.00,-14050.00,1150.00,-12900.00,-12950.00,50.00,84.60 +-13000.00,-14500.00,1500.00,-13000.00,-13450.00,450.00,87.34 +-13100.00,-14250.00,1150.00,-13100.00,-13500.00,400.00,89.42 +-13200.00,-14450.00,1250.00,-13200.00,-14150.00,950.00,89.42 +-13300.00,-13600.00,300.00,-13300.00,-13550.00,250.00,91.74 +-13400.00,-13900.00,500.00,-13400.00,-13700.00,300.00,92.71 +-13500.00,-15450.00,1950.00,-13500.00,-15000.00,1500.00,92.71 +-13600.00,-14800.00,1200.00,-13600.00,-14000.00,400.00,95.33 +-13700.00,-14700.00,1000.00,-13700.00,-13750.00,50.00,96.81 +-13800.00,-15400.00,1600.00,-13800.00,-14550.00,750.00,98.35 +-13900.00,-15500.00,1600.00,-13900.00,-15200.00,1300.00,98.35 +-14000.00,-14900.00,900.00,-14000.00,-14800.00,800.00,100.18 +-14100.00,-15050.00,950.00,-14100.00,-15050.00,950.00,101.39 +-14200.00,-15800.00,1600.00,-14200.00,-15600.00,1400.00,102.48 +-14300.00,-15800.00,1500.00,-14300.00,-15150.00,850.00,102.48 +-14400.00,-16400.00,2000.00,-14400.00,-15450.00,1050.00,103.60 +-14500.00,-16000.00,1500.00,-14500.00,-15300.00,800.00,104.33 +-14600.00,-15950.00,1350.00,-14600.00,-15550.00,950.00,104.33 +-14700.00,-16100.00,1400.00,-14700.00,-15900.00,1200.00,105.07 +-14800.00,-16650.00,1850.00,-14800.00,-16450.00,1650.00,106.22 +-14900.00,-16000.00,1100.00,-14900.00,-15550.00,650.00,106.17 +-15000.00,-16200.00,1200.00,-15000.00,-15550.00,550.00,106.17 +-15100.00,-17050.00,1950.00,-15100.00,-16400.00,1300.00,106.81 +-15200.00,-17250.00,2050.00,-15200.00,-16850.00,1650.00,107.61 +-15300.00,-16800.00,1500.00,-15300.00,-16450.00,1150.00,107.66 +-15400.00,-17050.00,1650.00,-15400.00,-16900.00,1500.00,107.66 +-15500.00,-17550.00,2050.00,-15500.00,-17450.00,1950.00,107.89 +-15600.00,-17650.00,2050.00,-15600.00,-17200.00,1600.00,108.16 +-15700.00,-17450.00,1750.00,-15700.00,-17000.00,1300.00,108.16 +-15800.00,-17400.00,1600.00,-15800.00,-17100.00,1300.00,107.95 +-15900.00,-17650.00,1750.00,-15900.00,-17300.00,1400.00,107.44 +-16000.00,-17850.00,1850.00,-16000.00,-17900.00,1900.00,107.23 +-16100.00,-17900.00,1800.00,-16100.00,-18000.00,1900.00,107.23 +-16200.00,-18200.00,2000.00,-16200.00,-17800.00,1600.00,106.65 +-16300.00,-18150.00,1850.00,-16300.00,-18000.00,1700.00,106.05 +-16400.00,-18400.00,2000.00,-16400.00,-18300.00,1900.00,104.94 +-16500.00,-18750.00,2250.00,-16500.00,-18700.00,2200.00,104.94 +-16600.00,-21850.00,5250.00,-16600.00,-21450.00,4850.00,103.96 +-16700.00,-18700.00,2000.00,-16700.00,-17850.00,1150.00,102.45 +-16800.00,-18000.00,1200.00,-16800.00,-17600.00,800.00,101.78 +-16900.00,-17850.00,950.00,-16900.00,-18200.00,1300.00,101.78 +-17000.00,-18350.00,1350.00,-17000.00,-18200.00,1200.00,100.68 +-17100.00,-18600.00,1500.00,-17100.00,-18100.00,1000.00,98.90 +-17200.00,-19550.00,2350.00,-17200.00,-18750.00,1550.00,98.90 +-17300.00,-19450.00,2150.00,-17152.29,-18450.00,1297.71,97.74 +-17400.00,-19400.00,2000.00,-17052.29,-19000.00,1947.71,96.38 +-17481.14,-20000.00,2518.86,-16952.29,-19400.00,2447.71,95.02 +-17381.14,-19800.00,2418.86,-16852.29,-19300.00,2447.71,95.02 +-17281.14,-20050.00,2768.86,-16752.29,-19650.00,2897.71,92.68 +-17181.14,-19600.00,2418.86,-16652.29,-18550.00,1897.71,91.91 +-17081.14,-19650.00,2568.86,-16552.29,-18600.00,2047.71,90.97 +-16981.14,-20250.00,3268.86,-16452.29,-18850.00,2397.71,90.97 +-16881.14,-19250.00,2368.86,-16352.29,-18400.00,2047.71,89.59 +-16781.14,-19200.00,2418.86,-16252.29,-18350.00,2097.71,88.74 +-16681.14,-19000.00,2318.86,-16152.29,-17700.00,1547.71,88.74 +-16581.14,-19150.00,2568.86,-16052.29,-18100.00,2047.71,86.98 +-16481.14,-19150.00,2668.86,-15952.29,-17800.00,1847.71,86.27 +-16381.14,-18800.00,2418.86,-15852.29,-17700.00,1847.71,85.34 +-16281.14,-19250.00,2968.86,-15752.29,-18300.00,2547.71,85.34 +-16181.14,-19400.00,3218.86,-15652.29,-18150.00,2497.71,84.62 +-16081.14,-18700.00,2618.86,-15552.29,-17450.00,1897.71,84.51 +-15981.14,-18250.00,2268.86,-15452.29,-17100.00,1647.71,83.97 +-15881.14,-18450.00,2568.86,-15352.29,-17000.00,1647.71,83.97 +-15781.14,-18400.00,2618.86,-15252.29,-16900.00,1647.71,84.02 +-15681.14,-18200.00,2518.86,-15152.29,-16900.00,1747.71,83.22 +-15581.14,-18000.00,2418.86,-15052.29,-16800.00,1747.71,83.22 +-15481.14,-17650.00,2168.86,-14952.29,-16700.00,1747.71,82.85 +-15381.14,-17800.00,2418.86,-14852.29,-17150.00,2297.71,82.59 +-15281.14,-17950.00,2668.86,-14752.29,-17350.00,2597.71,82.21 +-15181.14,-17600.00,2418.86,-14652.29,-17100.00,2447.71,82.21 +-15081.14,-17350.00,2268.86,-14552.29,-16900.00,2347.71,82.43 +-14981.14,-17250.00,2268.86,-14452.29,-16250.00,1797.71,82.52 +-14881.14,-16850.00,1968.86,-14352.29,-15600.00,1247.71,82.71 +-14781.14,-16800.00,2018.86,-14252.29,-15450.00,1197.71,82.71 +-14681.14,-16700.00,2018.86,-14152.29,-15500.00,1347.71,82.58 +-14581.14,-16700.00,2118.86,-14052.29,-15350.00,1297.71,81.98 +-14481.14,-17000.00,2518.86,-13952.29,-15650.00,1697.71,81.98 +-14381.14,-16600.00,2218.86,-13852.29,-15100.00,1247.71,82.27 +-14281.14,-16050.00,1768.86,-13752.29,-14800.00,1047.71,81.62 +-14181.14,-16350.00,2168.86,-13652.29,-15200.00,1547.71,81.47 +-14081.14,-16000.00,1918.86,-13552.29,-15000.00,1447.71,81.47 +-13981.14,-15650.00,1668.86,-13452.29,-14800.00,1347.71,81.28 +-13881.14,-15400.00,1518.86,-13352.29,-14900.00,1547.71,81.17 +-13781.14,-15450.00,1668.86,-13252.29,-15100.00,1847.71,81.35 +-13681.14,-15350.00,1668.86,-13152.29,-14500.00,1347.71,81.35 +-13581.14,-15400.00,1818.86,-13052.29,-14000.00,947.71,81.33 +-13481.14,-15500.00,2018.86,-12952.29,-13950.00,997.71,81.03 +-13381.14,-14700.00,1318.86,-12852.29,-13550.00,697.71,81.03 +-13281.14,-14600.00,1318.86,-12752.29,-14000.00,1247.71,80.74 +-13181.14,-14350.00,1168.86,-12652.29,-13600.00,947.71,80.80 +-13081.14,-14600.00,1518.86,-12552.29,-13600.00,1047.71,80.43 +-12981.14,-14550.00,1568.86,-12452.29,-13500.00,1047.71,80.43 +-12881.14,-14300.00,1418.86,-12352.29,-12950.00,597.71,80.33 +-12781.14,-14200.00,1418.86,-12252.29,-13150.00,897.71,80.21 +-12681.14,-13900.00,1218.86,-12152.29,-13150.00,997.71,79.67 +-12581.14,-13950.00,1368.86,-12052.29,-13350.00,1297.71,79.67 +-12481.14,-13700.00,1218.86,-11952.29,-12900.00,947.71,79.46 +-12381.14,-13700.00,1318.86,-11852.29,-12800.00,947.71,79.36 +-12281.14,-13600.00,1318.86,-11752.29,-12650.00,897.71,79.36 +-12181.14,-13400.00,1218.86,-11652.29,-12350.00,697.71,79.36 +-12081.14,-13350.00,1268.86,-11552.29,-12300.00,747.71,79.36 +-11981.14,-13250.00,1268.86,-11452.29,-12200.00,747.71,79.41 +-11881.14,-12900.00,1018.86,-11352.29,-12100.00,747.71,79.41 +-11781.14,-12700.00,918.86,-11252.29,-11750.00,497.71,78.85 +-11681.14,-12850.00,1168.86,-11152.29,-11850.00,697.71,78.38 +-11581.14,-12900.00,1318.86,-11052.29,-12150.00,1097.71,78.08 +-11481.14,-14600.00,3118.86,-10952.29,-13750.00,2797.71,78.08 +-11381.14,-11600.00,218.86,-10852.29,-10800.00,-52.29,77.70 +-11281.14,-10250.00,-1031.14,-10752.29,-9750.00,-1002.29,77.42 +-11181.14,-12700.00,1518.86,-10652.29,-12400.00,1747.71,76.89 +-11081.14,-12500.00,1418.86,-10552.29,-11950.00,1397.71,76.89 +-10981.14,-11450.00,468.86,-10452.29,-10600.00,147.71,77.00 +-10881.14,-11550.00,668.86,-10352.29,-10900.00,547.71,76.22 +-10781.14,-11800.00,1018.86,-10252.29,-11300.00,1047.71,76.22 +-10681.14,-11450.00,768.86,-10152.29,-11000.00,847.71,76.03 +-10581.14,-11500.00,918.86,-10052.29,-10800.00,747.71,75.11 +-10481.14,-11350.00,868.86,-9952.29,-10400.00,447.71,74.48 +-10381.14,-11100.00,718.86,-9852.29,-10000.00,147.71,74.48 +-10281.14,-11350.00,1068.86,-9752.29,-10050.00,297.71,74.19 +-10181.14,-11250.00,1068.86,-9652.29,-9700.00,47.71,73.73 +-10081.14,-11450.00,1368.86,-9552.29,-10250.00,697.71,73.23 +-9981.14,-11050.00,1068.86,-9452.29,-9800.00,347.71,73.23 +-9881.14,-10350.00,468.86,-9352.29,-9700.00,347.71,72.51 +-9781.14,-10450.00,668.86,-9252.29,-9600.00,347.71,71.78 +-9681.14,-10250.00,568.86,-9152.29,-9350.00,197.71,71.78 +-9581.14,-10600.00,1018.86,-9052.29,-9300.00,247.71,70.55 +-9481.14,-10350.00,868.86,-8952.29,-9300.00,347.71,70.17 +-9381.14,-9800.00,418.86,-8852.29,-8800.00,-52.29,69.80 +-9281.14,-9450.00,168.86,-8752.29,-8600.00,-152.29,69.80 +-9181.14,-9300.00,118.86,-8652.29,-8600.00,-52.29,69.24 +-9081.14,-9350.00,268.86,-8552.29,-8650.00,97.71,68.72 +-8981.14,-9350.00,368.86,-8452.29,-8650.00,197.71,68.72 +-8881.14,-9000.00,118.86,-8352.29,-8450.00,97.71,68.56 +-8781.14,-9150.00,368.86,-8252.29,-8400.00,147.71,67.85 +-8681.14,-9100.00,418.86,-8152.29,-8550.00,397.71,67.40 +-8581.14,-8950.00,368.86,-8052.29,-8450.00,397.71,67.40 +-8481.14,-8800.00,318.86,-7952.29,-8450.00,497.71,67.45 +-8381.14,-8500.00,118.86,-7852.29,-8150.00,297.71,66.72 +-8281.14,-8300.00,18.86,-7752.29,-7800.00,47.71,66.55 +-8181.14,-8150.00,-31.14,-7652.29,-7200.00,-452.29,66.55 +-8081.14,-8000.00,-81.14,-7552.29,-7000.00,-552.29,66.05 +-7981.14,-8050.00,68.86,-7452.29,-7050.00,-402.29,65.45 +-7881.14,-8150.00,268.86,-7352.29,-7050.00,-302.29,65.45 +-7781.14,-7900.00,118.86,-7252.29,-6900.00,-352.29,64.98 +-7681.14,-7900.00,218.86,-7152.29,-7050.00,-102.29,64.66 +-7581.14,-7650.00,68.86,-7052.29,-6600.00,-452.29,64.22 +-7481.14,-7450.00,-31.14,-6952.29,-6700.00,-252.29,64.22 +-7381.14,-7450.00,68.86,-6852.29,-6900.00,47.71,63.81 +-7281.14,-6850.00,-431.14,-6752.29,-6500.00,-252.29,63.83 +-7181.14,-6700.00,-481.14,-6652.29,-6550.00,-102.29,64.05 +-7081.14,-6800.00,-281.14,-6552.29,-6400.00,-152.29,64.05 +-6981.14,-6850.00,-131.14,-6452.29,-5900.00,-552.29,63.47 +-6881.14,-6800.00,-81.14,-6352.29,-5800.00,-552.29,63.07 +-6781.14,-6500.00,-281.14,-6252.29,-5650.00,-602.29,63.07 +-6681.14,-6300.00,-381.14,-6152.29,-5500.00,-652.29,62.81 +-6581.14,-6300.00,-281.14,-6052.29,-5550.00,-502.29,62.36 +-6481.14,-6350.00,-131.14,-5952.29,-5500.00,-452.29,61.84 +-6381.14,-6000.00,-381.14,-5852.29,-5150.00,-702.29,61.84 +-6281.14,-6150.00,-131.14,-5752.29,-5150.00,-602.29,62.07 +-6181.14,-5900.00,-281.14,-5652.29,-4900.00,-752.29,61.95 +-6081.14,-5400.00,-681.14,-5552.29,-4600.00,-952.29,61.95 +-5981.14,-5150.00,-831.14,-5452.29,-4400.00,-1052.29,61.82 +-5881.14,-5000.00,-881.14,-5352.29,-4300.00,-1052.29,61.86 +-5781.14,-5050.00,-731.14,-5252.29,-4500.00,-752.29,61.28 +-5681.14,-4900.00,-781.14,-5152.29,-4400.00,-752.29,61.28 +-5581.14,-5000.00,-581.14,-5052.29,-4450.00,-602.29,60.83 +-5481.14,-4850.00,-631.14,-4952.29,-4400.00,-552.29,61.23 +-5381.14,-4750.00,-631.14,-4852.29,-3400.00,-1452.29,61.00 +-5281.14,-4650.00,-631.14,-4752.29,-3200.00,-1552.29,61.00 +-5181.14,-4600.00,-581.14,-4652.29,-5250.00,597.71,60.93 +-5081.14,-4350.00,-731.14,-4552.29,-4000.00,-552.29,60.84 +-4981.14,-3150.00,-1831.14,-4452.29,-2600.00,-1852.29,60.84 +-4881.14,-3300.00,-1581.14,-4352.29,-2500.00,-1852.29,60.52 +-4781.14,-3900.00,-881.14,-4252.29,-4300.00,47.71,61.43 +-4681.14,-3350.00,-1331.14,-4152.29,-2500.00,-1652.29,61.30 +-4581.14,-2450.00,-2131.14,-4052.29,-1750.00,-2302.29,61.30 +-4481.14,-3750.00,-731.14,-3952.29,-3700.00,-252.29,60.24 +-4381.14,-3350.00,-1031.14,-3852.29,-2750.00,-1102.29,60.64 +-4281.14,-750.00,-3531.14,-3752.29,-1550.00,-2202.29,60.26 +-4181.14,-2000.00,-2181.14,-3652.29,-500.00,-3152.29,60.26 +-4081.14,-3400.00,-681.14,-3552.29,-2900.00,-652.29,59.73 +-3981.14,-3600.00,-381.14,-3452.29,-2050.00,-1402.29,60.04 +-3881.14,-750.00,-3131.14,-3352.29,-1000.00,-2352.29,60.04 +-3781.14,-1050.00,-2731.14,-3252.29,-400.00,-2852.29,59.84 +-3681.14,-2850.00,-831.14,-3152.29,-1950.00,-1202.29,58.70 +-3581.14,-3000.00,-581.14,-3052.29,-1700.00,-1352.29,59.89 +-3481.14,-50.00,-3431.14,-2952.29,250.00,-3202.29,59.89 +-3381.14,-1050.00,-2331.14,-2852.29,250.00,-3102.29,59.33 +-3281.14,-2200.00,-1081.14,-2752.29,-2350.00,-402.29,59.03 +-3181.14,-2050.00,-1131.14,-2652.29,-1200.00,-1452.29,58.78 +-3081.14,-300.00,-2781.14,-2552.29,700.00,-3252.29,58.78 +-2981.14,-700.00,-2281.14,-2452.29,-900.00,-1552.29,58.67 +-2881.14,-1650.00,-1231.14,-2352.29,-1850.00,-502.29,58.04 +-2781.14,-1250.00,-1531.14,-2252.29,-650.00,-1602.29,58.04 +-2681.14,400.00,-3081.14,-2152.29,100.00,-2252.29,59.03 +-2581.14,-750.00,-1831.14,-2052.29,50.00,-2102.29,58.17 +-2481.14,-350.00,-2131.14,-1952.29,0.00,-1952.29,58.49 +-2381.14,900.00,-3281.14,-1852.29,0.00,-1852.29,58.49 +-2281.14,-300.00,-1981.14,-1752.29,0.00,-1752.29,58.53 +-2181.14,0.00,-2181.14,-1652.29,0.00,-1652.29,58.80 +-2081.14,850.00,-2931.14,-1552.29,0.00,-1552.29,58.80 +-1981.14,-1000.00,-981.14,-1452.29,0.00,-1452.29,58.65 +-1881.14,150.00,-2031.14,-1352.29,0.00,-1352.29,58.95 +-1781.14,700.00,-2481.14,-1252.29,0.00,-1252.29,58.95 +-1681.14,-250.00,-1431.14,-1152.29,0.00,-1152.29,58.61 +-1581.14,0.00,-1581.14,-1052.29,0.00,-1052.29,59.08 +-1481.14,0.00,-1481.14,-952.29,0.00,-952.29,58.95 +-1381.14,0.00,-1381.14,-852.29,0.00,-852.29,58.95 +-1281.14,0.00,-1281.14,-752.29,0.00,-752.29,59.01 +-1181.14,0.00,-1181.14,-652.29,0.00,-652.29,58.97 +-1081.14,0.00,-1081.14,-552.29,0.00,-552.29,58.97 +-981.14,0.00,-981.14,-452.29,0.00,-452.29,58.81 +-881.14,0.00,-881.14,-352.29,0.00,-352.29,58.73 +-781.14,0.00,-781.14,-252.29,0.00,-252.29,58.73 +-681.14,0.00,-681.14,-152.29,0.00,-152.29,58.90 +-581.14,0.00,-581.14,-52.29,0.00,-52.29,58.94 +-481.14,0.00,-481.14,0.00,0.00,0.00,58.54 +-381.14,0.00,-381.14,0.00,0.00,0.00,58.54 +-281.14,0.00,-281.14,0.00,0.00,0.00,58.13 +-181.14,0.00,-181.14,0.00,0.00,0.00,58.64 +-81.14,0.00,-81.14,0.00,0.00,0.00,58.64 +0.00,0.00,0.00,0.00,0.00,0.00,58.64 +0.00,0.00,0.00,0.00,0.00,0.00,58.70 +0.00,0.00,0.00,0.00,0.00,0.00,58.70 +0.00,0.00,0.00,0.00,0.00,0.00,58.64 +0.00,0.00,0.00,0.00,0.00,0.00,58.92 +0.00,0.00,0.00,0.00,0.00,0.00,58.92 +0.00,0.00,0.00,0.00,0.00,0.00,58.70 +0.00,0.00,0.00,0.00,0.00,0.00,58.97 +0.00,0.00,0.00,0.00,0.00,0.00,58.75 +0.00,0.00,0.00,0.00,0.00,0.00,58.75 +0.00,0.00,0.00,0.00,0.00,0.00,58.34 +0.00,0.00,0.00,0.00,0.00,0.00,58.34 +0.00,0.00,0.00,0.00,0.00,0.00,58.34 +0.00,0.00,0.00,0.00,0.00,0.00,58.42 +0.00,0.00,0.00,0.00,0.00,0.00,58.20 +0.00,0.00,0.00,0.00,0.00,0.00,58.20 +0.00,0.00,0.00,0.00,0.00,0.00,58.63 +0.00,0.00,0.00,0.00,0.00,0.00,58.87 +0.00,0.00,0.00,0.00,0.00,0.00,58.87 +0.00,0.00,0.00,0.00,0.00,0.00,58.51 +0.00,0.00,0.00,0.00,0.00,0.00,58.75 +0.00,0.00,0.00,0.00,0.00,0.00,59.13 +0.00,0.00,0.00,0.00,0.00,0.00,59.13 +0.00,0.00,0.00,0.00,0.00,0.00,59.05 \ No newline at end of file diff --git a/pid_vis.py b/pid_vis.py index fa3a18f..e298db5 100644 --- a/pid_vis.py +++ b/pid_vis.py @@ -2,12 +2,14 @@ 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 = "LeftSetpoint,LeftVelocity,LeftError,RightSetpoint,RightVelocity,RightError" + header = "LeftSetpoint,LeftVelocity,LeftError,RightSetpoint,RightVelocity,RightError,Heading" keys = header.split(",") for row in reader: for k in keys: @@ -16,27 +18,50 @@ # val *= -1 # Correct for rotation test lists[k].append(val) - # 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.plot(lists["LeftSetpoint"], "-b", lists["LeftVelocity"], "-r", lists["LeftError"], "-g", lists["RightSetpoint"], "--c", lists["RightVelocity"], "--m", lists["RightError"], "--y") - plt.show() +# 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"], "-b", lists["LeftVelocity"], "-r", lists["LeftError"], "-g", + lists["RightSetpoint"], "--c", lists["RightVelocity"], "--m", lists["RightError"], "--y") +ax_vel.legend(["Left Setpoint", "Left Velocity", "Left Error", "Right Setpoint", "Right Velocity", "Right Error"]) + +# 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.legend(["Heading"]) +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.set_rticks([]) # Hide radial ticks for clarity + +plt.tight_layout() +plt.show() diff --git a/src/main.cpp b/src/main.cpp index 4127120..6aa163c 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -21,7 +21,6 @@ //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; -Magnet* magnet = nullptr; // Declare a pointer to Magnet // Setup gets run at startup void setup() { @@ -34,9 +33,6 @@ void setup() { // Any setup needed to get bot ready setupBot(); - // Initialize the Magnet object - magnet = new Magnet(); - // Create a WiFi network for the laptop to connect to if (!RUN_OFFLINE) connectWiFI(); @@ -74,11 +70,6 @@ void loop() { // Run control loop controlLoop(loopDelayMilliseconds, framesUntilPrint); - // test magnet data - MagnetReading mag_data = magnet->read_calibrated_data(); - float heading = magnet->getCompassDegree(mag_data); - serialLogln(heading, 3); - // 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); diff --git a/src/robot/control.cpp b/src/robot/control.cpp index 9e96419..40e3892 100644 --- a/src/robot/control.cpp +++ b/src/robot/control.cpp @@ -25,8 +25,12 @@ #include "robot/profiledPIDController.h" #include "robot/trapezoidalProfileNew.h" +#include "robot/magnet.h" -//PLEASE ONLY USE CHESSBOT #4 FOR TESTING + +Magnet *magnet = nullptr; // Declare a pointer to Magnet + +// pid constants TrapezoidProfile::Constraints profileConstraints(MAX_VELOCITY_TPS, MAX_ACCELERATION_TPSPS); TrapezoidProfile leftProfile(profileConstraints); TrapezoidProfile rightProfile(profileConstraints); @@ -181,6 +185,7 @@ void setupBot() { setupMotors(); setupIR(); setupEncodersNew(); + magnet = new Magnet(); serialLogln("Bot Set Up!", 2); encoderAVelocityController.Reset(); @@ -332,9 +337,13 @@ void controlLoop(int loopDelayMs, int8_t framesUntilPrint) { serialLog(",", 3); serialLog(currentVelocityB, 3); serialLog(",", 3); - serialLogln(rightSetpoint.velocity - currentVelocityB, 3); + serialLog(rightSetpoint.velocity - currentVelocityB, 3); + serialLog(",", 3); + // test magnet data + float heading = magnet->readDegrees(); + serialLogln(heading, 3); - #endif +#endif drive( leftMotorPower, // leftMotorPower, From d1edc7210a80e5a8478e8c7c013975089cac68be Mon Sep 17 00:00:00 2001 From: Mason Thomas Date: Tue, 16 Sep 2025 22:15:56 -0500 Subject: [PATCH 11/47] Update src/robot/magnet.cpp Co-authored-by: Copilot <175728472+Copilot@users.noreply.github.com> --- src/robot/magnet.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/robot/magnet.cpp b/src/robot/magnet.cpp index deda628..a2bfe92 100644 --- a/src/robot/magnet.cpp +++ b/src/robot/magnet.cpp @@ -32,9 +32,9 @@ MagnetReading Magnet::read_calibrated_data() { sBmm350MagData_t sensor_mag_data = bmm350.getGeomagneticData(); float mag_data[3]; - mag_data[0] = sensor_mag_data.float_x + hard_iron_offset[0]; - mag_data[1] = sensor_mag_data.float_y + hard_iron_offset[1]; - mag_data[2] = sensor_mag_data.float_z + hard_iron_offset[2]; + mag_data[0] = sensor_mag_data.float_x - hard_iron_offset[0]; + mag_data[1] = sensor_mag_data.float_y - hard_iron_offset[1]; + mag_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] * mag_data[0]) + (soft_iron_matrix[i][1] * mag_data[1]) + (soft_iron_matrix[i][2] * mag_data[2]); From 7c8b89bc5e9bf3df36a0224e3d975b19b2cccfd9 Mon Sep 17 00:00:00 2001 From: Mason Thomas Date: Tue, 16 Sep 2025 22:19:44 -0500 Subject: [PATCH 12/47] move readDegrees from header to cpp --- include/robot/magnet.h | 5 +---- src/robot/magnet.cpp | 5 +++++ 2 files changed, 6 insertions(+), 4 deletions(-) diff --git a/include/robot/magnet.h b/include/robot/magnet.h index db4c45b..7694a8b 100644 --- a/include/robot/magnet.h +++ b/include/robot/magnet.h @@ -17,10 +17,7 @@ class Magnet { void set_soft_iron_matrix(float matrix[3][3]); struct MagnetReading read_calibrated_data(); float getCompassDegree(struct MagnetReading mag); - float readDegrees() { - MagnetReading mag = read_calibrated_data(); - return getCompassDegree(mag); - } + float readDegrees(); private: float hard_iron_offset[3] = { 23.71, 5.45, 8.27 }; float soft_iron_matrix[3][3] = { diff --git a/src/robot/magnet.cpp b/src/robot/magnet.cpp index a2bfe92..1e9be51 100644 --- a/src/robot/magnet.cpp +++ b/src/robot/magnet.cpp @@ -55,3 +55,8 @@ float Magnet::getCompassDegree(MagnetReading mag) { } return compass * 180 / M_PI; } + +float Magnet::readDegrees() { + MagnetReading mag = read_calibrated_data(); + return getCompassDegree(mag); +} \ No newline at end of file From 8381fc6abaec142fe40638398aa725c21c54c903 Mon Sep 17 00:00:00 2001 From: Mason Thomas Date: Tue, 16 Sep 2025 22:55:09 -0500 Subject: [PATCH 13/47] reset the default offsets to the correct sign --- include/robot/magnet.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/include/robot/magnet.h b/include/robot/magnet.h index 7694a8b..e6d508a 100644 --- a/include/robot/magnet.h +++ b/include/robot/magnet.h @@ -19,7 +19,7 @@ class Magnet { float getCompassDegree(struct MagnetReading mag); float readDegrees(); private: - float hard_iron_offset[3] = { 23.71, 5.45, 8.27 }; + float hard_iron_offset[3] = { -23.71, -5.45, -8.27 }; float soft_iron_matrix[3][3] = { { 1.017, -0.024, 0.023 }, { -0.024, 0.994, 0.002 }, From d9afdcbaa03c5bbbc8f425eb388c7986f9e98368 Mon Sep 17 00:00:00 2001 From: democat Date: Thu, 25 Sep 2025 01:51:21 -0500 Subject: [PATCH 14/47] Remove .DS_Store --- .DS_Store | Bin 6148 -> 0 bytes .gitignore | 3 ++- 2 files changed, 2 insertions(+), 1 deletion(-) delete mode 100644 .DS_Store 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 From 53bb40364090b2b9339fb1583e45003243ee4345 Mon Sep 17 00:00:00 2001 From: democat Date: Mon, 29 Sep 2025 21:09:51 -0500 Subject: [PATCH 15/47] Fix feedforward overpowering PID --- include/robot/control.h | 4 +- include/utils/config.h | 6 +- pid_test.csv | 1779 ++++++++++++++++----------------------- src/robot/control.cpp | 10 +- src/utils/config.cpp | 10 +- 5 files changed, 732 insertions(+), 1077 deletions(-) diff --git a/include/robot/control.h b/include/robot/control.h index f10a906..4c7b97b 100644 --- a/include/robot/control.h +++ b/include/robot/control.h @@ -20,8 +20,8 @@ struct ControlSetting static ControlSetting leftMotorControl; static ControlSetting rightMotorControl; -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 profileA = {THEORETICAL_MAX_VELOCITY_TPS, THEORETICAL_MAX_ACCELERATION_TPSPS, 0, 0, 0, 0, 75.0}; // maxVelocity, maxAcceleration, currentPosition, currentVelocity, targetPosition, targetVelocity +static MotionProfile profileB = {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); diff --git a/include/utils/config.h b/include/utils/config.h index b98a5cb..743a031 100644 --- a/include/utils/config.h +++ b/include/utils/config.h @@ -33,8 +33,10 @@ 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 TILES_TO_TICKS; extern float PID_POSITION_TOLERANCE; diff --git a/pid_test.csv b/pid_test.csv index 217dadb..e9dd924 100644 --- a/pid_test.csv +++ b/pid_test.csv @@ -1,1065 +1,716 @@ LeftSetpoint,LeftVelocity,LeftError,RightSetpoint,RightVelocity,RightError,Heading --15300.00,-18050.00,2750.00,-15300.00,-17550.00,2250.00,62.64 --15400.00,-17050.00,1650.00,-15400.00,-16650.00,1250.00,66.25 --15500.00,-17150.00,1650.00,-15500.00,-16800.00,1300.00,68.92 --15600.00,-17750.00,2150.00,-15600.00,-17100.00,1500.00,68.92 --15700.00,-18900.00,3200.00,-15700.00,-17900.00,2200.00,72.08 --15800.00,-18150.00,2350.00,-15800.00,-17400.00,1600.00,75.90 --15900.00,-17600.00,1700.00,-15900.00,-16900.00,1000.00,75.90 --16000.00,-17500.00,1500.00,-16000.00,-16950.00,950.00,78.43 --16100.00,-18250.00,2150.00,-16100.00,-17750.00,1650.00,80.81 --16200.00,-18650.00,2450.00,-16200.00,-18150.00,1950.00,83.73 --16300.00,-22150.00,5850.00,-16300.00,-21350.00,5050.00,86.48 --16400.00,-18200.00,1800.00,-16400.00,-17800.00,1400.00,86.48 --16500.00,-18000.00,1500.00,-16500.00,-17900.00,1400.00,88.49 --16600.00,-18550.00,1950.00,-16600.00,-18300.00,1700.00,90.02 --16700.00,-19200.00,2500.00,-16700.00,-18600.00,1900.00,90.02 --16800.00,-19150.00,2350.00,-16800.00,-18100.00,1300.00,92.08 --16900.00,-19050.00,2150.00,-16900.00,-18450.00,1550.00,94.08 --17000.00,-18700.00,1700.00,-17000.00,-18300.00,1300.00,95.82 --17100.00,-19000.00,1900.00,-17100.00,-18300.00,1200.00,95.82 --17200.00,-19500.00,2300.00,-17200.00,-18750.00,1550.00,96.45 --17300.00,-20050.00,2750.00,-17207.97,-19100.00,1892.03,97.55 --17400.00,-19800.00,2400.00,-17107.97,-18800.00,1692.03,97.94 --17500.00,-20500.00,3000.00,-17007.97,-19900.00,2892.03,97.94 --17553.09,-20050.00,2496.91,-16907.97,-19300.00,2392.03,98.88 --17453.09,-19550.00,2096.91,-16807.97,-19000.00,2192.03,99.44 --17353.09,-20200.00,2846.91,-16707.97,-19150.00,2442.03,99.44 --17253.09,-20350.00,3096.91,-16607.97,-18900.00,2292.03,100.38 --17153.09,-19950.00,2796.91,-16507.97,-18400.00,1892.03,100.92 --17053.09,-21050.00,3996.91,-16407.97,-19050.00,2642.03,100.69 --16953.09,-19800.00,2846.91,-16307.97,-18600.00,2292.03,100.69 --16853.09,-19650.00,2796.91,-16207.97,-18250.00,2042.03,101.10 --16753.09,-19850.00,3096.91,-16107.97,-17900.00,1792.03,101.09 --16653.09,-19400.00,2746.91,-16007.97,-17800.00,1792.03,101.43 --16553.09,-19050.00,2496.91,-15907.97,-17250.00,1342.03,101.43 --16453.09,-18950.00,2496.91,-15807.97,-17500.00,1692.03,101.32 --16353.09,-19150.00,2796.91,-15707.97,-17850.00,2142.03,100.92 --16253.09,-19050.00,2796.91,-15607.97,-17650.00,2042.03,100.92 --16153.09,-18850.00,2696.91,-15507.97,-17500.00,1992.03,101.07 --16053.09,-18450.00,2396.91,-15407.97,-17300.00,1892.03,101.28 --15953.09,-18150.00,2196.91,-15307.97,-16900.00,1592.03,100.11 --15853.09,-18100.00,2246.91,-15207.97,-17200.00,1992.03,100.11 --15753.09,-18350.00,2596.91,-15107.97,-17450.00,2342.03,99.67 --15653.09,-17900.00,2246.91,-15007.97,-16950.00,1942.03,99.24 --15553.09,-18050.00,2496.91,-14907.97,-17050.00,2142.03,98.27 --15453.09,-18000.00,2546.91,-14807.97,-17100.00,2292.03,98.27 --15353.09,-17900.00,2546.91,-14707.97,-16850.00,2142.03,97.29 --15253.09,-17650.00,2396.91,-14607.97,-16700.00,2092.03,95.89 --15153.09,-17350.00,2196.91,-14507.97,-16300.00,1792.03,95.89 --15053.09,-17150.00,2096.91,-14407.97,-16000.00,1592.03,94.66 --14953.09,-17100.00,2146.91,-14307.97,-15900.00,1592.03,93.90 --14853.09,-16850.00,1996.91,-14207.97,-15800.00,1592.03,92.57 --14753.09,-16650.00,1896.91,-14107.97,-15500.00,1392.03,92.57 --14653.09,-16650.00,1996.91,-14007.97,-15100.00,1092.03,91.45 --14553.09,-16850.00,2296.91,-13907.97,-15200.00,1292.03,89.73 --14453.09,-16650.00,2196.91,-13807.97,-15050.00,1242.03,89.73 --14353.09,-16300.00,1946.91,-13707.97,-14650.00,942.03,87.93 --14253.09,-16000.00,1746.91,-13607.97,-14500.00,892.03,86.35 --14153.09,-16350.00,2196.91,-13507.97,-15250.00,1742.03,84.98 --14053.09,-15350.00,1296.91,-13407.97,-14450.00,1042.03,84.98 --13953.09,-14850.00,896.91,-13307.97,-14100.00,792.03,83.67 --13853.09,-16250.00,2396.91,-13207.97,-15300.00,2092.03,82.27 --13753.09,-15500.00,1746.91,-13107.97,-13800.00,692.03,80.71 --13653.09,-15050.00,1396.91,-13007.97,-13650.00,642.03,80.71 --13553.09,-15400.00,1846.91,-12907.97,-14250.00,1342.03,79.48 --13453.09,-14750.00,1296.91,-12807.97,-13850.00,1042.03,78.68 --13353.09,-14350.00,996.91,-12707.97,-13250.00,542.03,78.68 --13253.09,-14900.00,1646.91,-12607.97,-13800.00,1192.03,77.04 --13153.09,-14550.00,1396.91,-12507.97,-13350.00,842.03,76.07 --13053.09,-14200.00,1146.91,-12407.97,-12800.00,392.03,74.69 --12953.09,-14850.00,1896.91,-12307.97,-13050.00,742.03,74.69 --12853.09,-14450.00,1596.91,-12207.97,-12800.00,592.03,73.98 --12753.09,-13750.00,996.91,-12107.97,-12600.00,492.03,73.28 --12653.09,-13600.00,946.91,-12007.97,-12600.00,592.03,72.72 --12553.09,-13400.00,846.91,-11907.97,-12700.00,792.03,72.72 --12453.09,-13750.00,1296.91,-11807.97,-13200.00,1392.03,71.66 --12353.09,-13500.00,1146.91,-11707.97,-12700.00,992.03,71.77 --12253.09,-13400.00,1146.91,-11607.97,-12100.00,492.03,71.77 --12153.09,-13300.00,1146.91,-11507.97,-12100.00,592.03,71.05 --12053.09,-13100.00,1046.91,-11407.97,-12200.00,792.03,70.63 --11953.09,-15000.00,3046.91,-11307.97,-14000.00,2692.03,70.52 --11853.09,-12600.00,746.91,-11207.97,-11900.00,692.03,70.52 --11753.09,-12050.00,296.91,-11107.97,-11250.00,142.03,70.38 --11653.09,-12250.00,596.91,-11007.97,-11250.00,242.03,70.38 --11553.09,-12550.00,996.91,-10907.97,-11550.00,642.03,70.49 --11453.09,-12750.00,1296.91,-10807.97,-11650.00,842.03,70.49 --11353.09,-12700.00,1346.91,-10707.97,-11200.00,492.03,70.85 --11253.09,-12450.00,1196.91,-10607.97,-11150.00,542.03,70.58 --11153.09,-12000.00,846.91,-10507.97,-11100.00,592.03,70.68 --11053.09,-11850.00,796.91,-10407.97,-11350.00,942.03,70.68 --10953.09,-11300.00,346.91,-10307.97,-10800.00,492.03,70.82 --10853.09,-11000.00,146.91,-10207.97,-10650.00,442.03,70.76 --10753.09,-11100.00,346.91,-10107.97,-10850.00,742.03,70.76 --10653.09,-11400.00,746.91,-10007.97,-10400.00,392.03,71.20 --10553.09,-11500.00,946.91,-9907.97,-10100.00,192.03,71.18 --10453.09,-11350.00,896.91,-9807.97,-9750.00,-57.97,71.47 --10353.09,-11000.00,646.91,-9707.97,-9500.00,-207.97,71.47 --10253.09,-10950.00,696.91,-9607.97,-9500.00,-107.97,70.98 --10153.09,-11150.00,996.91,-9507.97,-9850.00,342.03,70.91 --10053.09,-10900.00,846.91,-9407.97,-9950.00,542.03,70.92 --9953.09,-10600.00,646.91,-9307.97,-9850.00,542.03,70.92 --9853.09,-10000.00,146.91,-9207.97,-9400.00,192.03,71.04 --9753.09,-10050.00,296.91,-9107.97,-9050.00,-57.97,70.73 --9653.09,-10600.00,946.91,-9007.97,-9650.00,642.03,70.73 --9553.09,-9850.00,296.91,-8907.97,-9000.00,92.03,70.83 --9453.09,-9450.00,-3.09,-8807.97,-8750.00,-57.97,70.24 --9353.09,-9600.00,246.91,-8707.97,-9250.00,542.03,70.20 --9253.09,-9100.00,-153.09,-8607.97,-8400.00,-207.97,70.20 --9153.09,-9250.00,96.91,-8507.97,-8300.00,-207.97,70.34 --9053.09,-9350.00,296.91,-8407.97,-8600.00,192.03,69.85 --8953.09,-9000.00,46.91,-8307.97,-8050.00,-257.97,70.05 --8853.09,-9000.00,146.91,-8207.97,-8350.00,142.03,70.05 --8753.09,-9300.00,546.91,-8107.97,-8500.00,392.03,69.22 --8653.09,-9150.00,496.91,-8007.97,-8450.00,442.03,69.22 --8553.09,-9200.00,646.91,-7907.97,-8500.00,592.03,69.22 --8453.09,-8900.00,446.91,-7807.97,-8150.00,342.03,68.54 --8353.09,-8900.00,546.91,-7707.97,-7900.00,192.03,68.26 --8253.09,-8650.00,396.91,-7607.97,-7350.00,-257.97,67.64 --8153.09,-8400.00,246.91,-7507.97,-7000.00,-507.97,67.64 --8053.09,-8450.00,396.91,-7407.97,-7450.00,42.03,67.08 --7953.09,-8150.00,196.91,-7307.97,-7300.00,-7.97,67.32 --7853.09,-7900.00,46.91,-7207.97,-7200.00,-7.97,67.32 --7753.09,-7850.00,96.91,-7107.97,-7200.00,92.03,66.74 --7653.09,-7700.00,46.91,-7007.97,-6900.00,-107.97,66.08 --7553.09,-8050.00,496.91,-6907.97,-7100.00,192.03,65.57 --7453.09,-8050.00,596.91,-6807.97,-7050.00,242.03,65.57 --7353.09,-7400.00,46.91,-6707.97,-6450.00,-257.97,65.20 --7253.09,-7450.00,196.91,-6607.97,-6800.00,192.03,64.82 --7153.09,-7350.00,196.91,-6507.97,-6800.00,292.03,64.15 --7053.09,-6550.00,-503.09,-6407.97,-5750.00,-657.97,64.15 --6953.09,-6750.00,-203.09,-6307.97,-5350.00,-957.97,63.84 --6853.09,-6950.00,96.91,-6207.97,-5900.00,-307.97,63.56 --6753.09,-6800.00,46.91,-6107.97,-5900.00,-207.97,63.56 --6653.09,-6250.00,-403.09,-6007.97,-5300.00,-707.97,63.06 --6553.09,-6200.00,-353.09,-5907.97,-5400.00,-507.97,62.43 --6453.09,-6000.00,-453.09,-5807.97,-5300.00,-507.97,62.12 --6353.09,-5900.00,-453.09,-5707.97,-4850.00,-857.97,62.12 --6253.09,-5400.00,-853.09,-5607.97,-4650.00,-957.97,61.76 --6153.09,-5800.00,-353.09,-5507.97,-5000.00,-507.97,61.20 --6053.09,-6000.00,-53.09,-5407.97,-5000.00,-407.97,61.20 --5953.09,-5600.00,-353.09,-5307.97,-4500.00,-807.97,60.76 --5853.09,-4900.00,-953.09,-5207.97,-4000.00,-1207.97,60.56 --5753.09,-5200.00,-553.09,-5107.97,-4900.00,-207.97,60.16 --5653.09,-5150.00,-503.09,-5007.97,-4500.00,-507.97,60.16 --5553.09,-4800.00,-753.09,-4907.97,-3500.00,-1407.97,60.09 --5453.09,-4950.00,-503.09,-4807.97,-3250.00,-1557.97,59.71 --5353.09,-4950.00,-403.09,-4707.97,-4950.00,242.03,58.79 --5253.09,-4300.00,-953.09,-4607.97,-3800.00,-807.97,58.79 --5153.09,-3450.00,-1703.09,-4507.97,-2900.00,-1607.97,58.55 --5053.09,-5350.00,296.91,-4407.97,-3400.00,-1007.97,58.44 --4953.09,-4450.00,-503.09,-4307.97,-4500.00,192.03,58.03 --4853.09,-3200.00,-1653.09,-4207.97,-2200.00,-2007.97,58.03 --4753.09,-3100.00,-1653.09,-4107.97,-1800.00,-2307.97,57.82 --4653.09,-3500.00,-1153.09,-4007.97,-3350.00,-657.97,57.31 --4553.09,-3350.00,-1203.09,-3907.97,-2700.00,-1207.97,57.31 --4453.09,-3100.00,-1353.09,-3807.97,-1350.00,-2457.97,57.29 --4353.09,-3100.00,-1253.09,-3707.97,-1850.00,-1857.97,56.42 --4253.09,-3300.00,-953.09,-3607.97,-2500.00,-1107.97,55.85 --4153.09,-2600.00,-1553.09,-3507.97,-1900.00,-1607.97,55.85 --4053.09,-1700.00,-2353.09,-3407.97,-1350.00,-2057.97,55.76 --3953.09,-2150.00,-1803.09,-3307.97,0.00,-3307.97,55.79 --3853.09,-2450.00,-1403.09,-3207.97,-1900.00,-1307.97,55.52 --3753.09,-2200.00,-1553.09,-3107.97,-1300.00,-1807.97,55.52 --3653.09,-1350.00,-2303.09,-3007.97,200.00,-3207.97,55.22 --3553.09,-1450.00,-2103.09,-2907.97,-650.00,-2257.97,54.64 --3453.09,-1950.00,-1503.09,-2807.97,-1850.00,-957.97,54.64 --3353.09,-1350.00,-2003.09,-2707.97,-1300.00,-1407.97,54.95 --3253.09,150.00,-3403.09,-2607.97,700.00,-3307.97,54.87 --3153.09,-1500.00,-1653.09,-2507.97,-500.00,-2007.97,54.59 --3053.09,-1600.00,-1453.09,-2407.97,-1150.00,-1257.97,54.59 --2953.09,-50.00,-2903.09,-2307.97,0.00,-2307.97,53.92 --2853.09,-250.00,-2603.09,-2207.97,0.00,-2207.97,53.36 --2753.09,-1700.00,-1053.09,-2107.97,0.00,-2107.97,53.36 --2653.09,-1550.00,-1103.09,-2007.97,0.00,-2007.97,53.58 --2553.09,550.00,-3103.09,-1907.97,150.00,-2057.97,53.64 --2453.09,-350.00,-2103.09,-1807.97,350.00,-2157.97,53.29 --2353.09,-550.00,-1803.09,-1707.97,950.00,-2657.97,53.29 --2253.09,1150.00,-3403.09,-1607.97,450.00,-2057.97,53.87 --2153.09,-650.00,-1503.09,-1507.97,-250.00,-1257.97,53.53 --2053.09,-300.00,-1753.09,-1407.97,0.00,-1407.97,53.53 --1953.09,900.00,-2853.09,-1307.97,0.00,-1307.97,53.89 --1853.09,-500.00,-1353.09,-1207.97,0.00,-1207.97,53.76 --1753.09,150.00,-1903.09,-1107.97,0.00,-1107.97,53.76 --1653.09,700.00,-2353.09,-1007.97,0.00,-1007.97,53.87 --1553.09,-350.00,-1203.09,-907.97,0.00,-907.97,53.73 --1453.09,0.00,-1453.09,-807.97,0.00,-807.97,53.53 --1353.09,0.00,-1353.09,-707.97,0.00,-707.97,53.53 --1253.09,0.00,-1253.09,-607.97,0.00,-607.97,53.93 --1153.09,0.00,-1153.09,-507.97,0.00,-507.97,53.82 --1053.09,0.00,-1053.09,-407.97,0.00,-407.97,53.82 --953.09,0.00,-953.09,-307.97,0.00,-307.97,54.02 --853.09,0.00,-853.09,-207.97,0.00,-207.97,53.34 --753.09,0.00,-753.09,-107.97,0.00,-107.97,53.34 --653.09,0.00,-653.09,-7.97,0.00,-7.97,53.53 --553.09,0.00,-553.09,0.00,0.00,0.00,53.55 --453.09,0.00,-453.09,0.00,0.00,0.00,53.67 --353.09,0.00,-353.09,0.00,0.00,0.00,53.67 --253.09,0.00,-253.09,0.00,0.00,0.00,53.67 --153.09,0.00,-153.09,0.00,0.00,0.00,53.67 --53.09,0.00,-53.09,0.00,0.00,0.00,53.67 -0.00,0.00,0.00,0.00,0.00,0.00,53.53 -0.00,0.00,0.00,0.00,0.00,0.00,53.77 -0.00,0.00,0.00,0.00,0.00,0.00,53.77 -0.00,0.00,0.00,0.00,0.00,0.00,53.63 -0.00,0.00,0.00,0.00,0.00,0.00,53.34 -0.00,0.00,0.00,0.00,0.00,0.00,53.34 -0.00,0.00,0.00,0.00,0.00,0.00,53.45 -0.00,0.00,0.00,0.00,0.00,0.00,53.34 -0.00,0.00,0.00,0.00,0.00,0.00,53.43 -0.00,0.00,0.00,0.00,0.00,0.00,53.43 -0.00,0.00,0.00,0.00,0.00,0.00,53.79 -0.00,0.00,0.00,0.00,0.00,0.00,53.61 -0.00,0.00,0.00,0.00,0.00,0.00,53.61 -0.00,0.00,0.00,0.00,0.00,0.00,53.50 -0.00,0.00,0.00,0.00,0.00,0.00,53.41 -0.00,0.00,0.00,0.00,0.00,0.00,53.41 -0.00,0.00,0.00,0.00,0.00,0.00,53.69 -0.00,0.00,0.00,0.00,0.00,0.00,53.58 -0.00,0.00,0.00,0.00,0.00,0.00,53.58 -0.00,0.00,0.00,0.00,0.00,0.00,53.72 -0.00,0.00,0.00,0.00,0.00,0.00,53.89 -0.00,0.00,0.00,0.00,0.00,0.00,53.70 -0.00,0.00,0.00,0.00,0.00,0.00,53.70 -0.00,0.00,0.00,0.00,0.00,0.00,53.48 -0.00,0.00,0.00,0.00,0.00,0.00,53.73 -0.00,0.00,0.00,0.00,0.00,0.00,53.73 -0.00,0.00,0.00,0.00,0.00,0.00,53.19 -0.00,0.00,0.00,0.00,0.00,0.00,53.55 -0.00,0.00,0.00,0.00,0.00,0.00,53.55 -0.00,0.00,0.00,0.00,0.00,0.00,53.52 -0.00,0.00,0.00,0.00,0.00,0.00,53.62 -0.00,0.00,0.00,0.00,0.00,0.00,53.62 -0.00,0.00,0.00,0.00,0.00,0.00,53.67 -0.00,0.00,0.00,0.00,0.00,0.00,53.54 -0.00,0.00,0.00,0.00,0.00,0.00,53.67 -0.00,0.00,0.00,0.00,0.00,0.00,53.67 -0.00,0.00,0.00,0.00,0.00,0.00,53.57 -0.00,0.00,0.00,0.00,0.00,0.00,53.62 -0.00,0.00,0.00,0.00,0.00,0.00,53.62 -0.00,0.00,0.00,0.00,0.00,0.00,53.47 -0.00,0.00,0.00,0.00,0.00,0.00,54.00 -0.00,0.00,0.00,0.00,0.00,0.00,54.00 -0.00,0.00,0.00,0.00,0.00,0.00,53.78 -0.00,0.00,0.00,0.00,0.00,0.00,53.72 -0.00,0.00,0.00,0.00,0.00,0.00,53.72 -0.00,0.00,0.00,0.00,0.00,0.00,53.34 -0.00,0.00,0.00,0.00,0.00,0.00,53.79 -0.00,0.00,0.00,0.00,0.00,0.00,53.79 -0.00,0.00,0.00,0.00,0.00,0.00,53.59 -0.00,0.00,0.00,0.00,0.00,0.00,53.55 -0.00,0.00,0.00,0.00,0.00,0.00,53.59 -0.00,0.00,0.00,0.00,0.00,0.00,53.59 -0.00,0.00,0.00,0.00,0.00,0.00,53.87 -0.00,0.00,0.00,0.00,0.00,0.00,53.86 -0.00,0.00,0.00,0.00,0.00,0.00,53.86 -0.00,0.00,0.00,0.00,0.00,0.00,53.96 -0.00,0.00,0.00,0.00,0.00,0.00,53.83 -0.00,0.00,0.00,0.00,0.00,0.00,53.83 -0.00,0.00,0.00,0.00,0.00,0.00,53.97 -0.00,0.00,0.00,0.00,0.00,0.00,53.51 -0.00,0.00,0.00,0.00,0.00,0.00,53.51 -0.00,0.00,0.00,0.00,0.00,0.00,53.89 -0.00,0.00,0.00,0.00,0.00,0.00,53.62 -0.00,0.00,0.00,0.00,0.00,0.00,53.62 -0.00,0.00,0.00,0.00,0.00,0.00,53.74 -0.00,0.00,0.00,0.00,0.00,0.00,53.54 -0.00,0.00,0.00,0.00,0.00,0.00,53.59 -0.00,0.00,0.00,0.00,0.00,0.00,53.59 -100.00,0.00,100.00,100.00,0.00,100.00,54.05 -200.00,0.00,200.00,200.00,0.00,200.00,53.88 -300.00,0.00,300.00,300.00,0.00,300.00,53.88 -400.00,0.00,400.00,400.00,0.00,400.00,53.79 -500.00,0.00,500.00,500.00,0.00,500.00,53.82 -600.00,0.00,600.00,600.00,0.00,600.00,53.82 -700.00,0.00,700.00,700.00,0.00,700.00,53.75 -800.00,0.00,800.00,800.00,0.00,800.00,53.61 -900.00,0.00,900.00,900.00,0.00,900.00,53.37 -1000.00,0.00,1000.00,1000.00,0.00,1000.00,53.37 -1100.00,0.00,1100.00,1100.00,0.00,1100.00,53.60 -1200.00,0.00,1200.00,1200.00,0.00,1200.00,53.80 -1300.00,0.00,1300.00,1300.00,0.00,1300.00,53.80 -1400.00,0.00,1400.00,1400.00,0.00,1400.00,53.66 -1500.00,0.00,1500.00,1500.00,0.00,1500.00,53.44 -1600.00,0.00,1600.00,1600.00,0.00,1600.00,53.44 -1700.00,0.00,1700.00,1700.00,0.00,1700.00,53.57 -1800.00,0.00,1800.00,1800.00,0.00,1800.00,53.72 -1900.00,0.00,1900.00,1900.00,0.00,1900.00,53.59 -2000.00,0.00,2000.00,2000.00,0.00,2000.00,53.59 -2100.00,0.00,2100.00,2100.00,0.00,2100.00,53.65 -2200.00,0.00,2200.00,2200.00,0.00,2200.00,53.55 -2300.00,0.00,2300.00,2300.00,0.00,2300.00,53.55 -2400.00,0.00,2400.00,2400.00,0.00,2400.00,53.66 -2500.00,500.00,2000.00,2500.00,450.00,2050.00,53.59 -2600.00,150.00,2450.00,2600.00,450.00,2150.00,53.33 -2700.00,-350.00,3050.00,2700.00,-1050.00,3750.00,53.33 -2800.00,1350.00,1450.00,2800.00,800.00,2000.00,53.67 -2900.00,1450.00,1450.00,2900.00,1950.00,950.00,53.36 -3000.00,550.00,2450.00,3000.00,800.00,2200.00,53.36 -3100.00,250.00,2850.00,3100.00,350.00,2750.00,53.92 -3200.00,1350.00,1850.00,3200.00,900.00,2300.00,54.30 -3300.00,2200.00,1100.00,3300.00,1950.00,1350.00,54.30 -3400.00,1650.00,1750.00,3400.00,1050.00,2350.00,53.56 -3500.00,1300.00,2200.00,3500.00,-100.00,3600.00,54.11 -3600.00,1700.00,1900.00,3600.00,2350.00,1250.00,54.11 -3700.00,2550.00,1150.00,3700.00,1100.00,2600.00,54.78 -3800.00,2100.00,1700.00,3800.00,700.00,3100.00,54.54 -3900.00,1200.00,2700.00,3900.00,2950.00,950.00,55.02 -4000.00,2650.00,1350.00,4000.00,2150.00,1850.00,55.02 -4100.00,2350.00,1750.00,4100.00,1900.00,2200.00,55.33 -4200.00,2500.00,1700.00,4200.00,2100.00,2100.00,55.13 -4300.00,2550.00,1750.00,4300.00,2700.00,1600.00,55.13 -4400.00,2900.00,1500.00,4400.00,2750.00,1650.00,55.48 -4500.00,3000.00,1500.00,4500.00,3050.00,1450.00,55.64 -4600.00,3250.00,1350.00,4600.00,3150.00,1450.00,55.56 -4700.00,3550.00,1150.00,4700.00,2900.00,1800.00,55.56 -4800.00,3600.00,1200.00,4800.00,3050.00,1750.00,55.54 -4900.00,3600.00,1300.00,4900.00,3100.00,1800.00,55.70 -5000.00,3450.00,1550.00,5000.00,3100.00,1900.00,55.70 -5100.00,3700.00,1400.00,5100.00,3350.00,1750.00,55.86 -5200.00,3900.00,1300.00,5200.00,3300.00,1900.00,56.43 -5300.00,4150.00,1150.00,5300.00,3450.00,1850.00,56.43 -5400.00,4350.00,1050.00,5400.00,3700.00,1700.00,56.48 -5500.00,4300.00,1200.00,5500.00,4100.00,1400.00,56.92 -5600.00,4500.00,1100.00,5600.00,4300.00,1300.00,57.37 -5700.00,4700.00,1000.00,5700.00,4400.00,1300.00,57.37 -5800.00,4850.00,950.00,5800.00,4500.00,1300.00,57.65 -5900.00,5050.00,850.00,5900.00,4800.00,1100.00,58.00 -6000.00,5000.00,1000.00,6000.00,4650.00,1350.00,58.00 -6100.00,5050.00,1050.00,6100.00,4800.00,1300.00,58.43 -6200.00,5100.00,1100.00,6200.00,4950.00,1250.00,58.91 -6300.00,5400.00,900.00,6300.00,5100.00,1200.00,58.91 -6400.00,5500.00,900.00,6400.00,5150.00,1250.00,59.12 -6500.00,5650.00,850.00,6500.00,5400.00,1100.00,59.18 -6600.00,5950.00,650.00,6600.00,5500.00,1100.00,60.11 -6700.00,6050.00,650.00,6700.00,5700.00,1000.00,60.11 -6800.00,6350.00,450.00,6800.00,5650.00,1150.00,60.08 -6900.00,6000.00,900.00,6900.00,5350.00,1550.00,60.74 -7000.00,5950.00,1050.00,7000.00,5300.00,1700.00,60.74 -7100.00,6300.00,800.00,7100.00,5550.00,1550.00,60.79 -7200.00,6500.00,700.00,7200.00,6000.00,1200.00,61.01 -7300.00,6450.00,850.00,7300.00,6200.00,1100.00,61.01 -7400.00,6600.00,800.00,7400.00,6550.00,850.00,61.63 -7500.00,6700.00,800.00,7500.00,6850.00,650.00,61.98 -7600.00,6700.00,900.00,7600.00,6950.00,650.00,62.20 -7700.00,6800.00,900.00,7700.00,7000.00,700.00,62.20 -7800.00,7200.00,600.00,7800.00,6900.00,900.00,62.19 -7900.00,7050.00,850.00,7900.00,6950.00,950.00,62.29 -8000.00,7250.00,750.00,8000.00,7200.00,800.00,62.29 -8100.00,7400.00,700.00,8100.00,7650.00,450.00,63.16 -8200.00,7450.00,750.00,8200.00,7750.00,450.00,63.26 -8300.00,7850.00,450.00,8300.00,8200.00,100.00,63.26 -8400.00,7950.00,450.00,8400.00,7950.00,450.00,63.59 -8500.00,7900.00,600.00,8500.00,7850.00,650.00,63.77 -8600.00,8400.00,200.00,8600.00,7950.00,650.00,63.70 -8700.00,8500.00,200.00,8700.00,8150.00,550.00,63.70 -8800.00,8700.00,100.00,8800.00,8100.00,700.00,64.15 -8900.00,8850.00,50.00,8900.00,8750.00,150.00,64.45 -9000.00,9200.00,-200.00,9000.00,9250.00,-250.00,64.45 -9100.00,9350.00,-250.00,9100.00,9400.00,-300.00,64.99 -9200.00,8950.00,250.00,9200.00,8800.00,400.00,64.88 -9300.00,9150.00,150.00,9300.00,8800.00,500.00,64.88 -9400.00,9550.00,-150.00,9400.00,9300.00,100.00,64.89 -9500.00,9550.00,-50.00,9500.00,9250.00,250.00,64.63 -9600.00,9800.00,-200.00,9600.00,9000.00,600.00,65.01 -9700.00,10100.00,-400.00,9700.00,9150.00,550.00,65.01 -9800.00,12350.00,-2550.00,9800.00,10950.00,-1150.00,65.09 -9900.00,10500.00,-600.00,9900.00,9750.00,150.00,65.34 -10000.00,8650.00,1350.00,10000.00,9350.00,650.00,65.36 -10100.00,10300.00,-200.00,10100.00,9650.00,450.00,65.36 -10200.00,9700.00,500.00,10200.00,9850.00,350.00,64.95 -10300.00,10100.00,200.00,10300.00,9750.00,550.00,64.73 -10400.00,10750.00,-350.00,10400.00,10500.00,-100.00,64.73 -10500.00,11250.00,-750.00,10500.00,11000.00,-500.00,64.66 -10600.00,11800.00,-1200.00,10600.00,11250.00,-650.00,65.14 -10700.00,11500.00,-800.00,10700.00,10950.00,-250.00,65.14 -10800.00,11500.00,-700.00,10800.00,10800.00,0.00,64.85 -10900.00,11300.00,-400.00,10900.00,10950.00,-50.00,64.33 -11000.00,11700.00,-700.00,11000.00,11250.00,-250.00,64.05 -11100.00,11800.00,-700.00,11100.00,11300.00,-200.00,64.05 -11200.00,11700.00,-500.00,11200.00,11300.00,-100.00,63.84 -11300.00,12450.00,-1150.00,11300.00,12200.00,-900.00,63.56 -11400.00,12450.00,-1050.00,11400.00,11900.00,-500.00,63.48 -11500.00,12550.00,-1050.00,11500.00,11700.00,-200.00,63.48 -11600.00,12850.00,-1250.00,11600.00,11900.00,-300.00,63.03 -11700.00,13150.00,-1450.00,11700.00,12550.00,-850.00,63.07 -11800.00,12650.00,-850.00,11800.00,12650.00,-850.00,63.07 -11900.00,12500.00,-600.00,11900.00,12550.00,-650.00,62.59 -12000.00,13100.00,-1100.00,12000.00,12900.00,-900.00,62.46 -12100.00,12650.00,-550.00,12100.00,12450.00,-350.00,62.11 -12200.00,13050.00,-850.00,12200.00,12700.00,-500.00,62.11 -12300.00,13300.00,-1000.00,12300.00,12750.00,-450.00,63.11 -12400.00,14050.00,-1650.00,12400.00,12700.00,-300.00,62.69 -12500.00,13650.00,-1150.00,12500.00,11950.00,550.00,62.69 -12600.00,13650.00,-1050.00,12600.00,12000.00,600.00,62.59 -12700.00,13100.00,-400.00,12700.00,12400.00,300.00,62.64 -12800.00,13400.00,-600.00,12800.00,14100.00,-1300.00,62.99 -12900.00,13350.00,-450.00,12900.00,14900.00,-2000.00,62.99 -13000.00,13800.00,-800.00,13000.00,15250.00,-2250.00,64.03 -13100.00,14900.00,-1800.00,13100.00,15350.00,-2250.00,64.26 -13200.00,15250.00,-2050.00,13200.00,14650.00,-1450.00,64.91 -13300.00,14600.00,-1300.00,13300.00,14150.00,-850.00,64.91 -13400.00,14700.00,-1300.00,13400.00,14500.00,-1100.00,65.59 -13500.00,14800.00,-1300.00,13500.00,14650.00,-1150.00,66.15 -13600.00,14250.00,-650.00,13600.00,14500.00,-900.00,66.15 -13700.00,14900.00,-1200.00,13700.00,14650.00,-950.00,66.96 -13800.00,15400.00,-1600.00,13800.00,14450.00,-650.00,67.76 -13900.00,15300.00,-1400.00,13900.00,14300.00,-400.00,68.76 -14000.00,15750.00,-1750.00,14000.00,15450.00,-1450.00,68.76 -14100.00,16000.00,-1900.00,14100.00,15500.00,-1400.00,69.69 -14200.00,15400.00,-1200.00,14200.00,14600.00,-400.00,70.52 -14300.00,15700.00,-1400.00,14300.00,14900.00,-600.00,70.52 -14400.00,16350.00,-1950.00,14400.00,15650.00,-1250.00,71.62 -14500.00,16000.00,-1500.00,14500.00,15050.00,-550.00,72.80 -14600.00,16250.00,-1650.00,14600.00,15350.00,-750.00,73.67 -14700.00,16900.00,-2200.00,14700.00,15650.00,-950.00,73.67 -14800.00,17100.00,-2300.00,14800.00,16000.00,-1200.00,74.41 -14900.00,16300.00,-1400.00,14900.00,15800.00,-900.00,75.67 -15000.00,16150.00,-1150.00,15000.00,16050.00,-1050.00,77.18 -15100.00,16400.00,-1300.00,15100.00,16150.00,-1050.00,77.18 -15200.00,17100.00,-1900.00,15200.00,16500.00,-1300.00,78.24 -15300.00,17450.00,-2150.00,15300.00,16800.00,-1500.00,78.13 -15400.00,17350.00,-1950.00,15400.00,16200.00,-800.00,78.13 -15500.00,17550.00,-2050.00,15500.00,16850.00,-1350.00,79.48 -15600.00,17750.00,-2150.00,15600.00,17150.00,-1550.00,79.88 -15700.00,17550.00,-1850.00,15700.00,17000.00,-1300.00,80.67 -15800.00,17500.00,-1700.00,15800.00,17100.00,-1300.00,80.67 -15900.00,17750.00,-1850.00,15900.00,17100.00,-1200.00,81.19 -16000.00,18100.00,-2100.00,16000.00,17600.00,-1600.00,81.80 -16100.00,17750.00,-1650.00,16100.00,17700.00,-1600.00,82.41 -16200.00,18200.00,-2000.00,16200.00,17850.00,-1650.00,82.41 -16300.00,18450.00,-2150.00,16300.00,17800.00,-1500.00,83.55 -16400.00,18800.00,-2400.00,16400.00,18150.00,-1750.00,83.72 -16500.00,18700.00,-2200.00,16500.00,18200.00,-1700.00,83.72 -16600.00,18650.00,-2050.00,16600.00,18400.00,-1800.00,84.19 -16700.00,18700.00,-2000.00,16700.00,18650.00,-1950.00,84.36 -16800.00,22000.00,-5200.00,16800.00,21500.00,-4700.00,84.82 -16900.00,18550.00,-1650.00,16900.00,18050.00,-1150.00,84.82 -17000.00,18250.00,-1250.00,17000.00,17900.00,-900.00,85.02 -17100.00,18600.00,-1500.00,17100.00,18400.00,-1300.00,84.85 -17200.00,18750.00,-1550.00,17200.00,18500.00,-1300.00,84.73 -17300.00,19350.00,-2050.00,17166.22,18600.00,-1433.78,84.73 -17400.00,19450.00,-2050.00,17066.22,18750.00,-1683.78,85.59 -17500.00,19950.00,-2450.00,16966.22,19350.00,-2383.78,85.52 -17428.56,19850.00,-2421.44,16866.22,19300.00,-2433.78,85.89 -17328.56,19500.00,-2171.44,16766.22,18800.00,-2033.78,85.89 -17228.56,20550.00,-3321.44,16666.22,19100.00,-2433.78,86.99 -17128.56,20400.00,-3271.44,16566.22,18900.00,-2333.78,86.71 -17028.56,19750.00,-2721.44,16466.22,18200.00,-1733.78,86.71 -16928.56,19600.00,-2671.44,16366.22,18050.00,-1683.78,87.00 -16828.56,19150.00,-2321.44,16266.22,18200.00,-1933.78,87.18 -16728.56,19000.00,-2271.44,16166.22,18350.00,-2183.78,87.97 -16628.56,19000.00,-2371.44,16066.22,18300.00,-2233.78,87.97 -16528.56,18950.00,-2421.44,15966.22,17850.00,-1883.78,88.39 -16428.56,19350.00,-2921.44,15866.22,17900.00,-2033.78,88.62 -16328.56,19450.00,-3121.44,15766.22,17650.00,-1883.78,88.69 -16228.56,18600.00,-2371.44,15666.22,17450.00,-1783.78,88.69 -16128.56,18300.00,-2171.44,15566.22,17650.00,-2083.78,88.62 -16028.56,18700.00,-2671.44,15466.22,17750.00,-2283.78,88.44 -15928.56,18100.00,-2171.44,15366.22,17200.00,-1833.78,88.44 -15828.56,17750.00,-1921.44,15266.22,16900.00,-1633.78,88.42 -15728.56,17750.00,-2021.44,15166.22,17100.00,-1933.78,88.49 -15628.56,17750.00,-2121.44,15066.22,17300.00,-2233.78,88.47 -15528.56,17100.00,-1571.44,14966.22,16850.00,-1883.78,88.47 -15428.56,17650.00,-2221.44,14866.22,16950.00,-2083.78,87.75 -15328.56,17700.00,-2371.44,14766.22,16400.00,-1633.78,86.54 -15228.56,17200.00,-1971.44,14666.22,16050.00,-1383.78,86.80 -15128.56,17050.00,-1921.44,14566.22,16200.00,-1633.78,86.80 -15028.56,17050.00,-2021.44,14466.22,16750.00,-2283.78,85.78 -14928.56,16700.00,-1771.44,14366.22,16300.00,-1933.78,84.67 -14828.56,16700.00,-1871.44,14266.22,16100.00,-1833.78,84.67 -14728.56,16750.00,-2021.44,14166.22,15850.00,-1683.78,83.27 -14628.56,16400.00,-1771.44,14066.22,15200.00,-1133.78,81.73 -14528.56,15550.00,-1021.44,13966.22,14350.00,-383.78,80.47 -14428.56,16650.00,-2221.44,13866.22,15750.00,-1883.78,80.47 -14328.56,16750.00,-2421.44,13766.22,16000.00,-2233.78,78.46 -14228.56,15350.00,-1121.44,13666.22,14200.00,-533.78,76.36 -14128.56,15250.00,-1121.44,13566.22,14000.00,-433.78,76.36 -14028.56,16300.00,-2271.44,13466.22,15000.00,-1533.78,75.75 -13928.56,16250.00,-2321.44,13366.22,14600.00,-1233.78,74.13 -13828.56,16050.00,-2221.44,13266.22,14900.00,-1633.78,72.85 -13728.56,15900.00,-2171.44,13166.22,15100.00,-1933.78,72.85 -13628.56,15400.00,-1771.44,13066.22,14400.00,-1333.78,70.28 -13528.56,15550.00,-2021.44,12966.22,14000.00,-1033.78,67.94 -13428.56,15250.00,-1821.44,12866.22,13900.00,-1033.78,67.94 -13328.56,14900.00,-1571.44,12766.22,14000.00,-1233.78,65.69 -13228.56,14600.00,-1371.44,12666.22,13500.00,-833.78,63.24 -13128.56,14400.00,-1271.44,12566.22,13200.00,-633.78,61.64 -13028.56,14750.00,-1721.44,12466.22,13900.00,-1433.78,61.64 -12928.56,14700.00,-1771.44,12366.22,13900.00,-1533.78,59.51 -12828.56,14600.00,-1771.44,12266.22,13400.00,-1133.78,57.52 -12728.56,14550.00,-1821.44,12166.22,13200.00,-1033.78,54.77 -12628.56,14250.00,-1621.44,12066.22,12900.00,-833.78,54.77 -12528.56,14250.00,-1721.44,11966.22,13050.00,-1083.78,53.75 -12428.56,14100.00,-1671.44,11866.22,13300.00,-1433.78,51.44 -12328.56,13300.00,-971.44,11766.22,12550.00,-783.78,51.44 -12228.56,13350.00,-1121.44,11666.22,12400.00,-733.78,48.68 -12128.56,13750.00,-1621.44,11566.22,12700.00,-1133.78,47.52 -12028.56,13550.00,-1521.44,11466.22,12750.00,-1283.78,45.24 -11928.56,13000.00,-1071.44,11366.22,12150.00,-783.78,45.24 -11828.56,12750.00,-921.44,11266.22,12150.00,-883.78,43.98 -11728.56,12850.00,-1121.44,11166.22,12250.00,-1083.78,42.92 -11628.56,12850.00,-1221.44,11066.22,12300.00,-1233.78,41.14 -11528.56,12500.00,-971.44,10966.22,12050.00,-1083.78,41.14 -11428.56,12450.00,-1021.44,10866.22,11950.00,-1083.78,40.38 -11328.56,14750.00,-3421.44,10766.22,14000.00,-3233.78,39.85 -11228.56,11450.00,-221.44,10666.22,10600.00,66.22,38.62 -11128.56,10100.00,1028.56,10566.22,9000.00,1566.22,38.62 -11028.56,11900.00,-871.44,10466.22,11450.00,-983.78,39.36 -10928.56,11550.00,-621.44,10366.22,10800.00,-433.78,37.97 -10828.56,10950.00,-121.44,10266.22,10200.00,66.22,37.97 -10728.56,11600.00,-871.44,10166.22,11200.00,-1033.78,38.29 -10628.56,11300.00,-671.44,10066.22,11000.00,-933.78,37.68 -10528.56,11550.00,-1021.44,9966.22,11200.00,-1233.78,37.95 -10428.56,11500.00,-1071.44,9866.22,10850.00,-983.78,37.95 -10328.56,10650.00,-321.44,9766.22,9600.00,166.22,38.12 -10228.56,11100.00,-871.44,9666.22,10100.00,-433.78,38.65 -10128.56,11550.00,-1421.44,9566.22,9800.00,-233.78,38.65 -10028.56,11500.00,-1471.44,9466.22,9700.00,-233.78,38.33 -9928.56,11100.00,-1171.44,9366.22,9700.00,-333.78,38.85 -9828.56,10500.00,-671.44,9266.22,9550.00,-283.78,39.29 -9728.56,10200.00,-471.44,9166.22,9450.00,-283.78,39.29 -9628.56,9800.00,-171.44,9066.22,9000.00,66.22,40.22 -9528.56,10250.00,-721.44,8966.22,9600.00,-633.78,41.02 -9428.56,10100.00,-671.44,8866.22,9250.00,-383.78,41.35 -9328.56,10300.00,-971.44,8766.22,8800.00,-33.78,41.35 -9228.56,10200.00,-971.44,8666.22,8400.00,266.22,41.98 -9128.56,9850.00,-721.44,8566.22,8150.00,416.22,43.08 -9028.56,9700.00,-671.44,8466.22,8100.00,366.22,43.08 -8928.56,9500.00,-571.44,8366.22,8800.00,-433.78,43.89 -8828.56,9150.00,-321.44,8266.22,8600.00,-333.78,44.46 -8728.56,8800.00,-71.44,8166.22,8100.00,66.22,45.22 -8628.56,8950.00,-321.44,8066.22,8050.00,16.22,45.22 -8528.56,9100.00,-571.44,7966.22,8050.00,-83.78,45.58 -8428.56,8750.00,-321.44,7866.22,8000.00,-133.78,46.88 -8328.56,8900.00,-571.44,7766.22,8150.00,-383.78,46.88 -8228.56,8550.00,-321.44,7666.22,7950.00,-283.78,47.06 -8128.56,8500.00,-371.44,7566.22,7500.00,66.22,48.03 -8028.56,8300.00,-271.44,7466.22,6900.00,566.22,48.03 -7928.56,8050.00,-121.44,7366.22,6600.00,766.22,48.68 -7828.56,7900.00,-71.44,7266.22,6500.00,766.22,49.68 -7728.56,7650.00,78.56,7166.22,6850.00,316.22,50.01 -7628.56,7500.00,128.56,7066.22,6650.00,416.22,50.01 -7528.56,7300.00,228.56,6966.22,6600.00,366.22,50.05 -7428.56,7450.00,-21.44,6866.22,6400.00,466.22,50.73 -7328.56,7750.00,-421.44,6766.22,6500.00,266.22,50.73 -7228.56,7650.00,-421.44,6666.22,6350.00,316.22,51.86 -7128.56,7600.00,-471.44,6566.22,6600.00,-33.78,52.04 -7028.56,7250.00,-221.44,6466.22,6450.00,16.22,52.58 -6928.56,6750.00,178.56,6366.22,6100.00,266.22,52.58 -6828.56,6900.00,-71.44,6266.22,6300.00,-33.78,53.36 -6728.56,6550.00,178.56,6166.22,6150.00,16.22,53.50 -6628.56,6050.00,578.56,6066.22,5450.00,616.22,53.50 -6528.56,6100.00,428.56,5966.22,5000.00,966.22,54.23 -6428.56,6250.00,178.56,5866.22,5800.00,66.22,54.79 -6328.56,5900.00,428.56,5766.22,4800.00,966.22,54.79 -6228.56,5700.00,528.56,5666.22,4300.00,1366.22,54.75 -6128.56,5850.00,278.56,5566.22,4700.00,866.22,55.42 -6028.56,5600.00,428.56,5466.22,4700.00,766.22,55.33 -5928.56,5350.00,578.56,5366.22,4600.00,766.22,55.33 -5828.56,5450.00,378.56,5266.22,4800.00,466.22,55.78 -5728.56,5400.00,328.56,5166.22,4450.00,716.22,56.19 -5628.56,5050.00,578.56,5066.22,4050.00,1016.22,56.19 -5528.56,5050.00,478.56,4966.22,3900.00,1066.22,56.50 -5428.56,4750.00,678.56,4866.22,4000.00,866.22,56.56 -5328.56,4650.00,678.56,4766.22,3950.00,816.22,56.56 -5228.56,4500.00,728.56,4666.22,3550.00,1116.22,56.55 -5128.56,4350.00,778.56,4566.22,3200.00,1366.22,56.94 -5028.56,4350.00,678.56,4466.22,3300.00,1166.22,57.56 -4928.56,3850.00,1078.56,4366.22,3450.00,916.22,57.56 -4828.56,3400.00,1428.56,4266.22,3250.00,1016.22,57.16 -4728.56,3550.00,1178.56,4166.22,2200.00,1966.22,57.63 -4628.56,3650.00,978.56,4066.22,2200.00,1866.22,57.63 -4528.56,3400.00,1128.56,3966.22,3200.00,766.22,57.65 -4428.56,2650.00,1778.56,3866.22,2400.00,1466.22,58.10 -4328.56,2500.00,1828.56,3766.22,800.00,2966.22,58.10 -4228.56,3600.00,628.56,3666.22,3900.00,-233.78,58.17 -4128.56,2500.00,1628.56,3566.22,1900.00,1666.22,58.27 -4028.56,2250.00,1778.56,3466.22,-200.00,3666.22,58.35 -3928.56,2650.00,1278.56,3366.22,1600.00,1766.22,58.35 -3828.56,2600.00,1228.56,3266.22,2100.00,1166.22,59.05 -3728.56,900.00,2828.56,3166.22,-800.00,3966.22,59.07 -3628.56,750.00,2878.56,3066.22,800.00,2266.22,59.07 -3528.56,2700.00,828.56,2966.22,2800.00,166.22,59.59 -3428.56,1000.00,2428.56,2866.22,350.00,2516.22,59.16 -3328.56,1150.00,2178.56,2766.22,-300.00,3066.22,59.61 -3228.56,2350.00,878.56,2666.22,1700.00,966.22,59.61 -3128.56,1800.00,1328.56,2566.22,1150.00,1416.22,59.58 -3028.56,50.00,2978.56,2466.22,-450.00,2916.22,60.33 -2928.56,650.00,2278.56,2366.22,1150.00,1216.22,60.33 -2828.56,1600.00,1228.56,2266.22,2050.00,216.22,59.87 -2728.56,900.00,1828.56,2166.22,150.00,2016.22,59.61 -2628.56,-100.00,2728.56,2066.22,50.00,2016.22,59.61 -2528.56,550.00,1978.56,1966.22,100.00,1866.22,60.21 -2428.56,350.00,2078.56,1866.22,0.00,1866.22,59.85 -2328.56,-950.00,3278.56,1766.22,0.00,1766.22,59.76 -2228.56,600.00,1628.56,1666.22,0.00,1666.22,59.76 -2128.56,-200.00,2328.56,1566.22,0.00,1566.22,59.91 -2028.56,-550.00,2578.56,1466.22,-50.00,1516.22,60.26 -1928.56,650.00,1278.56,1366.22,0.00,1366.22,60.26 -1828.56,-50.00,1878.56,1266.22,0.00,1266.22,59.81 -1728.56,-650.00,2378.56,1166.22,0.00,1166.22,60.03 -1628.56,200.00,1428.56,1066.22,0.00,1066.22,60.03 -1528.56,0.00,1528.56,966.22,0.00,966.22,59.92 -1428.56,0.00,1428.56,866.22,0.00,866.22,59.96 -1328.56,0.00,1328.56,766.22,0.00,766.22,59.96 -1228.56,0.00,1228.56,666.22,0.00,666.22,60.00 -1128.56,0.00,1128.56,566.22,0.00,566.22,60.07 -1028.56,0.00,1028.56,466.22,0.00,466.22,59.51 -928.56,0.00,928.56,366.22,0.00,366.22,59.51 -828.56,0.00,828.56,266.22,0.00,266.22,59.66 -728.56,0.00,728.56,166.22,0.00,166.22,59.46 -628.56,0.00,628.56,66.22,0.00,66.22,59.46 -528.56,0.00,528.56,0.00,0.00,0.00,59.94 -428.56,0.00,428.56,0.00,0.00,0.00,60.11 -328.56,0.00,328.56,0.00,0.00,0.00,60.11 -228.56,0.00,228.56,0.00,0.00,0.00,60.04 -128.56,0.00,128.56,0.00,0.00,0.00,59.64 -28.56,0.00,28.56,0.00,0.00,0.00,59.59 -0.00,0.00,0.00,0.00,0.00,0.00,59.59 -0.00,0.00,0.00,0.00,0.00,0.00,59.65 -0.00,0.00,0.00,0.00,0.00,0.00,59.44 -0.00,0.00,0.00,0.00,0.00,0.00,59.44 -0.00,0.00,0.00,0.00,0.00,0.00,59.25 -0.00,0.00,0.00,0.00,0.00,0.00,59.37 -0.00,0.00,0.00,0.00,0.00,0.00,59.37 -0.00,0.00,0.00,0.00,0.00,0.00,59.43 -0.00,0.00,0.00,0.00,0.00,0.00,59.65 -0.00,0.00,0.00,0.00,0.00,0.00,59.65 -0.00,0.00,0.00,0.00,0.00,0.00,59.70 -0.00,0.00,0.00,0.00,0.00,0.00,59.66 -0.00,0.00,0.00,0.00,0.00,0.00,59.37 -0.00,0.00,0.00,0.00,0.00,0.00,59.37 -0.00,0.00,0.00,0.00,0.00,0.00,59.84 -0.00,0.00,0.00,0.00,0.00,0.00,59.57 -0.00,0.00,0.00,0.00,0.00,0.00,59.57 -0.00,0.00,0.00,0.00,0.00,0.00,59.37 -0.00,0.00,0.00,0.00,0.00,0.00,59.15 -0.00,0.00,0.00,0.00,0.00,0.00,59.15 -0.00,0.00,0.00,0.00,0.00,0.00,59.52 -0.00,0.00,0.00,0.00,0.00,0.00,59.57 -0.00,0.00,0.00,0.00,0.00,0.00,59.57 -0.00,0.00,0.00,0.00,0.00,0.00,59.48 -0.00,0.00,0.00,0.00,0.00,0.00,59.46 -0.00,0.00,0.00,0.00,0.00,0.00,59.24 -0.00,0.00,0.00,0.00,0.00,0.00,59.24 -0.00,0.00,0.00,0.00,0.00,0.00,59.62 -0.00,0.00,0.00,0.00,0.00,0.00,59.45 -0.00,0.00,0.00,0.00,0.00,0.00,59.45 -0.00,0.00,0.00,0.00,0.00,0.00,59.69 -0.00,0.00,0.00,0.00,0.00,0.00,59.52 -0.00,0.00,0.00,0.00,0.00,0.00,59.82 -0.00,0.00,0.00,0.00,0.00,0.00,59.82 -0.00,0.00,0.00,0.00,0.00,0.00,59.96 -0.00,0.00,0.00,0.00,0.00,0.00,59.96 -0.00,0.00,0.00,0.00,0.00,0.00,59.96 -0.00,0.00,0.00,0.00,0.00,0.00,59.97 -0.00,0.00,0.00,0.00,0.00,0.00,59.35 -0.00,0.00,0.00,0.00,0.00,0.00,59.35 -0.00,0.00,0.00,0.00,0.00,0.00,59.66 -0.00,0.00,0.00,0.00,0.00,0.00,59.91 -0.00,0.00,0.00,0.00,0.00,0.00,59.91 -0.00,0.00,0.00,0.00,0.00,0.00,59.77 -0.00,0.00,0.00,0.00,0.00,0.00,59.64 -0.00,0.00,0.00,0.00,0.00,0.00,59.64 -0.00,0.00,0.00,0.00,0.00,0.00,59.84 -0.00,0.00,0.00,0.00,0.00,0.00,59.73 -0.00,0.00,0.00,0.00,0.00,0.00,60.11 -0.00,0.00,0.00,0.00,0.00,0.00,60.11 -0.00,0.00,0.00,0.00,0.00,0.00,59.67 -0.00,0.00,0.00,0.00,0.00,0.00,59.77 -0.00,0.00,0.00,0.00,0.00,0.00,59.77 -0.00,0.00,0.00,0.00,0.00,0.00,59.64 -0.00,0.00,0.00,0.00,0.00,0.00,59.82 -0.00,0.00,0.00,0.00,0.00,0.00,59.82 -0.00,0.00,0.00,0.00,0.00,0.00,59.65 -0.00,0.00,0.00,0.00,0.00,0.00,59.81 -0.00,0.00,0.00,0.00,0.00,0.00,59.81 -0.00,0.00,0.00,0.00,0.00,0.00,59.81 -0.00,0.00,0.00,0.00,0.00,0.00,59.95 -0.00,0.00,0.00,0.00,0.00,0.00,59.94 -0.00,0.00,0.00,0.00,0.00,0.00,59.94 -0.00,0.00,0.00,0.00,0.00,0.00,59.79 -0.00,0.00,0.00,0.00,0.00,0.00,59.82 -0.00,0.00,0.00,0.00,0.00,0.00,59.82 -0.00,0.00,0.00,0.00,0.00,0.00,59.56 -0.00,0.00,0.00,0.00,0.00,0.00,59.86 -0.00,0.00,0.00,0.00,0.00,0.00,60.13 -0.00,0.00,0.00,0.00,0.00,0.00,60.13 -0.00,0.00,0.00,0.00,0.00,0.00,59.79 -0.00,0.00,0.00,0.00,0.00,0.00,60.21 -0.00,0.00,0.00,0.00,0.00,0.00,60.21 -0.00,0.00,0.00,0.00,0.00,0.00,59.72 --100.00,0.00,-100.00,-100.00,0.00,-100.00,59.67 --200.00,0.00,-200.00,-200.00,0.00,-200.00,59.67 --300.00,0.00,-300.00,-300.00,0.00,-300.00,59.74 --400.00,0.00,-400.00,-400.00,0.00,-400.00,59.88 --500.00,0.00,-500.00,-500.00,0.00,-500.00,59.85 --600.00,0.00,-600.00,-600.00,0.00,-600.00,59.85 --700.00,0.00,-700.00,-700.00,0.00,-700.00,59.97 --800.00,0.00,-800.00,-800.00,0.00,-800.00,60.03 --900.00,0.00,-900.00,-900.00,0.00,-900.00,60.03 --1000.00,0.00,-1000.00,-1000.00,0.00,-1000.00,59.86 --1100.00,0.00,-1100.00,-1100.00,0.00,-1100.00,59.83 --1200.00,0.00,-1200.00,-1200.00,0.00,-1200.00,59.83 --1300.00,0.00,-1300.00,-1300.00,0.00,-1300.00,59.68 --1400.00,0.00,-1400.00,-1400.00,0.00,-1400.00,59.44 --1500.00,0.00,-1500.00,-1500.00,0.00,-1500.00,59.76 --1600.00,0.00,-1600.00,-1600.00,0.00,-1600.00,59.76 --1700.00,0.00,-1700.00,-1700.00,0.00,-1700.00,59.56 --1800.00,0.00,-1800.00,-1800.00,0.00,-1800.00,60.00 --1900.00,0.00,-1900.00,-1900.00,0.00,-1900.00,60.00 --2000.00,0.00,-2000.00,-2000.00,0.00,-2000.00,59.97 --2100.00,0.00,-2100.00,-2100.00,0.00,-2100.00,59.72 --2200.00,0.00,-2200.00,-2200.00,0.00,-2200.00,59.72 --2300.00,0.00,-2300.00,-2300.00,0.00,-2300.00,59.88 --2400.00,0.00,-2400.00,-2400.00,0.00,-2400.00,59.83 --2500.00,-400.00,-2100.00,-2500.00,-300.00,-2200.00,60.05 --2600.00,-150.00,-2450.00,-2600.00,-750.00,-1850.00,60.05 --2700.00,200.00,-2900.00,-2700.00,600.00,-3300.00,59.72 --2800.00,-1350.00,-1450.00,-2800.00,-450.00,-2350.00,60.47 --2900.00,-1500.00,-1400.00,-2900.00,-2200.00,-700.00,60.31 --3000.00,-350.00,-2650.00,-3000.00,-1000.00,-2000.00,60.31 --3100.00,-350.00,-2750.00,-3100.00,200.00,-3300.00,59.55 --3200.00,-1950.00,-1250.00,-3200.00,-1800.00,-1400.00,59.90 --3300.00,-1800.00,-1500.00,-3300.00,-1300.00,-2000.00,59.90 --3400.00,250.00,-3650.00,-3400.00,200.00,-3600.00,59.76 --3500.00,-750.00,-2750.00,-3500.00,-2000.00,-1500.00,59.91 --3600.00,-2150.00,-1450.00,-3600.00,-1850.00,-1750.00,59.65 --3700.00,-1400.00,-2300.00,-3700.00,250.00,-3950.00,59.65 --3800.00,-1800.00,-2000.00,-3800.00,-2100.00,-1700.00,59.57 --3900.00,-2200.00,-1700.00,-3900.00,-2500.00,-1400.00,60.22 --4000.00,-1850.00,-2150.00,-4000.00,-2200.00,-1800.00,60.22 --4100.00,-2300.00,-1800.00,-4100.00,-1900.00,-2200.00,59.91 --4200.00,-2900.00,-1300.00,-4200.00,-2900.00,-1300.00,59.48 --4300.00,-2850.00,-1450.00,-4300.00,-2650.00,-1650.00,59.61 --4400.00,-2900.00,-1500.00,-4400.00,-2850.00,-1550.00,59.61 --4500.00,-3500.00,-1000.00,-4500.00,-3100.00,-1400.00,59.55 --4600.00,-3400.00,-1200.00,-4600.00,-3000.00,-1600.00,59.45 --4700.00,-3050.00,-1650.00,-4700.00,-2700.00,-2000.00,59.54 --4800.00,-3400.00,-1400.00,-4800.00,-3100.00,-1700.00,59.54 --4900.00,-3850.00,-1050.00,-4900.00,-3600.00,-1300.00,59.95 --5000.00,-3950.00,-1050.00,-5000.00,-3800.00,-1200.00,59.50 --5100.00,-4050.00,-1050.00,-5100.00,-3750.00,-1350.00,59.50 --5200.00,-4200.00,-1000.00,-5200.00,-3850.00,-1350.00,59.36 --5300.00,-4250.00,-1050.00,-5300.00,-4000.00,-1300.00,59.19 --5400.00,-4450.00,-950.00,-5400.00,-4400.00,-1000.00,59.28 --5500.00,-4350.00,-1150.00,-5500.00,-4400.00,-1100.00,59.28 --5600.00,-4500.00,-1100.00,-5600.00,-4400.00,-1200.00,59.46 --5700.00,-4850.00,-850.00,-5700.00,-4700.00,-1000.00,58.82 --5800.00,-4850.00,-950.00,-5800.00,-4700.00,-1100.00,58.82 --5900.00,-5050.00,-850.00,-5900.00,-4750.00,-1150.00,58.99 --6000.00,-5000.00,-1000.00,-6000.00,-5100.00,-900.00,58.86 --6100.00,-5100.00,-1000.00,-6100.00,-5050.00,-1050.00,58.78 --6200.00,-5150.00,-1050.00,-6200.00,-5350.00,-850.00,58.78 --6300.00,-5250.00,-1050.00,-6300.00,-5550.00,-750.00,58.99 --6400.00,-5150.00,-1250.00,-6400.00,-5300.00,-1100.00,58.78 --6500.00,-5550.00,-950.00,-6500.00,-5350.00,-1150.00,58.19 --6600.00,-5900.00,-700.00,-6600.00,-5500.00,-1100.00,58.19 --6700.00,-6250.00,-450.00,-6700.00,-5450.00,-1250.00,57.95 --6800.00,-6450.00,-350.00,-6800.00,-5600.00,-1200.00,56.80 --6900.00,-6850.00,-50.00,-6900.00,-5750.00,-1150.00,56.80 --7000.00,-6600.00,-400.00,-7000.00,-5850.00,-1150.00,56.56 --7100.00,-6200.00,-900.00,-7100.00,-6000.00,-1100.00,56.06 --7200.00,-6350.00,-850.00,-7200.00,-6150.00,-1050.00,55.88 --7300.00,-6450.00,-850.00,-7300.00,-6350.00,-950.00,55.88 --7400.00,-6600.00,-800.00,-7400.00,-6550.00,-850.00,55.28 --7500.00,-6600.00,-900.00,-7500.00,-6550.00,-950.00,54.90 --7600.00,-6650.00,-950.00,-7600.00,-6700.00,-900.00,54.91 --7700.00,-6650.00,-1050.00,-7700.00,-7100.00,-600.00,54.91 --7800.00,-6700.00,-1100.00,-7800.00,-7250.00,-550.00,54.44 --7900.00,-7150.00,-750.00,-7900.00,-7450.00,-450.00,54.23 --8000.00,-7650.00,-350.00,-8000.00,-7600.00,-400.00,54.23 --8100.00,-8100.00,0.00,-8100.00,-7450.00,-650.00,53.95 --8200.00,-8050.00,-150.00,-8200.00,-7650.00,-550.00,53.36 --8300.00,-8000.00,-300.00,-8300.00,-7700.00,-600.00,52.59 --8400.00,-8150.00,-250.00,-8400.00,-8050.00,-350.00,52.59 --8500.00,-8450.00,-50.00,-8500.00,-8250.00,-250.00,52.05 --8600.00,-8700.00,100.00,-8600.00,-8300.00,-300.00,52.26 --8700.00,-8650.00,-50.00,-8700.00,-8450.00,-250.00,51.48 --8800.00,-8700.00,-100.00,-8800.00,-8500.00,-300.00,51.48 --8900.00,-8550.00,-350.00,-8900.00,-8950.00,50.00,50.77 --9000.00,-8650.00,-350.00,-9000.00,-9250.00,250.00,50.37 --9100.00,-9050.00,-50.00,-9100.00,-9650.00,550.00,50.37 --9200.00,-9300.00,100.00,-9200.00,-9700.00,500.00,50.20 --9300.00,-9400.00,100.00,-9300.00,-9100.00,-200.00,50.00 --9400.00,-9750.00,350.00,-9400.00,-9300.00,-100.00,49.74 --9500.00,-9500.00,0.00,-9500.00,-9000.00,-500.00,49.74 --9600.00,-9150.00,-450.00,-9600.00,-9000.00,-600.00,49.73 --9700.00,-11150.00,1450.00,-9700.00,-11150.00,1450.00,49.48 --9800.00,-9700.00,-100.00,-9800.00,-9750.00,-50.00,49.74 --9900.00,-9700.00,-200.00,-9900.00,-9700.00,-200.00,49.74 --10000.00,-9800.00,-200.00,-10000.00,-10400.00,400.00,49.89 --10100.00,-9900.00,-200.00,-10100.00,-10000.00,-100.00,50.57 --10200.00,-10000.00,-200.00,-10200.00,-10200.00,0.00,49.90 --10300.00,-11050.00,750.00,-10300.00,-10800.00,500.00,49.90 --10400.00,-11050.00,650.00,-10400.00,-10400.00,0.00,51.11 --10500.00,-10400.00,-100.00,-10500.00,-9800.00,-700.00,51.47 --10600.00,-10750.00,150.00,-10600.00,-10700.00,100.00,51.47 --10700.00,-11200.00,500.00,-10700.00,-11300.00,600.00,51.90 --10800.00,-11650.00,850.00,-10800.00,-11300.00,500.00,53.17 --10900.00,-11250.00,350.00,-10900.00,-10850.00,-50.00,54.61 --11000.00,-11300.00,300.00,-11000.00,-10900.00,-100.00,54.61 --11100.00,-11900.00,800.00,-11100.00,-11750.00,650.00,55.48 --11200.00,-12100.00,900.00,-11200.00,-11600.00,400.00,56.95 --11300.00,-12050.00,750.00,-11300.00,-11700.00,400.00,59.28 --11400.00,-12450.00,1050.00,-11400.00,-11950.00,550.00,59.28 --11500.00,-11300.00,-200.00,-11500.00,-10650.00,-850.00,60.95 --11600.00,-12250.00,650.00,-11600.00,-11550.00,-50.00,62.04 --11700.00,-12850.00,1150.00,-11700.00,-12650.00,950.00,62.04 --11800.00,-12650.00,850.00,-11800.00,-12700.00,900.00,64.63 --11900.00,-12450.00,550.00,-11900.00,-12400.00,500.00,66.89 --12000.00,-12900.00,900.00,-12000.00,-12750.00,750.00,68.83 --12100.00,-13250.00,1150.00,-12100.00,-12850.00,750.00,68.83 --12200.00,-13150.00,950.00,-12200.00,-12800.00,600.00,71.94 --12300.00,-13050.00,750.00,-12300.00,-13000.00,700.00,74.78 --12400.00,-13450.00,1050.00,-12400.00,-13350.00,950.00,74.78 --12500.00,-13450.00,950.00,-12500.00,-13250.00,750.00,77.45 --12600.00,-13650.00,1050.00,-12600.00,-13450.00,850.00,79.87 --12700.00,-13750.00,1050.00,-12700.00,-13700.00,1000.00,82.89 --12800.00,-13900.00,1100.00,-12800.00,-13250.00,450.00,82.89 --12900.00,-14050.00,1150.00,-12900.00,-12950.00,50.00,84.60 --13000.00,-14500.00,1500.00,-13000.00,-13450.00,450.00,87.34 --13100.00,-14250.00,1150.00,-13100.00,-13500.00,400.00,89.42 --13200.00,-14450.00,1250.00,-13200.00,-14150.00,950.00,89.42 --13300.00,-13600.00,300.00,-13300.00,-13550.00,250.00,91.74 --13400.00,-13900.00,500.00,-13400.00,-13700.00,300.00,92.71 --13500.00,-15450.00,1950.00,-13500.00,-15000.00,1500.00,92.71 --13600.00,-14800.00,1200.00,-13600.00,-14000.00,400.00,95.33 --13700.00,-14700.00,1000.00,-13700.00,-13750.00,50.00,96.81 --13800.00,-15400.00,1600.00,-13800.00,-14550.00,750.00,98.35 --13900.00,-15500.00,1600.00,-13900.00,-15200.00,1300.00,98.35 --14000.00,-14900.00,900.00,-14000.00,-14800.00,800.00,100.18 --14100.00,-15050.00,950.00,-14100.00,-15050.00,950.00,101.39 --14200.00,-15800.00,1600.00,-14200.00,-15600.00,1400.00,102.48 --14300.00,-15800.00,1500.00,-14300.00,-15150.00,850.00,102.48 --14400.00,-16400.00,2000.00,-14400.00,-15450.00,1050.00,103.60 --14500.00,-16000.00,1500.00,-14500.00,-15300.00,800.00,104.33 --14600.00,-15950.00,1350.00,-14600.00,-15550.00,950.00,104.33 --14700.00,-16100.00,1400.00,-14700.00,-15900.00,1200.00,105.07 --14800.00,-16650.00,1850.00,-14800.00,-16450.00,1650.00,106.22 --14900.00,-16000.00,1100.00,-14900.00,-15550.00,650.00,106.17 --15000.00,-16200.00,1200.00,-15000.00,-15550.00,550.00,106.17 --15100.00,-17050.00,1950.00,-15100.00,-16400.00,1300.00,106.81 --15200.00,-17250.00,2050.00,-15200.00,-16850.00,1650.00,107.61 --15300.00,-16800.00,1500.00,-15300.00,-16450.00,1150.00,107.66 --15400.00,-17050.00,1650.00,-15400.00,-16900.00,1500.00,107.66 --15500.00,-17550.00,2050.00,-15500.00,-17450.00,1950.00,107.89 --15600.00,-17650.00,2050.00,-15600.00,-17200.00,1600.00,108.16 --15700.00,-17450.00,1750.00,-15700.00,-17000.00,1300.00,108.16 --15800.00,-17400.00,1600.00,-15800.00,-17100.00,1300.00,107.95 --15900.00,-17650.00,1750.00,-15900.00,-17300.00,1400.00,107.44 --16000.00,-17850.00,1850.00,-16000.00,-17900.00,1900.00,107.23 --16100.00,-17900.00,1800.00,-16100.00,-18000.00,1900.00,107.23 --16200.00,-18200.00,2000.00,-16200.00,-17800.00,1600.00,106.65 --16300.00,-18150.00,1850.00,-16300.00,-18000.00,1700.00,106.05 --16400.00,-18400.00,2000.00,-16400.00,-18300.00,1900.00,104.94 --16500.00,-18750.00,2250.00,-16500.00,-18700.00,2200.00,104.94 --16600.00,-21850.00,5250.00,-16600.00,-21450.00,4850.00,103.96 --16700.00,-18700.00,2000.00,-16700.00,-17850.00,1150.00,102.45 --16800.00,-18000.00,1200.00,-16800.00,-17600.00,800.00,101.78 --16900.00,-17850.00,950.00,-16900.00,-18200.00,1300.00,101.78 --17000.00,-18350.00,1350.00,-17000.00,-18200.00,1200.00,100.68 --17100.00,-18600.00,1500.00,-17100.00,-18100.00,1000.00,98.90 --17200.00,-19550.00,2350.00,-17200.00,-18750.00,1550.00,98.90 --17300.00,-19450.00,2150.00,-17152.29,-18450.00,1297.71,97.74 --17400.00,-19400.00,2000.00,-17052.29,-19000.00,1947.71,96.38 --17481.14,-20000.00,2518.86,-16952.29,-19400.00,2447.71,95.02 --17381.14,-19800.00,2418.86,-16852.29,-19300.00,2447.71,95.02 --17281.14,-20050.00,2768.86,-16752.29,-19650.00,2897.71,92.68 --17181.14,-19600.00,2418.86,-16652.29,-18550.00,1897.71,91.91 --17081.14,-19650.00,2568.86,-16552.29,-18600.00,2047.71,90.97 --16981.14,-20250.00,3268.86,-16452.29,-18850.00,2397.71,90.97 --16881.14,-19250.00,2368.86,-16352.29,-18400.00,2047.71,89.59 --16781.14,-19200.00,2418.86,-16252.29,-18350.00,2097.71,88.74 --16681.14,-19000.00,2318.86,-16152.29,-17700.00,1547.71,88.74 --16581.14,-19150.00,2568.86,-16052.29,-18100.00,2047.71,86.98 --16481.14,-19150.00,2668.86,-15952.29,-17800.00,1847.71,86.27 --16381.14,-18800.00,2418.86,-15852.29,-17700.00,1847.71,85.34 --16281.14,-19250.00,2968.86,-15752.29,-18300.00,2547.71,85.34 --16181.14,-19400.00,3218.86,-15652.29,-18150.00,2497.71,84.62 --16081.14,-18700.00,2618.86,-15552.29,-17450.00,1897.71,84.51 --15981.14,-18250.00,2268.86,-15452.29,-17100.00,1647.71,83.97 --15881.14,-18450.00,2568.86,-15352.29,-17000.00,1647.71,83.97 --15781.14,-18400.00,2618.86,-15252.29,-16900.00,1647.71,84.02 --15681.14,-18200.00,2518.86,-15152.29,-16900.00,1747.71,83.22 --15581.14,-18000.00,2418.86,-15052.29,-16800.00,1747.71,83.22 --15481.14,-17650.00,2168.86,-14952.29,-16700.00,1747.71,82.85 --15381.14,-17800.00,2418.86,-14852.29,-17150.00,2297.71,82.59 --15281.14,-17950.00,2668.86,-14752.29,-17350.00,2597.71,82.21 --15181.14,-17600.00,2418.86,-14652.29,-17100.00,2447.71,82.21 --15081.14,-17350.00,2268.86,-14552.29,-16900.00,2347.71,82.43 --14981.14,-17250.00,2268.86,-14452.29,-16250.00,1797.71,82.52 --14881.14,-16850.00,1968.86,-14352.29,-15600.00,1247.71,82.71 --14781.14,-16800.00,2018.86,-14252.29,-15450.00,1197.71,82.71 --14681.14,-16700.00,2018.86,-14152.29,-15500.00,1347.71,82.58 --14581.14,-16700.00,2118.86,-14052.29,-15350.00,1297.71,81.98 --14481.14,-17000.00,2518.86,-13952.29,-15650.00,1697.71,81.98 --14381.14,-16600.00,2218.86,-13852.29,-15100.00,1247.71,82.27 --14281.14,-16050.00,1768.86,-13752.29,-14800.00,1047.71,81.62 --14181.14,-16350.00,2168.86,-13652.29,-15200.00,1547.71,81.47 --14081.14,-16000.00,1918.86,-13552.29,-15000.00,1447.71,81.47 --13981.14,-15650.00,1668.86,-13452.29,-14800.00,1347.71,81.28 --13881.14,-15400.00,1518.86,-13352.29,-14900.00,1547.71,81.17 --13781.14,-15450.00,1668.86,-13252.29,-15100.00,1847.71,81.35 --13681.14,-15350.00,1668.86,-13152.29,-14500.00,1347.71,81.35 --13581.14,-15400.00,1818.86,-13052.29,-14000.00,947.71,81.33 --13481.14,-15500.00,2018.86,-12952.29,-13950.00,997.71,81.03 --13381.14,-14700.00,1318.86,-12852.29,-13550.00,697.71,81.03 --13281.14,-14600.00,1318.86,-12752.29,-14000.00,1247.71,80.74 --13181.14,-14350.00,1168.86,-12652.29,-13600.00,947.71,80.80 --13081.14,-14600.00,1518.86,-12552.29,-13600.00,1047.71,80.43 --12981.14,-14550.00,1568.86,-12452.29,-13500.00,1047.71,80.43 --12881.14,-14300.00,1418.86,-12352.29,-12950.00,597.71,80.33 --12781.14,-14200.00,1418.86,-12252.29,-13150.00,897.71,80.21 --12681.14,-13900.00,1218.86,-12152.29,-13150.00,997.71,79.67 --12581.14,-13950.00,1368.86,-12052.29,-13350.00,1297.71,79.67 --12481.14,-13700.00,1218.86,-11952.29,-12900.00,947.71,79.46 --12381.14,-13700.00,1318.86,-11852.29,-12800.00,947.71,79.36 --12281.14,-13600.00,1318.86,-11752.29,-12650.00,897.71,79.36 --12181.14,-13400.00,1218.86,-11652.29,-12350.00,697.71,79.36 --12081.14,-13350.00,1268.86,-11552.29,-12300.00,747.71,79.36 --11981.14,-13250.00,1268.86,-11452.29,-12200.00,747.71,79.41 --11881.14,-12900.00,1018.86,-11352.29,-12100.00,747.71,79.41 --11781.14,-12700.00,918.86,-11252.29,-11750.00,497.71,78.85 --11681.14,-12850.00,1168.86,-11152.29,-11850.00,697.71,78.38 --11581.14,-12900.00,1318.86,-11052.29,-12150.00,1097.71,78.08 --11481.14,-14600.00,3118.86,-10952.29,-13750.00,2797.71,78.08 --11381.14,-11600.00,218.86,-10852.29,-10800.00,-52.29,77.70 --11281.14,-10250.00,-1031.14,-10752.29,-9750.00,-1002.29,77.42 --11181.14,-12700.00,1518.86,-10652.29,-12400.00,1747.71,76.89 --11081.14,-12500.00,1418.86,-10552.29,-11950.00,1397.71,76.89 --10981.14,-11450.00,468.86,-10452.29,-10600.00,147.71,77.00 --10881.14,-11550.00,668.86,-10352.29,-10900.00,547.71,76.22 --10781.14,-11800.00,1018.86,-10252.29,-11300.00,1047.71,76.22 --10681.14,-11450.00,768.86,-10152.29,-11000.00,847.71,76.03 --10581.14,-11500.00,918.86,-10052.29,-10800.00,747.71,75.11 --10481.14,-11350.00,868.86,-9952.29,-10400.00,447.71,74.48 --10381.14,-11100.00,718.86,-9852.29,-10000.00,147.71,74.48 --10281.14,-11350.00,1068.86,-9752.29,-10050.00,297.71,74.19 --10181.14,-11250.00,1068.86,-9652.29,-9700.00,47.71,73.73 --10081.14,-11450.00,1368.86,-9552.29,-10250.00,697.71,73.23 --9981.14,-11050.00,1068.86,-9452.29,-9800.00,347.71,73.23 --9881.14,-10350.00,468.86,-9352.29,-9700.00,347.71,72.51 --9781.14,-10450.00,668.86,-9252.29,-9600.00,347.71,71.78 --9681.14,-10250.00,568.86,-9152.29,-9350.00,197.71,71.78 --9581.14,-10600.00,1018.86,-9052.29,-9300.00,247.71,70.55 --9481.14,-10350.00,868.86,-8952.29,-9300.00,347.71,70.17 --9381.14,-9800.00,418.86,-8852.29,-8800.00,-52.29,69.80 --9281.14,-9450.00,168.86,-8752.29,-8600.00,-152.29,69.80 --9181.14,-9300.00,118.86,-8652.29,-8600.00,-52.29,69.24 --9081.14,-9350.00,268.86,-8552.29,-8650.00,97.71,68.72 --8981.14,-9350.00,368.86,-8452.29,-8650.00,197.71,68.72 --8881.14,-9000.00,118.86,-8352.29,-8450.00,97.71,68.56 --8781.14,-9150.00,368.86,-8252.29,-8400.00,147.71,67.85 --8681.14,-9100.00,418.86,-8152.29,-8550.00,397.71,67.40 --8581.14,-8950.00,368.86,-8052.29,-8450.00,397.71,67.40 --8481.14,-8800.00,318.86,-7952.29,-8450.00,497.71,67.45 --8381.14,-8500.00,118.86,-7852.29,-8150.00,297.71,66.72 --8281.14,-8300.00,18.86,-7752.29,-7800.00,47.71,66.55 --8181.14,-8150.00,-31.14,-7652.29,-7200.00,-452.29,66.55 --8081.14,-8000.00,-81.14,-7552.29,-7000.00,-552.29,66.05 --7981.14,-8050.00,68.86,-7452.29,-7050.00,-402.29,65.45 --7881.14,-8150.00,268.86,-7352.29,-7050.00,-302.29,65.45 --7781.14,-7900.00,118.86,-7252.29,-6900.00,-352.29,64.98 --7681.14,-7900.00,218.86,-7152.29,-7050.00,-102.29,64.66 --7581.14,-7650.00,68.86,-7052.29,-6600.00,-452.29,64.22 --7481.14,-7450.00,-31.14,-6952.29,-6700.00,-252.29,64.22 --7381.14,-7450.00,68.86,-6852.29,-6900.00,47.71,63.81 --7281.14,-6850.00,-431.14,-6752.29,-6500.00,-252.29,63.83 --7181.14,-6700.00,-481.14,-6652.29,-6550.00,-102.29,64.05 --7081.14,-6800.00,-281.14,-6552.29,-6400.00,-152.29,64.05 --6981.14,-6850.00,-131.14,-6452.29,-5900.00,-552.29,63.47 --6881.14,-6800.00,-81.14,-6352.29,-5800.00,-552.29,63.07 --6781.14,-6500.00,-281.14,-6252.29,-5650.00,-602.29,63.07 --6681.14,-6300.00,-381.14,-6152.29,-5500.00,-652.29,62.81 --6581.14,-6300.00,-281.14,-6052.29,-5550.00,-502.29,62.36 --6481.14,-6350.00,-131.14,-5952.29,-5500.00,-452.29,61.84 --6381.14,-6000.00,-381.14,-5852.29,-5150.00,-702.29,61.84 --6281.14,-6150.00,-131.14,-5752.29,-5150.00,-602.29,62.07 --6181.14,-5900.00,-281.14,-5652.29,-4900.00,-752.29,61.95 --6081.14,-5400.00,-681.14,-5552.29,-4600.00,-952.29,61.95 --5981.14,-5150.00,-831.14,-5452.29,-4400.00,-1052.29,61.82 --5881.14,-5000.00,-881.14,-5352.29,-4300.00,-1052.29,61.86 --5781.14,-5050.00,-731.14,-5252.29,-4500.00,-752.29,61.28 --5681.14,-4900.00,-781.14,-5152.29,-4400.00,-752.29,61.28 --5581.14,-5000.00,-581.14,-5052.29,-4450.00,-602.29,60.83 --5481.14,-4850.00,-631.14,-4952.29,-4400.00,-552.29,61.23 --5381.14,-4750.00,-631.14,-4852.29,-3400.00,-1452.29,61.00 --5281.14,-4650.00,-631.14,-4752.29,-3200.00,-1552.29,61.00 --5181.14,-4600.00,-581.14,-4652.29,-5250.00,597.71,60.93 --5081.14,-4350.00,-731.14,-4552.29,-4000.00,-552.29,60.84 --4981.14,-3150.00,-1831.14,-4452.29,-2600.00,-1852.29,60.84 --4881.14,-3300.00,-1581.14,-4352.29,-2500.00,-1852.29,60.52 --4781.14,-3900.00,-881.14,-4252.29,-4300.00,47.71,61.43 --4681.14,-3350.00,-1331.14,-4152.29,-2500.00,-1652.29,61.30 --4581.14,-2450.00,-2131.14,-4052.29,-1750.00,-2302.29,61.30 --4481.14,-3750.00,-731.14,-3952.29,-3700.00,-252.29,60.24 --4381.14,-3350.00,-1031.14,-3852.29,-2750.00,-1102.29,60.64 --4281.14,-750.00,-3531.14,-3752.29,-1550.00,-2202.29,60.26 --4181.14,-2000.00,-2181.14,-3652.29,-500.00,-3152.29,60.26 --4081.14,-3400.00,-681.14,-3552.29,-2900.00,-652.29,59.73 --3981.14,-3600.00,-381.14,-3452.29,-2050.00,-1402.29,60.04 --3881.14,-750.00,-3131.14,-3352.29,-1000.00,-2352.29,60.04 --3781.14,-1050.00,-2731.14,-3252.29,-400.00,-2852.29,59.84 --3681.14,-2850.00,-831.14,-3152.29,-1950.00,-1202.29,58.70 --3581.14,-3000.00,-581.14,-3052.29,-1700.00,-1352.29,59.89 --3481.14,-50.00,-3431.14,-2952.29,250.00,-3202.29,59.89 --3381.14,-1050.00,-2331.14,-2852.29,250.00,-3102.29,59.33 --3281.14,-2200.00,-1081.14,-2752.29,-2350.00,-402.29,59.03 --3181.14,-2050.00,-1131.14,-2652.29,-1200.00,-1452.29,58.78 --3081.14,-300.00,-2781.14,-2552.29,700.00,-3252.29,58.78 --2981.14,-700.00,-2281.14,-2452.29,-900.00,-1552.29,58.67 --2881.14,-1650.00,-1231.14,-2352.29,-1850.00,-502.29,58.04 --2781.14,-1250.00,-1531.14,-2252.29,-650.00,-1602.29,58.04 --2681.14,400.00,-3081.14,-2152.29,100.00,-2252.29,59.03 --2581.14,-750.00,-1831.14,-2052.29,50.00,-2102.29,58.17 --2481.14,-350.00,-2131.14,-1952.29,0.00,-1952.29,58.49 --2381.14,900.00,-3281.14,-1852.29,0.00,-1852.29,58.49 --2281.14,-300.00,-1981.14,-1752.29,0.00,-1752.29,58.53 --2181.14,0.00,-2181.14,-1652.29,0.00,-1652.29,58.80 --2081.14,850.00,-2931.14,-1552.29,0.00,-1552.29,58.80 --1981.14,-1000.00,-981.14,-1452.29,0.00,-1452.29,58.65 --1881.14,150.00,-2031.14,-1352.29,0.00,-1352.29,58.95 --1781.14,700.00,-2481.14,-1252.29,0.00,-1252.29,58.95 --1681.14,-250.00,-1431.14,-1152.29,0.00,-1152.29,58.61 --1581.14,0.00,-1581.14,-1052.29,0.00,-1052.29,59.08 --1481.14,0.00,-1481.14,-952.29,0.00,-952.29,58.95 --1381.14,0.00,-1381.14,-852.29,0.00,-852.29,58.95 --1281.14,0.00,-1281.14,-752.29,0.00,-752.29,59.01 --1181.14,0.00,-1181.14,-652.29,0.00,-652.29,58.97 --1081.14,0.00,-1081.14,-552.29,0.00,-552.29,58.97 --981.14,0.00,-981.14,-452.29,0.00,-452.29,58.81 --881.14,0.00,-881.14,-352.29,0.00,-352.29,58.73 --781.14,0.00,-781.14,-252.29,0.00,-252.29,58.73 --681.14,0.00,-681.14,-152.29,0.00,-152.29,58.90 --581.14,0.00,-581.14,-52.29,0.00,-52.29,58.94 --481.14,0.00,-481.14,0.00,0.00,0.00,58.54 --381.14,0.00,-381.14,0.00,0.00,0.00,58.54 --281.14,0.00,-281.14,0.00,0.00,0.00,58.13 --181.14,0.00,-181.14,0.00,0.00,0.00,58.64 --81.14,0.00,-81.14,0.00,0.00,0.00,58.64 -0.00,0.00,0.00,0.00,0.00,0.00,58.64 -0.00,0.00,0.00,0.00,0.00,0.00,58.70 -0.00,0.00,0.00,0.00,0.00,0.00,58.70 -0.00,0.00,0.00,0.00,0.00,0.00,58.64 -0.00,0.00,0.00,0.00,0.00,0.00,58.92 -0.00,0.00,0.00,0.00,0.00,0.00,58.92 -0.00,0.00,0.00,0.00,0.00,0.00,58.70 -0.00,0.00,0.00,0.00,0.00,0.00,58.97 -0.00,0.00,0.00,0.00,0.00,0.00,58.75 -0.00,0.00,0.00,0.00,0.00,0.00,58.75 -0.00,0.00,0.00,0.00,0.00,0.00,58.34 -0.00,0.00,0.00,0.00,0.00,0.00,58.34 -0.00,0.00,0.00,0.00,0.00,0.00,58.34 -0.00,0.00,0.00,0.00,0.00,0.00,58.42 -0.00,0.00,0.00,0.00,0.00,0.00,58.20 -0.00,0.00,0.00,0.00,0.00,0.00,58.20 -0.00,0.00,0.00,0.00,0.00,0.00,58.63 -0.00,0.00,0.00,0.00,0.00,0.00,58.87 -0.00,0.00,0.00,0.00,0.00,0.00,58.87 -0.00,0.00,0.00,0.00,0.00,0.00,58.51 -0.00,0.00,0.00,0.00,0.00,0.00,58.75 -0.00,0.00,0.00,0.00,0.00,0.00,59.13 -0.00,0.00,0.00,0.00,0.00,0.00,59.13 -0.00,0.00,0.00,0.00,0.00,0.00,59.05 \ No newline at end of file +0.00,0.00,0.00,0.00,0.00,0.00,221.03 +0.00,0.00,0.00,0.00,0.00,0.00,221.03 +0.00,0.00,0.00,0.00,0.00,0.00,220.77 +0.00,0.00,0.00,0.00,0.00,0.00,220.63 +0.00,0.00,0.00,0.00,0.00,0.00,220.63 +0.00,0.00,0.00,0.00,0.00,0.00,221.08 +0.00,0.00,0.00,0.00,0.00,0.00,220.77 +0.00,0.00,0.00,0.00,0.00,0.00,220.77 +0.00,0.00,0.00,0.00,0.00,0.00,220.90 +0.00,0.00,0.00,0.00,0.00,0.00,220.74 +0.00,0.00,0.00,0.00,0.00,0.00,220.74 +0.00,0.00,0.00,0.00,0.00,0.00,220.86 +0.00,0.00,0.00,0.00,0.00,0.00,220.90 +0.00,0.00,0.00,0.00,0.00,0.00,220.90 +0.00,0.00,0.00,0.00,0.00,0.00,220.72 +0.00,0.00,0.00,0.00,0.00,0.00,221.12 +0.00,0.00,0.00,0.00,0.00,0.00,221.12 +0.00,0.00,0.00,0.00,0.00,0.00,221.09 +0.00,0.00,0.00,0.00,0.00,0.00,220.94 +0.00,0.00,0.00,0.00,0.00,0.00,220.92 +0.00,0.00,0.00,0.00,0.00,0.00,220.92 +0.00,0.00,0.00,0.00,0.00,0.00,221.17 +0.00,0.00,0.00,0.00,0.00,0.00,221.07 +0.00,0.00,0.00,0.00,0.00,0.00,221.07 +0.00,0.00,0.00,0.00,0.00,0.00,220.83 +0.00,0.00,0.00,0.00,0.00,0.00,220.93 +0.00,0.00,0.00,0.00,0.00,0.00,220.93 +0.00,0.00,0.00,0.00,0.00,0.00,221.38 +0.00,0.00,0.00,0.00,0.00,0.00,221.15 +0.00,0.00,0.00,0.00,0.00,0.00,220.72 +0.00,0.00,0.00,0.00,0.00,0.00,220.72 +0.00,0.00,0.00,0.00,0.00,0.00,221.12 +-200.00,0.00,-200.00,-200.00,0.00,-200.00,221.16 +-400.00,0.00,-400.00,-400.00,0.00,-400.00,221.16 +-600.00,0.00,-600.00,-600.00,0.00,-600.00,220.43 +-800.00,0.00,-800.00,-800.00,0.00,-800.00,220.85 +-1000.00,0.00,-1000.00,-1000.00,0.00,-1000.00,220.85 +-1200.00,0.00,-1200.00,-1200.00,0.00,-1200.00,220.83 +-1400.00,0.00,-1400.00,-1400.00,0.00,-1400.00,220.95 +-1600.00,0.00,-1600.00,-1600.00,0.00,-1600.00,220.45 +-1800.00,0.00,-1800.00,-1800.00,0.00,-1800.00,220.45 +-2000.00,0.00,-2000.00,-2000.00,0.00,-2000.00,220.83 +-2200.00,0.00,-2200.00,-2200.00,0.00,-2200.00,221.02 +-2400.00,0.00,-2400.00,-2400.00,0.00,-2400.00,221.02 +-2600.00,0.00,-2600.00,-2600.00,0.00,-2600.00,220.84 +-2800.00,0.00,-2800.00,-2800.00,0.00,-2800.00,220.62 +-3000.00,0.00,-3000.00,-3000.00,0.00,-3000.00,220.96 +-3200.00,0.00,-3200.00,-3200.00,0.00,-3200.00,220.96 +-3400.00,0.00,-3400.00,-3400.00,0.00,-3400.00,221.11 +-3600.00,0.00,-3600.00,-3600.00,0.00,-3600.00,220.88 +-3800.00,0.00,-3800.00,-3800.00,0.00,-3800.00,220.88 +-4000.00,0.00,-4000.00,-4000.00,0.00,-4000.00,220.78 +-4200.00,0.00,-4200.00,-4200.00,0.00,-4200.00,221.04 +-4400.00,0.00,-4400.00,-4400.00,0.00,-4400.00,221.04 +-4600.00,0.00,-4600.00,-4600.00,0.00,-4600.00,220.71 +-4800.00,-400.00,-4400.00,-4800.00,-400.00,-4400.00,220.73 +-5000.00,-1050.00,-3950.00,-5000.00,-1000.00,-4000.00,222.67 +-5200.00,-2050.00,-3150.00,-5200.00,-1900.00,-3300.00,222.67 +-5400.00,-700.00,-4700.00,-5400.00,-850.00,-4550.00,221.18 +-5600.00,-150.00,-5450.00,-5600.00,200.00,-5800.00,220.35 +-5800.00,-2050.00,-3750.00,-5800.00,-1500.00,-4300.00,220.35 +-6000.00,-3750.00,-2250.00,-6000.00,-3100.00,-2900.00,221.60 +-6200.00,-4200.00,-2000.00,-6200.00,-3350.00,-2850.00,221.05 +-6400.00,-3300.00,-3100.00,-6400.00,-2400.00,-4000.00,221.66 +-6600.00,-3050.00,-3550.00,-6600.00,-1650.00,-4950.00,221.66 +-6800.00,-3800.00,-3000.00,-6800.00,-3250.00,-3550.00,221.92 +-7000.00,-4750.00,-2250.00,-7000.00,-4750.00,-2250.00,221.88 +-7200.00,-5300.00,-1900.00,-7200.00,-4800.00,-2400.00,221.88 +-7400.00,-3900.00,-3500.00,-7400.00,-3950.00,-3450.00,221.67 +-7600.00,-3900.00,-3700.00,-7600.00,-4450.00,-3150.00,221.56 +-7800.00,-4900.00,-2900.00,-7800.00,-5000.00,-2800.00,221.78 +-8000.00,-5950.00,-2050.00,-8000.00,-5650.00,-2350.00,221.78 +-8200.00,-6900.00,-1300.00,-8200.00,-6100.00,-2100.00,221.36 +-8400.00,-6800.00,-1600.00,-8400.00,-6050.00,-2350.00,221.84 +-8600.00,-6050.00,-2550.00,-8600.00,-6350.00,-2250.00,221.84 +-8800.00,-6900.00,-1900.00,-8800.00,-6900.00,-1900.00,222.03 +-9000.00,-7350.00,-1650.00,-9000.00,-6900.00,-2100.00,222.03 +-9200.00,-8050.00,-1150.00,-9200.00,-7400.00,-1800.00,221.63 +-9400.00,-8550.00,-850.00,-9400.00,-7600.00,-1800.00,221.63 +-9600.00,-8750.00,-850.00,-9600.00,-7900.00,-1700.00,221.25 +-9800.00,-8900.00,-900.00,-9800.00,-8050.00,-1750.00,221.63 +-10000.00,-8750.00,-1250.00,-10000.00,-7950.00,-2050.00,221.63 +-10200.00,-9300.00,-900.00,-10200.00,-8600.00,-1600.00,221.90 +-10400.00,-9700.00,-700.00,-10400.00,-8800.00,-1600.00,221.59 +-10600.00,-9850.00,-750.00,-10600.00,-9100.00,-1500.00,221.51 +-10800.00,-10200.00,-600.00,-10800.00,-9350.00,-1450.00,221.51 +-11000.00,-10250.00,-750.00,-11000.00,-9650.00,-1350.00,221.42 +-11200.00,-10550.00,-650.00,-11200.00,-9800.00,-1400.00,221.27 +-11400.00,-10800.00,-600.00,-11400.00,-10100.00,-1300.00,221.27 +-11600.00,-10950.00,-650.00,-11600.00,-10250.00,-1350.00,221.32 +-11800.00,-11100.00,-700.00,-11800.00,-10500.00,-1300.00,221.12 +-12000.00,-11450.00,-550.00,-12000.00,-10800.00,-1200.00,220.94 +-12200.00,-11700.00,-500.00,-12200.00,-11150.00,-1050.00,220.94 +-12400.00,-11900.00,-500.00,-12400.00,-11250.00,-1150.00,221.20 +-12600.00,-12100.00,-500.00,-12600.00,-11550.00,-1050.00,221.09 +-12800.00,-12250.00,-550.00,-12800.00,-11700.00,-1100.00,221.04 +-13000.00,-12550.00,-450.00,-13000.00,-11950.00,-1050.00,221.04 +-13200.00,-12800.00,-400.00,-13200.00,-12150.00,-1050.00,220.94 +-13400.00,-12550.00,-850.00,-13400.00,-11950.00,-1450.00,220.88 +-13600.00,-13200.00,-400.00,-13600.00,-12650.00,-950.00,220.88 +-13800.00,-13500.00,-300.00,-13800.00,-13050.00,-750.00,220.60 +-14000.00,-13700.00,-300.00,-14000.00,-13150.00,-850.00,220.47 +-14200.00,-13950.00,-250.00,-14200.00,-13500.00,-700.00,220.29 +-14400.00,-14000.00,-400.00,-14400.00,-13700.00,-700.00,220.29 +-14600.00,-14150.00,-450.00,-14600.00,-13950.00,-650.00,220.52 +-14800.00,-14350.00,-450.00,-14800.00,-14200.00,-600.00,220.63 +-15000.00,-14600.00,-400.00,-15000.00,-14350.00,-650.00,221.10 +-15200.00,-14950.00,-250.00,-15200.00,-14550.00,-650.00,221.10 +-15400.00,-15250.00,-150.00,-15400.00,-14850.00,-550.00,221.38 +-15600.00,-18150.00,2550.00,-15600.00,-17700.00,2100.00,220.75 +-15800.00,-15550.00,-250.00,-15800.00,-15100.00,-700.00,221.06 +-16000.00,-15250.00,-750.00,-16000.00,-14900.00,-1100.00,221.06 +-16200.00,-15500.00,-700.00,-16200.00,-15100.00,-1100.00,220.84 +-16400.00,-16000.00,-400.00,-16400.00,-15500.00,-900.00,221.07 +-16600.00,-16550.00,-50.00,-16600.00,-16000.00,-600.00,221.07 +-16800.00,-16800.00,0.00,-16800.00,-16200.00,-600.00,221.03 +-17000.00,-17050.00,50.00,-17000.00,-16500.00,-500.00,221.26 +-17200.00,-17250.00,50.00,-17200.00,-16750.00,-450.00,221.05 +-17400.00,-17500.00,100.00,-17400.00,-16900.00,-500.00,221.05 +-17600.00,-17900.00,300.00,-17600.00,-17100.00,-500.00,221.35 +-17800.00,-18200.00,400.00,-17800.00,-17450.00,-350.00,221.61 +-18000.00,-18300.00,300.00,-18000.00,-17650.00,-350.00,221.43 +-18200.00,-18550.00,350.00,-18200.00,-17750.00,-450.00,221.43 +-18400.00,-18750.00,350.00,-18400.00,-18000.00,-400.00,221.05 +-18600.00,-19650.00,1050.00,-18600.00,-18900.00,300.00,221.02 +-18800.00,-19250.00,450.00,-18800.00,-18450.00,-350.00,221.02 +-19000.00,-19300.00,300.00,-19000.00,-18650.00,-350.00,221.30 +-19200.00,-19550.00,350.00,-19200.00,-18700.00,-500.00,221.37 +-19400.00,-19800.00,400.00,-19400.00,-18900.00,-500.00,221.20 +-19600.00,-19950.00,350.00,-19600.00,-19200.00,-400.00,221.20 +-19800.00,-20300.00,500.00,-19800.00,-19500.00,-300.00,220.71 +-20000.00,-20400.00,400.00,-20000.00,-19800.00,-200.00,220.65 +-20200.00,-20600.00,400.00,-20200.00,-19900.00,-300.00,220.71 +-20400.00,-21600.00,1200.00,-20400.00,-20900.00,500.00,220.71 +-20600.00,-21000.00,400.00,-20600.00,-20400.00,-200.00,220.44 +-20800.00,-21850.00,1050.00,-20800.00,-21150.00,350.00,220.61 +-21000.00,-21250.00,250.00,-21000.00,-20750.00,-250.00,220.61 +-21200.00,-22250.00,1050.00,-21200.00,-21600.00,400.00,220.68 +-21400.00,-21700.00,300.00,-21400.00,-21250.00,-150.00,220.30 +-21600.00,-21800.00,200.00,-21600.00,-21450.00,-150.00,220.71 +-21800.00,-22950.00,1150.00,-21800.00,-22600.00,800.00,220.71 +-22000.00,-22350.00,350.00,-22000.00,-22200.00,200.00,221.00 +-22200.00,-22650.00,450.00,-22200.00,-22200.00,0.00,221.13 +-22400.00,-22850.00,450.00,-22400.00,-22500.00,100.00,220.68 +-22600.00,-23450.00,850.00,-22600.00,-22700.00,100.00,220.68 +-22800.00,-23500.00,700.00,-22800.00,-23050.00,250.00,221.56 +-23000.00,-24650.00,1650.00,-23000.00,-24000.00,1000.00,221.36 +-23200.00,-24750.00,1550.00,-23200.00,-24200.00,1000.00,221.33 +-23400.00,-24000.00,600.00,-23334.14,-23250.00,-84.14,221.33 +-23600.00,-25100.00,1500.00,-23134.14,-24200.00,1065.86,221.70 +-23723.05,-25250.00,1526.95,-22934.14,-24300.00,1365.86,221.14 +-23523.05,-24500.00,976.95,-22734.14,-23450.00,715.86,220.94 +-23323.05,-24800.00,1476.95,-22534.14,-23250.00,715.86,220.94 +-23123.05,-24650.00,1526.95,-22334.14,-23150.00,815.86,221.25 +-22923.05,-24750.00,1826.95,-22134.14,-23150.00,1015.86,220.90 +-22723.05,-25400.00,2676.95,-21934.14,-23900.00,1965.86,220.90 +-22523.05,-24500.00,1976.95,-21734.14,-22900.00,1165.86,220.55 +-22323.05,-23750.00,1426.95,-21534.14,-22450.00,915.86,220.64 +-22123.05,-23650.00,1526.95,-21334.14,-22200.00,865.86,220.79 +-21923.05,-23450.00,1526.95,-21134.14,-22050.00,915.86,220.79 +-21723.05,-23350.00,1626.95,-20934.14,-21900.00,965.86,220.73 +-21523.05,-23250.00,1726.95,-20734.14,-21600.00,865.86,220.30 +-21323.05,-22950.00,1626.95,-20534.14,-21500.00,965.86,220.37 +-21123.05,-22750.00,1626.95,-20334.14,-21500.00,1165.86,220.37 +-20923.05,-23100.00,2176.95,-20134.14,-22000.00,1865.86,220.46 +-20723.05,-22250.00,1526.95,-19934.14,-21000.00,1065.86,220.55 +-20523.05,-21600.00,1076.95,-19734.14,-20600.00,865.86,220.55 +-20323.05,-21700.00,1376.95,-19534.14,-20500.00,965.86,220.64 +-20123.05,-21600.00,1476.95,-19334.14,-20350.00,1015.86,220.78 +-19923.05,-21400.00,1476.95,-19134.14,-20250.00,1115.86,221.21 +-19723.05,-21400.00,1676.95,-18934.14,-20050.00,1115.86,221.21 +-19523.05,-21150.00,1626.95,-18734.14,-19700.00,965.86,220.91 +-19323.05,-20800.00,1476.95,-18534.14,-19400.00,865.86,220.73 +-19123.05,-20650.00,1526.95,-18334.14,-19150.00,815.86,220.78 +-18923.05,-20450.00,1526.95,-18134.14,-18900.00,765.86,220.78 +-18723.05,-20300.00,1576.95,-17934.14,-18750.00,815.86,221.03 +-18523.05,-20100.00,1576.95,-17734.14,-18400.00,665.86,220.85 +-18323.05,-19850.00,1526.95,-17534.14,-18150.00,615.86,220.85 +-18123.05,-23000.00,4876.95,-17334.14,-20850.00,3515.86,220.95 +-17923.05,-19100.00,1176.95,-17134.14,-17350.00,215.86,220.85 +-17723.05,-18200.00,476.95,-16934.14,-16750.00,-184.14,220.65 +-17523.05,-18350.00,826.95,-16734.14,-16650.00,-84.14,220.65 +-17323.05,-18350.00,1026.95,-16534.14,-16800.00,265.86,220.96 +-17123.05,-18250.00,1126.95,-16334.14,-16850.00,515.86,220.90 +-16923.05,-18050.00,1126.95,-16134.14,-16750.00,615.86,220.94 +-16723.05,-17950.00,1226.95,-15934.14,-16400.00,465.86,220.94 +-16523.05,-17750.00,1226.95,-15734.14,-16200.00,465.86,220.76 +-16323.05,-17350.00,1026.95,-15534.14,-16000.00,465.86,220.88 +-16123.05,-17150.00,1026.95,-15334.14,-15800.00,465.86,220.99 +-15923.05,-16950.00,1026.95,-15134.14,-15750.00,615.86,220.99 +-15723.05,-16800.00,1076.95,-14934.14,-15400.00,465.86,220.43 +-15523.05,-16550.00,1026.95,-14734.14,-15050.00,315.86,220.59 +-15323.05,-16300.00,976.95,-14534.14,-14800.00,265.86,220.59 +-15123.05,-16100.00,976.95,-14334.14,-14750.00,415.86,220.59 +-14923.05,-15950.00,1026.95,-14134.14,-14450.00,315.86,220.63 +-14723.05,-15550.00,826.95,-13934.14,-14300.00,365.86,220.95 +-14523.05,-15400.00,876.95,-13734.14,-14050.00,315.86,220.95 +-14323.05,-15100.00,776.95,-13534.14,-13850.00,315.86,220.70 +-14123.05,-14850.00,726.95,-13334.14,-13600.00,265.86,220.80 +-13923.05,-14750.00,826.95,-13134.14,-13400.00,265.86,221.13 +-13723.05,-14450.00,726.95,-12934.14,-13300.00,365.86,221.13 +-13523.05,-14350.00,826.95,-12734.14,-13150.00,415.86,220.94 +-13323.05,-13500.00,176.95,-12534.14,-12500.00,-34.14,221.28 +-13123.05,-13900.00,776.95,-12334.14,-12800.00,465.86,221.28 +-12923.05,-13900.00,976.95,-12134.14,-12600.00,465.86,220.79 +-12723.05,-13500.00,776.95,-11934.14,-12350.00,415.86,221.00 +-12523.05,-13300.00,776.95,-11734.14,-12000.00,265.86,221.05 +-12323.05,-13100.00,776.95,-11534.14,-11850.00,315.86,221.05 +-12123.05,-12450.00,326.95,-11334.14,-11250.00,-84.14,221.04 +-11923.05,-12700.00,776.95,-11134.14,-11400.00,265.86,221.05 +-11723.05,-12600.00,876.95,-10934.14,-11100.00,165.86,221.05 +-11523.05,-12300.00,776.95,-10734.14,-10900.00,165.86,221.30 +-11323.05,-12050.00,726.95,-10534.14,-10700.00,165.86,221.74 +-11123.05,-11850.00,726.95,-10334.14,-10350.00,15.86,221.96 +-10923.05,-11550.00,626.95,-10134.14,-10150.00,15.86,221.96 +-10723.05,-11350.00,626.95,-9934.14,-9850.00,-84.14,221.04 +-10523.05,-10650.00,126.95,-9734.14,-9300.00,-434.14,221.56 +-10323.05,-8950.00,-1373.05,-9534.14,-7650.00,-1884.14,221.56 +-10123.05,-9650.00,-473.05,-9334.14,-8400.00,-934.14,221.69 +-9923.05,-9800.00,-123.05,-9134.14,-8500.00,-634.14,221.60 +-9723.05,-9600.00,-123.05,-8934.14,-8250.00,-684.14,221.72 +-9523.05,-7950.00,-1573.05,-8734.14,-6800.00,-1934.14,221.72 +-9323.05,-7100.00,-2223.05,-8534.14,-5700.00,-2834.14,221.74 +-9123.05,-7700.00,-1423.05,-8334.14,-6250.00,-2084.14,221.14 +-8923.05,-8550.00,-373.05,-8134.14,-7050.00,-1084.14,221.57 +-8723.05,-8300.00,-423.05,-7934.14,-6650.00,-1284.14,221.57 +-8523.05,-7150.00,-1373.05,-7734.14,-5800.00,-1934.14,221.55 +-8323.05,-6600.00,-1723.05,-7534.14,-5000.00,-2534.14,221.78 +-8123.05,-6900.00,-1223.05,-7334.14,-5150.00,-2184.14,221.78 +-7923.05,-6950.00,-973.05,-7134.14,-5500.00,-1634.14,221.27 +-7723.05,-5750.00,-1973.05,-6934.14,-5550.00,-1384.14,221.92 +-7523.05,-5450.00,-2073.05,-6734.14,-4550.00,-2184.14,221.34 +-7323.05,-5800.00,-1523.05,-6534.14,-3250.00,-3284.14,221.34 +-7123.05,-5750.00,-1373.05,-6334.14,-2450.00,-3884.14,221.06 +-6923.05,-4950.00,-1973.05,-6134.14,-3500.00,-2634.14,221.21 +-6723.05,-3900.00,-2823.05,-5934.14,-4100.00,-1834.14,221.21 +-6523.05,-3850.00,-2673.05,-5734.14,-3000.00,-2734.14,221.75 +-6323.05,-4150.00,-2173.05,-5534.14,-1850.00,-3684.14,221.41 +-6123.05,-2850.00,-3273.05,-5334.14,-1900.00,-3434.14,222.11 +-5923.05,-2850.00,-3073.05,-5134.14,-1950.00,-3184.14,222.11 +-5723.05,-3100.00,-2623.05,-4934.14,-1350.00,-3584.14,221.27 +-5523.05,-2350.00,-3173.05,-4734.14,350.00,-5084.14,221.04 +-5323.05,-850.00,-4473.05,-4534.14,-300.00,-4234.14,221.04 +-5123.05,-1300.00,-3823.05,-4334.14,-500.00,-3834.14,221.31 +-4923.05,-2200.00,-2723.05,-4134.14,750.00,-4884.14,220.41 +-4723.05,-1850.00,-2873.05,-3934.14,-100.00,-3834.14,220.81 +-4523.05,-300.00,-4223.05,-3734.14,-650.00,-3084.14,220.81 +-4323.05,950.00,-5273.05,-3534.14,900.00,-4434.14,220.67 +-4123.05,-750.00,-3373.05,-3334.14,200.00,-3534.14,219.77 +-3923.05,-1000.00,-2923.05,-3134.14,-50.00,-3084.14,220.88 +-3723.05,0.00,-3723.05,-2934.14,0.00,-2934.14,220.88 +-3523.05,50.00,-3573.05,-2734.14,0.00,-2734.14,220.98 +-3323.05,0.00,-3323.05,-2534.14,0.00,-2534.14,220.92 +-3123.05,0.00,-3123.05,-2334.14,0.00,-2334.14,220.92 +-2923.05,0.00,-2923.05,-2134.14,0.00,-2134.14,220.88 +-2723.05,0.00,-2723.05,-1934.14,0.00,-1934.14,221.08 +-2523.05,0.00,-2523.05,-1734.14,0.00,-1734.14,221.25 +-2323.05,0.00,-2323.05,-1534.14,0.00,-1534.14,221.25 +-2123.05,0.00,-2123.05,-1334.14,0.00,-1334.14,221.05 +-1923.05,0.00,-1923.05,-1134.14,0.00,-1134.14,221.02 +-1723.05,0.00,-1723.05,-934.14,0.00,-934.14,221.02 +-1523.05,0.00,-1523.05,-734.14,0.00,-734.14,220.87 +-1323.05,0.00,-1323.05,-534.14,0.00,-534.14,220.39 +-1123.05,0.00,-1123.05,-334.14,0.00,-334.14,220.39 +-923.05,0.00,-923.05,-134.14,0.00,-134.14,220.99 +-723.05,0.00,-723.05,0.00,0.00,0.00,220.82 +-523.05,0.00,-523.05,0.00,0.00,0.00,221.14 +-323.05,0.00,-323.05,0.00,0.00,0.00,221.14 +-123.05,0.00,-123.05,0.00,0.00,0.00,221.06 +0.00,0.00,0.00,0.00,0.00,0.00,220.87 +0.00,0.00,0.00,0.00,0.00,0.00,220.87 +0.00,0.00,0.00,0.00,0.00,0.00,220.54 +0.00,0.00,0.00,0.00,0.00,0.00,221.22 +0.00,0.00,0.00,0.00,0.00,0.00,221.22 +0.00,0.00,0.00,0.00,0.00,0.00,221.18 +0.00,0.00,0.00,0.00,0.00,0.00,220.86 +0.00,0.00,0.00,0.00,0.00,0.00,220.86 +0.00,0.00,0.00,0.00,0.00,0.00,220.45 +0.00,0.00,0.00,0.00,0.00,0.00,220.94 +0.00,0.00,0.00,0.00,0.00,0.00,220.94 +0.00,0.00,0.00,0.00,0.00,0.00,220.68 +0.00,0.00,0.00,0.00,0.00,0.00,220.62 +0.00,0.00,0.00,0.00,0.00,0.00,220.66 +0.00,0.00,0.00,0.00,0.00,0.00,220.66 +0.00,0.00,0.00,0.00,0.00,0.00,220.36 +0.00,0.00,0.00,0.00,0.00,0.00,220.26 +0.00,0.00,0.00,0.00,0.00,0.00,220.26 +0.00,0.00,0.00,0.00,0.00,0.00,220.65 +0.00,0.00,0.00,0.00,0.00,0.00,220.80 +0.00,0.00,0.00,0.00,0.00,0.00,220.80 +0.00,0.00,0.00,0.00,0.00,0.00,220.35 +0.00,0.00,0.00,0.00,0.00,0.00,220.46 +0.00,0.00,0.00,0.00,0.00,0.00,220.69 +0.00,0.00,0.00,0.00,0.00,0.00,220.69 +0.00,0.00,0.00,0.00,0.00,0.00,220.78 +0.00,0.00,0.00,0.00,0.00,0.00,220.50 +0.00,0.00,0.00,0.00,0.00,0.00,220.50 +0.00,0.00,0.00,0.00,0.00,0.00,220.88 +0.00,0.00,0.00,0.00,0.00,0.00,220.90 +0.00,0.00,0.00,0.00,0.00,0.00,220.90 +0.00,0.00,0.00,0.00,0.00,0.00,220.95 +0.00,0.00,0.00,0.00,0.00,0.00,221.08 +0.00,0.00,0.00,0.00,0.00,0.00,221.08 +0.00,0.00,0.00,0.00,0.00,0.00,221.06 +0.00,0.00,0.00,0.00,0.00,0.00,220.44 +0.00,0.00,0.00,0.00,0.00,0.00,220.62 +0.00,0.00,0.00,0.00,0.00,0.00,220.62 +0.00,0.00,0.00,0.00,0.00,0.00,220.60 +0.00,0.00,0.00,0.00,0.00,0.00,220.66 +0.00,0.00,0.00,0.00,0.00,0.00,220.66 +0.00,0.00,0.00,0.00,0.00,0.00,220.40 +0.00,0.00,0.00,0.00,0.00,0.00,221.17 +0.00,0.00,0.00,0.00,0.00,0.00,221.17 +0.00,0.00,0.00,0.00,0.00,0.00,220.69 +0.00,0.00,0.00,0.00,0.00,0.00,220.99 +0.00,0.00,0.00,0.00,0.00,0.00,220.99 +0.00,0.00,0.00,0.00,0.00,0.00,220.95 +0.00,0.00,0.00,0.00,0.00,0.00,220.54 +0.00,0.00,0.00,0.00,0.00,0.00,220.62 +0.00,0.00,0.00,0.00,0.00,0.00,220.62 +0.00,0.00,0.00,0.00,0.00,0.00,220.87 +0.00,0.00,0.00,0.00,0.00,0.00,220.73 +0.00,0.00,0.00,0.00,0.00,0.00,220.73 +0.00,0.00,0.00,0.00,0.00,0.00,220.82 +0.00,0.00,0.00,0.00,0.00,0.00,220.81 +0.00,0.00,0.00,0.00,0.00,0.00,221.15 +0.00,0.00,0.00,0.00,0.00,0.00,221.15 +0.00,0.00,0.00,0.00,0.00,0.00,221.08 +0.00,0.00,0.00,0.00,0.00,0.00,220.86 +0.00,0.00,0.00,0.00,0.00,0.00,220.86 +0.00,0.00,0.00,0.00,0.00,0.00,220.94 +0.00,0.00,0.00,0.00,0.00,0.00,221.10 +0.00,0.00,0.00,0.00,0.00,0.00,221.10 +0.00,0.00,0.00,0.00,0.00,0.00,220.86 +0.00,0.00,0.00,0.00,0.00,0.00,220.85 +0.00,0.00,0.00,0.00,0.00,0.00,220.85 +0.00,0.00,0.00,0.00,0.00,0.00,220.77 +0.00,0.00,0.00,0.00,0.00,0.00,220.95 +0.00,0.00,0.00,0.00,0.00,0.00,220.27 +0.00,0.00,0.00,0.00,0.00,0.00,220.27 +0.00,0.00,0.00,0.00,0.00,0.00,220.59 +0.00,0.00,0.00,0.00,0.00,0.00,220.84 +0.00,0.00,0.00,0.00,0.00,0.00,220.84 +0.00,0.00,0.00,0.00,0.00,0.00,220.88 +0.00,0.00,0.00,0.00,0.00,0.00,220.83 +0.00,0.00,0.00,0.00,0.00,0.00,220.83 +0.00,0.00,0.00,0.00,0.00,0.00,220.43 +0.00,0.00,0.00,0.00,0.00,0.00,220.42 +0.00,0.00,0.00,0.00,0.00,0.00,220.42 +0.00,0.00,0.00,0.00,0.00,0.00,220.51 +0.00,0.00,0.00,0.00,0.00,0.00,220.52 +0.00,0.00,0.00,0.00,0.00,0.00,220.58 +0.00,0.00,0.00,0.00,0.00,0.00,220.58 +0.00,0.00,0.00,0.00,0.00,0.00,220.81 +0.00,0.00,0.00,0.00,0.00,0.00,220.52 +0.00,0.00,0.00,0.00,0.00,0.00,220.52 +0.00,0.00,0.00,0.00,0.00,0.00,220.69 +0.00,0.00,0.00,0.00,0.00,0.00,220.79 +0.00,0.00,0.00,0.00,0.00,0.00,220.79 +0.00,0.00,0.00,0.00,0.00,0.00,220.19 +0.00,0.00,0.00,0.00,0.00,0.00,220.34 +0.00,0.00,0.00,0.00,0.00,0.00,220.34 +0.00,0.00,0.00,0.00,0.00,0.00,220.61 +0.00,0.00,0.00,0.00,0.00,0.00,220.90 +0.00,0.00,0.00,0.00,0.00,0.00,220.51 +0.00,0.00,0.00,0.00,0.00,0.00,220.51 +0.00,0.00,0.00,0.00,0.00,0.00,220.68 +0.00,0.00,0.00,0.00,0.00,0.00,220.87 +0.00,0.00,0.00,0.00,0.00,0.00,220.87 +0.00,0.00,0.00,0.00,0.00,0.00,221.11 +0.00,0.00,0.00,0.00,0.00,0.00,220.77 +0.00,0.00,0.00,0.00,0.00,0.00,220.77 +0.00,0.00,0.00,0.00,0.00,0.00,220.87 +0.00,0.00,0.00,0.00,0.00,0.00,220.82 +0.00,0.00,0.00,0.00,0.00,0.00,220.74 +0.00,0.00,0.00,0.00,0.00,0.00,220.74 +0.00,0.00,0.00,0.00,0.00,0.00,220.82 +0.00,0.00,0.00,0.00,0.00,0.00,221.13 +0.00,0.00,0.00,0.00,0.00,0.00,221.13 +0.00,0.00,0.00,0.00,0.00,0.00,221.15 +0.00,0.00,0.00,0.00,0.00,0.00,220.98 +0.00,0.00,0.00,0.00,0.00,0.00,220.98 +0.00,0.00,0.00,0.00,0.00,0.00,221.16 +0.00,0.00,0.00,0.00,0.00,0.00,221.10 +0.00,0.00,0.00,0.00,0.00,0.00,220.85 +0.00,0.00,0.00,0.00,0.00,0.00,220.85 +0.00,0.00,0.00,0.00,0.00,0.00,220.73 +0.00,0.00,0.00,0.00,0.00,0.00,220.54 +0.00,0.00,0.00,0.00,0.00,0.00,220.54 +0.00,0.00,0.00,0.00,0.00,0.00,220.60 +0.00,0.00,0.00,0.00,0.00,0.00,221.06 +0.00,0.00,0.00,0.00,0.00,0.00,221.06 +0.00,0.00,0.00,0.00,0.00,0.00,220.69 +0.00,0.00,0.00,0.00,0.00,0.00,220.90 +0.00,0.00,0.00,0.00,0.00,0.00,220.84 +0.00,0.00,0.00,0.00,0.00,0.00,220.84 +0.00,0.00,0.00,0.00,0.00,0.00,220.99 +0.00,0.00,0.00,0.00,0.00,0.00,220.75 +0.00,0.00,0.00,0.00,0.00,0.00,220.75 +0.00,0.00,0.00,0.00,0.00,0.00,221.20 +0.00,0.00,0.00,0.00,0.00,0.00,220.90 +0.00,0.00,0.00,0.00,0.00,0.00,220.90 +0.00,0.00,0.00,0.00,0.00,0.00,220.78 +0.00,0.00,0.00,0.00,0.00,0.00,220.44 +0.00,0.00,0.00,0.00,0.00,0.00,220.44 +0.00,0.00,0.00,0.00,0.00,0.00,220.93 +0.00,0.00,0.00,0.00,0.00,0.00,220.63 +0.00,0.00,0.00,0.00,0.00,0.00,220.88 +0.00,0.00,0.00,0.00,0.00,0.00,220.88 +0.00,0.00,0.00,0.00,0.00,0.00,220.45 +0.00,0.00,0.00,0.00,0.00,0.00,220.23 +0.00,0.00,0.00,0.00,0.00,0.00,220.23 +0.00,0.00,0.00,0.00,0.00,0.00,220.74 +0.00,0.00,0.00,0.00,0.00,0.00,220.55 +0.00,0.00,0.00,0.00,0.00,0.00,220.55 +0.00,0.00,0.00,0.00,0.00,0.00,220.56 +0.00,0.00,0.00,0.00,0.00,0.00,220.37 +0.00,0.00,0.00,0.00,0.00,0.00,220.59 +0.00,0.00,0.00,0.00,0.00,0.00,220.59 +0.00,0.00,0.00,0.00,0.00,0.00,220.09 +0.00,0.00,0.00,0.00,0.00,0.00,220.26 +0.00,0.00,0.00,0.00,0.00,0.00,220.26 +0.00,0.00,0.00,0.00,0.00,0.00,220.21 +0.00,0.00,0.00,0.00,0.00,0.00,220.86 +0.00,0.00,0.00,0.00,0.00,0.00,220.86 +0.00,0.00,0.00,0.00,0.00,0.00,220.88 +0.00,0.00,0.00,0.00,0.00,0.00,220.56 +0.00,0.00,0.00,0.00,0.00,0.00,220.56 +0.00,0.00,0.00,0.00,0.00,0.00,220.82 +0.00,0.00,0.00,0.00,0.00,0.00,220.44 +0.00,0.00,0.00,0.00,0.00,0.00,220.72 +0.00,0.00,0.00,0.00,0.00,0.00,220.72 +0.00,0.00,0.00,0.00,0.00,0.00,220.29 +0.00,0.00,0.00,0.00,0.00,0.00,220.26 +0.00,0.00,0.00,0.00,0.00,0.00,220.26 +0.00,0.00,0.00,0.00,0.00,0.00,220.45 +0.00,0.00,0.00,0.00,0.00,0.00,220.56 +0.00,0.00,0.00,0.00,0.00,0.00,220.56 +0.00,0.00,0.00,0.00,0.00,0.00,220.30 +0.00,0.00,0.00,0.00,0.00,0.00,220.41 +0.00,0.00,0.00,0.00,0.00,0.00,221.04 +0.00,0.00,0.00,0.00,0.00,0.00,221.04 +0.00,0.00,0.00,0.00,0.00,0.00,220.58 +0.00,0.00,0.00,0.00,0.00,0.00,220.74 +0.00,0.00,0.00,0.00,0.00,0.00,220.74 +0.00,0.00,0.00,0.00,0.00,0.00,220.43 +0.00,0.00,0.00,0.00,0.00,0.00,220.70 +0.00,0.00,0.00,0.00,0.00,0.00,220.70 +0.00,0.00,0.00,0.00,0.00,0.00,220.89 +0.00,0.00,0.00,0.00,0.00,0.00,220.55 +0.00,0.00,0.00,0.00,0.00,0.00,220.55 +0.00,0.00,0.00,0.00,0.00,0.00,220.69 +0.00,0.00,0.00,0.00,0.00,0.00,220.62 +0.00,0.00,0.00,0.00,0.00,0.00,220.62 +0.00,0.00,0.00,0.00,0.00,0.00,220.42 +200.00,0.00,200.00,200.00,0.00,200.00,220.62 +400.00,0.00,400.00,400.00,0.00,400.00,220.39 +600.00,0.00,600.00,600.00,0.00,600.00,220.39 +800.00,0.00,800.00,800.00,0.00,800.00,220.65 +1000.00,0.00,1000.00,1000.00,0.00,1000.00,221.22 +1200.00,0.00,1200.00,1200.00,0.00,1200.00,221.22 +1400.00,0.00,1400.00,1400.00,0.00,1400.00,221.12 +1600.00,0.00,1600.00,1600.00,0.00,1600.00,221.23 +1800.00,0.00,1800.00,1800.00,0.00,1800.00,221.23 +2000.00,0.00,2000.00,2000.00,0.00,2000.00,220.89 +2200.00,0.00,2200.00,2200.00,0.00,2200.00,220.74 +2400.00,0.00,2400.00,2400.00,0.00,2400.00,220.55 +2600.00,0.00,2600.00,2600.00,0.00,2600.00,220.55 +2800.00,0.00,2800.00,2800.00,0.00,2800.00,220.50 +3000.00,0.00,3000.00,3000.00,0.00,3000.00,220.87 +3200.00,0.00,3200.00,3200.00,0.00,3200.00,220.87 +3400.00,0.00,3400.00,3400.00,0.00,3400.00,220.84 +3600.00,0.00,3600.00,3600.00,0.00,3600.00,220.73 +3800.00,0.00,3800.00,3800.00,0.00,3800.00,220.57 +4000.00,0.00,4000.00,4000.00,0.00,4000.00,220.57 +4200.00,0.00,4200.00,4200.00,0.00,4200.00,220.63 +4400.00,0.00,4400.00,4400.00,0.00,4400.00,220.80 +4600.00,0.00,4600.00,4600.00,0.00,4600.00,220.80 +4800.00,500.00,4300.00,4800.00,350.00,4450.00,220.97 +5000.00,2450.00,2550.00,5000.00,1050.00,3950.00,220.88 +5200.00,2850.00,2350.00,5200.00,1600.00,3600.00,220.88 +5400.00,1500.00,3900.00,5400.00,900.00,4500.00,220.68 +5600.00,2200.00,3400.00,5600.00,0.00,5600.00,219.66 +5800.00,2350.00,3450.00,5800.00,1400.00,4400.00,219.66 +6000.00,1400.00,4600.00,6000.00,3100.00,2900.00,220.45 +6200.00,2800.00,3400.00,6200.00,3250.00,2950.00,221.57 +6400.00,4050.00,2350.00,6400.00,2350.00,4050.00,221.57 +6600.00,4500.00,2100.00,6600.00,1600.00,5000.00,220.62 +6800.00,3400.00,3400.00,6800.00,3100.00,3700.00,220.53 +7000.00,3200.00,3800.00,7000.00,4600.00,2400.00,221.47 +7200.00,4150.00,3050.00,7200.00,4600.00,2600.00,221.47 +7400.00,5050.00,2350.00,7400.00,3950.00,3450.00,221.32 +7600.00,5750.00,1850.00,7600.00,4450.00,3150.00,220.87 +7800.00,5550.00,2250.00,7800.00,5000.00,2800.00,220.87 +8000.00,4850.00,3150.00,8000.00,5400.00,2600.00,221.20 +8200.00,5800.00,2400.00,8200.00,5750.00,2450.00,221.05 +8400.00,6200.00,2200.00,8400.00,6050.00,2350.00,221.05 +8600.00,6650.00,1950.00,8600.00,6350.00,2250.00,221.17 +8800.00,7350.00,1450.00,8800.00,6800.00,2000.00,221.22 +9000.00,7650.00,1350.00,9000.00,7050.00,1950.00,221.22 +9200.00,7650.00,1550.00,9200.00,7050.00,2150.00,220.66 +9400.00,7850.00,1550.00,9400.00,7350.00,2050.00,220.78 +9600.00,8100.00,1500.00,9600.00,7650.00,1950.00,220.78 +9800.00,8350.00,1450.00,9800.00,7950.00,1850.00,221.04 +10000.00,8550.00,1450.00,10000.00,8100.00,1900.00,221.34 +10200.00,9050.00,1150.00,10200.00,8700.00,1500.00,221.21 +10400.00,8950.00,1450.00,10400.00,8600.00,1800.00,221.21 +10600.00,9450.00,1150.00,10600.00,9150.00,1450.00,221.46 +10800.00,9700.00,1100.00,10800.00,9350.00,1450.00,220.90 +11000.00,9950.00,1050.00,11000.00,9500.00,1500.00,220.90 +11200.00,10100.00,1100.00,11200.00,9800.00,1400.00,221.04 +11400.00,10300.00,1100.00,11400.00,9900.00,1500.00,221.39 +11600.00,10450.00,1150.00,11600.00,10150.00,1450.00,221.39 +11800.00,10750.00,1050.00,11800.00,10350.00,1450.00,221.18 +12000.00,10950.00,1050.00,12000.00,10600.00,1400.00,221.05 +12200.00,11300.00,900.00,12200.00,10900.00,1300.00,221.05 +12400.00,11550.00,850.00,12400.00,11050.00,1350.00,220.65 +12600.00,11800.00,800.00,12600.00,11250.00,1350.00,220.93 +12800.00,12100.00,700.00,12800.00,11700.00,1100.00,220.94 +13000.00,12300.00,700.00,13000.00,11850.00,1150.00,220.94 +13200.00,12450.00,750.00,13200.00,11900.00,1300.00,221.15 +13400.00,12650.00,750.00,13400.00,12100.00,1300.00,220.63 +13600.00,12950.00,650.00,13600.00,12350.00,1250.00,220.63 +13800.00,13200.00,600.00,13800.00,12650.00,1150.00,221.14 +14000.00,13350.00,650.00,14000.00,12750.00,1250.00,220.89 +14200.00,13650.00,550.00,14200.00,12950.00,1250.00,220.89 +14400.00,13950.00,450.00,14400.00,13150.00,1250.00,221.05 +14600.00,14050.00,550.00,14600.00,13450.00,1150.00,220.88 +14800.00,14300.00,500.00,14800.00,13600.00,1200.00,220.85 +15000.00,14550.00,450.00,15000.00,13750.00,1250.00,220.85 +15200.00,14800.00,400.00,15200.00,13900.00,1300.00,220.83 +15400.00,15000.00,400.00,15400.00,14200.00,1200.00,220.77 +15600.00,15300.00,300.00,15600.00,14500.00,1100.00,220.77 +15800.00,15550.00,250.00,15800.00,14750.00,1050.00,220.86 +16000.00,15750.00,250.00,16000.00,15000.00,1000.00,221.00 +16200.00,16550.00,-350.00,16200.00,15800.00,400.00,220.55 +16400.00,19700.00,-3300.00,16400.00,18850.00,-2450.00,220.55 +16600.00,16600.00,0.00,16600.00,16200.00,400.00,220.60 +16800.00,16050.00,750.00,16800.00,15750.00,1050.00,220.80 +17000.00,16100.00,900.00,17000.00,15600.00,1400.00,220.71 +17200.00,16550.00,650.00,17200.00,16100.00,1100.00,220.71 +17400.00,16850.00,550.00,17400.00,16500.00,900.00,220.92 +17600.00,17250.00,350.00,17600.00,16900.00,700.00,220.99 +17800.00,17450.00,350.00,17800.00,17200.00,600.00,220.99 +18000.00,17750.00,250.00,18000.00,17450.00,550.00,221.58 +18200.00,17950.00,250.00,18200.00,17700.00,500.00,221.40 +18400.00,18800.00,-400.00,18400.00,18600.00,-200.00,221.40 +18600.00,18350.00,250.00,18600.00,18000.00,600.00,221.31 +18800.00,19100.00,-300.00,18800.00,19000.00,-200.00,221.49 +19000.00,19400.00,-400.00,19000.00,19150.00,-150.00,221.72 +19200.00,18850.00,350.00,19200.00,18400.00,800.00,221.72 +19400.00,19600.00,-200.00,19400.00,19550.00,-150.00,221.62 +19600.00,19900.00,-300.00,19600.00,19700.00,-100.00,221.66 +19800.00,20100.00,-300.00,19800.00,19900.00,-100.00,220.94 +20000.00,20150.00,-150.00,20000.00,20000.00,0.00,220.94 +20200.00,20450.00,-250.00,20200.00,20000.00,200.00,221.49 +20400.00,20600.00,-200.00,20400.00,20300.00,100.00,220.95 +20600.00,20900.00,-300.00,20600.00,20450.00,150.00,220.95 +20800.00,21150.00,-350.00,20800.00,20450.00,350.00,221.12 +21000.00,21400.00,-400.00,21000.00,20900.00,100.00,221.24 +21200.00,21800.00,-600.00,21200.00,21100.00,100.00,221.17 +21400.00,21800.00,-400.00,21400.00,21300.00,100.00,221.17 +21600.00,22100.00,-500.00,21600.00,21600.00,0.00,220.86 +21800.00,21650.00,150.00,21800.00,21400.00,400.00,220.87 +22000.00,22800.00,-800.00,22000.00,22350.00,-350.00,220.87 +22200.00,23250.00,-1050.00,22200.00,22650.00,-450.00,220.88 +22400.00,23050.00,-650.00,22400.00,22450.00,-50.00,221.11 +22600.00,23300.00,-700.00,22600.00,22900.00,-300.00,221.20 +22800.00,23300.00,-500.00,22800.00,23200.00,-400.00,221.20 +23000.00,23700.00,-700.00,23000.00,23350.00,-350.00,220.83 +23200.00,23850.00,-650.00,23200.00,23600.00,-400.00,221.40 +23400.00,24050.00,-650.00,23400.00,23750.00,-350.00,221.28 +23600.00,24200.00,-600.00,23388.51,23850.00,-461.49,221.28 +23800.00,24450.00,-650.00,23188.51,24200.00,-1011.49,221.48 +23786.61,24600.00,-813.39,22988.51,24300.00,-1311.49,221.53 +23586.61,24850.00,-1263.39,22788.51,24200.00,-1411.49,221.53 +23386.61,24600.00,-1213.39,22588.51,24050.00,-1461.49,221.35 +23186.61,24500.00,-1313.39,22388.51,23950.00,-1561.49,221.55 +22986.61,24450.00,-1463.39,22188.51,23700.00,-1511.49,221.79 +22786.61,24500.00,-1713.39,21988.51,23350.00,-1361.49,221.79 +22586.61,24200.00,-1613.39,21788.51,23150.00,-1361.49,221.66 +22386.61,23850.00,-1463.39,21588.51,22900.00,-1311.49,221.51 +22186.61,23850.00,-1663.39,21388.51,22700.00,-1311.49,221.45 +21986.61,23650.00,-1663.39,21188.51,22350.00,-1161.49,221.45 +21786.61,23300.00,-1513.39,20988.51,22050.00,-1061.49,221.13 +21586.61,23150.00,-1563.39,20788.51,21850.00,-1061.49,221.44 +21386.61,23000.00,-1613.39,20588.51,21700.00,-1111.49,221.44 +21186.61,22600.00,-1413.39,20388.51,21250.00,-861.49,220.83 +20986.61,22550.00,-1563.39,20188.51,21200.00,-1011.49,220.90 +20786.61,21650.00,-863.39,19988.51,20200.00,-211.49,221.04 +20586.61,22250.00,-1663.39,19788.51,20850.00,-1061.49,221.04 +20386.61,22300.00,-1913.39,19588.51,20750.00,-1161.49,220.68 +20186.61,21950.00,-1763.39,19388.51,20600.00,-1211.49,220.92 +19986.61,21550.00,-1563.39,19188.51,19900.00,-711.49,220.92 +19786.61,21100.00,-1313.39,18988.51,20100.00,-1111.49,220.48 +19586.61,21050.00,-1463.39,18788.51,19800.00,-1011.49,220.80 +19386.61,20850.00,-1463.39,18588.51,19400.00,-811.49,221.40 +19186.61,20650.00,-1463.39,18388.51,19400.00,-1011.49,221.40 +18986.61,20150.00,-1163.39,18188.51,19000.00,-811.49,221.43 +18786.61,19400.00,-613.39,17988.51,18200.00,-211.49,221.80 +18586.61,19850.00,-1263.39,17788.51,18750.00,-961.49,221.62 +18386.61,19700.00,-1313.39,17588.51,18400.00,-811.49,221.62 +18186.61,18850.00,-663.39,17388.51,17700.00,-311.49,221.84 +17986.61,19250.00,-1263.39,17188.51,18100.00,-911.49,221.58 +17786.61,19200.00,-1413.39,16988.51,17750.00,-761.49,221.58 +17586.61,18800.00,-1213.39,16788.51,17700.00,-911.49,221.39 +17386.61,21600.00,-4213.39,16588.51,19900.00,-3311.49,221.62 +17186.61,17900.00,-713.39,16388.51,16800.00,-411.49,221.36 +16986.61,16600.00,386.61,16188.51,15500.00,688.51,221.36 +16786.61,16750.00,36.61,15988.51,15400.00,588.51,221.73 +16586.61,17550.00,-963.39,15788.51,16250.00,-461.49,221.70 +16386.61,17550.00,-1163.39,15588.51,16350.00,-761.49,221.37 +16186.61,17400.00,-1213.39,15388.51,16100.00,-711.49,221.37 +15986.61,16550.00,-563.39,15188.51,15250.00,-61.49,221.18 +15786.61,16850.00,-1063.39,14988.51,15650.00,-661.49,221.37 +15586.61,16750.00,-1163.39,14788.51,15350.00,-561.49,221.37 +15386.61,16000.00,-613.39,14588.51,14600.00,-11.49,221.21 +15186.61,16300.00,-1113.39,14388.51,14850.00,-461.49,221.13 +14986.61,16100.00,-1113.39,14188.51,14600.00,-411.49,220.88 +14786.61,15400.00,-613.39,13988.51,13900.00,88.51,220.88 +14586.61,15700.00,-1113.39,13788.51,14100.00,-311.49,220.58 +14386.61,15550.00,-1163.39,13588.51,13950.00,-361.49,220.36 +14186.61,14800.00,-613.39,13388.51,13200.00,188.51,220.36 +13986.61,14550.00,-563.39,13188.51,13000.00,188.51,220.37 +13786.61,14400.00,-613.39,12988.51,12850.00,138.51,220.65 +13586.61,14750.00,-1163.39,12788.51,13150.00,-361.49,220.77 +13386.61,14450.00,-1063.39,12588.51,12850.00,-261.49,220.77 +13186.61,13550.00,-363.39,12388.51,12150.00,238.51,220.46 +12986.61,13400.00,-413.39,12188.51,11950.00,238.51,220.81 +12786.61,13400.00,-613.39,11988.51,11800.00,188.51,220.81 +12586.61,13250.00,-663.39,11788.51,11600.00,188.51,220.20 +12386.61,12850.00,-463.39,11588.51,11450.00,138.51,220.73 +12186.61,12650.00,-463.39,11388.51,11250.00,138.51,220.73 +11986.61,12550.00,-563.39,11188.51,11150.00,38.51,220.51 +11786.61,12150.00,-363.39,10988.51,10850.00,138.51,220.91 +11586.61,11900.00,-313.39,10788.51,10550.00,238.51,221.04 +11386.61,11800.00,-413.39,10588.51,10300.00,288.51,221.04 +11186.61,11700.00,-513.39,10388.51,10150.00,238.51,220.83 +10986.61,11300.00,-313.39,10188.51,9900.00,288.51,221.14 +10786.61,11450.00,-663.39,9988.51,10000.00,-11.49,221.14 +10586.61,10650.00,-63.39,9788.51,9400.00,388.51,221.26 +10386.61,8800.00,1586.61,9588.51,7700.00,1888.51,221.43 +10186.61,9150.00,1036.61,9388.51,8150.00,1238.51,221.33 +9986.61,9400.00,586.61,9188.51,8100.00,1088.51,221.33 +9786.61,9500.00,286.61,8988.51,8350.00,638.51,221.18 +9586.61,9200.00,386.61,8788.51,7700.00,1088.51,221.62 +9386.61,8950.00,436.61,8588.51,6900.00,1688.51,221.62 +9186.61,7400.00,1786.61,8388.51,7300.00,1088.51,221.43 +8986.61,6400.00,2586.61,8188.51,6350.00,1838.51,221.05 +8786.61,7250.00,1536.61,7988.51,6100.00,1888.51,221.05 +8586.61,7550.00,1036.61,7788.51,6450.00,1338.51,221.44 +8386.61,7750.00,636.61,7588.51,6200.00,1388.51,221.30 +8186.61,6450.00,1736.61,7388.51,5100.00,2288.51,221.30 +7986.61,5950.00,2036.61,7188.51,4700.00,2488.51,221.44 +7786.61,6250.00,1536.61,6988.51,5200.00,1788.51,221.57 +7586.61,6350.00,1236.61,6788.51,5000.00,1788.51,221.36 +7386.61,5100.00,2286.61,6588.51,3900.00,2688.51,221.36 +7186.61,4950.00,2236.61,6388.51,3050.00,3338.51,221.68 +6986.61,4950.00,2036.61,6188.51,2900.00,3288.51,221.59 +6786.61,3800.00,2986.61,5988.51,3550.00,2438.51,221.59 +6586.61,3600.00,2986.61,5788.51,3700.00,2088.51,221.69 +6386.61,4500.00,1886.61,5588.51,2800.00,2788.51,221.60 +6186.61,4550.00,1636.61,5388.51,2050.00,3338.51,221.60 +5986.61,3850.00,2136.61,5188.51,450.00,4738.51,221.56 +5786.61,3000.00,2786.61,4988.51,200.00,4788.51,221.93 +5586.61,2300.00,3286.61,4788.51,2400.00,2388.51,221.93 +5386.61,1000.00,4386.61,4588.51,2700.00,1888.51,221.02 +5186.61,650.00,4536.61,4388.51,1800.00,2588.51,222.40 +4986.61,2550.00,2436.61,4188.51,1300.00,2888.51,222.40 +4786.61,3250.00,1536.61,3988.51,1050.00,2938.51,221.88 +4586.61,2650.00,1936.61,3788.51,-600.00,4388.51,221.71 +4386.61,1050.00,3336.61,3588.51,-150.00,3738.51,221.98 +4186.61,650.00,3536.61,3388.51,0.00,3388.51,221.98 +3986.61,1050.00,2936.61,3188.51,0.00,3188.51,221.31 +3786.61,100.00,3686.61,2988.51,0.00,2988.51,220.91 +3586.61,-100.00,3686.61,2788.51,0.00,2788.51,220.91 +3386.61,0.00,3386.61,2588.51,0.00,2588.51,221.35 +3186.61,0.00,3186.61,2388.51,0.00,2388.51,220.72 +2986.61,0.00,2986.61,2188.51,0.00,2188.51,220.62 +2786.61,0.00,2786.61,1988.51,0.00,1988.51,220.62 +2586.61,0.00,2586.61,1788.51,0.00,1788.51,220.88 +2386.61,0.00,2386.61,1588.51,0.00,1588.51,221.06 +2186.61,0.00,2186.61,1388.51,0.00,1388.51,221.06 +1986.61,0.00,1986.61,1188.51,0.00,1188.51,220.99 +1786.61,0.00,1786.61,988.51,0.00,988.51,220.77 +1586.61,0.00,1586.61,788.51,0.00,788.51,220.77 +1386.61,0.00,1386.61,588.51,0.00,588.51,220.73 +1186.61,0.00,1186.61,388.51,0.00,388.51,220.52 +986.61,0.00,986.61,188.51,0.00,188.51,220.52 +786.61,0.00,786.61,0.00,0.00,0.00,220.94 +586.61,0.00,586.61,0.00,0.00,0.00,221.05 +386.61,0.00,386.61,0.00,0.00,0.00,221.20 +186.61,0.00,186.61,0.00,0.00,0.00,221.20 +0.00,0.00,0.00,0.00,0.00,0.00,221.03 +0.00,0.00,0.00,0.00,0.00,0.00,221.16 +0.00,0.00,0.00,0.00,0.00,0.00,221.16 +0.00,0.00,0.00,0.00,0.00,0.00,220.68 +0.00,0.00,0.00,0.00,0.00,0.00,221.08 +0.00,0.00,0.00,0.00,0.00,0.00,221.08 +0.00,0.00,0.00,0.00,0.00,0.00,220.48 +0.00,0.00,0.00,0.00,0.00,0.00,220.21 +0.00,0.00,0.00,0.00,0.00,0.00,220.21 +0.00,0.00,0.00,0.00,0.00,0.00,220.58 +0.00,0.00,0.00,0.00,0.00,0.00,220.51 +0.00,0.00,0.00,0.00,0.00,0.00,220.51 +0.00,0.00,0.00,0.00,0.00,0.00,220.60 +0.00,0.00,0.00,0.00,0.00,0.00,220.66 +0.00,0.00,0.00,0.00,0.00,0.00,220.45 +0.00,0.00,0.00,0.00,0.00,0.00,220.45 +0.00,0.00,0.00,0.00,0.00,0.00,220.25 +0.00,0.00,0.00,0.00,0.00,0.00,220.38 +0.00,0.00,0.00,0.00,0.00,0.00,220.38 +0.00,0.00,0.00,0.00,0.00,0.00,220.32 +0.00,0.00,0.00,0.00,0.00,0.00,220.39 +0.00,0.00,0.00,0.00,0.00,0.00,220.39 \ No newline at end of file diff --git a/src/robot/control.cpp b/src/robot/control.cpp index 8806749..ddb9471 100644 --- a/src/robot/control.cpp +++ b/src/robot/control.cpp @@ -31,12 +31,12 @@ Magnet *magnet = nullptr; // Declare a pointer to Magnet // pid constants -TrapezoidProfile::Constraints profileConstraints(MAX_VELOCITY_TPS, MAX_ACCELERATION_TPSPS); +TrapezoidProfile::Constraints profileConstraints(VELOCITY_LIMIT_TPS, ACCELERATION_LIMIT_TPSPS); TrapezoidProfile leftProfile(profileConstraints); TrapezoidProfile rightProfile(profileConstraints); TrapezoidProfile::State leftSetpoint, rightSetpoint; -PIDController encoderAVelocityController(0.00004, 0.000005, 0.00000, -1, +1); // Blue -PIDController encoderBVelocityController(0.00004, 0.000005, 0.00000, -1, +1); //Red +PIDController encoderAVelocityController(0.00002, 0.000000, 0.00000, -1, +1); // Blue +PIDController encoderBVelocityController(0.00002, 0.000000, 0.00000, -1, +1); //Red //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; @@ -274,8 +274,8 @@ void controlLoop(int loopDelayMs, int8_t framesUntilPrint) { prevPositionA = currentPositionEncoderA; prevPositionB = currentPositionEncoderB; - double leftFeedForward = leftSetpoint.velocity / MAX_VELOCITY_TPS; - double rightFeedForward = rightSetpoint.velocity / MAX_VELOCITY_TPS; + double leftFeedForward = leftSetpoint.velocity / THEORETICAL_MAX_VELOCITY_TPS; + double rightFeedForward = rightSetpoint.velocity / THEORETICAL_MAX_VELOCITY_TPS; double leftMotorPower = encoderAVelocityController.Compute(leftSetpoint.velocity, currentVelocityA, loopDelaySeconds) + leftFeedForward; double rightMotorPower = encoderBVelocityController.Compute(rightSetpoint.velocity, currentVelocityB, loopDelaySeconds) + rightFeedForward; diff --git a/src/utils/config.cpp b/src/utils/config.cpp index 6049e39..7929814 100644 --- a/src/utils/config.cpp +++ b/src/utils/config.cpp @@ -37,8 +37,10 @@ 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 = 63000; +float THEORETICAL_MAX_ACCELERATION_TPSPS = 16000; +float VELOCITY_LIMIT_TPS = 40000; +float ACCELERATION_LIMIT_TPSPS = 10000; float TILES_TO_TICKS = 2*12*TICKS_PER_ROTATION/(WHEEL_DIAMETER_INCHES*M_PI); float PID_POSITION_TOLERANCE = 100; @@ -68,8 +70,8 @@ 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"]; serialLogln("Config Set!", 2); } From fc783edf80deceb0a7d50562594b73c43168cced Mon Sep 17 00:00:00 2001 From: democat Date: Mon, 29 Sep 2025 21:48:35 -0500 Subject: [PATCH 16/47] Low pass filter over magnetometer readings --- include/robot/magnet.h | 3 +++ src/robot/magnet.cpp | 18 ++++++++++++++++-- 2 files changed, 19 insertions(+), 2 deletions(-) diff --git a/include/robot/magnet.h b/include/robot/magnet.h index e6d508a..54cc155 100644 --- a/include/robot/magnet.h +++ b/include/robot/magnet.h @@ -17,6 +17,7 @@ class Magnet { void set_soft_iron_matrix(float matrix[3][3]); struct MagnetReading read_calibrated_data(); float getCompassDegree(struct MagnetReading mag); + float readDegreesRaw(); float readDegrees(); private: float hard_iron_offset[3] = { -23.71, -5.45, -8.27 }; @@ -26,6 +27,8 @@ class Magnet { { 0.023, 0.002, .991 } }; DFRobot_BMM350_I2C bmm350; + + float previousReading = 0.0; }; #endif // MAGNET_H \ No newline at end of file diff --git a/src/robot/magnet.cpp b/src/robot/magnet.cpp index 1e9be51..20495db 100644 --- a/src/robot/magnet.cpp +++ b/src/robot/magnet.cpp @@ -56,7 +56,21 @@ float Magnet::getCompassDegree(MagnetReading mag) { return compass * 180 / M_PI; } -float Magnet::readDegrees() { +float Magnet::readDegreesRaw() { MagnetReading mag = read_calibrated_data(); return getCompassDegree(mag); -} \ No newline at end of file +} + +float Magnet::readDegrees() { + float currentReading = readDegreesRaw(); + // 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; + previousReading = currentReading; + return currentReading; +} From 2ef2c0b549788433479fbc47b7e6c905d7df9371 Mon Sep 17 00:00:00 2001 From: democat Date: Mon, 29 Sep 2025 21:50:18 -0500 Subject: [PATCH 17/47] Ensure no state changes (it really didn't before anyway, might revert later) --- include/robot/trapezoidalProfileNew.h | 15 +---- src/robot/trapezoidalProfileNew.cpp | 83 +++------------------------ 2 files changed, 10 insertions(+), 88 deletions(-) diff --git a/include/robot/trapezoidalProfileNew.h b/include/robot/trapezoidalProfileNew.h index 855a180..67e551b 100644 --- a/include/robot/trapezoidalProfileNew.h +++ b/include/robot/trapezoidalProfileNew.h @@ -40,15 +40,11 @@ class TrapezoidProfile }; TrapezoidProfile(const Constraints& constraints) - : m_constraints(constraints), m_direction(1), m_endAccel(0), m_endFullSpeed(0), m_endDecel(0) {} + : m_constraints(constraints) {} State calculate(double t, const State& current, const State& goal); - double timeLeftUntil(double target); - - double totalTime() const { return m_endDecel; } - - bool isFinished(double t) const { return t >= totalTime(); } + // bool isFinished(double t) const { return t >= totalTime(); } private: static bool shouldFlipAcceleration(const State& initial, const State& goal) @@ -56,17 +52,12 @@ class TrapezoidProfile return initial.position > goal.position; } - State direct(const State& in) const + State direct(const State& in, int m_direction) const { return State(in.position * m_direction, in.velocity * m_direction); } - int m_direction; Constraints m_constraints; - State m_current; - double m_endAccel; - double m_endFullSpeed; - double m_endDecel; }; #endif \ No newline at end of file diff --git a/src/robot/trapezoidalProfileNew.cpp b/src/robot/trapezoidalProfileNew.cpp index 5a75c3c..962fe6f 100644 --- a/src/robot/trapezoidalProfileNew.cpp +++ b/src/robot/trapezoidalProfileNew.cpp @@ -2,9 +2,9 @@ TrapezoidProfile::State TrapezoidProfile::calculate(double t, const State ¤t, const State &goal) { - m_direction = shouldFlipAcceleration(current, goal) ? -1 : 1; - m_current = direct(current); - State goalDir = direct(goal); + int m_direction = shouldFlipAcceleration(current, goal) ? -1 : 1; + State m_current = direct(current, m_direction); + State goalDir = direct(goal, m_direction); if (std::abs(m_current.velocity) > m_constraints.maxVelocity) { @@ -28,9 +28,9 @@ TrapezoidProfile::State TrapezoidProfile::calculate(double t, const State &curre fullSpeedDist = 0; } - m_endAccel = accelerationTime - cutoffBegin; - m_endFullSpeed = m_endAccel + fullSpeedDist / m_constraints.maxVelocity; - m_endDecel = m_endFullSpeed + accelerationTime - cutoffEnd; + 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) @@ -57,74 +57,5 @@ TrapezoidProfile::State TrapezoidProfile::calculate(double t, const State &curre result = goalDir; } - return direct(result); + return direct(result, m_direction); } - -double TrapezoidProfile::timeLeftUntil(double target) -{ - double position = m_current.position * m_direction; - double velocity = m_current.velocity * m_direction; - - double endAccel = m_endAccel * m_direction; - double endFullSpeed = m_endFullSpeed * m_direction - endAccel; - - if (target < position) - { - endAccel = -endAccel; - endFullSpeed = -endFullSpeed; - velocity = -velocity; - } - - endAccel = std::max(endAccel, 0.0); - endFullSpeed = std::max(endFullSpeed, 0.0); - - const double acceleration = m_constraints.maxAcceleration; - const double deceleration = -m_constraints.maxAcceleration; - - double distToTarget = std::abs(target - position); - if (distToTarget < 1e-6) - { - return 0; - } - - double accelDist = velocity * endAccel + 0.5 * acceleration * endAccel * endAccel; - - double decelVelocity; - if (endAccel > 0) - { - decelVelocity = std::sqrt(std::abs(velocity * velocity + 2 * acceleration * accelDist)); - } - else - { - decelVelocity = velocity; - } - - double fullSpeedDist = m_constraints.maxVelocity * endFullSpeed; - double decelDist; - - if (accelDist > distToTarget) - { - accelDist = distToTarget; - fullSpeedDist = 0; - decelDist = 0; - } - else if (accelDist + fullSpeedDist > distToTarget) - { - fullSpeedDist = distToTarget - accelDist; - decelDist = 0; - } - else - { - decelDist = distToTarget - fullSpeedDist - accelDist; - } - - double accelTime = - (-velocity + std::sqrt(std::abs(velocity * velocity + 2 * acceleration * accelDist))) / acceleration; - - double decelTime = - (-decelVelocity + std::sqrt(std::abs(decelVelocity * decelVelocity + 2 * deceleration * decelDist))) / deceleration; - - double fullSpeedTime = fullSpeedDist / m_constraints.maxVelocity; - - return accelTime + fullSpeedTime + decelTime; -} \ No newline at end of file From 2201721b98036f11af608661abef6b779a2b544e Mon Sep 17 00:00:00 2001 From: democat Date: Mon, 29 Sep 2025 21:50:30 -0500 Subject: [PATCH 18/47] Add minimum motor power config value --- include/utils/config.h | 1 + src/robot/control.cpp | 5 ++--- src/utils/config.cpp | 2 ++ 3 files changed, 5 insertions(+), 3 deletions(-) diff --git a/include/utils/config.h b/include/utils/config.h index 743a031..803c9b3 100644 --- a/include/utils/config.h +++ b/include/utils/config.h @@ -37,6 +37,7 @@ 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 TILES_TO_TICKS; extern float PID_POSITION_TOLERANCE; diff --git a/src/robot/control.cpp b/src/robot/control.cpp index ddb9471..0d4ffeb 100644 --- a/src/robot/control.cpp +++ b/src/robot/control.cpp @@ -567,10 +567,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; } diff --git a/src/utils/config.cpp b/src/utils/config.cpp index 7929814..2f9aebc 100644 --- a/src/utils/config.cpp +++ b/src/utils/config.cpp @@ -41,6 +41,7 @@ float THEORETICAL_MAX_VELOCITY_TPS = 63000; float THEORETICAL_MAX_ACCELERATION_TPSPS = 16000; float VELOCITY_LIMIT_TPS = 40000; float ACCELERATION_LIMIT_TPSPS = 10000; +float MIN_MOTOR_POWER = 0.12; // Minimum motor power to elicit motor response, empirically determined float TILES_TO_TICKS = 2*12*TICKS_PER_ROTATION/(WHEEL_DIAMETER_INCHES*M_PI); float PID_POSITION_TOLERANCE = 100; @@ -72,6 +73,7 @@ void setConfig(JsonObject config) { if (config["WHEEL_DIAMETER_INCHES"].is()) WHEEL_DIAMETER_INCHES = config["WHEEL_DIAMETER_INCHES"]; 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"]; serialLogln("Config Set!", 2); } From 1e5698470777e566abf3a8f0f4eca5d6c8efac8b Mon Sep 17 00:00:00 2001 From: democat Date: Mon, 29 Sep 2025 21:09:51 -0500 Subject: [PATCH 19/47] Fix feedforward overpowering PID --- include/robot/control.h | 4 +- include/utils/config.h | 6 +- pid_test.csv | 4187 +++++++-------------------------------- src/robot/control.cpp | 13 +- src/utils/config.cpp | 10 +- 5 files changed, 735 insertions(+), 3485 deletions(-) diff --git a/include/robot/control.h b/include/robot/control.h index f10a906..4c7b97b 100644 --- a/include/robot/control.h +++ b/include/robot/control.h @@ -20,8 +20,8 @@ struct ControlSetting static ControlSetting leftMotorControl; static ControlSetting rightMotorControl; -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 profileA = {THEORETICAL_MAX_VELOCITY_TPS, THEORETICAL_MAX_ACCELERATION_TPSPS, 0, 0, 0, 0, 75.0}; // maxVelocity, maxAcceleration, currentPosition, currentVelocity, targetPosition, targetVelocity +static MotionProfile profileB = {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); diff --git a/include/utils/config.h b/include/utils/config.h index b98a5cb..743a031 100644 --- a/include/utils/config.h +++ b/include/utils/config.h @@ -33,8 +33,10 @@ 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 TILES_TO_TICKS; extern float PID_POSITION_TOLERANCE; diff --git a/pid_test.csv b/pid_test.csv index df3ec6a..a285e3f 100644 --- a/pid_test.csv +++ b/pid_test.csv @@ -1,3471 +1,716 @@ -LeftSetpoint,LeftVelocity,LeftError,RightSetpoint,RightVelocity,RightError -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 --100.00,0.00,-100.00,-100.00,0.00,-100.00 --200.00,0.00,-200.00,-200.00,0.00,-200.00 --300.00,0.00,-300.00,-300.00,0.00,-300.00 --400.00,0.00,-400.00,-400.00,0.00,-400.00 --500.00,0.00,-500.00,-500.00,0.00,-500.00 --600.00,0.00,-600.00,-600.00,0.00,-600.00 --700.00,0.00,-700.00,-700.00,0.00,-700.00 --800.00,0.00,-800.00,-800.00,0.00,-800.00 --900.00,0.00,-900.00,-900.00,0.00,-900.00 --1000.00,0.00,-1000.00,-1000.00,0.00,-1000.00 --1100.00,0.00,-1100.00,-1100.00,0.00,-1100.00 --1200.00,0.00,-1200.00,-1200.00,0.00,-1200.00 --1300.00,0.00,-1300.00,-1300.00,0.00,-1300.00 --1400.00,0.00,-1400.00,-1400.00,0.00,-1400.00 --1500.00,0.00,-1500.00,-1500.00,0.00,-1500.00 --1600.00,0.00,-1600.00,-1600.00,0.00,-1600.00 --1700.00,-400.00,-1300.00,-1700.00,-500.00,-1200.00 --1800.00,-600.00,-1200.00,-1800.00,-600.00,-1200.00 --1900.00,650.00,-2550.00,-1900.00,800.00,-2700.00 --2000.00,-450.00,-1550.00,-2000.00,-500.00,-1500.00 --2100.00,-3150.00,1050.00,-2100.00,-3350.00,1250.00 --2200.00,-4000.00,1800.00,-2200.00,-3600.00,1400.00 --2300.00,-3150.00,850.00,-2300.00,-2500.00,200.00 --2400.00,-2400.00,0.00,-2400.00,-1300.00,-1100.00 --2500.00,-1300.00,-1200.00,-2500.00,-350.00,-2150.00 --2600.00,-1200.00,-1400.00,-2600.00,-1100.00,-1500.00 --2700.00,-2750.00,50.00,-2700.00,-3750.00,1050.00 --2800.00,-3600.00,800.00,-2800.00,-4000.00,1200.00 --2900.00,-2650.00,-250.00,-2900.00,-2850.00,-50.00 --3000.00,-2150.00,-850.00,-3000.00,-1200.00,-1800.00 --3100.00,-650.00,-2450.00,-3100.00,-1200.00,-1900.00 --3200.00,-750.00,-2450.00,-3200.00,-3600.00,400.00 --3300.00,-5050.00,1750.00,-3300.00,-4800.00,1500.00 --3400.00,-6800.00,3400.00,-3400.00,-3500.00,100.00 --3500.00,-4900.00,1400.00,-3500.00,-2400.00,-1100.00 --3600.00,-1300.00,-2300.00,-3600.00,-1450.00,-2150.00 --3700.00,-1750.00,-1950.00,-3700.00,-3150.00,-550.00 --3800.00,-5300.00,1500.00,-3800.00,-4800.00,1000.00 --3900.00,-6850.00,2950.00,-3900.00,-3850.00,-50.00 --4000.00,-5750.00,1750.00,-4000.00,-2550.00,-1450.00 --4100.00,-4900.00,800.00,-4100.00,-2300.00,-1800.00 --4200.00,-3950.00,-250.00,-4200.00,-4200.00,0.00 --4300.00,-3050.00,-1250.00,-4300.00,-5350.00,1050.00 --4400.00,-3050.00,-1350.00,-4400.00,-4150.00,-250.00 --4500.00,-4900.00,400.00,-4500.00,-3200.00,-1300.00 --4600.00,-5900.00,1300.00,-4600.00,-2900.00,-1700.00 --4700.00,-4950.00,250.00,-4700.00,-4850.00,150.00 --4800.00,-4100.00,-700.00,-4800.00,-6050.00,1250.00 --4900.00,-3750.00,-1150.00,-4900.00,-5150.00,250.00 --5000.00,-4700.00,-300.00,-5000.00,-4050.00,-950.00 --5100.00,-5400.00,300.00,-5100.00,-3500.00,-1600.00 --5200.00,-4650.00,-550.00,-5200.00,-5250.00,50.00 --5300.00,-4450.00,-850.00,-5300.00,-6550.00,1250.00 --5400.00,-5100.00,-300.00,-5400.00,-5500.00,100.00 --5500.00,-6150.00,650.00,-5500.00,-4700.00,-800.00 --5600.00,-5800.00,200.00,-5600.00,-4300.00,-1300.00 --5700.00,-4850.00,-850.00,-5700.00,-5900.00,200.00 --5800.00,-4750.00,-1050.00,-5800.00,-6950.00,1150.00 --5900.00,-6300.00,400.00,-5900.00,-5650.00,-250.00 --6000.00,-7200.00,1200.00,-6000.00,-5350.00,-650.00 --6100.00,-5800.00,-300.00,-6100.00,-5850.00,-250.00 --6200.00,-5500.00,-700.00,-6200.00,-6600.00,400.00 --6300.00,-6300.00,0.00,-6300.00,-6200.00,-100.00 --6400.00,-7050.00,650.00,-6400.00,-5900.00,-500.00 --6500.00,-6850.00,350.00,-6500.00,-6650.00,150.00 --6600.00,-5750.00,-850.00,-6600.00,-6450.00,-150.00 --6700.00,-5650.00,-1050.00,-6700.00,-6000.00,-700.00 --6800.00,-7400.00,600.00,-6800.00,-6700.00,-100.00 --6900.00,-8100.00,1200.00,-6900.00,-7450.00,550.00 --7000.00,-6500.00,-500.00,-7000.00,-7050.00,50.00 --7100.00,-6350.00,-750.00,-7100.00,-6300.00,-800.00 --7200.00,-7450.00,250.00,-7200.00,-7200.00,0.00 --7300.00,-8400.00,1100.00,-7300.00,-8100.00,800.00 --7400.00,-8200.00,800.00,-7400.00,-7800.00,400.00 --7500.00,-6450.00,-1050.00,-7500.00,-6150.00,-1350.00 --7600.00,-6650.00,-950.00,-7600.00,-6700.00,-900.00 --7700.00,-8900.00,1200.00,-7700.00,-8650.00,950.00 --7800.00,-11050.00,3250.00,-7800.00,-10700.00,2900.00 --7900.00,-7500.00,-400.00,-7900.00,-7100.00,-800.00 --8000.00,-6850.00,-1150.00,-8000.00,-6800.00,-1200.00 --8100.00,-8600.00,500.00,-8100.00,-8600.00,500.00 --8200.00,-10100.00,1900.00,-8200.00,-9950.00,1750.00 --8300.00,-9600.00,1300.00,-8300.00,-9350.00,1050.00 --8400.00,-7750.00,-650.00,-8400.00,-7700.00,-700.00 --8500.00,-7550.00,-950.00,-8500.00,-7300.00,-1200.00 --8600.00,-9050.00,450.00,-8600.00,-8850.00,250.00 --8700.00,-10750.00,2050.00,-8700.00,-10500.00,1800.00 --8800.00,-10250.00,1450.00,-8800.00,-10250.00,1450.00 --8900.00,-8300.00,-600.00,-8900.00,-8300.00,-600.00 --9000.00,-7950.00,-1050.00,-9000.00,-7800.00,-1200.00 --9100.00,-9750.00,650.00,-9100.00,-9600.00,500.00 --9200.00,-11550.00,2350.00,-9200.00,-11250.00,2050.00 --9300.00,-10950.00,1650.00,-9300.00,-10550.00,1250.00 --9400.00,-8850.00,-550.00,-9400.00,-8400.00,-1000.00 --9500.00,-8300.00,-1200.00,-9500.00,-8250.00,-1250.00 --9600.00,-10000.00,400.00,-9600.00,-10200.00,600.00 --9700.00,-12600.00,2900.00,-9700.00,-12150.00,2450.00 --9800.00,-12050.00,2250.00,-9800.00,-11350.00,1550.00 --9900.00,-9400.00,-500.00,-9900.00,-8500.00,-1400.00 --10000.00,-9350.00,-650.00,-10000.00,-9000.00,-1000.00 --10100.00,-10850.00,750.00,-10100.00,-11350.00,1250.00 --10200.00,-12300.00,2100.00,-10200.00,-12000.00,1800.00 --10300.00,-11650.00,1350.00,-10300.00,-9550.00,-750.00 --10400.00,-9450.00,-950.00,-10400.00,-8800.00,-1600.00 --10500.00,-9050.00,-1450.00,-10500.00,-11100.00,600.00 --10600.00,-12200.00,1600.00,-10600.00,-13650.00,3050.00 --10700.00,-14000.00,3300.00,-10700.00,-12500.00,1800.00 --10800.00,-11150.00,350.00,-10800.00,-9750.00,-1050.00 --10900.00,-9700.00,-1200.00,-10900.00,-9350.00,-1550.00 --11000.00,-11300.00,300.00,-11000.00,-12050.00,1050.00 --11100.00,-13950.00,2850.00,-11100.00,-14250.00,3150.00 --11200.00,-13550.00,2350.00,-11200.00,-12900.00,1700.00 --11300.00,-10750.00,-550.00,-11300.00,-9900.00,-1400.00 --11400.00,-10000.00,-1400.00,-11400.00,-9700.00,-1700.00 --11500.00,-12650.00,1150.00,-11500.00,-12950.00,1450.00 --11600.00,-15100.00,3500.00,-11600.00,-15150.00,3550.00 --11700.00,-13950.00,2250.00,-11700.00,-13500.00,1800.00 --11800.00,-11000.00,-800.00,-11800.00,-10650.00,-1150.00 --11900.00,-10700.00,-1200.00,-11900.00,-10650.00,-1250.00 --12000.00,-13400.00,1400.00,-12000.00,-13350.00,1350.00 --12100.00,-15600.00,3500.00,-12100.00,-15400.00,3300.00 --12200.00,-14200.00,2000.00,-12200.00,-14100.00,1900.00 --12300.00,-11300.00,-1000.00,-12300.00,-11650.00,-650.00 --12400.00,-10450.00,-1950.00,-12400.00,-11950.00,-450.00 --12500.00,-14350.00,1850.00,-12500.00,-14050.00,1550.00 --12600.00,-17600.00,5000.00,-12600.00,-15000.00,2400.00 --12700.00,-15550.00,2850.00,-12700.00,-13700.00,1000.00 --12800.00,-12250.00,-550.00,-12800.00,-11450.00,-1350.00 --12900.00,-11450.00,-1450.00,-12900.00,-13550.00,650.00 --13000.00,-14300.00,1300.00,-13000.00,-15800.00,2800.00 --13100.00,-17200.00,4100.00,-13100.00,-14800.00,1700.00 --13200.00,-15750.00,2550.00,-13200.00,-12250.00,-950.00 --13300.00,-12400.00,-900.00,-13300.00,-12800.00,-500.00 --13400.00,-11500.00,-1900.00,-13400.00,-15550.00,2150.00 --13500.00,-15200.00,1700.00,-13500.00,-16500.00,3000.00 --13600.00,-18700.00,5100.00,-13600.00,-14700.00,1100.00 --13700.00,-17200.00,3500.00,-13700.00,-12100.00,-1600.00 --13800.00,-13150.00,-650.00,-13800.00,-13800.00,0.00 --13900.00,-12000.00,-1900.00,-13900.00,-17300.00,3400.00 --14000.00,-15800.00,1800.00,-14000.00,-16900.00,2900.00 --14100.00,-19250.00,5150.00,-14100.00,-13150.00,-950.00 --14200.00,-17550.00,3350.00,-14200.00,-12000.00,-2200.00 --14300.00,-13450.00,-850.00,-14300.00,-16050.00,1750.00 --14400.00,-12350.00,-2050.00,-14400.00,-19500.00,5100.00 --14500.00,-16650.00,2150.00,-14500.00,-17650.00,3150.00 --14600.00,-20450.00,5850.00,-14600.00,-13450.00,-1150.00 --14700.00,-18250.00,3550.00,-14700.00,-12150.00,-2550.00 --14800.00,-14450.00,-350.00,-14800.00,-17300.00,2500.00 --14900.00,-12850.00,-2050.00,-14900.00,-21250.00,6350.00 --15000.00,-16450.00,1450.00,-15000.00,-18150.00,3150.00 --15100.00,-20550.00,5450.00,-15100.00,-13550.00,-1550.00 --15200.00,-22900.00,7700.00,-15200.00,-15700.00,500.00 --15300.00,-12400.00,-2900.00,-15300.00,-17250.00,1950.00 --15400.00,-8150.00,-7250.00,-15400.00,-18200.00,2800.00 --15500.00,-15900.00,400.00,-15500.00,-16150.00,650.00 --15600.00,-22150.00,6550.00,-15600.00,-14500.00,-1100.00 --15700.00,-21050.00,5350.00,-15700.00,-16000.00,300.00 --15800.00,-16050.00,250.00,-15800.00,-18900.00,3100.00 --15900.00,-13850.00,-2050.00,-15900.00,-18250.00,2350.00 --16000.00,-16750.00,750.00,-16000.00,-15150.00,-850.00 --16100.00,-21250.00,5150.00,-16100.00,-15400.00,-700.00 --16200.00,-20800.00,4600.00,-16200.00,-19650.00,3450.00 --16300.00,-15300.00,-1000.00,-16300.00,-19600.00,3300.00 --16400.00,-13950.00,-2450.00,-16400.00,-15250.00,-1150.00 --16500.00,-19500.00,3000.00,-16500.00,-13800.00,-2700.00 --16600.00,-21600.00,5000.00,-16600.00,-16900.00,300.00 --16700.00,-18850.00,2150.00,-16700.00,-21400.00,4700.00 --16800.00,-15400.00,-1400.00,-16800.00,-20900.00,4100.00 --16900.00,-16700.00,-200.00,-16900.00,-15750.00,-1150.00 --17000.00,-21550.00,4550.00,-17000.00,-14700.00,-2300.00 --17100.00,-20700.00,3600.00,-17100.00,-18350.00,1250.00 --17200.00,-15950.00,-1250.00,-17200.00,-22350.00,5150.00 --17300.00,-14450.00,-2850.00,-17300.00,-20850.00,3550.00 --17400.00,-20700.00,3300.00,-17400.00,-16350.00,-1050.00 --17500.00,-25000.00,7500.00,-17332.74,-14450.00,-2882.74 --17404.00,-21150.00,3746.00,-17232.74,-18900.00,1667.26 --17304.00,-15900.00,-1404.00,-17132.74,-23000.00,5867.26 --17204.00,-14450.00,-2754.00,-17032.74,-21200.00,4167.26 --17104.00,-20800.00,3696.00,-16932.74,-16650.00,-282.74 --17004.00,-23300.00,6296.00,-16832.74,-13750.00,-3082.74 --16904.00,-17950.00,1046.00,-16732.74,-17800.00,1067.26 --16804.00,-14900.00,-1904.00,-16632.74,-22050.00,5417.26 --16704.00,-17750.00,1046.00,-16532.74,-21350.00,4817.26 --16604.00,-21400.00,4796.00,-16432.74,-15800.00,-632.74 --16504.00,-20400.00,3896.00,-16332.74,-13500.00,-2832.74 --16404.00,-16000.00,-404.00,-16232.74,-18700.00,2467.26 --16304.00,-14100.00,-2204.00,-16132.74,-22800.00,6667.26 --16204.00,-18100.00,1896.00,-16032.74,-19300.00,3267.26 --16104.00,-22000.00,5896.00,-15932.74,-14550.00,-1382.74 --16004.00,-20900.00,4896.00,-15832.74,-13600.00,-2232.74 --15904.00,-15700.00,-204.00,-15732.74,-18450.00,2717.26 --15804.00,-13700.00,-2104.00,-15632.74,-22000.00,6367.26 --15704.00,-17750.00,2046.00,-15532.74,-19100.00,3567.26 --15604.00,-21050.00,5446.00,-15432.74,-14200.00,-1232.74 --15504.00,-19100.00,3596.00,-15332.74,-12900.00,-2432.74 --15404.00,-15000.00,-404.00,-15232.74,-18400.00,3167.26 --15304.00,-13300.00,-2004.00,-15132.74,-20950.00,5817.26 --15204.00,-17650.00,2446.00,-15032.74,-16250.00,1217.26 --15104.00,-21550.00,6446.00,-14932.74,-13100.00,-1832.74 --15004.00,-19050.00,4046.00,-14832.74,-15200.00,367.26 --14904.00,-14400.00,-504.00,-14732.74,-19250.00,4517.26 --14804.00,-12900.00,-1904.00,-14632.74,-18500.00,3867.26 --14704.00,-17100.00,2396.00,-14532.74,-14050.00,-482.74 --14604.00,-20850.00,6246.00,-14432.74,-12500.00,-1932.74 --14504.00,-18600.00,4096.00,-14332.74,-16000.00,1667.26 --14404.00,-14050.00,-354.00,-14232.74,-19700.00,5467.26 --14304.00,-12400.00,-1904.00,-14132.74,-17900.00,3767.26 --14204.00,-16400.00,2196.00,-14032.74,-13350.00,-682.74 --14104.00,-20400.00,6296.00,-13932.74,-12150.00,-1782.74 --14004.00,-18200.00,4196.00,-13832.74,-15700.00,1867.26 --13904.00,-12950.00,-954.00,-13732.74,-17400.00,3667.26 --13804.00,-12750.00,-1054.00,-13632.74,-16700.00,3067.26 --13704.00,-16750.00,3046.00,-13532.74,-12750.00,-782.74 --13604.00,-18250.00,4646.00,-13432.74,-11700.00,-1732.74 --13504.00,-14100.00,596.00,-13332.74,-15150.00,1817.26 --13404.00,-11550.00,-1854.00,-13232.74,-17600.00,4367.26 --13304.00,-14150.00,846.00,-13132.74,-16450.00,3317.26 --13204.00,-18600.00,5396.00,-13032.74,-12250.00,-782.74 --13104.00,-17200.00,4096.00,-12932.74,-10900.00,-2032.74 --13004.00,-13700.00,696.00,-12832.74,-14800.00,1967.26 --12904.00,-11450.00,-1454.00,-12732.74,-18200.00,5467.26 --12804.00,-13550.00,746.00,-12632.74,-16200.00,3567.26 --12704.00,-17250.00,4546.00,-12532.74,-12400.00,-132.74 --12604.00,-16350.00,3746.00,-12432.74,-10600.00,-1832.74 --12504.00,-14600.00,2096.00,-12332.74,-15900.00,3567.26 --12404.00,-9100.00,-3304.00,-12232.74,-15700.00,3467.26 --12304.00,-10300.00,-2004.00,-12132.74,-12500.00,367.26 --12204.00,-17200.00,4996.00,-12032.74,-10550.00,-1482.74 --12104.00,-16150.00,4046.00,-11932.74,-10100.00,-1832.74 --12004.00,-14600.00,2596.00,-11832.74,-15650.00,3817.26 --11904.00,-10650.00,-1254.00,-11732.74,-16600.00,4867.26 --11804.00,-10350.00,-1454.00,-11632.74,-12900.00,1267.26 --11704.00,-14900.00,3196.00,-11532.74,-10900.00,-632.74 --11604.00,-16500.00,4896.00,-11432.74,-11600.00,167.26 --11504.00,-12600.00,1096.00,-11332.74,-12900.00,1567.26 --11404.00,-10350.00,-1054.00,-11232.74,-13350.00,2117.26 --11304.00,-12000.00,696.00,-11132.74,-12300.00,1167.26 --11204.00,-14100.00,2896.00,-11032.74,-9750.00,-1282.74 --11104.00,-13350.00,2246.00,-10932.74,-11200.00,267.26 --11004.00,-10650.00,-354.00,-10832.74,-13000.00,2167.26 --10904.00,-9550.00,-1354.00,-10732.74,-12950.00,2217.26 --10804.00,-12100.00,1296.00,-10632.74,-9800.00,-832.74 --10704.00,-14550.00,3846.00,-10532.74,-9550.00,-982.74 --10604.00,-13250.00,2646.00,-10432.74,-11800.00,1367.26 --10504.00,-10450.00,-54.00,-10332.74,-12600.00,2267.26 --10404.00,-9350.00,-1054.00,-10232.74,-10100.00,-132.74 --10304.00,-10900.00,596.00,-10132.74,-9000.00,-1132.74 --10204.00,-13100.00,2896.00,-10032.74,-10300.00,267.26 --10104.00,-12350.00,2246.00,-9932.74,-12300.00,2367.26 --10004.00,-9900.00,-104.00,-9832.74,-11950.00,2117.26 --9904.00,-8800.00,-1104.00,-9732.74,-9250.00,-482.74 --9804.00,-10700.00,896.00,-9632.74,-8700.00,-932.74 --9704.00,-12950.00,3246.00,-9532.74,-10300.00,767.26 --9604.00,-12000.00,2396.00,-9432.74,-11700.00,2267.26 --9504.00,-9650.00,146.00,-9332.74,-10800.00,1467.26 --9404.00,-8500.00,-904.00,-9232.74,-8400.00,-832.74 --9304.00,-9850.00,546.00,-9132.74,-8200.00,-932.74 --9204.00,-11750.00,2546.00,-9032.74,-10050.00,1017.26 --9104.00,-11150.00,2046.00,-8932.74,-10550.00,1617.26 --9004.00,-9000.00,-4.00,-8832.74,-8500.00,-332.74 --8904.00,-8450.00,-454.00,-8732.74,-8100.00,-632.74 --8804.00,-9500.00,696.00,-8632.74,-9000.00,367.26 --8704.00,-10350.00,1646.00,-8532.74,-9650.00,1117.26 --8604.00,-9750.00,1146.00,-8432.74,-9200.00,767.26 --8504.00,-8100.00,-404.00,-8332.74,-7350.00,-982.74 --8404.00,-7600.00,-804.00,-8232.74,-6750.00,-1482.74 --8304.00,-9600.00,1296.00,-8132.74,-9400.00,1267.26 --8204.00,-10300.00,2096.00,-8032.74,-10150.00,2117.26 --8104.00,-8450.00,346.00,-7932.74,-8150.00,217.26 --8004.00,-7500.00,-504.00,-7832.74,-6950.00,-882.74 --7904.00,-8400.00,496.00,-7732.74,-7200.00,-532.74 --7804.00,-9550.00,1746.00,-7632.74,-8850.00,1217.26 --7704.00,-8900.00,1196.00,-7532.74,-8600.00,1067.26 --7604.00,-7400.00,-204.00,-7432.74,-6950.00,-482.74 --7504.00,-7200.00,-304.00,-7332.74,-6250.00,-1082.74 --7404.00,-7800.00,396.00,-7232.74,-7350.00,117.26 --7304.00,-8250.00,946.00,-7132.74,-8650.00,1517.26 --7204.00,-6850.00,-354.00,-7032.74,-8350.00,1317.26 --7104.00,-6500.00,-604.00,-6932.74,-6800.00,-132.74 --7004.00,-7550.00,546.00,-6832.74,-5900.00,-932.74 --6904.00,-8200.00,1296.00,-6732.74,-6450.00,-282.74 --6804.00,-7000.00,196.00,-6632.74,-7950.00,1317.26 --6704.00,-5850.00,-854.00,-6532.74,-7550.00,1017.26 --6604.00,-5800.00,-804.00,-6432.74,-6250.00,-182.74 --6504.00,-7350.00,846.00,-6332.74,-5400.00,-932.74 --6404.00,-8050.00,1646.00,-6232.74,-5950.00,-282.74 --6304.00,-6750.00,446.00,-6132.74,-7050.00,917.26 --6204.00,-5800.00,-404.00,-6032.74,-6900.00,867.26 --6104.00,-5450.00,-654.00,-5932.74,-5550.00,-382.74 --6004.00,-6250.00,246.00,-5832.74,-4850.00,-982.74 --5904.00,-6750.00,846.00,-5732.74,-5450.00,-282.74 --5804.00,-5650.00,-154.00,-5632.74,-6450.00,817.26 --5704.00,-5350.00,-354.00,-5532.74,-6150.00,617.26 --5604.00,-5700.00,96.00,-5432.74,-4850.00,-582.74 --5504.00,-5850.00,346.00,-5332.74,-4100.00,-1232.74 --5404.00,-4800.00,-604.00,-5232.74,-5050.00,-182.74 --5304.00,-4450.00,-854.00,-5132.74,-5850.00,717.26 --5204.00,-5800.00,596.00,-5032.74,-4700.00,-332.74 --5104.00,-7150.00,2046.00,-4932.74,-4100.00,-832.74 --5004.00,-5150.00,146.00,-4832.74,-2900.00,-1932.74 --4904.00,-4250.00,-654.00,-4732.74,-4500.00,-232.74 --4804.00,-3950.00,-854.00,-4632.74,-6250.00,1617.26 --4704.00,-4900.00,196.00,-4532.74,-5150.00,617.26 --4604.00,-5450.00,846.00,-4432.74,-4400.00,-32.74 --4504.00,-4550.00,46.00,-4332.74,-3400.00,-932.74 --4404.00,-3600.00,-804.00,-4232.74,-2850.00,-1382.74 --4304.00,-3450.00,-854.00,-4132.74,-4250.00,117.26 --4204.00,-4300.00,96.00,-4032.74,-5200.00,1167.26 --4104.00,-4750.00,646.00,-3932.74,-4400.00,467.26 --4004.00,-4000.00,-4.00,-3832.74,-3400.00,-432.74 --3904.00,-3100.00,-804.00,-3732.74,-2650.00,-1082.74 --3804.00,-2750.00,-1054.00,-3632.74,-2350.00,-1282.74 --3704.00,-3900.00,196.00,-3532.74,-3700.00,167.26 --3604.00,-4350.00,746.00,-3432.74,-4500.00,1067.26 --3504.00,-3600.00,96.00,-3332.74,-3650.00,317.26 --3404.00,-2850.00,-554.00,-3232.74,-2650.00,-582.74 --3304.00,-1800.00,-1504.00,-3132.74,-1600.00,-1532.74 --3204.00,-2050.00,-1154.00,-3032.74,-2100.00,-932.74 --3104.00,-3800.00,696.00,-2932.74,-3100.00,167.26 --3004.00,-4350.00,1346.00,-2832.74,-2100.00,-732.74 --2904.00,-3500.00,596.00,-2732.74,-1650.00,-1082.74 --2804.00,-2650.00,-154.00,-2632.74,200.00,-2832.74 --2704.00,-1950.00,-754.00,-2532.74,-450.00,-2082.74 --2604.00,-800.00,-1804.00,-2432.74,-4450.00,2017.26 --2504.00,-1900.00,-604.00,-2332.74,-5950.00,3617.26 --2404.00,-3150.00,746.00,-2232.74,-3100.00,867.26 --2304.00,-2500.00,196.00,-2132.74,1200.00,-3332.74 --2204.00,-1700.00,-504.00,-2032.74,-650.00,-1382.74 --2104.00,-350.00,-1754.00,-1932.74,-4400.00,2467.26 --2004.00,-1300.00,-704.00,-1832.74,-4600.00,2767.26 --1904.00,-2450.00,546.00,-1732.74,-2650.00,917.26 --1804.00,-2200.00,396.00,-1632.74,-500.00,-1132.74 --1704.00,-750.00,-954.00,-1532.74,-300.00,-1232.74 --1604.00,-750.00,-854.00,-1432.74,50.00,-1482.74 --1504.00,-950.00,-554.00,-1332.74,0.00,-1332.74 --1404.00,300.00,-1704.00,-1232.74,0.00,-1232.74 --1304.00,-400.00,-904.00,-1132.74,0.00,-1132.74 --1204.00,-950.00,-254.00,-1032.74,0.00,-1032.74 --1104.00,450.00,-1554.00,-932.74,0.00,-932.74 --1004.00,1050.00,-2054.00,-832.74,0.00,-832.74 --904.00,-550.00,-354.00,-732.74,0.00,-732.74 --804.00,-1200.00,396.00,-632.74,0.00,-632.74 --704.00,-200.00,-504.00,-532.74,0.00,-532.74 --604.00,0.00,-604.00,-432.74,0.00,-432.74 --504.00,0.00,-504.00,-332.74,0.00,-332.74 --404.00,0.00,-404.00,-232.74,0.00,-232.74 --304.00,0.00,-304.00,-132.74,0.00,-132.74 --204.00,0.00,-204.00,-32.74,0.00,-32.74 --104.00,0.00,-104.00,0.00,0.00,0.00 --4.00,0.00,-4.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -100.00,0.00,100.00,100.00,0.00,100.00 -200.00,0.00,200.00,200.00,0.00,200.00 -300.00,0.00,300.00,300.00,0.00,300.00 -400.00,0.00,400.00,400.00,0.00,400.00 -500.00,0.00,500.00,500.00,0.00,500.00 -600.00,0.00,600.00,600.00,0.00,600.00 -700.00,0.00,700.00,700.00,0.00,700.00 -800.00,0.00,800.00,800.00,0.00,800.00 -900.00,0.00,900.00,900.00,0.00,900.00 -1000.00,0.00,1000.00,1000.00,0.00,1000.00 -1100.00,0.00,1100.00,1100.00,0.00,1100.00 -1200.00,0.00,1200.00,1200.00,0.00,1200.00 -1300.00,0.00,1300.00,1300.00,0.00,1300.00 -1400.00,0.00,1400.00,1400.00,0.00,1400.00 -1500.00,0.00,1500.00,1500.00,0.00,1500.00 -1600.00,0.00,1600.00,1600.00,0.00,1600.00 -1700.00,550.00,1150.00,1700.00,550.00,1150.00 -1800.00,1950.00,-150.00,1800.00,550.00,1250.00 -1900.00,300.00,1600.00,1900.00,-700.00,2600.00 -2000.00,0.00,2000.00,2000.00,250.00,1750.00 -2100.00,750.00,1350.00,2100.00,3100.00,-1000.00 -2200.00,2450.00,-250.00,2200.00,3600.00,-1400.00 -2300.00,2700.00,-400.00,2300.00,2200.00,100.00 -2400.00,1800.00,600.00,2400.00,1450.00,950.00 -2500.00,1750.00,750.00,2500.00,-350.00,2850.00 -2600.00,350.00,2250.00,2600.00,400.00,2200.00 -2700.00,550.00,2150.00,2700.00,4000.00,-1300.00 -2800.00,3350.00,-550.00,2800.00,5100.00,-2300.00 -2900.00,5200.00,-2300.00,2900.00,4300.00,-1400.00 -3000.00,4200.00,-1200.00,3000.00,3100.00,-100.00 -3100.00,3350.00,-250.00,3100.00,1700.00,1400.00 -3200.00,2900.00,300.00,3200.00,2000.00,1200.00 -3300.00,1850.00,1450.00,3300.00,2950.00,350.00 -3400.00,2450.00,950.00,3400.00,3400.00,0.00 -3500.00,3550.00,-50.00,3500.00,2400.00,1100.00 -3600.00,3750.00,-150.00,3600.00,2050.00,1550.00 -3700.00,3200.00,500.00,3700.00,3250.00,450.00 -3800.00,2650.00,1150.00,3800.00,4150.00,-350.00 -3900.00,2350.00,1550.00,3900.00,3300.00,600.00 -4000.00,3700.00,300.00,4000.00,2100.00,1900.00 -4100.00,4850.00,-750.00,4100.00,2400.00,1700.00 -4200.00,4250.00,-50.00,4200.00,5200.00,-1000.00 -4300.00,3200.00,1100.00,4300.00,6000.00,-1700.00 -4400.00,3400.00,1000.00,4400.00,5100.00,-700.00 -4500.00,4900.00,-400.00,4500.00,4100.00,400.00 -4600.00,4800.00,-200.00,4600.00,2900.00,1700.00 -4700.00,4100.00,600.00,4700.00,2700.00,2000.00 -4800.00,4000.00,800.00,4800.00,5350.00,-550.00 -4900.00,4850.00,50.00,4900.00,6950.00,-2050.00 -5000.00,4900.00,100.00,5000.00,5650.00,-650.00 -5100.00,4200.00,900.00,5100.00,4350.00,750.00 -5200.00,4150.00,1050.00,5200.00,3500.00,1700.00 -5300.00,5200.00,100.00,5300.00,4700.00,600.00 -5400.00,5950.00,-550.00,5400.00,6500.00,-1100.00 -5500.00,5100.00,400.00,5500.00,6300.00,-800.00 -5600.00,4600.00,1000.00,5600.00,5000.00,600.00 -5700.00,5450.00,250.00,5700.00,4250.00,1450.00 -5800.00,6400.00,-600.00,5800.00,5200.00,600.00 -5900.00,6400.00,-500.00,5900.00,6800.00,-900.00 -6000.00,5600.00,400.00,6000.00,6850.00,-850.00 -6100.00,4900.00,1200.00,6100.00,5500.00,600.00 -6200.00,6150.00,50.00,6200.00,4800.00,1400.00 -6300.00,6900.00,-600.00,6300.00,5800.00,500.00 -6400.00,5900.00,500.00,6400.00,7400.00,-1000.00 -6500.00,5400.00,1100.00,6500.00,7200.00,-700.00 -6600.00,6700.00,-100.00,6600.00,5900.00,700.00 -6700.00,7750.00,-1050.00,6700.00,5450.00,1250.00 -6800.00,7700.00,-900.00,6800.00,6850.00,-50.00 -6900.00,6250.00,650.00,6900.00,8050.00,-1150.00 -7000.00,6050.00,950.00,7000.00,7600.00,-600.00 -7100.00,7200.00,-100.00,7100.00,6250.00,850.00 -7200.00,8100.00,-900.00,7200.00,5700.00,1500.00 -7300.00,8350.00,-1050.00,7300.00,7950.00,-650.00 -7400.00,6850.00,550.00,7400.00,8900.00,-1500.00 -7500.00,6450.00,1050.00,7500.00,7250.00,250.00 -7600.00,7700.00,-100.00,7600.00,6600.00,1000.00 -7700.00,9050.00,-1350.00,7700.00,7300.00,400.00 -7800.00,8700.00,-900.00,7800.00,8600.00,-800.00 -7900.00,7250.00,650.00,7900.00,8600.00,-700.00 -8000.00,7000.00,1000.00,8000.00,6900.00,1100.00 -8100.00,8350.00,-250.00,8100.00,6550.00,1550.00 -8200.00,11600.00,-3400.00,8200.00,10850.00,-2650.00 -8300.00,9600.00,-1300.00,8300.00,10800.00,-2500.00 -8400.00,7950.00,450.00,8400.00,8650.00,-250.00 -8500.00,7200.00,1300.00,8500.00,7350.00,1150.00 -8600.00,8700.00,-100.00,8600.00,8200.00,400.00 -8700.00,10600.00,-1900.00,8700.00,9800.00,-1100.00 -8800.00,10150.00,-1350.00,8800.00,9700.00,-900.00 -8900.00,8750.00,150.00,8900.00,8100.00,800.00 -9000.00,7650.00,1350.00,9000.00,7600.00,1400.00 -9100.00,9100.00,0.00,9100.00,9600.00,-500.00 -9200.00,11700.00,-2500.00,9200.00,11850.00,-2650.00 -9300.00,11500.00,-2200.00,9300.00,11000.00,-1700.00 -9400.00,9350.00,50.00,9400.00,8750.00,650.00 -9500.00,8100.00,1400.00,9500.00,8150.00,1350.00 -9600.00,9550.00,50.00,9600.00,10050.00,-450.00 -9700.00,12500.00,-2800.00,9700.00,12350.00,-2650.00 -9800.00,12200.00,-2400.00,9800.00,11550.00,-1750.00 -9900.00,9900.00,0.00,9900.00,9100.00,800.00 -10000.00,8500.00,1500.00,10000.00,8500.00,1500.00 -10100.00,10700.00,-600.00,10100.00,11300.00,-1200.00 -10200.00,13200.00,-3000.00,10200.00,13200.00,-3000.00 -10300.00,12450.00,-2150.00,10300.00,12000.00,-1700.00 -10400.00,10100.00,300.00,10400.00,9400.00,1000.00 -10500.00,8850.00,1650.00,10500.00,8900.00,1600.00 -10600.00,11100.00,-500.00,10600.00,11400.00,-800.00 -10700.00,14200.00,-3500.00,10700.00,14050.00,-3350.00 -10800.00,13500.00,-2700.00,10800.00,13000.00,-2200.00 -10900.00,10900.00,0.00,10900.00,10100.00,800.00 -11000.00,9400.00,1600.00,11000.00,9450.00,1550.00 -11100.00,11400.00,-300.00,11100.00,11550.00,-450.00 -11200.00,14500.00,-3300.00,11200.00,14450.00,-3250.00 -11300.00,13950.00,-2650.00,11300.00,13600.00,-2300.00 -11400.00,11200.00,200.00,11400.00,10500.00,900.00 -11500.00,9750.00,1750.00,11500.00,9700.00,1800.00 -11600.00,12100.00,-500.00,11600.00,12300.00,-700.00 -11700.00,15200.00,-3500.00,11700.00,15400.00,-3700.00 -11800.00,14500.00,-2700.00,11800.00,14400.00,-2600.00 -11900.00,11650.00,250.00,11900.00,10900.00,1000.00 -12000.00,10150.00,1850.00,12000.00,9900.00,2100.00 -12100.00,12550.00,-450.00,12100.00,12700.00,-600.00 -12200.00,15750.00,-3550.00,12200.00,15950.00,-3750.00 -12300.00,15100.00,-2800.00,12300.00,14650.00,-2350.00 -12400.00,11500.00,900.00,12400.00,10900.00,1500.00 -12500.00,10600.00,1900.00,12500.00,10350.00,2150.00 -12600.00,13550.00,-950.00,12600.00,13850.00,-1250.00 -12700.00,16600.00,-3900.00,12700.00,16850.00,-4150.00 -12800.00,15450.00,-2650.00,12800.00,15400.00,-2600.00 -12900.00,12200.00,700.00,12900.00,11850.00,1050.00 -13000.00,11200.00,1800.00,13000.00,11200.00,1800.00 -13100.00,14000.00,-900.00,13100.00,13900.00,-800.00 -13200.00,17000.00,-3800.00,13200.00,17050.00,-3850.00 -13300.00,15950.00,-2650.00,13300.00,16050.00,-2750.00 -13400.00,12600.00,800.00,13400.00,12200.00,1200.00 -13500.00,11050.00,2450.00,13500.00,11200.00,2300.00 -13600.00,14200.00,-600.00,13600.00,14500.00,-900.00 -13700.00,17950.00,-4250.00,13700.00,17850.00,-4150.00 -13800.00,16400.00,-2600.00,13800.00,16200.00,-2400.00 -13900.00,13250.00,650.00,13900.00,13950.00,-50.00 -14000.00,11700.00,2300.00,14000.00,13000.00,1000.00 -14100.00,15100.00,-1000.00,14100.00,14700.00,-600.00 -14200.00,18250.00,-4050.00,14200.00,16500.00,-2300.00 -14300.00,17800.00,-3500.00,14300.00,17100.00,-2800.00 -14400.00,13800.00,600.00,14400.00,15250.00,-850.00 -14500.00,12550.00,1950.00,14500.00,12650.00,1850.00 -14600.00,15550.00,-950.00,14600.00,14250.00,350.00 -14700.00,19000.00,-4300.00,14700.00,17850.00,-3150.00 -14800.00,17200.00,-2400.00,14800.00,17050.00,-2250.00 -14900.00,14750.00,150.00,14900.00,14450.00,450.00 -15000.00,14400.00,600.00,15000.00,14300.00,700.00 -15100.00,16650.00,-1550.00,15100.00,16500.00,-1400.00 -15200.00,18950.00,-3750.00,15200.00,18800.00,-3600.00 -15300.00,16950.00,-1650.00,15300.00,16950.00,-1650.00 -15400.00,14950.00,450.00,15400.00,14200.00,1200.00 -15500.00,15000.00,500.00,15500.00,15150.00,350.00 -15600.00,18200.00,-2600.00,15600.00,18650.00,-3050.00 -15700.00,19550.00,-3850.00,15700.00,18450.00,-2750.00 -15800.00,20150.00,-4350.00,15800.00,18000.00,-2200.00 -15900.00,12950.00,2950.00,15900.00,13700.00,2200.00 -16000.00,12150.00,3850.00,16000.00,13950.00,2050.00 -16100.00,16950.00,-850.00,16100.00,16950.00,-850.00 -16200.00,21300.00,-5100.00,16200.00,19250.00,-3050.00 -16300.00,20000.00,-3700.00,16300.00,18850.00,-2550.00 -16400.00,14900.00,1500.00,16400.00,16650.00,-250.00 -16500.00,14000.00,2500.00,16500.00,16250.00,250.00 -16600.00,18250.00,-1650.00,16600.00,17300.00,-700.00 -16700.00,21450.00,-4750.00,16700.00,18350.00,-1650.00 -16800.00,20400.00,-3600.00,16800.00,19650.00,-2850.00 -16900.00,15550.00,1350.00,16900.00,18900.00,-2000.00 -17000.00,13850.00,3150.00,17000.00,17200.00,-200.00 -17100.00,18850.00,-1750.00,17100.00,16900.00,200.00 -17200.00,22400.00,-5200.00,17200.00,17950.00,-750.00 -17300.00,21400.00,-4100.00,17300.00,20750.00,-3450.00 -17400.00,15700.00,1700.00,17400.00,19700.00,-2300.00 -17500.00,14600.00,2900.00,17500.00,18400.00,-900.00 -17600.00,19750.00,-2150.00,17600.00,18200.00,-600.00 -17700.00,24150.00,-6450.00,17700.00,19450.00,-1750.00 -17800.00,21750.00,-3950.00,17658.43,20350.00,-2691.57 -17900.00,16050.00,1850.00,17558.43,19350.00,-1791.57 -17897.35,14850.00,3047.35,17458.43,18700.00,-1241.57 -17797.35,20200.00,-2402.65,17358.43,18350.00,-991.57 -17697.35,24550.00,-6852.65,17258.43,19100.00,-1841.57 -17597.35,22200.00,-4602.65,17158.43,19600.00,-2441.57 -17497.35,16900.00,597.35,17058.43,19200.00,-2141.57 -17397.35,15250.00,2147.35,16958.43,18550.00,-1591.57 -17297.35,18900.00,-1602.65,16858.43,17250.00,-391.57 -17197.35,23400.00,-6202.65,16758.43,18100.00,-1341.57 -17097.35,20950.00,-3852.65,16658.43,18600.00,-1941.57 -16997.35,16150.00,847.35,16558.43,18600.00,-2041.57 -16897.35,14700.00,2197.35,16458.43,18150.00,-1691.57 -16797.35,18800.00,-2002.65,16358.43,17700.00,-1341.57 -16697.35,22200.00,-5502.65,16258.43,17100.00,-841.57 -16597.35,21000.00,-4402.65,16158.43,18050.00,-1891.57 -16497.35,16150.00,347.35,16058.43,18400.00,-2341.57 -16397.35,13850.00,2547.35,15958.43,17000.00,-1041.57 -16297.35,18300.00,-2002.65,15858.43,17150.00,-1291.57 -16197.35,22000.00,-5802.65,15758.43,17150.00,-1391.57 -16097.35,19450.00,-3352.65,15658.43,16700.00,-1041.57 -15997.35,14950.00,1047.35,15558.43,16800.00,-1241.57 -15897.35,13750.00,2147.35,15458.43,17100.00,-1641.57 -15797.35,18650.00,-2852.65,15358.43,17650.00,-2291.57 -15697.35,21900.00,-6202.65,15258.43,17000.00,-1741.57 -15597.35,18650.00,-3052.65,15158.43,15650.00,-491.57 -15497.35,14750.00,747.35,15058.43,16100.00,-1041.57 -15397.35,13400.00,1997.35,14958.43,16900.00,-1941.57 -15297.35,17600.00,-2302.65,14858.43,16950.00,-2091.57 -15197.35,20950.00,-5752.65,14758.43,16250.00,-1491.57 -15097.35,18800.00,-3702.65,14658.43,15650.00,-991.57 -14997.35,14400.00,597.35,14558.43,15850.00,-1291.57 -14897.35,13000.00,1897.35,14458.43,16150.00,-1691.57 -14797.35,16900.00,-2102.65,14358.43,16100.00,-1741.57 -14697.35,20400.00,-5702.65,14258.43,15750.00,-1491.57 -14597.35,18400.00,-3802.65,14158.43,15450.00,-1291.57 -14497.35,14250.00,247.35,14058.43,15400.00,-1341.57 -14397.35,12900.00,1497.35,13958.43,15500.00,-1541.57 -14297.35,15450.00,-1152.65,13858.43,14800.00,-941.57 -14197.35,19200.00,-5002.65,13758.43,15150.00,-1391.57 -14097.35,17550.00,-3452.65,13658.43,14850.00,-1191.57 -13997.35,14200.00,-202.65,13558.43,15300.00,-1741.57 -13897.35,12300.00,1597.35,13458.43,15100.00,-1641.57 -13797.35,15150.00,-1352.65,13358.43,14650.00,-1291.57 -13697.35,17500.00,-3802.65,13258.43,13800.00,-541.57 -13597.35,17050.00,-3452.65,13158.43,14500.00,-1341.57 -13497.35,13350.00,147.35,13058.43,14850.00,-1791.57 -13397.35,11800.00,1597.35,12958.43,14550.00,-1591.57 -13297.35,14900.00,-1602.65,12858.43,14000.00,-1141.57 -13197.35,17950.00,-4752.65,12758.43,13600.00,-841.57 -13097.35,16550.00,-3452.65,12658.43,13600.00,-941.57 -12997.35,12850.00,147.35,12558.43,13900.00,-1341.57 -12897.35,11450.00,1447.35,12458.43,13750.00,-1291.57 -12797.35,14100.00,-1302.65,12358.43,13250.00,-891.57 -12697.35,16750.00,-4052.65,12258.43,12950.00,-691.57 -12597.35,18050.00,-5452.65,12158.43,15450.00,-3291.57 -12497.35,11650.00,847.35,12058.43,12350.00,-291.57 -12397.35,10950.00,1447.35,11958.43,10650.00,1308.43 -12297.35,13500.00,-1202.65,11858.43,11900.00,-41.57 -12197.35,16350.00,-4152.65,11758.43,14800.00,-3041.57 -12097.35,15100.00,-3002.65,11658.43,14450.00,-2791.57 -11997.35,11950.00,47.35,11558.43,11250.00,308.43 -11897.35,10150.00,1747.35,11458.43,9850.00,1608.43 -11797.35,13000.00,-1202.65,11358.43,12500.00,-1141.57 -11697.35,15700.00,-4002.65,11258.43,14950.00,-3691.57 -11597.35,14450.00,-2852.65,11158.43,13650.00,-2491.57 -11497.35,11400.00,97.35,11058.43,10450.00,608.43 -11397.35,9650.00,1747.35,10958.43,9500.00,1458.43 -11297.35,12350.00,-1052.65,10858.43,11950.00,-1091.57 -11197.35,15100.00,-3902.65,10758.43,14100.00,-3341.57 -11097.35,14050.00,-2952.65,10658.43,12850.00,-2191.57 -10997.35,11150.00,-152.65,10558.43,10100.00,458.43 -10897.35,9800.00,1097.35,10458.43,9500.00,958.43 -10797.35,11050.00,-252.65,10358.43,10900.00,-541.57 -10697.35,13850.00,-3152.65,10258.43,12950.00,-2691.57 -10597.35,13400.00,-2802.65,10158.43,12450.00,-2291.57 -10497.35,10400.00,97.35,10058.43,9300.00,758.43 -10397.35,9550.00,847.35,9958.43,9400.00,558.43 -10297.35,11250.00,-952.65,9858.43,11050.00,-1191.57 -10197.35,12750.00,-2552.65,9758.43,11650.00,-1891.57 -10097.35,11900.00,-1802.65,9658.43,9100.00,558.43 -9997.35,9800.00,197.35,9558.43,8900.00,658.43 -9897.35,8850.00,1047.35,9458.43,10300.00,-841.57 -9797.35,10350.00,-552.65,9358.43,11050.00,-1691.57 -9697.35,12750.00,-3052.65,9258.43,10550.00,-1291.57 -9597.35,11650.00,-2052.65,9158.43,8200.00,958.43 -9497.35,9650.00,-152.65,9058.43,8150.00,908.43 -9397.35,9000.00,397.35,8958.43,10400.00,-1441.57 -9297.35,9900.00,-602.65,8858.43,11100.00,-2241.57 -9197.35,11000.00,-1802.65,8758.43,8850.00,-91.57 -9097.35,10000.00,-902.65,8658.43,7900.00,758.43 -8997.35,9250.00,-252.65,8558.43,9200.00,-641.57 -8897.35,9350.00,-452.65,8458.43,10200.00,-1741.57 -8797.35,9800.00,-1002.65,8358.43,9500.00,-1141.57 -8697.35,9500.00,-802.65,8258.43,7700.00,558.43 -8597.35,7550.00,1047.35,8158.43,7100.00,1058.43 -8497.35,7800.00,697.35,8058.43,8700.00,-641.57 -8397.35,10100.00,-1702.65,7958.43,9800.00,-1841.57 -8297.35,10300.00,-2002.65,7858.43,7600.00,258.43 -8197.35,8850.00,-652.65,7758.43,7400.00,358.43 -8097.35,7400.00,697.35,7658.43,8300.00,-641.57 -7997.35,6900.00,1097.35,7558.43,8000.00,-441.57 -7897.35,9100.00,-1202.65,7458.43,6800.00,658.43 -7797.35,9850.00,-2052.65,7358.43,6400.00,958.43 -7697.35,8050.00,-352.65,7258.43,7700.00,-441.57 -7597.35,7400.00,197.35,7158.43,8150.00,-991.57 -7497.35,7600.00,-102.65,7058.43,6800.00,258.43 -7397.35,8150.00,-752.65,6958.43,6450.00,508.43 -7297.35,8050.00,-752.65,6858.43,7000.00,-141.57 -7197.35,6700.00,497.35,6758.43,7450.00,-691.57 -7097.35,6300.00,797.35,6658.43,7200.00,-541.57 -6997.35,7600.00,-602.65,6558.43,5950.00,608.43 -6897.35,8050.00,-1152.65,6458.43,5400.00,1058.43 -6797.35,6700.00,97.35,6358.43,6400.00,-41.57 -6697.35,6350.00,347.35,6258.43,7700.00,-1441.57 -6597.35,6850.00,-252.65,6158.43,7000.00,-841.57 -6497.35,7150.00,-652.65,6058.43,5850.00,208.43 -6397.35,5800.00,597.35,5958.43,4650.00,1308.43 -6297.35,5500.00,797.35,5858.43,5400.00,458.43 -6197.35,6600.00,-402.65,5758.43,6750.00,-991.57 -6097.35,7350.00,-1252.65,5658.43,6850.00,-1191.57 -5997.35,6300.00,-302.65,5558.43,5400.00,158.43 -5897.35,5250.00,647.35,5458.43,4150.00,1308.43 -5797.35,5000.00,797.35,5358.43,3750.00,1608.43 -5697.35,6100.00,-402.65,5258.43,6150.00,-891.57 -5597.35,6350.00,-752.65,5158.43,7100.00,-1941.57 -5497.35,5350.00,147.35,5058.43,5850.00,-791.57 -5397.35,4850.00,547.35,4958.43,4900.00,58.43 -5297.35,4300.00,997.35,4858.43,3600.00,1258.43 -5197.35,5200.00,-2.65,4758.43,3400.00,1358.43 -5097.35,5850.00,-752.65,4658.43,5200.00,-541.57 -4997.35,5850.00,-852.65,4558.43,6900.00,-2341.57 -4897.35,4050.00,847.35,4458.43,4800.00,-341.57 -4797.35,3900.00,897.35,4358.43,3700.00,658.43 -4697.35,4900.00,-202.65,4258.43,3200.00,1058.43 -4597.35,5600.00,-1002.65,4158.43,4100.00,58.43 -4497.35,4700.00,-202.65,4058.43,4600.00,-541.57 -4397.35,3850.00,547.35,3958.43,3700.00,258.43 -4297.35,2850.00,1447.35,3858.43,2650.00,1208.43 -4197.35,3100.00,1097.35,3758.43,2450.00,1308.43 -4097.35,4950.00,-852.65,3658.43,4000.00,-341.57 -3997.35,5650.00,-1652.65,3558.43,4900.00,-1341.57 -3897.35,4800.00,-902.65,3458.43,3950.00,-491.57 -3797.35,3900.00,-102.65,3358.43,2750.00,608.43 -3697.35,3050.00,647.35,3258.43,2200.00,1058.43 -3597.35,2150.00,1447.35,3158.43,1400.00,1758.43 -3497.35,2250.00,1247.35,3058.43,3150.00,-91.57 -3397.35,4100.00,-702.65,2958.43,4450.00,-1491.57 -3297.35,4750.00,-1452.65,2858.43,3400.00,-541.57 -3197.35,3850.00,-652.65,2758.43,2400.00,358.43 -3097.35,3100.00,-2.65,2658.43,1700.00,958.43 -2997.35,2400.00,597.35,2558.43,-50.00,2608.43 -2897.35,1200.00,1697.35,2458.43,350.00,2108.43 -2797.35,1650.00,1147.35,2358.43,3700.00,-1341.57 -2697.35,3550.00,-852.65,2258.43,4950.00,-2691.57 -2597.35,3950.00,-1352.65,2158.43,4150.00,-1991.57 -2497.35,3200.00,-702.65,2058.43,3000.00,-941.57 -2397.35,2400.00,-2.65,1958.43,1800.00,158.43 -2297.35,1700.00,597.35,1858.43,1200.00,658.43 -2197.35,750.00,1447.35,1758.43,600.00,1158.43 -2097.35,1600.00,497.35,1658.43,-450.00,2108.43 -1997.35,2050.00,-52.65,1558.43,750.00,808.43 -1897.35,1800.00,97.35,1458.43,1900.00,-441.57 -1797.35,50.00,1747.35,1358.43,1500.00,-141.57 -1697.35,-100.00,1797.35,1258.43,-300.00,1558.43 -1597.35,1800.00,-202.65,1158.43,-500.00,1658.43 -1497.35,2900.00,-1402.65,1058.43,650.00,408.43 -1397.35,2250.00,-852.65,958.43,950.00,8.43 -1297.35,1300.00,-2.65,858.43,-200.00,1058.43 -1197.35,1400.00,-202.65,758.43,-950.00,1708.43 -1097.35,-450.00,1547.35,658.43,-650.00,1308.43 -997.35,-550.00,1547.35,558.43,350.00,208.43 -897.35,200.00,697.35,458.43,100.00,358.43 -797.35,0.00,797.35,358.43,0.00,358.43 -697.35,0.00,697.35,258.43,0.00,258.43 -597.35,0.00,597.35,158.43,0.00,158.43 -497.35,0.00,497.35,58.43,0.00,58.43 -397.35,0.00,397.35,0.00,0.00,0.00 -297.35,0.00,297.35,0.00,0.00,0.00 -197.35,0.00,197.35,0.00,0.00,0.00 -97.35,0.00,97.35,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 --100.00,0.00,-100.00,-100.00,0.00,-100.00 --200.00,0.00,-200.00,-200.00,0.00,-200.00 --300.00,0.00,-300.00,-300.00,0.00,-300.00 --400.00,0.00,-400.00,-400.00,0.00,-400.00 --500.00,0.00,-500.00,-500.00,0.00,-500.00 --600.00,0.00,-600.00,-600.00,0.00,-600.00 --700.00,0.00,-700.00,-700.00,0.00,-700.00 --800.00,0.00,-800.00,-800.00,0.00,-800.00 --900.00,0.00,-900.00,-900.00,0.00,-900.00 --1000.00,0.00,-1000.00,-1000.00,0.00,-1000.00 --1100.00,0.00,-1100.00,-1100.00,0.00,-1100.00 --1200.00,0.00,-1200.00,-1200.00,0.00,-1200.00 --1300.00,0.00,-1300.00,-1300.00,0.00,-1300.00 --1400.00,0.00,-1400.00,-1400.00,0.00,-1400.00 --1500.00,0.00,-1500.00,-1500.00,0.00,-1500.00 --1600.00,0.00,-1600.00,-1600.00,0.00,-1600.00 --1700.00,0.00,-1700.00,-1700.00,0.00,-1700.00 --1800.00,0.00,-1800.00,-1800.00,0.00,-1800.00 --1900.00,0.00,-1900.00,-1900.00,0.00,-1900.00 --2000.00,0.00,-2000.00,-2000.00,0.00,-2000.00 --2100.00,0.00,-2100.00,-2100.00,0.00,-2100.00 --2200.00,0.00,-2200.00,-2200.00,0.00,-2200.00 --2300.00,0.00,-2300.00,-2300.00,0.00,-2300.00 --2400.00,0.00,-2400.00,-2400.00,0.00,-2400.00 --2500.00,0.00,-2500.00,-2500.00,0.00,-2500.00 --2600.00,-450.00,-2150.00,-2600.00,-450.00,-2150.00 --2700.00,-450.00,-2250.00,-2700.00,-500.00,-2200.00 --2800.00,800.00,-3600.00,-2800.00,800.00,-3600.00 --2900.00,-500.00,-2400.00,-2900.00,-450.00,-2450.00 --3000.00,-2600.00,-400.00,-3000.00,-2650.00,-350.00 --3100.00,-3200.00,100.00,-3100.00,-2800.00,-300.00 --3200.00,-2500.00,-700.00,-3200.00,-1800.00,-1400.00 --3300.00,-2050.00,-1250.00,-3300.00,100.00,-3400.00 --3400.00,-200.00,-3200.00,-3400.00,0.00,-3400.00 --3500.00,-350.00,-3150.00,-3500.00,-2700.00,-800.00 --3600.00,-3250.00,-350.00,-3600.00,-4150.00,550.00 --3700.00,-4200.00,500.00,-3700.00,-2950.00,-750.00 --3800.00,-3650.00,-150.00,-3800.00,-1600.00,-2200.00 --3900.00,-2900.00,-1000.00,-3900.00,-1850.00,-2050.00 --4000.00,-2250.00,-1750.00,-4000.00,-2750.00,-1250.00 --4100.00,-1550.00,-2550.00,-4100.00,-3400.00,-700.00 --4200.00,-3250.00,-950.00,-4200.00,-1900.00,-2300.00 --4300.00,-4450.00,150.00,-4300.00,-2100.00,-2200.00 --4400.00,-3550.00,-850.00,-4400.00,-3250.00,-1150.00 --4500.00,-2850.00,-1650.00,-4500.00,-3850.00,-650.00 --4600.00,-2700.00,-1900.00,-4600.00,-2700.00,-1900.00 --4700.00,-3800.00,-900.00,-4700.00,-1750.00,-2950.00 --4800.00,-4650.00,-150.00,-4800.00,-3350.00,-1450.00 --4900.00,-3600.00,-1300.00,-4900.00,-4800.00,-100.00 --5000.00,-3450.00,-1550.00,-5000.00,-4500.00,-500.00 --5100.00,-4500.00,-600.00,-5100.00,-3300.00,-1800.00 --5200.00,-5300.00,100.00,-5200.00,-2700.00,-2500.00 --5300.00,-4200.00,-1100.00,-5300.00,-4000.00,-1300.00 --5400.00,-3950.00,-1450.00,-5400.00,-5400.00,0.00 --5500.00,-4950.00,-550.00,-5500.00,-5100.00,-400.00 --5600.00,-5800.00,200.00,-5600.00,-3850.00,-1750.00 --5700.00,-5900.00,200.00,-5700.00,-3200.00,-2500.00 --5800.00,-5000.00,-800.00,-5800.00,-4750.00,-1050.00 --5900.00,-4600.00,-1300.00,-5900.00,-6100.00,200.00 --6000.00,-5450.00,-550.00,-6000.00,-6000.00,0.00 --6100.00,-6500.00,400.00,-6100.00,-4700.00,-1400.00 --6200.00,-6600.00,400.00,-6200.00,-4100.00,-2100.00 --6300.00,-5550.00,-750.00,-6300.00,-5600.00,-700.00 --6400.00,-5200.00,-1200.00,-6400.00,-6750.00,350.00 --6500.00,-6150.00,-350.00,-6500.00,-6650.00,150.00 --6600.00,-7200.00,600.00,-6600.00,-5800.00,-800.00 --6700.00,-7200.00,500.00,-6700.00,-5850.00,-850.00 --6800.00,-6100.00,-700.00,-6800.00,-6350.00,-450.00 --6900.00,-5850.00,-1050.00,-6900.00,-6750.00,-150.00 --7000.00,-6750.00,-250.00,-7000.00,-7050.00,50.00 --7100.00,-7800.00,700.00,-7100.00,-7100.00,0.00 --7200.00,-7900.00,700.00,-7200.00,-7200.00,0.00 --7300.00,-6550.00,-750.00,-7300.00,-7250.00,-50.00 --7400.00,-6300.00,-1100.00,-7400.00,-7350.00,-50.00 --7500.00,-7400.00,-100.00,-7500.00,-7500.00,0.00 --7600.00,-8450.00,850.00,-7600.00,-7600.00,0.00 --7700.00,-8950.00,1250.00,-7700.00,-7800.00,100.00 --7800.00,-9750.00,1950.00,-7800.00,-9400.00,1600.00 --7900.00,-6900.00,-1000.00,-7900.00,-7500.00,-400.00 --8000.00,-6600.00,-1400.00,-8000.00,-6700.00,-1300.00 --8100.00,-7950.00,-150.00,-8100.00,-7450.00,-650.00 --8200.00,-9800.00,1600.00,-8200.00,-9000.00,800.00 --8300.00,-9550.00,1250.00,-8300.00,-9300.00,1000.00 --8400.00,-8200.00,-200.00,-8400.00,-9100.00,700.00 --8500.00,-8700.00,200.00,-8500.00,-9000.00,500.00 --8600.00,-9150.00,550.00,-8600.00,-8950.00,350.00 --8700.00,-9650.00,950.00,-8700.00,-9300.00,600.00 --8800.00,-9950.00,1150.00,-8800.00,-9500.00,700.00 --8900.00,-9950.00,1050.00,-8900.00,-9700.00,800.00 --9000.00,-10000.00,1000.00,-9000.00,-9800.00,800.00 --9100.00,-10000.00,900.00,-9100.00,-9900.00,800.00 --9200.00,-10100.00,900.00,-9200.00,-10000.00,800.00 --9300.00,-10350.00,1050.00,-9300.00,-10200.00,900.00 --9400.00,-10450.00,1050.00,-9400.00,-10400.00,1000.00 --9500.00,-10600.00,1100.00,-9500.00,-10500.00,1000.00 --9600.00,-10700.00,1100.00,-9600.00,-10500.00,900.00 --9700.00,-10850.00,1150.00,-9700.00,-10700.00,1000.00 --9800.00,-11000.00,1200.00,-9800.00,-10900.00,1100.00 --9900.00,-11250.00,1350.00,-9900.00,-11050.00,1150.00 --10000.00,-11250.00,1250.00,-10000.00,-11150.00,1150.00 --10100.00,-11350.00,1250.00,-10100.00,-11200.00,1100.00 --10200.00,-11400.00,1200.00,-10200.00,-11350.00,1150.00 --10300.00,-11600.00,1300.00,-10300.00,-11450.00,1150.00 --10400.00,-11700.00,1300.00,-10400.00,-11600.00,1200.00 --10500.00,-11800.00,1300.00,-10500.00,-11600.00,1100.00 --10600.00,-11950.00,1350.00,-10600.00,-11900.00,1300.00 --10700.00,-12150.00,1450.00,-10700.00,-12050.00,1350.00 --10800.00,-12250.00,1450.00,-10800.00,-12100.00,1300.00 --10900.00,-12350.00,1450.00,-10900.00,-12200.00,1300.00 --11000.00,-12450.00,1450.00,-11000.00,-12250.00,1250.00 --11100.00,-12600.00,1500.00,-11100.00,-12350.00,1250.00 --11200.00,-12700.00,1500.00,-11200.00,-12400.00,1200.00 --11300.00,-12850.00,1550.00,-11300.00,-12550.00,1250.00 --11400.00,-13000.00,1600.00,-11400.00,-12600.00,1200.00 --11500.00,-13150.00,1650.00,-11500.00,-12650.00,1150.00 --11600.00,-13250.00,1650.00,-11600.00,-12850.00,1250.00 --11700.00,-13350.00,1650.00,-11700.00,-13000.00,1300.00 --11800.00,-13600.00,1800.00,-11800.00,-13000.00,1200.00 --11900.00,-13650.00,1750.00,-11900.00,-13100.00,1200.00 --12000.00,-13800.00,1800.00,-12000.00,-13100.00,1100.00 --12100.00,-13900.00,1800.00,-12100.00,-13200.00,1100.00 --12200.00,-14150.00,1950.00,-12200.00,-13400.00,1200.00 --12300.00,-14200.00,1900.00,-12300.00,-13700.00,1400.00 --12400.00,-14200.00,1800.00,-12400.00,-13900.00,1500.00 --12500.00,-14450.00,1950.00,-12500.00,-13950.00,1450.00 --12600.00,-14650.00,2050.00,-12600.00,-13950.00,1350.00 --12700.00,-14700.00,2000.00,-12700.00,-13900.00,1200.00 --12800.00,-14750.00,1950.00,-12800.00,-14050.00,1250.00 --12900.00,-14900.00,2000.00,-12900.00,-14200.00,1300.00 --13000.00,-15050.00,2050.00,-13000.00,-14300.00,1300.00 --13100.00,-15250.00,2150.00,-13100.00,-14400.00,1300.00 --13200.00,-15450.00,2250.00,-13200.00,-14600.00,1400.00 --13300.00,-15500.00,2200.00,-13300.00,-14800.00,1500.00 --13400.00,-15450.00,2050.00,-13400.00,-15050.00,1650.00 --13500.00,-15550.00,2050.00,-13500.00,-15400.00,1900.00 --13600.00,-15700.00,2100.00,-13600.00,-15700.00,2100.00 --13700.00,-15800.00,2100.00,-13700.00,-15800.00,2100.00 --13800.00,-16000.00,2200.00,-13800.00,-15750.00,1950.00 --13900.00,-15550.00,1650.00,-13900.00,-15150.00,1250.00 --14000.00,-16200.00,2200.00,-14000.00,-16000.00,2000.00 --14100.00,-15900.00,1800.00,-14100.00,-15700.00,1600.00 --14200.00,-16750.00,2550.00,-14200.00,-16500.00,2300.00 --14300.00,-16850.00,2550.00,-14300.00,-16800.00,2500.00 --14400.00,-16850.00,2450.00,-14400.00,-16750.00,2350.00 --14500.00,-16800.00,2300.00,-14500.00,-16650.00,2150.00 --14600.00,-16750.00,2150.00,-14600.00,-16750.00,2150.00 --14700.00,-17000.00,2300.00,-14700.00,-16750.00,2050.00 --14800.00,-17150.00,2350.00,-14800.00,-16950.00,2150.00 --14900.00,-17450.00,2550.00,-14900.00,-17150.00,2250.00 --15000.00,-17550.00,2550.00,-15000.00,-17300.00,2300.00 --15100.00,-17550.00,2450.00,-15100.00,-17450.00,2350.00 --15200.00,-20900.00,5700.00,-15200.00,-20900.00,5700.00 --15300.00,-17350.00,2050.00,-15300.00,-17250.00,1950.00 --15400.00,-16500.00,1100.00,-15400.00,-16400.00,1000.00 --15500.00,-17450.00,1950.00,-15500.00,-17050.00,1550.00 --15600.00,-17600.00,2000.00,-15600.00,-17200.00,1600.00 --15700.00,-18700.00,3000.00,-15700.00,-18300.00,2600.00 --15800.00,-19700.00,3900.00,-15800.00,-19000.00,3200.00 --15900.00,-18850.00,2950.00,-15900.00,-17950.00,2050.00 --16000.00,-18550.00,2550.00,-16000.00,-17800.00,1800.00 --16100.00,-19250.00,3150.00,-16100.00,-18850.00,2750.00 --16200.00,-18900.00,2700.00,-16200.00,-18450.00,2250.00 --16300.00,-19700.00,3400.00,-16300.00,-19200.00,2900.00 --16400.00,-19000.00,2600.00,-16400.00,-18450.00,2050.00 --16500.00,-19150.00,2650.00,-16500.00,-18400.00,1900.00 --16600.00,-19250.00,2650.00,-16600.00,-18550.00,1950.00 --16700.00,-19650.00,2950.00,-16700.00,-18700.00,2000.00 --16800.00,-20500.00,3700.00,-16800.00,-19800.00,3000.00 --16900.00,-20600.00,3700.00,-16900.00,-20150.00,3250.00 --17000.00,-19500.00,2500.00,-17000.00,-19500.00,2500.00 --17100.00,-20200.00,3100.00,-17100.00,-20350.00,3250.00 --17200.00,-19750.00,2550.00,-17200.00,-19800.00,2600.00 --17300.00,-19950.00,2650.00,-17300.00,-19800.00,2500.00 --17400.00,-20250.00,2850.00,-17400.00,-20100.00,2700.00 --17500.00,-21500.00,4000.00,-17500.00,-21100.00,3600.00 --17600.00,-21450.00,3850.00,-17600.00,-21150.00,3550.00 --17700.00,-21100.00,3400.00,-17700.00,-20850.00,3150.00 --17800.00,-20100.00,2300.00,-17800.00,-20100.00,2300.00 --17900.00,-20550.00,2650.00,-17900.00,-20250.00,2350.00 --18000.00,-21000.00,3000.00,-17952.47,-20750.00,2797.53 --18047.75,-21500.00,3452.25,-17852.47,-21200.00,3347.53 --17947.75,-21500.00,3552.25,-17752.47,-21300.00,3547.53 --17847.75,-21550.00,3702.25,-17652.47,-21200.00,3547.53 --17747.75,-21250.00,3502.25,-17552.47,-20900.00,3347.53 --17647.75,-21850.00,4202.25,-17452.47,-21400.00,3947.53 --17547.75,-21000.00,3452.25,-17352.47,-20350.00,2997.53 --17447.75,-21550.00,4102.25,-17252.47,-20550.00,3297.53 --17347.75,-21250.00,3902.25,-17152.47,-20300.00,3147.53 --17247.75,-20300.00,3052.25,-17052.47,-19250.00,2197.53 --17147.75,-19900.00,2752.25,-16952.47,-19300.00,2347.53 --17047.75,-21000.00,3952.25,-16852.47,-20450.00,3597.53 --16947.75,-20400.00,3452.25,-16752.47,-19700.00,2947.53 --16847.75,-20050.00,3202.25,-16652.47,-19350.00,2697.53 --16747.75,-20000.00,3252.25,-16552.47,-19150.00,2597.53 --16647.75,-19900.00,3252.25,-16452.47,-19050.00,2597.53 --16547.75,-19750.00,3202.25,-16352.47,-18800.00,2447.53 --16447.75,-19750.00,3302.25,-16252.47,-18700.00,2447.53 --16347.75,-19600.00,3252.25,-16152.47,-18750.00,2597.53 --16247.75,-20300.00,4052.25,-16052.47,-19550.00,3497.53 --16147.75,-19200.00,3052.25,-15952.47,-18900.00,2947.53 --16047.75,-18850.00,2802.25,-15852.47,-18650.00,2797.53 --15947.75,-18950.00,3002.25,-15752.47,-18650.00,2897.53 --15847.75,-18750.00,2902.25,-15652.47,-18650.00,2997.53 --15747.75,-18950.00,3202.25,-15552.47,-18600.00,3047.53 --15647.75,-19550.00,3902.25,-15452.47,-19150.00,3697.53 --15547.75,-18650.00,3102.25,-15352.47,-18250.00,2897.53 --15447.75,-18850.00,3402.25,-15252.47,-18250.00,2997.53 --15347.75,-18050.00,2702.25,-15152.47,-17300.00,2147.53 --15247.75,-18550.00,3302.25,-15052.47,-17850.00,2797.53 --15147.75,-17850.00,2702.25,-14952.47,-17300.00,2347.53 --15047.75,-17750.00,2702.25,-14852.47,-17200.00,2347.53 --14947.75,-18600.00,3652.25,-14752.47,-18000.00,3247.53 --14847.75,-17700.00,2852.25,-14652.47,-17200.00,2547.53 --14747.75,-17500.00,2752.25,-14552.47,-16950.00,2397.53 --14647.75,-18150.00,3502.25,-14452.47,-17500.00,3047.53 --14547.75,-17250.00,2702.25,-14352.47,-16800.00,2447.53 --14447.75,-17750.00,3302.25,-14252.47,-17150.00,2897.53 --14347.75,-17000.00,2652.25,-14152.47,-16600.00,2447.53 --14247.75,-17450.00,3202.25,-14052.47,-16800.00,2747.53 --14147.75,-17500.00,3352.25,-13952.47,-16500.00,2547.53 --14047.75,-17100.00,3052.25,-13852.47,-15950.00,2097.53 --13947.75,-16700.00,2752.25,-13752.47,-15700.00,1947.53 --13847.75,-16750.00,2902.25,-13652.47,-15650.00,1997.53 --13747.75,-16600.00,2852.25,-13552.47,-15850.00,2297.53 --13647.75,-18750.00,5102.25,-13452.47,-18050.00,4597.53 --13547.75,-14800.00,1252.25,-13352.47,-14700.00,1347.53 --13447.75,-12750.00,-697.75,-13252.47,-13800.00,547.53 --13347.75,-14000.00,652.25,-13152.47,-14300.00,1147.53 --13247.75,-16100.00,2852.25,-13052.47,-14850.00,1797.53 --13147.75,-17400.00,4252.25,-12952.47,-15550.00,2597.53 --13047.75,-16600.00,3552.25,-12852.47,-15150.00,2297.53 --12947.75,-15650.00,2702.25,-12752.47,-14700.00,1947.53 --12847.75,-14750.00,1902.25,-12652.47,-13900.00,1247.53 --12747.75,-14600.00,1852.25,-12552.47,-14050.00,1497.53 --12647.75,-15350.00,2702.25,-12452.47,-14950.00,2497.53 --12547.75,-15300.00,2752.25,-12352.47,-15150.00,2797.53 --12447.75,-15000.00,2552.25,-12252.47,-14950.00,2697.53 --12347.75,-14400.00,2052.25,-12152.47,-14000.00,1847.53 --12247.75,-14650.00,2402.25,-12052.47,-14300.00,2247.53 --12147.75,-14700.00,2552.25,-11952.47,-14350.00,2397.53 --12047.75,-14000.00,1952.25,-11852.47,-13750.00,1897.53 --11947.75,-13850.00,1902.25,-11752.47,-13550.00,1797.53 --11847.75,-13950.00,2102.25,-11652.47,-13500.00,1847.53 --11747.75,-13900.00,2152.25,-11552.47,-13600.00,2047.53 --11647.75,-13900.00,2252.25,-11452.47,-13450.00,1997.53 --11547.75,-13900.00,2352.25,-11352.47,-13350.00,1997.53 --11447.75,-13600.00,2152.25,-11252.47,-13200.00,1947.53 --11347.75,-13350.00,2002.25,-11152.47,-12900.00,1747.53 --11247.75,-13300.00,2052.25,-11052.47,-12650.00,1597.53 --11147.75,-13200.00,2052.25,-10952.47,-12400.00,1447.53 --11047.75,-13000.00,1952.25,-10852.47,-12450.00,1597.53 --10947.75,-12900.00,1952.25,-10752.47,-12400.00,1647.53 --10847.75,-12800.00,1952.25,-10652.47,-12200.00,1547.53 --10747.75,-12750.00,2002.25,-10552.47,-12050.00,1497.53 --10647.75,-12650.00,2002.25,-10452.47,-11950.00,1497.53 --10547.75,-12500.00,1952.25,-10352.47,-11900.00,1547.53 --10447.75,-12500.00,2052.25,-10252.47,-11800.00,1547.53 --10347.75,-12300.00,1952.25,-10152.47,-11650.00,1497.53 --10247.75,-12150.00,1902.25,-10052.47,-11550.00,1497.53 --10147.75,-12050.00,1902.25,-9952.47,-11400.00,1447.53 --10047.75,-11900.00,1852.25,-9852.47,-11350.00,1497.53 --9947.75,-11900.00,1952.25,-9752.47,-11150.00,1397.53 --9847.75,-11700.00,1852.25,-9652.47,-11000.00,1347.53 --9747.75,-11450.00,1702.25,-9552.47,-10700.00,1147.53 --9647.75,-11350.00,1702.25,-9452.47,-10450.00,997.53 --9547.75,-11400.00,1852.25,-9352.47,-10250.00,897.53 --9447.75,-11200.00,1752.25,-9252.47,-10200.00,947.53 --9347.75,-11050.00,1702.25,-9152.47,-10200.00,1047.53 --9247.75,-11000.00,1752.25,-9052.47,-10150.00,1097.53 --9147.75,-10750.00,1602.25,-8952.47,-10200.00,1247.53 --9047.75,-10650.00,1602.25,-8852.47,-10050.00,1197.53 --8947.75,-10550.00,1602.25,-8752.47,-9750.00,997.53 --8847.75,-10400.00,1552.25,-8652.47,-9500.00,847.53 --8747.75,-10250.00,1502.25,-8552.47,-9350.00,797.53 --8647.75,-9750.00,1102.25,-8452.47,-8800.00,347.53 --8547.75,-9700.00,1152.25,-8352.47,-8800.00,447.53 --8447.75,-9700.00,1252.25,-8252.47,-8800.00,547.53 --8347.75,-9700.00,1352.25,-8152.47,-8750.00,597.53 --8247.75,-9400.00,1152.25,-8052.47,-9050.00,997.53 --8147.75,-7800.00,-347.75,-7952.47,-8500.00,547.53 --8047.75,-8500.00,452.25,-7852.47,-8300.00,447.53 --7947.75,-8800.00,852.25,-7752.47,-8100.00,347.53 --7847.75,-9300.00,1452.25,-7652.47,-8000.00,347.53 --7747.75,-8650.00,902.25,-7552.47,-8000.00,447.53 --7647.75,-7900.00,252.25,-7452.47,-8200.00,747.53 --7547.75,-8300.00,752.25,-7352.47,-8200.00,847.53 --7447.75,-8500.00,1052.25,-7252.47,-7700.00,447.53 --7347.75,-8250.00,902.25,-7152.47,-6850.00,-302.47 --7247.75,-6600.00,-647.75,-7052.47,-6850.00,-202.47 --7147.75,-6550.00,-597.75,-6952.47,-7650.00,697.53 --7047.75,-7400.00,352.25,-6852.47,-7700.00,847.53 --6947.75,-8100.00,1152.25,-6752.47,-6500.00,-252.47 --6847.75,-7950.00,1102.25,-6652.47,-5950.00,-702.47 --6747.75,-6650.00,-97.75,-6552.47,-6950.00,397.53 --6647.75,-5900.00,-747.75,-6452.47,-6850.00,397.53 --6547.75,-6850.00,302.25,-6352.47,-5800.00,-552.47 --6447.75,-6850.00,402.25,-6252.47,-5500.00,-752.47 --6347.75,-5800.00,-547.75,-6152.47,-6200.00,47.53 --6247.75,-6550.00,302.25,-6052.47,-7300.00,1247.53 --6147.75,-5950.00,-197.75,-5952.47,-5200.00,-752.47 --6047.75,-5100.00,-947.75,-5852.47,-4750.00,-1102.47 --5947.75,-6100.00,152.25,-5752.47,-5450.00,-302.47 --5847.75,-6150.00,302.25,-5652.47,-5800.00,147.53 --5747.75,-5250.00,-497.75,-5552.47,-4900.00,-652.47 --5647.75,-4800.00,-847.75,-5452.47,-4400.00,-1052.47 --5547.75,-5450.00,-97.75,-5352.47,-4900.00,-452.47 --5447.75,-5700.00,252.25,-5252.47,-5150.00,-102.47 --5347.75,-4750.00,-597.75,-5152.47,-4400.00,-752.47 --5247.75,-4200.00,-1047.75,-5052.47,-3850.00,-1202.47 --5147.75,-5050.00,-97.75,-4952.47,-4300.00,-652.47 --5047.75,-5250.00,202.25,-4852.47,-4600.00,-252.47 --4947.75,-4450.00,-497.75,-4752.47,-3800.00,-952.47 --4847.75,-3450.00,-1397.75,-4652.47,-2700.00,-1952.47 --4747.75,-3100.00,-1647.75,-4552.47,-2850.00,-1702.47 --4647.75,-4400.00,-247.75,-4452.47,-4100.00,-352.47 --4547.75,-5050.00,502.25,-4352.47,-4650.00,297.53 --4447.75,-4300.00,-147.75,-4252.47,-3750.00,-502.47 --4347.75,-3350.00,-997.75,-4152.47,-2850.00,-1302.47 --4247.75,-2550.00,-1697.75,-4052.47,-1650.00,-2402.47 --4147.75,-2400.00,-1747.75,-3952.47,-2250.00,-1702.47 --4047.75,-3650.00,-397.75,-3852.47,-3500.00,-352.47 --3947.75,-4250.00,302.25,-3752.47,-3900.00,147.53 --3847.75,-3400.00,-447.75,-3652.47,-3000.00,-652.47 --3747.75,-2600.00,-1147.75,-3552.47,-2350.00,-1202.47 --3647.75,-1800.00,-1847.75,-3452.47,-650.00,-2802.47 --3547.75,-1300.00,-2247.75,-3352.47,-600.00,-2752.47 --3447.75,-2800.00,-647.75,-3252.47,-3000.00,-252.47 --3347.75,-3750.00,402.25,-3152.47,-4050.00,897.53 --3247.75,-2800.00,-447.75,-3052.47,-3050.00,-2.47 --3147.75,-2300.00,-847.75,-2952.47,-2400.00,-552.47 --3047.75,-900.00,-2147.75,-2852.47,-1200.00,-1652.47 --2947.75,-1600.00,-1347.75,-2752.47,-1200.00,-1552.47 --2847.75,-1550.00,-1297.75,-2652.47,100.00,-2752.47 --2747.75,-1450.00,-1297.75,-2552.47,-150.00,-2402.47 --2647.75,-700.00,-1947.75,-2452.47,-1450.00,-1002.47 --2547.75,600.00,-3147.75,-2352.47,-2050.00,-302.47 --2447.75,-600.00,-1847.75,-2252.47,-650.00,-1602.47 --2347.75,-1250.00,-1097.75,-2152.47,500.00,-2652.47 --2247.75,-1250.00,-997.75,-2052.47,400.00,-2452.47 --2147.75,-900.00,-1247.75,-1952.47,-600.00,-1352.47 --2047.75,750.00,-2797.75,-1852.47,800.00,-2652.47 --1947.75,-250.00,-1697.75,-1752.47,300.00,-2052.47 --1847.75,-900.00,-947.75,-1652.47,-400.00,-1252.47 --1747.75,350.00,-2097.75,-1552.47,50.00,-1602.47 --1647.75,900.00,-2547.75,-1452.47,0.00,-1452.47 --1547.75,50.00,-1597.75,-1352.47,0.00,-1352.47 --1447.75,-200.00,-1247.75,-1252.47,0.00,-1252.47 --1347.75,0.00,-1347.75,-1152.47,0.00,-1152.47 --1247.75,0.00,-1247.75,-1052.47,0.00,-1052.47 --1147.75,0.00,-1147.75,-952.47,0.00,-952.47 --1047.75,0.00,-1047.75,-852.47,0.00,-852.47 --947.75,0.00,-947.75,-752.47,0.00,-752.47 --847.75,0.00,-847.75,-652.47,0.00,-652.47 --747.75,0.00,-747.75,-552.47,0.00,-552.47 --647.75,0.00,-647.75,-452.47,0.00,-452.47 --547.75,0.00,-547.75,-352.47,0.00,-352.47 --447.75,0.00,-447.75,-252.47,0.00,-252.47 --347.75,0.00,-347.75,-152.47,0.00,-152.47 --247.75,0.00,-247.75,-52.47,0.00,-52.47 --147.75,0.00,-147.75,0.00,0.00,0.00 --47.75,0.00,-47.75,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -100.00,0.00,100.00,100.00,0.00,100.00 -200.00,0.00,200.00,200.00,0.00,200.00 -300.00,0.00,300.00,300.00,0.00,300.00 -400.00,0.00,400.00,400.00,0.00,400.00 -500.00,0.00,500.00,500.00,0.00,500.00 -600.00,0.00,600.00,600.00,0.00,600.00 -700.00,0.00,700.00,700.00,0.00,700.00 -800.00,0.00,800.00,800.00,0.00,800.00 -900.00,0.00,900.00,900.00,0.00,900.00 -1000.00,0.00,1000.00,1000.00,0.00,1000.00 -1100.00,0.00,1100.00,1100.00,0.00,1100.00 -1200.00,0.00,1200.00,1200.00,0.00,1200.00 -1300.00,0.00,1300.00,1300.00,0.00,1300.00 -1400.00,0.00,1400.00,1400.00,0.00,1400.00 -1500.00,0.00,1500.00,1500.00,0.00,1500.00 -1600.00,0.00,1600.00,1600.00,0.00,1600.00 -1700.00,0.00,1700.00,1700.00,0.00,1700.00 -1800.00,0.00,1800.00,1800.00,0.00,1800.00 -1900.00,0.00,1900.00,1900.00,0.00,1900.00 -2000.00,0.00,2000.00,2000.00,0.00,2000.00 -2100.00,0.00,2100.00,2100.00,0.00,2100.00 -2200.00,0.00,2200.00,2200.00,0.00,2200.00 -2300.00,0.00,2300.00,2300.00,0.00,2300.00 -2400.00,0.00,2400.00,2400.00,0.00,2400.00 -2500.00,0.00,2500.00,2500.00,0.00,2500.00 -2600.00,500.00,2100.00,2600.00,500.00,2100.00 -2700.00,550.00,2150.00,2700.00,400.00,2300.00 -2800.00,-900.00,3700.00,2800.00,-250.00,3050.00 -2900.00,450.00,2450.00,2900.00,1250.00,1650.00 -3000.00,2400.00,600.00,3000.00,2350.00,650.00 -3100.00,2900.00,200.00,3100.00,800.00,2300.00 -3200.00,2450.00,750.00,3200.00,700.00,2500.00 -3300.00,2000.00,1300.00,3300.00,2400.00,900.00 -3400.00,750.00,2650.00,3400.00,2950.00,450.00 -3500.00,250.00,3250.00,3500.00,1600.00,1900.00 -3600.00,2700.00,900.00,3600.00,1850.00,1750.00 -3700.00,4100.00,-400.00,3700.00,2350.00,1350.00 -3800.00,3150.00,650.00,3800.00,2550.00,1250.00 -3900.00,2650.00,1250.00,3900.00,1700.00,2200.00 -4000.00,1650.00,2350.00,4000.00,900.00,3100.00 -4100.00,2450.00,1650.00,4100.00,3000.00,1100.00 -4200.00,3500.00,700.00,4200.00,4100.00,100.00 -4300.00,3950.00,350.00,4300.00,3100.00,1200.00 -4400.00,3250.00,1150.00,4400.00,2350.00,2050.00 -4500.00,2750.00,1750.00,4500.00,1650.00,2850.00 -4600.00,2650.00,1950.00,4600.00,3550.00,1050.00 -4700.00,3800.00,900.00,4700.00,4650.00,50.00 -4800.00,4600.00,200.00,4800.00,3700.00,1100.00 -4900.00,3800.00,1100.00,4900.00,3150.00,1750.00 -5000.00,3800.00,1200.00,5000.00,3700.00,1300.00 -5100.00,4500.00,600.00,5100.00,4550.00,550.00 -5200.00,4600.00,600.00,5200.00,4700.00,500.00 -5300.00,3900.00,1400.00,5300.00,3600.00,1700.00 -5400.00,4000.00,1400.00,5400.00,3200.00,2200.00 -5500.00,4950.00,550.00,5500.00,4500.00,1000.00 -5600.00,5850.00,-250.00,5600.00,5700.00,-100.00 -5700.00,6100.00,-400.00,5700.00,6000.00,-300.00 -5800.00,5150.00,650.00,5800.00,4800.00,1000.00 -5900.00,4850.00,1050.00,5900.00,4150.00,1750.00 -6000.00,5400.00,600.00,6000.00,5000.00,1000.00 -6100.00,6150.00,-50.00,6100.00,6050.00,50.00 -6200.00,6650.00,-450.00,6200.00,6300.00,-100.00 -6300.00,5300.00,1000.00,6300.00,5000.00,1300.00 -6400.00,5100.00,1300.00,6400.00,4900.00,1500.00 -6500.00,6450.00,50.00,6500.00,5750.00,750.00 -6600.00,6950.00,-350.00,6600.00,6650.00,-50.00 -6700.00,7000.00,-300.00,6700.00,7000.00,-300.00 -6800.00,6050.00,750.00,6800.00,6950.00,-150.00 -6900.00,5800.00,1100.00,6900.00,6150.00,750.00 -7000.00,7100.00,-100.00,7000.00,6300.00,700.00 -7100.00,7450.00,-350.00,7100.00,6800.00,300.00 -7200.00,7950.00,-750.00,7200.00,7300.00,-100.00 -7300.00,7900.00,-600.00,7300.00,7950.00,-650.00 -7400.00,7100.00,300.00,7400.00,7950.00,-550.00 -7500.00,7700.00,-200.00,7500.00,7900.00,-400.00 -7600.00,8250.00,-650.00,7600.00,7700.00,-100.00 -7700.00,8500.00,-800.00,7700.00,7750.00,-50.00 -7800.00,8300.00,-500.00,7800.00,7550.00,250.00 -7900.00,8750.00,-850.00,7900.00,8100.00,-200.00 -8000.00,8850.00,-850.00,8000.00,8300.00,-300.00 -8100.00,10550.00,-2450.00,8100.00,9800.00,-1700.00 -8200.00,8550.00,-350.00,8200.00,7800.00,400.00 -8300.00,7300.00,1000.00,8300.00,6500.00,1800.00 -8400.00,7950.00,450.00,8400.00,7500.00,900.00 -8500.00,9050.00,-550.00,8500.00,8900.00,-400.00 -8600.00,10050.00,-1450.00,8600.00,9950.00,-1350.00 -8700.00,10250.00,-1550.00,8700.00,9800.00,-1100.00 -8800.00,9900.00,-1100.00,8800.00,9400.00,-600.00 -8900.00,9700.00,-800.00,8900.00,9250.00,-350.00 -9000.00,9800.00,-800.00,9000.00,9400.00,-400.00 -9100.00,10050.00,-950.00,9100.00,9700.00,-600.00 -9200.00,10200.00,-1000.00,9200.00,10000.00,-800.00 -9300.00,10400.00,-1100.00,9300.00,10200.00,-900.00 -9400.00,10500.00,-1100.00,9400.00,10300.00,-900.00 -9500.00,10550.00,-1050.00,9500.00,10300.00,-800.00 -9600.00,10650.00,-1050.00,9600.00,10300.00,-700.00 -9700.00,10850.00,-1150.00,9700.00,10550.00,-850.00 -9800.00,10850.00,-1050.00,9800.00,10650.00,-850.00 -9900.00,11050.00,-1150.00,9900.00,10650.00,-750.00 -10000.00,11150.00,-1150.00,10000.00,10850.00,-850.00 -10100.00,11350.00,-1250.00,10100.00,11150.00,-1050.00 -10200.00,11500.00,-1300.00,10200.00,11450.00,-1250.00 -10300.00,11550.00,-1250.00,10300.00,11500.00,-1200.00 -10400.00,11700.00,-1300.00,10400.00,11650.00,-1250.00 -10500.00,11800.00,-1300.00,10500.00,11750.00,-1250.00 -10600.00,12050.00,-1450.00,10600.00,12000.00,-1400.00 -10700.00,12150.00,-1450.00,10700.00,12050.00,-1350.00 -10800.00,12250.00,-1450.00,10800.00,12150.00,-1350.00 -10900.00,12500.00,-1600.00,10900.00,12350.00,-1450.00 -11000.00,12600.00,-1600.00,11000.00,12400.00,-1400.00 -11100.00,12650.00,-1550.00,11100.00,12450.00,-1350.00 -11200.00,12750.00,-1550.00,11200.00,12450.00,-1250.00 -11300.00,12900.00,-1600.00,11300.00,12550.00,-1250.00 -11400.00,13050.00,-1650.00,11400.00,12600.00,-1200.00 -11500.00,13250.00,-1750.00,11500.00,12800.00,-1300.00 -11600.00,13300.00,-1700.00,11600.00,12900.00,-1300.00 -11700.00,13450.00,-1750.00,11700.00,13050.00,-1350.00 -11800.00,13650.00,-1850.00,11800.00,13250.00,-1450.00 -11900.00,13800.00,-1900.00,11900.00,13500.00,-1600.00 -12000.00,13950.00,-1950.00,12000.00,13650.00,-1650.00 -12100.00,14100.00,-2000.00,12100.00,13750.00,-1650.00 -12200.00,14050.00,-1850.00,12200.00,13850.00,-1650.00 -12300.00,14200.00,-1900.00,12300.00,13900.00,-1600.00 -12400.00,14300.00,-1900.00,12400.00,14050.00,-1650.00 -12500.00,14500.00,-2000.00,12500.00,14200.00,-1700.00 -12600.00,14600.00,-2000.00,12600.00,14450.00,-1850.00 -12700.00,14800.00,-2100.00,12700.00,14650.00,-1950.00 -12800.00,14900.00,-2100.00,12800.00,14800.00,-2000.00 -12900.00,15000.00,-2100.00,12900.00,14800.00,-1900.00 -13000.00,15050.00,-2050.00,13000.00,14750.00,-1750.00 -13100.00,15200.00,-2100.00,13100.00,14650.00,-1550.00 -13200.00,15250.00,-2050.00,13200.00,14700.00,-1500.00 -13300.00,15250.00,-1950.00,13300.00,14800.00,-1500.00 -13400.00,15500.00,-2100.00,13400.00,15050.00,-1650.00 -13500.00,15650.00,-2150.00,13500.00,15350.00,-1850.00 -13600.00,15650.00,-2050.00,13600.00,15500.00,-1900.00 -13700.00,15800.00,-2100.00,13700.00,15500.00,-1800.00 -13800.00,16000.00,-2200.00,13800.00,15700.00,-1900.00 -13900.00,16100.00,-2200.00,13900.00,16050.00,-2150.00 -14000.00,16150.00,-2150.00,14000.00,16100.00,-2100.00 -14100.00,16300.00,-2200.00,14100.00,16100.00,-2000.00 -14200.00,16450.00,-2250.00,14200.00,16150.00,-1950.00 -14300.00,16600.00,-2300.00,14300.00,16300.00,-2000.00 -14400.00,16800.00,-2400.00,14400.00,16600.00,-2200.00 -14500.00,16800.00,-2300.00,14500.00,16900.00,-2400.00 -14600.00,16950.00,-2350.00,14600.00,17000.00,-2400.00 -14700.00,17050.00,-2350.00,14700.00,17100.00,-2400.00 -14800.00,17150.00,-2350.00,14800.00,17300.00,-2500.00 -14900.00,17300.00,-2400.00,14900.00,17350.00,-2450.00 -15000.00,17500.00,-2500.00,15000.00,17200.00,-2200.00 -15100.00,17600.00,-2500.00,15100.00,17550.00,-2450.00 -15200.00,17750.00,-2550.00,15200.00,17500.00,-2300.00 -15300.00,17850.00,-2550.00,15300.00,17550.00,-2250.00 -15400.00,18050.00,-2650.00,15400.00,17550.00,-2150.00 -15500.00,18100.00,-2600.00,15500.00,17700.00,-2200.00 -15600.00,21700.00,-6100.00,15600.00,21400.00,-5800.00 -15700.00,17000.00,-1300.00,15700.00,17750.00,-2050.00 -15800.00,14800.00,1000.00,15800.00,16800.00,-1000.00 -15900.00,16600.00,-700.00,15900.00,17650.00,-1750.00 -16000.00,19250.00,-3250.00,16000.00,18550.00,-2550.00 -16100.00,20350.00,-4250.00,16100.00,19000.00,-2900.00 -16200.00,19700.00,-3500.00,16200.00,18950.00,-2750.00 -16300.00,19200.00,-2900.00,16300.00,19100.00,-2800.00 -16400.00,19300.00,-2900.00,16400.00,19150.00,-2750.00 -16500.00,19050.00,-2550.00,16500.00,18850.00,-2350.00 -16600.00,19300.00,-2700.00,16600.00,18900.00,-2300.00 -16700.00,19450.00,-2750.00,16700.00,19300.00,-2600.00 -16800.00,19600.00,-2800.00,16800.00,19450.00,-2650.00 -16900.00,19750.00,-2850.00,16900.00,19650.00,-2750.00 -17000.00,19900.00,-2900.00,17000.00,19750.00,-2750.00 -17100.00,20100.00,-3000.00,17100.00,19850.00,-2750.00 -17200.00,20200.00,-3000.00,17200.00,19900.00,-2700.00 -17300.00,20200.00,-2900.00,17300.00,20000.00,-2700.00 -17400.00,20300.00,-2900.00,17400.00,20200.00,-2800.00 -17500.00,20350.00,-2850.00,17500.00,20200.00,-2700.00 -17600.00,20600.00,-3000.00,17600.00,20350.00,-2750.00 -17700.00,20750.00,-3050.00,17700.00,20800.00,-3100.00 -17800.00,20900.00,-3100.00,17800.00,20850.00,-3050.00 -17900.00,21000.00,-3100.00,17900.00,21050.00,-3150.00 -18000.00,21200.00,-3200.00,17956.36,21250.00,-3293.64 -18100.00,21400.00,-3300.00,17856.36,21150.00,-3293.64 -18200.00,21450.00,-3250.00,17756.36,21450.00,-3693.64 -18189.72,21600.00,-3410.28,17656.36,21000.00,-3343.64 -18089.72,21800.00,-3710.28,17556.36,21100.00,-3543.64 -17989.72,21750.00,-3760.28,17456.36,20850.00,-3393.64 -17889.72,21600.00,-3710.28,17356.36,20650.00,-3293.64 -17789.72,21550.00,-3760.28,17256.36,20550.00,-3293.64 -17689.72,21400.00,-3710.28,17156.36,20350.00,-3193.64 -17589.72,21200.00,-3610.28,17056.36,20350.00,-3293.64 -17489.72,21100.00,-3610.28,16956.36,20200.00,-3243.64 -17389.72,20900.00,-3510.28,16856.36,20100.00,-3243.64 -17289.72,20850.00,-3560.28,16756.36,19950.00,-3193.64 -17189.72,20800.00,-3610.28,16656.36,19700.00,-3043.64 -17089.72,20450.00,-3360.28,16556.36,19700.00,-3143.64 -16989.72,20250.00,-3260.28,16456.36,19450.00,-2993.64 -16889.72,20150.00,-3260.28,16356.36,19250.00,-2893.64 -16789.72,20100.00,-3310.28,16256.36,18900.00,-2643.64 -16689.72,19950.00,-3260.28,16156.36,18800.00,-2643.64 -16589.72,19850.00,-3260.28,16056.36,18850.00,-2793.64 -16489.72,19750.00,-3260.28,15956.36,18850.00,-2893.64 -16389.72,19750.00,-3360.28,15856.36,18700.00,-2843.64 -16289.72,19600.00,-3310.28,15756.36,18800.00,-3043.64 -16189.72,19450.00,-3260.28,15656.36,18600.00,-2943.64 -16089.72,19150.00,-3060.28,15556.36,18200.00,-2643.64 -15989.72,19050.00,-3060.28,15456.36,18150.00,-2693.64 -15889.72,18950.00,-3060.28,15356.36,18050.00,-2693.64 -15789.72,18850.00,-3060.28,15256.36,17900.00,-2643.64 -15689.72,18850.00,-3160.28,15156.36,18050.00,-2893.64 -15589.72,18650.00,-3060.28,15056.36,17950.00,-2893.64 -15489.72,18650.00,-3160.28,14956.36,17900.00,-2943.64 -15389.72,18550.00,-3160.28,14856.36,17700.00,-2843.64 -15289.72,18300.00,-3010.28,14756.36,17700.00,-2943.64 -15189.72,18250.00,-3060.28,14656.36,17550.00,-2893.64 -15089.72,18150.00,-3060.28,14556.36,17200.00,-2643.64 -14989.72,18000.00,-3010.28,14456.36,17050.00,-2593.64 -14889.72,17950.00,-3060.28,14356.36,17200.00,-2843.64 -14789.72,17950.00,-3160.28,14256.36,16950.00,-2693.64 -14689.72,17900.00,-3210.28,14156.36,16650.00,-2493.64 -14589.72,17650.00,-3060.28,14056.36,16750.00,-2693.64 -14489.72,17400.00,-2910.28,13956.36,16550.00,-2593.64 -14389.72,17300.00,-2910.28,13856.36,16450.00,-2593.64 -14289.72,17100.00,-2810.28,13756.36,16300.00,-2543.64 -14189.72,17000.00,-2810.28,13656.36,16100.00,-2443.64 -14089.72,16950.00,-2860.28,13556.36,16050.00,-2493.64 -13989.72,17000.00,-3010.28,13456.36,15750.00,-2293.64 -13889.72,16800.00,-2910.28,13356.36,15850.00,-2493.64 -13789.72,16550.00,-2760.28,13256.36,15800.00,-2543.64 -13689.72,16350.00,-2660.28,13156.36,15700.00,-2543.64 -13589.72,16150.00,-2560.28,13056.36,15350.00,-2293.64 -13489.72,14250.00,-760.28,12956.36,13400.00,-443.64 -13389.72,19200.00,-5810.28,12856.36,17900.00,-5043.64 -13289.72,15650.00,-2360.28,12756.36,14650.00,-1893.64 -13189.72,13350.00,-160.28,12656.36,12150.00,506.36 -13089.72,13750.00,-660.28,12556.36,13200.00,-643.64 -12989.72,15100.00,-2110.28,12456.36,14500.00,-2043.64 -12889.72,15700.00,-2810.28,12356.36,15000.00,-2643.64 -12789.72,15800.00,-3010.28,12256.36,14750.00,-2493.64 -12689.72,15250.00,-2560.28,12156.36,14500.00,-2343.64 -12589.72,14900.00,-2310.28,12056.36,14100.00,-2043.64 -12489.72,14700.00,-2210.28,11956.36,13900.00,-1943.64 -12389.72,14600.00,-2210.28,11856.36,13700.00,-1843.64 -12289.72,14600.00,-2310.28,11756.36,13700.00,-1943.64 -12189.72,14500.00,-2310.28,11656.36,13500.00,-1843.64 -12089.72,14400.00,-2310.28,11556.36,13350.00,-1793.64 -11989.72,14250.00,-2260.28,11456.36,13300.00,-1843.64 -11889.72,14150.00,-2260.28,11356.36,13300.00,-1943.64 -11789.72,14150.00,-2360.28,11256.36,13150.00,-1893.64 -11689.72,13950.00,-2260.28,11156.36,13050.00,-1893.64 -11589.72,13700.00,-2110.28,11056.36,12950.00,-1893.64 -11489.72,13650.00,-2160.28,10956.36,12800.00,-1843.64 -11389.72,13700.00,-2310.28,10856.36,12750.00,-1893.64 -11289.72,13500.00,-2210.28,10756.36,12700.00,-1943.64 -11189.72,13400.00,-2210.28,10656.36,12550.00,-1893.64 -11089.72,13200.00,-2110.28,10556.36,12450.00,-1893.64 -10989.72,13150.00,-2160.28,10456.36,12300.00,-1843.64 -10889.72,13050.00,-2160.28,10356.36,12100.00,-1743.64 -10789.72,12900.00,-2110.28,10256.36,12000.00,-1743.64 -10689.72,12750.00,-2060.28,10156.36,11800.00,-1643.64 -10589.72,12650.00,-2060.28,10056.36,11650.00,-1593.64 -10489.72,12550.00,-2060.28,9956.36,11550.00,-1593.64 -10389.72,12400.00,-2010.28,9856.36,11450.00,-1593.64 -10289.72,12200.00,-1910.28,9756.36,11300.00,-1543.64 -10189.72,12150.00,-1960.28,9656.36,11150.00,-1493.64 -10089.72,12000.00,-1910.28,9556.36,11050.00,-1493.64 -9989.72,11850.00,-1860.28,9456.36,10900.00,-1443.64 -9889.72,11800.00,-1910.28,9356.36,10850.00,-1493.64 -9789.72,11700.00,-1910.28,9256.36,10750.00,-1493.64 -9689.72,11500.00,-1810.28,9156.36,10400.00,-1243.64 -9589.72,11300.00,-1710.28,9056.36,10300.00,-1243.64 -9489.72,11100.00,-1610.28,8956.36,10300.00,-1343.64 -9389.72,11000.00,-1610.28,8856.36,10150.00,-1293.64 -9289.72,10900.00,-1610.28,8756.36,10000.00,-1243.64 -9189.72,10750.00,-1560.28,8656.36,9900.00,-1243.64 -9089.72,10550.00,-1460.28,8556.36,9750.00,-1193.64 -8989.72,10450.00,-1460.28,8456.36,9700.00,-1243.64 -8889.72,10400.00,-1510.28,8356.36,9500.00,-1143.64 -8789.72,10250.00,-1460.28,8256.36,9250.00,-993.64 -8689.72,10050.00,-1360.28,8156.36,9000.00,-843.64 -8589.72,9950.00,-1360.28,8056.36,8850.00,-793.64 -8489.72,9900.00,-1410.28,7956.36,8700.00,-743.64 -8389.72,9800.00,-1410.28,7856.36,8600.00,-743.64 -8289.72,8900.00,-610.28,7756.36,8250.00,-493.64 -8189.72,8100.00,89.72,7656.36,8500.00,-843.64 -8089.72,8800.00,-710.28,7556.36,8450.00,-893.64 -7989.72,9250.00,-1260.28,7456.36,7900.00,-443.64 -7889.72,8900.00,-1010.28,7356.36,6900.00,456.36 -7789.72,7950.00,-160.28,7256.36,7200.00,56.36 -7689.72,7900.00,-210.28,7156.36,7450.00,-293.64 -7589.72,8650.00,-1060.28,7056.36,8050.00,-993.64 -7489.72,8500.00,-1010.28,6956.36,7700.00,-743.64 -7389.72,7050.00,339.72,6856.36,6500.00,356.36 -7289.72,6450.00,839.72,6756.36,5650.00,1106.36 -7189.72,7400.00,-210.28,6656.36,6650.00,6.36 -7089.72,8250.00,-1160.28,6556.36,7400.00,-843.64 -6989.72,7850.00,-860.28,6456.36,7150.00,-693.64 -6889.72,6600.00,289.72,6356.36,6050.00,306.36 -6789.72,6450.00,339.72,6256.36,5600.00,656.36 -6689.72,6750.00,-60.28,6156.36,5850.00,306.36 -6589.72,7350.00,-760.28,6056.36,6350.00,-293.64 -6489.72,7600.00,-1110.28,5956.36,6550.00,-593.64 -6389.72,6350.00,39.72,5856.36,5300.00,556.36 -6289.72,5800.00,489.72,5756.36,4500.00,1256.36 -6189.72,6300.00,-110.28,5656.36,5300.00,356.36 -6089.72,6550.00,-460.28,5556.36,5550.00,6.36 -5989.72,5300.00,689.72,5456.36,4400.00,1056.36 -5889.72,6250.00,-360.28,5356.36,4600.00,756.36 -5789.72,5600.00,189.72,5256.36,4750.00,506.36 -5689.72,4650.00,1039.72,5156.36,4550.00,606.36 -5589.72,4700.00,889.72,5056.36,3850.00,1206.36 -5489.72,5500.00,-10.28,4956.36,3350.00,1606.36 -5389.72,5750.00,-360.28,4856.36,4100.00,756.36 -5289.72,4950.00,339.72,4756.36,4500.00,256.36 -5189.72,4150.00,1039.72,4656.36,3700.00,956.36 -5089.72,4000.00,1089.72,4556.36,2800.00,1756.36 -4989.72,4750.00,239.72,4456.36,2600.00,1856.36 -4889.72,5250.00,-360.28,4356.36,3800.00,556.36 -4789.72,4750.00,39.72,4256.36,4650.00,-393.64 -4689.72,3750.00,939.72,4156.36,3650.00,506.36 -4589.72,3050.00,1539.72,4056.36,2750.00,1306.36 -4489.72,3000.00,1489.72,3956.36,2200.00,1756.36 -4389.72,4250.00,139.72,3856.36,1550.00,2306.36 -4289.72,4650.00,-360.28,3756.36,2900.00,856.36 -4189.72,4150.00,39.72,3656.36,3800.00,-143.64 -4089.72,3100.00,989.72,3556.36,3000.00,556.36 -3989.72,2600.00,1389.72,3456.36,2200.00,1256.36 -3889.72,2200.00,1689.72,3356.36,600.00,2756.36 -3789.72,1700.00,2089.72,3256.36,950.00,2306.36 -3689.72,3200.00,489.72,3156.36,2900.00,256.36 -3589.72,3750.00,-160.28,3056.36,3400.00,-343.64 -3489.72,3300.00,189.72,2956.36,2650.00,306.36 -3389.72,2500.00,889.72,2856.36,1800.00,1056.36 -3289.72,2150.00,1139.72,2756.36,1150.00,1606.36 -3189.72,700.00,2489.72,2656.36,-550.00,3206.36 -3089.72,1600.00,1489.72,2556.36,-200.00,2756.36 -2989.72,2400.00,589.72,2456.36,2150.00,306.36 -2889.72,2000.00,889.72,2356.36,2650.00,-293.64 -2789.72,800.00,1989.72,2256.36,2000.00,256.36 -2689.72,1000.00,1689.72,2156.36,900.00,1256.36 -2589.72,1000.00,1589.72,2056.36,-100.00,2156.36 -2489.72,-500.00,2989.72,1956.36,-450.00,2406.36 -2389.72,400.00,1989.72,1856.36,-1050.00,2906.36 -2289.72,750.00,1539.72,1756.36,500.00,1256.36 -2189.72,-100.00,2289.72,1656.36,1200.00,456.36 -2089.72,-700.00,2789.72,1556.36,-100.00,1656.36 -1989.72,-150.00,2139.72,1456.36,-700.00,2156.36 -1889.72,650.00,1239.72,1356.36,-900.00,2256.36 -1789.72,-700.00,2489.72,1256.36,100.00,1156.36 -1689.72,-300.00,1989.72,1156.36,200.00,956.36 -1589.72,0.00,1589.72,1056.36,0.00,1056.36 -1489.72,0.00,1489.72,956.36,0.00,956.36 -1389.72,0.00,1389.72,856.36,0.00,856.36 -1289.72,0.00,1289.72,756.36,0.00,756.36 -1189.72,0.00,1189.72,656.36,0.00,656.36 -1089.72,0.00,1089.72,556.36,0.00,556.36 -989.72,0.00,989.72,456.36,0.00,456.36 -889.72,0.00,889.72,356.36,0.00,356.36 -789.72,0.00,789.72,256.36,0.00,256.36 -689.72,0.00,689.72,156.36,0.00,156.36 -589.72,0.00,589.72,56.36,0.00,56.36 -489.72,0.00,489.72,0.00,0.00,0.00 -389.72,0.00,389.72,0.00,0.00,0.00 -289.72,0.00,289.72,0.00,0.00,0.00 -189.72,0.00,189.72,0.00,0.00,0.00 -89.72,0.00,89.72,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -100.00,0.00,100.00,100.00,0.00,100.00 -200.00,0.00,200.00,200.00,0.00,200.00 -300.00,0.00,300.00,300.00,0.00,300.00 -400.00,0.00,400.00,400.00,0.00,400.00 -500.00,0.00,500.00,500.00,0.00,500.00 -600.00,0.00,600.00,600.00,0.00,600.00 -700.00,0.00,700.00,700.00,0.00,700.00 -800.00,0.00,800.00,800.00,0.00,800.00 -900.00,0.00,900.00,900.00,0.00,900.00 -1000.00,0.00,1000.00,1000.00,0.00,1000.00 -1100.00,0.00,1100.00,1100.00,0.00,1100.00 -1200.00,0.00,1200.00,1200.00,0.00,1200.00 -1300.00,0.00,1300.00,1300.00,0.00,1300.00 -1400.00,0.00,1400.00,1400.00,0.00,1400.00 -1500.00,0.00,1500.00,1500.00,0.00,1500.00 -1600.00,0.00,1600.00,1600.00,0.00,1600.00 -1700.00,0.00,1700.00,1700.00,0.00,1700.00 -1800.00,0.00,1800.00,1800.00,0.00,1800.00 -1900.00,0.00,1900.00,1900.00,0.00,1900.00 -2000.00,0.00,2000.00,2000.00,0.00,2000.00 -2100.00,0.00,2100.00,2100.00,0.00,2100.00 -2200.00,0.00,2200.00,2200.00,0.00,2200.00 -2300.00,0.00,2300.00,2300.00,0.00,2300.00 -2400.00,0.00,2400.00,2400.00,0.00,2400.00 -2500.00,450.00,2050.00,2500.00,400.00,2100.00 -2600.00,200.00,2400.00,2600.00,450.00,2150.00 -2700.00,-200.00,2900.00,2700.00,-800.00,3500.00 -2800.00,1150.00,1650.00,2800.00,350.00,2450.00 -2900.00,2200.00,700.00,2900.00,2500.00,400.00 -3000.00,1050.00,1950.00,3000.00,2500.00,500.00 -3100.00,100.00,3000.00,3100.00,1650.00,1450.00 -3200.00,850.00,2350.00,3200.00,-50.00,3250.00 -3300.00,2850.00,450.00,3300.00,150.00,3150.00 -3400.00,3550.00,-150.00,3400.00,1900.00,1500.00 -3500.00,3000.00,500.00,3500.00,2900.00,600.00 -3600.00,2400.00,1200.00,3600.00,2000.00,1600.00 -3700.00,1000.00,2700.00,3700.00,550.00,3150.00 -3800.00,1800.00,2000.00,3800.00,1500.00,2300.00 -3900.00,3400.00,500.00,3900.00,3500.00,400.00 -4000.00,4000.00,0.00,4000.00,3800.00,200.00 -4100.00,3150.00,950.00,4100.00,2450.00,1650.00 -4200.00,2500.00,1700.00,4200.00,2150.00,2050.00 -4300.00,2350.00,1950.00,4300.00,2950.00,1350.00 -4400.00,3350.00,1050.00,4400.00,3600.00,800.00 -4500.00,4050.00,450.00,4500.00,3550.00,950.00 -4600.00,3350.00,1250.00,4600.00,2500.00,2100.00 -4700.00,3100.00,1600.00,4700.00,1800.00,2900.00 -4800.00,3700.00,1100.00,4800.00,3650.00,1150.00 -4900.00,4600.00,300.00,4900.00,5050.00,-150.00 -5000.00,4850.00,150.00,5000.00,4800.00,200.00 -5100.00,4050.00,1050.00,5100.00,3750.00,1350.00 -5200.00,3700.00,1500.00,5200.00,2900.00,2300.00 -5300.00,4450.00,850.00,5300.00,3750.00,1550.00 -5400.00,5500.00,-100.00,5400.00,5100.00,300.00 -5500.00,5550.00,-50.00,5500.00,5050.00,450.00 -5600.00,4550.00,1050.00,5600.00,3850.00,1750.00 -5700.00,4300.00,1400.00,5700.00,3250.00,2450.00 -5800.00,5150.00,650.00,5800.00,4700.00,1100.00 -5900.00,6200.00,-300.00,5900.00,6150.00,-250.00 -6000.00,6250.00,-250.00,6000.00,5900.00,100.00 -6100.00,5400.00,700.00,6100.00,4550.00,1550.00 -6200.00,4900.00,1300.00,6200.00,3850.00,2350.00 -6300.00,5900.00,400.00,6300.00,5400.00,900.00 -6400.00,6700.00,-300.00,6400.00,6500.00,-100.00 -6500.00,6650.00,-150.00,6500.00,6700.00,-200.00 -6600.00,6050.00,550.00,6600.00,6000.00,600.00 -6700.00,6200.00,500.00,6700.00,4850.00,1850.00 -6800.00,7150.00,-350.00,6800.00,5650.00,1150.00 -6900.00,7500.00,-600.00,6900.00,6700.00,200.00 -7000.00,7300.00,-300.00,7000.00,7000.00,0.00 -7100.00,6500.00,600.00,7100.00,6800.00,300.00 -7200.00,7150.00,50.00,7200.00,6700.00,500.00 -7300.00,7650.00,-350.00,7300.00,6750.00,550.00 -7400.00,8050.00,-650.00,7400.00,6950.00,450.00 -7500.00,8350.00,-850.00,7500.00,7250.00,250.00 -7600.00,7900.00,-300.00,7600.00,7400.00,200.00 -7700.00,7200.00,500.00,7700.00,7500.00,200.00 -7800.00,7800.00,0.00,7800.00,7650.00,150.00 -7900.00,8500.00,-600.00,7900.00,7700.00,200.00 -8000.00,8950.00,-950.00,8000.00,8050.00,-50.00 -8100.00,9150.00,-1050.00,8100.00,8350.00,-250.00 -8200.00,9150.00,-950.00,8200.00,8400.00,-200.00 -8300.00,9200.00,-900.00,8300.00,8400.00,-100.00 -8400.00,9250.00,-850.00,8400.00,8600.00,-200.00 -8500.00,9400.00,-900.00,8500.00,8700.00,-200.00 -8600.00,11350.00,-2750.00,8600.00,10500.00,-1900.00 -8700.00,9150.00,-450.00,8700.00,8500.00,200.00 -8800.00,8250.00,550.00,8800.00,7400.00,1400.00 -8900.00,9250.00,-350.00,8900.00,8200.00,700.00 -9000.00,9900.00,-900.00,9000.00,9300.00,-300.00 -9100.00,10700.00,-1600.00,9100.00,10200.00,-1100.00 -9200.00,10850.00,-1650.00,9200.00,10150.00,-950.00 -9300.00,10500.00,-1200.00,9300.00,9400.00,-100.00 -9400.00,10450.00,-1050.00,9400.00,9300.00,100.00 -9500.00,10650.00,-1150.00,9500.00,9500.00,0.00 -9600.00,10700.00,-1100.00,9600.00,9800.00,-200.00 -9700.00,10850.00,-1150.00,9700.00,10150.00,-450.00 -9800.00,10950.00,-1150.00,9800.00,10400.00,-600.00 -9900.00,11200.00,-1300.00,9900.00,10500.00,-600.00 -10000.00,11800.00,-1800.00,10000.00,11000.00,-1000.00 -10100.00,11850.00,-1750.00,10100.00,11100.00,-1000.00 -10200.00,11700.00,-1500.00,10200.00,11100.00,-900.00 -10300.00,11700.00,-1400.00,10300.00,11100.00,-800.00 -10400.00,11800.00,-1400.00,10400.00,11150.00,-750.00 -10500.00,11900.00,-1400.00,10500.00,11350.00,-850.00 -10600.00,11650.00,-1050.00,10600.00,11050.00,-450.00 -10700.00,12250.00,-1550.00,10700.00,11800.00,-1100.00 -10800.00,12400.00,-1600.00,10800.00,12100.00,-1300.00 -10900.00,12500.00,-1600.00,10900.00,12100.00,-1200.00 -11000.00,12600.00,-1600.00,11000.00,12100.00,-1100.00 -11100.00,12600.00,-1500.00,11100.00,12050.00,-950.00 -11200.00,12700.00,-1500.00,11200.00,12150.00,-950.00 -11300.00,12400.00,-1100.00,11300.00,11800.00,-500.00 -11400.00,13150.00,-1750.00,11400.00,12650.00,-1250.00 -11500.00,13450.00,-1950.00,11500.00,12850.00,-1350.00 -11600.00,12950.00,-1350.00,11600.00,12450.00,-850.00 -11700.00,13050.00,-1350.00,11700.00,12500.00,-800.00 -11800.00,13350.00,-1550.00,11800.00,12800.00,-1000.00 -11900.00,13450.00,-1550.00,11900.00,13150.00,-1250.00 -12000.00,13550.00,-1550.00,12000.00,13200.00,-1200.00 -12100.00,13700.00,-1600.00,12100.00,13200.00,-1100.00 -12200.00,13850.00,-1650.00,12200.00,13200.00,-1000.00 -12300.00,14500.00,-2200.00,12300.00,13850.00,-1550.00 -12400.00,14050.00,-1650.00,12400.00,13400.00,-1000.00 -12500.00,13950.00,-1450.00,12500.00,13400.00,-900.00 -12600.00,14800.00,-2200.00,12600.00,14200.00,-1600.00 -12700.00,14950.00,-2250.00,12700.00,14300.00,-1600.00 -12800.00,14350.00,-1550.00,12800.00,13500.00,-700.00 -12900.00,14550.00,-1650.00,12900.00,13600.00,-700.00 -13000.00,15400.00,-2400.00,13000.00,14400.00,-1400.00 -13100.00,15550.00,-2450.00,13100.00,14700.00,-1600.00 -13200.00,15450.00,-2250.00,13200.00,14600.00,-1400.00 -13300.00,14850.00,-1550.00,13300.00,14100.00,-800.00 -13400.00,15500.00,-2100.00,13400.00,14800.00,-1400.00 -13500.00,15950.00,-2450.00,13500.00,15250.00,-1750.00 -13600.00,15450.00,-1850.00,13600.00,14950.00,-1350.00 -13700.00,16150.00,-2450.00,13700.00,15550.00,-1850.00 -13800.00,16450.00,-2650.00,13800.00,15750.00,-1950.00 -13900.00,15600.00,-1700.00,13900.00,15100.00,-1200.00 -14000.00,15600.00,-1600.00,14000.00,15200.00,-1200.00 -14100.00,16100.00,-2000.00,14100.00,15250.00,-1150.00 -14200.00,16250.00,-2050.00,14200.00,15750.00,-1550.00 -14300.00,16450.00,-2150.00,14300.00,16150.00,-1850.00 -14400.00,17250.00,-2850.00,14400.00,16850.00,-2450.00 -14500.00,16600.00,-2100.00,14500.00,16200.00,-1700.00 -14600.00,17150.00,-2550.00,14600.00,16750.00,-2150.00 -14700.00,16600.00,-1900.00,14700.00,16250.00,-1550.00 -14800.00,17400.00,-2600.00,14800.00,16900.00,-2100.00 -14900.00,17550.00,-2650.00,14900.00,17150.00,-2250.00 -15000.00,16800.00,-1800.00,15000.00,16500.00,-1500.00 -15100.00,17500.00,-2400.00,15100.00,17000.00,-1900.00 -15200.00,17750.00,-2550.00,15200.00,17450.00,-2250.00 -15300.00,17200.00,-1900.00,15300.00,16800.00,-1500.00 -15400.00,17900.00,-2500.00,15400.00,17500.00,-2100.00 -15500.00,18200.00,-2700.00,15500.00,17850.00,-2350.00 -15600.00,18300.00,-2700.00,15600.00,17750.00,-2150.00 -15700.00,18200.00,-2500.00,15700.00,17850.00,-2150.00 -15800.00,18150.00,-2350.00,15800.00,17900.00,-2100.00 -15900.00,18350.00,-2450.00,15900.00,17950.00,-2050.00 -16000.00,18500.00,-2500.00,16000.00,18050.00,-2050.00 -16100.00,18600.00,-2500.00,16100.00,18150.00,-2050.00 -16200.00,22300.00,-6100.00,16200.00,21500.00,-5300.00 -16300.00,17550.00,-1250.00,16300.00,17900.00,-1600.00 -16400.00,15200.00,1200.00,16400.00,17100.00,-700.00 -16500.00,16900.00,-400.00,16500.00,17650.00,-1150.00 -16600.00,19900.00,-3300.00,16600.00,18500.00,-1900.00 -16700.00,21050.00,-4350.00,16700.00,19050.00,-2350.00 -16800.00,20650.00,-3850.00,16800.00,19150.00,-2350.00 -16900.00,19850.00,-2950.00,16900.00,19250.00,-2350.00 -17000.00,19200.00,-2200.00,17000.00,18350.00,-1350.00 -17100.00,20300.00,-3200.00,17100.00,19550.00,-2450.00 -17200.00,20450.00,-3250.00,17033.32,19800.00,-2766.68 -17300.00,19650.00,-2350.00,16933.32,19150.00,-2216.68 -17400.00,20800.00,-3400.00,16833.32,19700.00,-2866.68 -17500.00,21200.00,-3700.00,16733.32,19650.00,-2916.68 -17600.00,20800.00,-3200.00,16633.32,19300.00,-2666.68 -17513.92,20800.00,-3286.08,16533.32,18950.00,-2416.68 -17413.92,21000.00,-3586.08,16433.32,18850.00,-2416.68 -17313.92,20800.00,-3486.08,16333.32,18900.00,-2566.68 -17213.92,20500.00,-3286.08,16233.32,18750.00,-2516.68 -17113.92,20300.00,-3186.08,16133.32,18650.00,-2516.68 -17013.92,20200.00,-3186.08,16033.32,18400.00,-2366.68 -16913.92,20100.00,-3186.08,15933.32,18200.00,-2266.68 -16813.92,20100.00,-3286.08,15833.32,18300.00,-2466.68 -16713.92,20000.00,-3286.08,15733.32,18200.00,-2466.68 -16613.92,19800.00,-3186.08,15633.32,17900.00,-2266.68 -16513.92,19750.00,-3236.08,15533.32,17800.00,-2266.68 -16413.92,19500.00,-3086.08,15433.32,17800.00,-2366.68 -16313.92,19350.00,-3036.08,15333.32,17700.00,-2366.68 -16213.92,19200.00,-2986.08,15233.32,17550.00,-2316.68 -16113.92,19150.00,-3036.08,15133.32,17250.00,-2116.68 -16013.92,19050.00,-3036.08,15033.32,17000.00,-1966.68 -15913.92,18950.00,-3036.08,14933.32,17000.00,-2066.68 -15813.92,18850.00,-3036.08,14833.32,16800.00,-1966.68 -15713.92,18700.00,-2986.08,14733.32,16750.00,-2016.68 -15613.92,18550.00,-2936.08,14633.32,16550.00,-1916.68 -15513.92,18450.00,-2936.08,14533.32,16350.00,-1816.68 -15413.92,18350.00,-2936.08,14433.32,16150.00,-1716.68 -15313.92,18200.00,-2886.08,14333.32,16050.00,-1716.68 -15213.92,18100.00,-2886.08,14233.32,15850.00,-1616.68 -15113.92,18000.00,-2886.08,14133.32,15700.00,-1566.68 -15013.92,17950.00,-2936.08,14033.32,15850.00,-1816.68 -14913.92,17750.00,-2836.08,13933.32,15800.00,-1866.68 -14813.92,17650.00,-2836.08,13833.32,15600.00,-1766.68 -14713.92,17500.00,-2786.08,13733.32,15450.00,-1716.68 -14613.92,17350.00,-2736.08,13633.32,15350.00,-1716.68 -14513.92,17250.00,-2736.08,13533.32,15150.00,-1616.68 -14413.92,17000.00,-2586.08,13433.32,15000.00,-1566.68 -14313.92,16900.00,-2586.08,13333.32,14750.00,-1416.68 -14213.92,16850.00,-2636.08,13233.32,14650.00,-1416.68 -14113.92,16650.00,-2536.08,13133.32,14650.00,-1516.68 -14013.92,16600.00,-2586.08,13033.32,14700.00,-1666.68 -13913.92,16400.00,-2486.08,12933.32,14650.00,-1716.68 -13813.92,16350.00,-2536.08,12833.32,14550.00,-1716.68 -13713.92,16100.00,-2386.08,12733.32,14350.00,-1616.68 -13613.92,15350.00,-1736.08,12633.32,13750.00,-1116.68 -13513.92,15950.00,-2436.08,12533.32,14250.00,-1716.68 -13413.92,16050.00,-2636.08,12433.32,14300.00,-1866.68 -13313.92,15700.00,-2386.08,12333.32,13900.00,-1566.68 -13213.92,15400.00,-2186.08,12233.32,13750.00,-1516.68 -13113.92,15300.00,-2186.08,12133.32,13550.00,-1416.68 -13013.92,15100.00,-2086.08,12033.32,13400.00,-1366.68 -12913.92,15000.00,-2086.08,11933.32,13200.00,-1266.68 -12813.92,14950.00,-2136.08,11833.32,13000.00,-1166.68 -12713.92,14850.00,-2136.08,11733.32,12950.00,-1216.68 -12613.92,14650.00,-2036.08,11633.32,12850.00,-1216.68 -12513.92,14600.00,-2086.08,11533.32,12800.00,-1266.68 -12413.92,14400.00,-1986.08,11433.32,12600.00,-1166.68 -12313.92,13850.00,-1536.08,11333.32,12100.00,-766.68 -12213.92,14450.00,-2236.08,11233.32,12550.00,-1316.68 -12113.92,14500.00,-2386.08,11133.32,12550.00,-1416.68 -12013.92,13650.00,-1636.08,11033.32,11750.00,-716.68 -11913.92,13500.00,-1586.08,10933.32,11550.00,-616.68 -11813.92,13550.00,-1736.08,10833.32,11500.00,-666.68 -11713.92,14050.00,-2336.08,10733.32,11950.00,-1216.68 -11613.92,13350.00,-1736.08,10633.32,11350.00,-716.68 -11513.92,16150.00,-4636.08,10533.32,13650.00,-3116.68 -11413.92,12650.00,-1236.08,10433.32,10700.00,-266.68 -11313.92,11050.00,263.92,10333.32,9150.00,1183.32 -11213.92,11050.00,163.92,10233.32,9300.00,933.32 -11113.92,12300.00,-1186.08,10133.32,10500.00,-366.68 -11013.92,13200.00,-2186.08,10033.32,11300.00,-1266.68 -10913.92,14000.00,-3086.08,9933.32,11850.00,-1916.68 -10813.92,12750.00,-1936.08,9833.32,11400.00,-1566.68 -10713.92,11000.00,-286.08,9733.32,10650.00,-916.68 -10613.92,11300.00,-686.08,9633.32,10400.00,-766.68 -10513.92,11750.00,-1236.08,9533.32,9900.00,-366.68 -10413.92,12700.00,-2286.08,9433.32,10500.00,-1066.68 -10313.92,12450.00,-2136.08,9333.32,10200.00,-866.68 -10213.92,12100.00,-1886.08,9233.32,10050.00,-816.68 -10113.92,12400.00,-2286.08,9133.32,10400.00,-1266.68 -10013.92,12200.00,-2186.08,9033.32,10250.00,-1216.68 -9913.92,11750.00,-1836.08,8933.32,9900.00,-966.68 -9813.92,11150.00,-1336.08,8833.32,9300.00,-466.68 -9713.92,11600.00,-1886.08,8733.32,9500.00,-766.68 -9613.92,11450.00,-1836.08,8633.32,9450.00,-816.68 -9513.92,11200.00,-1686.08,8533.32,9300.00,-766.68 -9413.92,10700.00,-1286.08,8433.32,8800.00,-366.68 -9313.92,10650.00,-1336.08,8333.32,8550.00,-216.68 -9213.92,10600.00,-1386.08,8233.32,8550.00,-316.68 -9113.92,10900.00,-1786.08,8133.32,8850.00,-716.68 -9013.92,9900.00,-886.08,8033.32,8450.00,-416.68 -8913.92,8650.00,263.92,7933.32,8200.00,-266.68 -8813.92,9350.00,-536.08,7833.32,8250.00,-416.68 -8713.92,9950.00,-1236.08,7733.32,8200.00,-466.68 -8613.92,10550.00,-1936.08,7633.32,8400.00,-766.68 -8513.92,9700.00,-1186.08,7533.32,8000.00,-466.68 -8413.92,8350.00,63.92,7433.32,7800.00,-366.68 -8313.92,8850.00,-536.08,7333.32,7700.00,-366.68 -8213.92,9200.00,-986.08,7233.32,7600.00,-366.68 -8113.92,9400.00,-1286.08,7133.32,7500.00,-366.68 -8013.92,8900.00,-886.08,7033.32,7500.00,-466.68 -7913.92,7850.00,63.92,6933.32,7000.00,-66.68 -7813.92,8650.00,-836.08,6833.32,6450.00,383.32 -7713.92,8700.00,-986.08,6733.32,6400.00,333.32 -7613.92,8300.00,-686.08,6633.32,6750.00,-116.68 -7513.92,7400.00,113.92,6533.32,6950.00,-416.68 -7413.92,7800.00,-386.08,6433.32,6750.00,-316.68 -7313.92,8200.00,-886.08,6333.32,5550.00,783.32 -7213.92,8350.00,-1136.08,6233.32,5100.00,1133.32 -7113.92,6700.00,413.92,6133.32,5650.00,483.32 -7013.92,6450.00,563.92,6033.32,6200.00,-166.68 -6913.92,7150.00,-236.08,5933.32,6200.00,-266.68 -6813.92,7900.00,-1086.08,5833.32,5100.00,733.32 -6713.92,7650.00,-936.08,5733.32,4300.00,1433.32 -6613.92,6500.00,113.92,5633.32,5000.00,633.32 -6513.92,6100.00,413.92,5533.32,5550.00,-16.68 -6413.92,6650.00,-236.08,5433.32,5550.00,-116.68 -6313.92,6700.00,-386.08,5333.32,4350.00,983.32 -6213.92,5750.00,463.92,5233.32,3850.00,1383.32 -6113.92,5500.00,613.92,5133.32,4200.00,933.32 -6013.92,6100.00,-86.08,5033.32,4700.00,333.32 -5913.92,6300.00,-386.08,4933.32,4650.00,283.32 -5813.92,5450.00,363.92,4833.32,3450.00,1383.32 -5713.92,5200.00,513.92,4733.32,3000.00,1733.32 -5613.92,5700.00,-86.08,4633.32,3800.00,833.32 -5513.92,5800.00,-286.08,4533.32,4150.00,383.32 -5413.92,4950.00,463.92,4433.32,3050.00,1383.32 -5313.92,4350.00,963.92,4333.32,2400.00,1933.32 -5213.92,4100.00,1113.92,4233.32,3300.00,933.32 -5113.92,5150.00,-36.08,4133.32,3800.00,333.32 -5013.92,5350.00,-336.08,4033.32,2650.00,1383.32 -4913.92,4650.00,263.92,3933.32,2050.00,1883.32 -4813.92,4000.00,813.92,3833.32,2800.00,1033.32 -4713.92,3300.00,1413.92,3733.32,3150.00,583.32 -4613.92,3100.00,1513.92,3633.32,2000.00,1633.32 -4513.92,4250.00,263.92,3533.32,1650.00,1883.32 -4413.92,4800.00,-386.08,3433.32,2350.00,1083.32 -4313.92,4050.00,263.92,3333.32,2450.00,883.32 -4213.92,3400.00,813.92,3233.32,1500.00,1733.32 -4113.92,2950.00,1163.92,3133.32,-250.00,3383.32 -4013.92,2000.00,2013.92,3033.32,-100.00,3133.32 -3913.92,2450.00,1463.92,2933.32,2200.00,733.32 -3813.92,3600.00,213.92,2833.32,3750.00,-916.68 -3713.92,2550.00,1163.92,2733.32,1950.00,783.32 -3613.92,1550.00,2063.92,2633.32,1200.00,1433.32 -3513.92,2300.00,1213.92,2533.32,750.00,1783.32 -3413.92,2800.00,613.92,2433.32,-350.00,2783.32 -3313.92,2000.00,1313.92,2333.32,300.00,2033.32 -3213.92,1800.00,1413.92,2233.32,450.00,1783.32 -3113.92,600.00,2513.92,2133.32,-800.00,2933.32 -3013.92,1450.00,1563.92,2033.32,300.00,1733.32 -2913.92,2300.00,613.92,1933.32,900.00,1033.32 -2813.92,2050.00,763.92,1833.32,-600.00,2433.32 -2713.92,1000.00,1713.92,1733.32,-1000.00,2733.32 -2613.92,1350.00,1263.92,1633.32,300.00,1333.32 -2513.92,500.00,2013.92,1533.32,250.00,1283.32 -2413.92,-800.00,3213.92,1433.32,-50.00,1483.32 -2313.92,800.00,1513.92,1333.32,0.00,1333.32 -2213.92,1700.00,513.92,1233.32,0.00,1233.32 -2113.92,1650.00,463.92,1133.32,0.00,1133.32 -2013.92,300.00,1713.92,1033.32,0.00,1033.32 -1913.92,-750.00,2663.92,933.32,0.00,933.32 -1813.92,-600.00,2413.92,833.32,0.00,833.32 -1713.92,300.00,1413.92,733.32,0.00,733.32 -1613.92,50.00,1563.92,633.32,0.00,633.32 -1513.92,0.00,1513.92,533.32,0.00,533.32 -1413.92,0.00,1413.92,433.32,0.00,433.32 -1313.92,0.00,1313.92,333.32,0.00,333.32 -1213.92,0.00,1213.92,233.32,0.00,233.32 -1113.92,0.00,1113.92,133.32,0.00,133.32 -1013.92,0.00,1013.92,33.32,0.00,33.32 -913.92,0.00,913.92,0.00,0.00,0.00 -813.92,0.00,813.92,0.00,0.00,0.00 -713.92,0.00,713.92,0.00,0.00,0.00 -613.92,0.00,613.92,0.00,0.00,0.00 -513.92,0.00,513.92,0.00,0.00,0.00 -413.92,0.00,413.92,0.00,0.00,0.00 -313.92,0.00,313.92,0.00,0.00,0.00 -213.92,0.00,213.92,0.00,0.00,0.00 -113.92,0.00,113.92,0.00,0.00,0.00 -13.92,0.00,13.92,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 --100.00,0.00,-100.00,-100.00,0.00,-100.00 --200.00,0.00,-200.00,-200.00,0.00,-200.00 --300.00,0.00,-300.00,-300.00,0.00,-300.00 --400.00,0.00,-400.00,-400.00,0.00,-400.00 --500.00,0.00,-500.00,-500.00,0.00,-500.00 --600.00,0.00,-600.00,-600.00,0.00,-600.00 --700.00,0.00,-700.00,-700.00,0.00,-700.00 --800.00,0.00,-800.00,-800.00,0.00,-800.00 --900.00,0.00,-900.00,-900.00,0.00,-900.00 --1000.00,0.00,-1000.00,-1000.00,0.00,-1000.00 --1100.00,0.00,-1100.00,-1100.00,0.00,-1100.00 --1200.00,0.00,-1200.00,-1200.00,0.00,-1200.00 --1300.00,0.00,-1300.00,-1300.00,0.00,-1300.00 --1400.00,0.00,-1400.00,-1400.00,0.00,-1400.00 --1500.00,0.00,-1500.00,-1500.00,0.00,-1500.00 --1600.00,0.00,-1600.00,-1600.00,0.00,-1600.00 --1700.00,0.00,-1700.00,-1700.00,0.00,-1700.00 --1800.00,0.00,-1800.00,-1800.00,0.00,-1800.00 --1900.00,0.00,-1900.00,-1900.00,0.00,-1900.00 --2000.00,0.00,-2000.00,-2000.00,0.00,-2000.00 --2100.00,0.00,-2100.00,-2100.00,0.00,-2100.00 --2200.00,0.00,-2200.00,-2200.00,0.00,-2200.00 --2300.00,0.00,-2300.00,-2300.00,0.00,-2300.00 --2400.00,0.00,-2400.00,-2400.00,0.00,-2400.00 --2500.00,-450.00,-2050.00,-2500.00,-500.00,-2000.00 --2600.00,-350.00,-2250.00,-2600.00,-600.00,-2000.00 --2700.00,300.00,-3000.00,-2700.00,800.00,-3500.00 --2800.00,-950.00,-1850.00,-2800.00,-200.00,-2600.00 --2900.00,-2000.00,-900.00,-2900.00,-2400.00,-500.00 --3000.00,-850.00,-2150.00,-3000.00,-2800.00,-200.00 --3100.00,-150.00,-2950.00,-3100.00,-1800.00,-1300.00 --3200.00,-1850.00,-1350.00,-3200.00,150.00,-3350.00 --3300.00,-3000.00,-300.00,-3300.00,50.00,-3350.00 --3400.00,-2400.00,-1000.00,-3400.00,-2650.00,-750.00 --3500.00,-1650.00,-1850.00,-3500.00,-3800.00,300.00 --3600.00,-1450.00,-2150.00,-3600.00,-2400.00,-1200.00 --3700.00,-2550.00,-1150.00,-3700.00,-1450.00,-2250.00 --3800.00,-2900.00,-900.00,-3800.00,-200.00,-3600.00 --3900.00,-2450.00,-1450.00,-3900.00,-1900.00,-2000.00 --4000.00,-2300.00,-1700.00,-4000.00,-4000.00,0.00 --4100.00,-2850.00,-1250.00,-4100.00,-4000.00,-100.00 --4200.00,-3750.00,-450.00,-4200.00,-2800.00,-1400.00 --4300.00,-4000.00,-300.00,-4300.00,-1800.00,-2500.00 --4400.00,-3300.00,-1100.00,-4400.00,-2900.00,-1500.00 --4500.00,-3000.00,-1500.00,-4500.00,-4150.00,-350.00 --4600.00,-3650.00,-950.00,-4600.00,-4000.00,-600.00 --4700.00,-4550.00,-150.00,-4700.00,-2550.00,-2150.00 --4800.00,-4700.00,-100.00,-4800.00,-2400.00,-2400.00 --4900.00,-3700.00,-1200.00,-4900.00,-3750.00,-1150.00 --5000.00,-3450.00,-1550.00,-5000.00,-4700.00,-300.00 --5100.00,-4300.00,-800.00,-5100.00,-4550.00,-550.00 --5200.00,-5400.00,200.00,-5200.00,-3450.00,-1750.00 --5300.00,-5600.00,300.00,-5300.00,-2850.00,-2450.00 --5400.00,-4600.00,-800.00,-5400.00,-4300.00,-1100.00 --5500.00,-4250.00,-1250.00,-5500.00,-5650.00,150.00 --5600.00,-4900.00,-700.00,-5600.00,-5250.00,-350.00 --5700.00,-5700.00,0.00,-5700.00,-4300.00,-1400.00 --5800.00,-5800.00,0.00,-5800.00,-3600.00,-2200.00 --5900.00,-4700.00,-1200.00,-5900.00,-4400.00,-1500.00 --6000.00,-4650.00,-1350.00,-6000.00,-6200.00,200.00 --6100.00,-5650.00,-450.00,-6100.00,-6400.00,300.00 --6200.00,-6400.00,200.00,-6200.00,-4750.00,-1450.00 --6300.00,-6700.00,400.00,-6300.00,-4450.00,-1850.00 --6400.00,-5650.00,-750.00,-6400.00,-5650.00,-750.00 --6500.00,-5350.00,-1150.00,-6500.00,-6850.00,350.00 --6600.00,-6300.00,-300.00,-6600.00,-6700.00,100.00 --6700.00,-6950.00,250.00,-6700.00,-5500.00,-1200.00 --6800.00,-7300.00,500.00,-6800.00,-5700.00,-1100.00 --6900.00,-7350.00,450.00,-6900.00,-6600.00,-300.00 --7000.00,-6200.00,-800.00,-7000.00,-7100.00,100.00 --7100.00,-6000.00,-1100.00,-7100.00,-7250.00,150.00 --7200.00,-7000.00,-200.00,-7200.00,-7150.00,-50.00 --7300.00,-7700.00,400.00,-7300.00,-6800.00,-500.00 --7400.00,-8550.00,1150.00,-7400.00,-7250.00,-150.00 --7500.00,-8300.00,800.00,-7500.00,-7450.00,-50.00 --7600.00,-7150.00,-450.00,-7600.00,-7250.00,-350.00 --7700.00,-7850.00,150.00,-7700.00,-7600.00,-100.00 --7800.00,-8450.00,650.00,-7800.00,-7750.00,-50.00 --7900.00,-8900.00,1000.00,-7900.00,-8000.00,100.00 --8000.00,-9100.00,1100.00,-8000.00,-7900.00,-100.00 --8100.00,-9100.00,1000.00,-8100.00,-7900.00,-200.00 --8200.00,-9050.00,850.00,-8200.00,-8050.00,-150.00 --8300.00,-9200.00,900.00,-8300.00,-8250.00,-50.00 --8400.00,-9400.00,1000.00,-8400.00,-8500.00,100.00 --8500.00,-9500.00,1000.00,-8500.00,-8600.00,100.00 --8600.00,-9550.00,950.00,-8600.00,-8650.00,50.00 --8700.00,-11200.00,2500.00,-8700.00,-10050.00,1350.00 --8800.00,-9000.00,200.00,-8800.00,-8350.00,-450.00 --8900.00,-8400.00,-500.00,-8900.00,-8550.00,-350.00 --9000.00,-9450.00,450.00,-9000.00,-9100.00,100.00 --9100.00,-10300.00,1200.00,-9100.00,-9600.00,500.00 --9200.00,-10550.00,1350.00,-9200.00,-9700.00,500.00 --9300.00,-10750.00,1450.00,-9300.00,-9800.00,500.00 --9400.00,-10800.00,1400.00,-9400.00,-9800.00,400.00 --9500.00,-10300.00,800.00,-9500.00,-9500.00,0.00 --9600.00,-10800.00,1200.00,-9600.00,-10100.00,500.00 --9700.00,-11150.00,1450.00,-9700.00,-10500.00,800.00 --9800.00,-11250.00,1450.00,-9800.00,-10550.00,750.00 --9900.00,-11250.00,1350.00,-9900.00,-10600.00,700.00 --10000.00,-11250.00,1250.00,-10000.00,-10550.00,550.00 --10100.00,-11300.00,1200.00,-10100.00,-10700.00,600.00 --10200.00,-11500.00,1300.00,-10200.00,-10750.00,550.00 --10300.00,-11700.00,1400.00,-10300.00,-10900.00,600.00 --10400.00,-11800.00,1400.00,-10400.00,-11100.00,700.00 --10500.00,-11850.00,1350.00,-10500.00,-11300.00,800.00 --10600.00,-11900.00,1300.00,-10600.00,-11450.00,850.00 --10700.00,-12150.00,1450.00,-10700.00,-11600.00,900.00 --10800.00,-12300.00,1500.00,-10800.00,-11700.00,900.00 --10900.00,-12350.00,1450.00,-10900.00,-11900.00,1000.00 --11000.00,-12450.00,1450.00,-11000.00,-12000.00,1000.00 --11100.00,-12550.00,1450.00,-11100.00,-12100.00,1000.00 --11200.00,-12750.00,1550.00,-11200.00,-12200.00,1000.00 --11300.00,-12850.00,1550.00,-11300.00,-12400.00,1100.00 --11400.00,-13000.00,1600.00,-11400.00,-12500.00,1100.00 --11500.00,-13200.00,1700.00,-11500.00,-12800.00,1300.00 --11600.00,-13250.00,1650.00,-11600.00,-12900.00,1300.00 --11700.00,-13250.00,1550.00,-11700.00,-12900.00,1200.00 --11800.00,-13550.00,1750.00,-11800.00,-13050.00,1250.00 --11900.00,-13700.00,1800.00,-11900.00,-13050.00,1150.00 --12000.00,-13750.00,1750.00,-12000.00,-13000.00,1000.00 --12100.00,-13850.00,1750.00,-12100.00,-13150.00,1050.00 --12200.00,-14150.00,1950.00,-12200.00,-13350.00,1150.00 --12300.00,-14200.00,1900.00,-12300.00,-13500.00,1200.00 --12400.00,-14200.00,1800.00,-12400.00,-13650.00,1250.00 --12500.00,-14400.00,1900.00,-12500.00,-13800.00,1300.00 --12600.00,-14600.00,2000.00,-12600.00,-13800.00,1200.00 --12700.00,-14700.00,2000.00,-12700.00,-14000.00,1300.00 --12800.00,-14800.00,2000.00,-12800.00,-14100.00,1300.00 --12900.00,-14950.00,2050.00,-12900.00,-14150.00,1250.00 --13000.00,-15000.00,2000.00,-13000.00,-14200.00,1200.00 --13100.00,-15100.00,2000.00,-13100.00,-14300.00,1200.00 --13200.00,-15250.00,2050.00,-13200.00,-14450.00,1250.00 --13300.00,-15500.00,2200.00,-13300.00,-14550.00,1250.00 --13400.00,-15500.00,2100.00,-13400.00,-14650.00,1250.00 --13500.00,-15600.00,2100.00,-13500.00,-14750.00,1250.00 --13600.00,-15800.00,2200.00,-13600.00,-14900.00,1300.00 --13700.00,-15850.00,2150.00,-13700.00,-15050.00,1350.00 --13800.00,-15900.00,2100.00,-13800.00,-15250.00,1450.00 --13900.00,-16100.00,2200.00,-13900.00,-15350.00,1450.00 --14000.00,-16300.00,2300.00,-14000.00,-15550.00,1550.00 --14100.00,-16500.00,2400.00,-14100.00,-15700.00,1600.00 --14200.00,-16600.00,2400.00,-14200.00,-15750.00,1550.00 --14300.00,-16600.00,2300.00,-14300.00,-15850.00,1550.00 --14400.00,-16500.00,2100.00,-14400.00,-15950.00,1550.00 --14500.00,-16750.00,2250.00,-14500.00,-16150.00,1650.00 --14600.00,-16850.00,2250.00,-14600.00,-16200.00,1600.00 --14700.00,-17050.00,2350.00,-14700.00,-16300.00,1600.00 --14800.00,-17100.00,2300.00,-14800.00,-16650.00,1850.00 --14900.00,-17250.00,2350.00,-14900.00,-16750.00,1850.00 --15000.00,-17300.00,2300.00,-15000.00,-16900.00,1900.00 --15100.00,-17450.00,2350.00,-15100.00,-17050.00,1950.00 --15200.00,-17550.00,2350.00,-15200.00,-17100.00,1900.00 --15300.00,-17700.00,2400.00,-15300.00,-17150.00,1850.00 --15400.00,-17750.00,2350.00,-15400.00,-17400.00,2000.00 --15500.00,-17950.00,2450.00,-15500.00,-17600.00,2100.00 --15600.00,-18050.00,2450.00,-15600.00,-17700.00,2100.00 --15700.00,-18300.00,2600.00,-15700.00,-17800.00,2100.00 --15800.00,-18300.00,2500.00,-15800.00,-17600.00,1800.00 --15900.00,-18600.00,2700.00,-15900.00,-17800.00,1900.00 --16000.00,-18700.00,2700.00,-16000.00,-18000.00,2000.00 --16100.00,-22150.00,6050.00,-16100.00,-21600.00,5500.00 --16200.00,-17500.00,1300.00,-16200.00,-17900.00,1700.00 --16300.00,-15200.00,-1100.00,-16300.00,-16900.00,600.00 --16400.00,-16800.00,400.00,-16400.00,-17500.00,1100.00 --16500.00,-20550.00,4050.00,-16500.00,-19100.00,2600.00 --16600.00,-20900.00,4300.00,-16600.00,-18800.00,2200.00 --16700.00,-20300.00,3600.00,-16700.00,-18600.00,1900.00 --16800.00,-19950.00,3150.00,-16800.00,-18600.00,1800.00 --16900.00,-19650.00,2750.00,-16900.00,-18850.00,1950.00 --17000.00,-19800.00,2800.00,-17000.00,-19050.00,2050.00 --17100.00,-20050.00,2950.00,-17100.00,-19200.00,2100.00 --17200.00,-20550.00,3350.00,-17200.00,-19300.00,2100.00 --17300.00,-20600.00,3300.00,-17300.00,-19600.00,2300.00 --17400.00,-20600.00,3200.00,-17400.00,-19700.00,2300.00 --17500.00,-20500.00,3000.00,-17500.00,-19900.00,2400.00 --17600.00,-20800.00,3200.00,-17549.96,-19900.00,2350.04 --17700.00,-20900.00,3200.00,-17449.96,-20000.00,2550.04 --17800.00,-20950.00,3150.00,-17349.96,-19950.00,2600.04 --17900.00,-19500.00,1600.00,-17249.96,-18350.00,1100.04 --18000.00,-21500.00,3500.00,-17149.96,-19800.00,2650.04 --18063.52,-22050.00,3986.48,-17049.96,-20300.00,3250.04 --17963.52,-21800.00,3836.48,-16949.96,-19950.00,3000.04 --17863.52,-22050.00,4186.48,-16849.96,-20250.00,3400.04 --17763.52,-21850.00,4086.48,-16749.96,-19700.00,2950.04 --17663.52,-20600.00,2936.48,-16649.96,-18450.00,1800.04 --17563.52,-20400.00,2836.48,-16549.96,-18450.00,1900.04 --17463.52,-20700.00,3236.48,-16449.96,-18800.00,2350.04 --17363.52,-20700.00,3336.48,-16349.96,-18850.00,2500.04 --17263.52,-21550.00,4286.48,-16249.96,-19350.00,3100.04 --17163.52,-20600.00,3436.48,-16149.96,-18350.00,2200.04 --17063.52,-20000.00,2936.48,-16049.96,-17950.00,1900.04 --16963.52,-20000.00,3036.48,-15949.96,-17800.00,1850.04 --16863.52,-20000.00,3136.48,-15849.96,-18000.00,2150.04 --16763.52,-20000.00,3236.48,-15749.96,-18100.00,2350.04 --16663.52,-20050.00,3386.48,-15649.96,-17950.00,2300.04 --16563.52,-19850.00,3286.48,-15549.96,-17750.00,2200.04 --16463.52,-19700.00,3236.48,-15449.96,-17400.00,1950.04 --16363.52,-19500.00,3136.48,-15349.96,-17250.00,1900.04 --16263.52,-19300.00,3036.48,-15249.96,-17150.00,1900.04 --16163.52,-19300.00,3136.48,-15149.96,-16900.00,1750.04 --16063.52,-19100.00,3036.48,-15049.96,-16700.00,1650.04 --15963.52,-19000.00,3036.48,-14949.96,-16600.00,1650.04 --15863.52,-18950.00,3086.48,-14849.96,-16500.00,1650.04 --15763.52,-18750.00,2986.48,-14749.96,-16300.00,1550.04 --15663.52,-18550.00,2886.48,-14649.96,-16300.00,1650.04 --15563.52,-18350.00,2786.48,-14549.96,-16300.00,1750.04 --15463.52,-18300.00,2836.48,-14449.96,-16300.00,1850.04 --15363.52,-18150.00,2786.48,-14349.96,-16250.00,1900.04 --15263.52,-18000.00,2736.48,-14249.96,-16150.00,1900.04 --15163.52,-18000.00,2836.48,-14149.96,-16000.00,1850.04 --15063.52,-17800.00,2736.48,-14049.96,-15850.00,1800.04 --14963.52,-17650.00,2686.48,-13949.96,-15500.00,1550.04 --14863.52,-17600.00,2736.48,-13849.96,-15300.00,1450.04 --14763.52,-17350.00,2586.48,-13749.96,-15150.00,1400.04 --14663.52,-17300.00,2636.48,-13649.96,-15300.00,1650.04 --14563.52,-17250.00,2686.48,-13549.96,-15250.00,1700.04 --14463.52,-17000.00,2536.48,-13449.96,-15050.00,1600.04 --14363.52,-16850.00,2486.48,-13349.96,-15000.00,1650.04 --14263.52,-16850.00,2586.48,-13249.96,-15000.00,1750.04 --14163.52,-16700.00,2536.48,-13149.96,-14900.00,1750.04 --14063.52,-16650.00,2586.48,-13049.96,-14750.00,1700.04 --13963.52,-16500.00,2536.48,-12949.96,-14550.00,1600.04 --13863.52,-16200.00,2336.48,-12849.96,-14400.00,1550.04 --13763.52,-16100.00,2336.48,-12749.96,-14200.00,1450.04 --13663.52,-16050.00,2386.48,-12649.96,-14050.00,1400.04 --13563.52,-15950.00,2386.48,-12549.96,-13900.00,1350.04 --13463.52,-15850.00,2386.48,-12449.96,-13750.00,1300.04 --13363.52,-15750.00,2386.48,-12349.96,-13650.00,1300.04 --13263.52,-15700.00,2436.48,-12249.96,-13550.00,1300.04 --13163.52,-15450.00,2286.48,-12149.96,-13500.00,1350.04 --13063.52,-15300.00,2236.48,-12049.96,-13350.00,1300.04 --12963.52,-15250.00,2286.48,-11949.96,-13200.00,1250.04 --12863.52,-15150.00,2286.48,-11849.96,-13050.00,1200.04 --12763.52,-14950.00,2186.48,-11749.96,-12900.00,1150.04 --12663.52,-17450.00,4786.48,-11649.96,-14950.00,3300.04 --12563.52,-13700.00,1136.48,-11549.96,-11750.00,200.04 --12463.52,-10900.00,-1563.52,-11449.96,-9150.00,-2299.96 --12363.52,-13300.00,936.48,-11349.96,-11350.00,0.04 --12263.52,-15300.00,3036.48,-11249.96,-13300.00,2050.04 --12163.52,-15650.00,3486.48,-11149.96,-13550.00,2400.04 --12063.52,-15000.00,2936.48,-11049.96,-12950.00,1900.04 --11963.52,-14400.00,2436.48,-10949.96,-12050.00,1100.04 --11863.52,-14100.00,2236.48,-10849.96,-11750.00,900.04 --11763.52,-13850.00,2086.48,-10749.96,-11500.00,750.04 --11663.52,-13650.00,1986.48,-10649.96,-11500.00,850.04 --11563.52,-13700.00,2136.48,-10549.96,-11600.00,1050.04 --11463.52,-13600.00,2136.48,-10449.96,-11400.00,950.04 --11363.52,-13600.00,2236.48,-10349.96,-11300.00,950.04 --11263.52,-13450.00,2186.48,-10249.96,-11300.00,1050.04 --11163.52,-13150.00,1986.48,-10149.96,-11250.00,1100.04 --11063.52,-13050.00,1986.48,-10049.96,-11250.00,1200.04 --10963.52,-12900.00,1936.48,-9949.96,-11100.00,1150.04 --10863.52,-12800.00,1936.48,-9849.96,-11050.00,1200.04 --10763.52,-12250.00,1486.48,-9749.96,-10600.00,850.04 --10663.52,-12650.00,1986.48,-9649.96,-10950.00,1300.04 --10563.52,-12650.00,2086.48,-9549.96,-10800.00,1250.04 --10463.52,-12500.00,2036.48,-9449.96,-10750.00,1300.04 --10363.52,-12200.00,1836.48,-9349.96,-10450.00,1100.04 --10263.52,-12050.00,1786.48,-9249.96,-10200.00,950.04 --10163.52,-11900.00,1736.48,-9149.96,-9900.00,750.04 --10063.52,-11750.00,1686.48,-9049.96,-9800.00,750.04 --9963.52,-11650.00,1686.48,-8949.96,-9650.00,700.04 --9863.52,-11250.00,1386.48,-8849.96,-9300.00,450.04 --9763.52,-11600.00,1836.48,-8749.96,-9600.00,850.04 --9663.52,-11550.00,1886.48,-8649.96,-9600.00,950.04 --9563.52,-10950.00,1386.48,-8549.96,-8950.00,400.04 --9463.52,-11200.00,1736.48,-8449.96,-9300.00,850.04 --9363.52,-11100.00,1736.48,-8349.96,-9250.00,900.04 --9263.52,-10950.00,1686.48,-8249.96,-9150.00,900.04 --9163.52,-10700.00,1536.48,-8149.96,-8900.00,750.04 --9063.52,-10550.00,1486.48,-8049.96,-8700.00,650.04 --8963.52,-10400.00,1436.48,-7949.96,-8700.00,750.04 --8863.52,-10350.00,1486.48,-7849.96,-8500.00,650.04 --8763.52,-10350.00,1586.48,-7749.96,-8500.00,750.04 --8663.52,-9650.00,986.48,-7649.96,-8400.00,750.04 --8563.52,-8600.00,36.48,-7549.96,-8250.00,700.04 --8463.52,-9050.00,586.48,-7449.96,-8050.00,600.04 --8363.52,-9600.00,1236.48,-7349.96,-7950.00,600.04 --8263.52,-9350.00,1086.48,-7249.96,-7750.00,500.04 --8163.52,-8200.00,36.48,-7149.96,-7600.00,450.04 --8063.52,-8650.00,586.48,-7049.96,-7500.00,450.04 --7963.52,-9100.00,1136.48,-6949.96,-7000.00,50.04 --7863.52,-8800.00,936.48,-6849.96,-5950.00,-899.96 --7763.52,-7500.00,-263.52,-6749.96,-6250.00,-499.96 --7663.52,-7000.00,-663.52,-6649.96,-6800.00,150.04 --7563.52,-7800.00,236.48,-6549.96,-6900.00,350.04 --7463.52,-8650.00,1186.48,-6449.96,-6500.00,50.04 --7363.52,-8650.00,1286.48,-6349.96,-5500.00,-849.96 --7263.52,-7450.00,186.48,-6249.96,-5650.00,-599.96 --7163.52,-6750.00,-413.52,-6149.96,-6150.00,0.04 --7063.52,-7350.00,286.48,-6049.96,-6000.00,-49.96 --6963.52,-8000.00,1036.48,-5949.96,-4850.00,-1099.96 --6863.52,-7800.00,936.48,-5849.96,-4150.00,-1699.96 --6763.52,-6600.00,-163.52,-5749.96,-5050.00,-699.96 --6663.52,-6300.00,-363.52,-5649.96,-6050.00,400.04 --6563.52,-6850.00,286.48,-5549.96,-5950.00,400.04 --6463.52,-6850.00,386.48,-5449.96,-4850.00,-599.96 --6363.52,-5750.00,-613.52,-5349.96,-3900.00,-1449.96 --6263.52,-5600.00,-663.52,-5249.96,-4400.00,-849.96 --6163.52,-6250.00,86.48,-5149.96,-5200.00,50.04 --6063.52,-6400.00,336.48,-5049.96,-4700.00,-349.96 --5963.52,-5650.00,-313.52,-4949.96,-3900.00,-1049.96 --5863.52,-4950.00,-913.52,-4849.96,-3200.00,-1649.96 --5763.52,-6050.00,286.48,-4749.96,-3800.00,-949.96 --5663.52,-6000.00,336.48,-4649.96,-4500.00,-149.96 --5563.52,-5150.00,-413.52,-4549.96,-4200.00,-349.96 --5463.52,-4400.00,-1063.52,-4449.96,-3200.00,-1249.96 --5363.52,-4100.00,-1263.52,-4349.96,-2600.00,-1749.96 --5263.52,-4800.00,-463.52,-4249.96,-3100.00,-1149.96 --5163.52,-6400.00,1236.48,-4149.96,-3900.00,-249.96 --5063.52,-4350.00,-713.52,-4049.96,-2200.00,-1849.96 --4963.52,-3450.00,-1513.52,-3949.96,-1400.00,-2549.96 --4863.52,-3350.00,-1513.52,-3849.96,-2500.00,-1349.96 --4763.52,-4400.00,-363.52,-3749.96,-3500.00,-249.96 --4663.52,-4950.00,286.48,-3649.96,-2200.00,-1449.96 --4563.52,-4050.00,-513.52,-3549.96,-1200.00,-2349.96 --4463.52,-3400.00,-1063.52,-3449.96,-100.00,-3349.96 --4363.52,-2550.00,-1813.52,-3349.96,-1400.00,-1949.96 --4263.52,-2300.00,-1963.52,-3249.96,-3500.00,250.04 --4163.52,-3700.00,-463.52,-3149.96,-3500.00,350.04 --4063.52,-4350.00,286.48,-3049.96,-2050.00,-999.96 --3963.52,-3550.00,-413.52,-2949.96,-900.00,-2049.96 --3863.52,-2850.00,-1013.52,-2849.96,-600.00,-2249.96 --3763.52,-1800.00,-1963.52,-2749.96,-850.00,-1899.96 --3663.52,-2350.00,-1313.52,-2649.96,-450.00,-2199.96 --3563.52,-2750.00,-813.52,-2549.96,900.00,-3449.96 --3463.52,-1800.00,-1663.52,-2449.96,-450.00,-1999.96 --3363.52,-1600.00,-1763.52,-2349.96,-1500.00,-849.96 --3263.52,200.00,-3463.52,-2249.96,-1000.00,-1249.96 --3163.52,-50.00,-3113.52,-2149.96,-400.00,-1749.96 --3063.52,-2300.00,-763.52,-2049.96,100.00,-2149.96 --2963.52,-3600.00,636.48,-1949.96,50.00,-1999.96 --2863.52,-2800.00,-63.52,-1849.96,0.00,-1849.96 --2763.52,-2250.00,-513.52,-1749.96,0.00,-1749.96 --2663.52,-1700.00,-963.52,-1649.96,0.00,-1649.96 --2563.52,-900.00,-1663.52,-1549.96,0.00,-1549.96 --2463.52,850.00,-3313.52,-1449.96,0.00,-1449.96 --2363.52,-200.00,-2163.52,-1349.96,0.00,-1349.96 --2263.52,-1700.00,-563.52,-1249.96,0.00,-1249.96 --2163.52,-1200.00,-963.52,-1149.96,0.00,-1149.96 --2063.52,-950.00,-1113.52,-1049.96,0.00,-1049.96 --1963.52,550.00,-2513.52,-949.96,0.00,-949.96 --1863.52,250.00,-2113.52,-849.96,0.00,-849.96 --1763.52,-100.00,-1663.52,-749.96,0.00,-749.96 --1663.52,0.00,-1663.52,-649.96,0.00,-649.96 --1563.52,0.00,-1563.52,-549.96,0.00,-549.96 --1463.52,0.00,-1463.52,-449.96,0.00,-449.96 --1363.52,0.00,-1363.52,-349.96,0.00,-349.96 --1263.52,0.00,-1263.52,-249.96,0.00,-249.96 --1163.52,0.00,-1163.52,-149.96,0.00,-149.96 --1063.52,0.00,-1063.52,-49.96,0.00,-49.96 --963.52,0.00,-963.52,0.00,0.00,0.00 --863.52,0.00,-863.52,0.00,0.00,0.00 --763.52,0.00,-763.52,0.00,0.00,0.00 --663.52,0.00,-663.52,0.00,0.00,0.00 --563.52,0.00,-563.52,0.00,0.00,0.00 --463.52,0.00,-463.52,0.00,0.00,0.00 --363.52,0.00,-363.52,0.00,0.00,0.00 --263.52,0.00,-263.52,0.00,0.00,0.00 --163.52,0.00,-163.52,0.00,0.00,0.00 --63.52,0.00,-63.52,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -100.00,0.00,100.00,100.00,0.00,100.00 -200.00,0.00,200.00,200.00,0.00,200.00 -300.00,0.00,300.00,300.00,0.00,300.00 -400.00,0.00,400.00,400.00,0.00,400.00 -500.00,0.00,500.00,500.00,0.00,500.00 -600.00,0.00,600.00,600.00,0.00,600.00 -700.00,0.00,700.00,700.00,0.00,700.00 -800.00,0.00,800.00,800.00,0.00,800.00 -900.00,0.00,900.00,900.00,0.00,900.00 -1000.00,0.00,1000.00,1000.00,0.00,1000.00 -1100.00,0.00,1100.00,1100.00,0.00,1100.00 -1200.00,0.00,1200.00,1200.00,0.00,1200.00 -1300.00,0.00,1300.00,1300.00,0.00,1300.00 -1400.00,0.00,1400.00,1400.00,0.00,1400.00 -1500.00,0.00,1500.00,1500.00,0.00,1500.00 -1600.00,0.00,1600.00,1600.00,0.00,1600.00 -1700.00,0.00,1700.00,1700.00,0.00,1700.00 -1800.00,0.00,1800.00,1800.00,0.00,1800.00 -1900.00,0.00,1900.00,1900.00,0.00,1900.00 -2000.00,0.00,2000.00,2000.00,0.00,2000.00 -2100.00,0.00,2100.00,2100.00,0.00,2100.00 -2200.00,0.00,2200.00,2200.00,0.00,2200.00 -2300.00,0.00,2300.00,2300.00,0.00,2300.00 -2400.00,0.00,2400.00,2400.00,0.00,2400.00 -2500.00,350.00,2150.00,2500.00,500.00,2000.00 -2600.00,250.00,2350.00,2600.00,600.00,2000.00 -2700.00,-250.00,2950.00,2700.00,-800.00,3500.00 -2800.00,850.00,1950.00,2800.00,50.00,2750.00 -2900.00,1000.00,1900.00,2900.00,1950.00,950.00 -3000.00,1050.00,1950.00,3000.00,1050.00,1950.00 -3100.00,-100.00,3200.00,3100.00,350.00,2750.00 -3200.00,850.00,2350.00,3200.00,450.00,2750.00 -3300.00,2400.00,900.00,3300.00,1150.00,2150.00 -3400.00,1300.00,2100.00,3400.00,1500.00,1900.00 -3500.00,350.00,3150.00,3500.00,1000.00,2500.00 -3600.00,2550.00,1050.00,3600.00,1300.00,2300.00 -3700.00,1850.00,1850.00,3700.00,1900.00,1800.00 -3800.00,2100.00,1700.00,3800.00,1450.00,2350.00 -3900.00,2200.00,1700.00,3900.00,1850.00,2050.00 -4000.00,2250.00,1750.00,4000.00,1950.00,2050.00 -4100.00,2500.00,1600.00,4100.00,2050.00,2050.00 -4200.00,2800.00,1400.00,4200.00,2200.00,2000.00 -4300.00,3100.00,1200.00,4300.00,2250.00,2050.00 -4400.00,3100.00,1300.00,4400.00,2400.00,2000.00 -4500.00,3200.00,1300.00,4500.00,2750.00,1750.00 -4600.00,3350.00,1250.00,4600.00,3000.00,1600.00 -4700.00,3450.00,1250.00,4700.00,3050.00,1650.00 -4800.00,3600.00,1200.00,4800.00,3150.00,1650.00 -4900.00,3700.00,1200.00,4900.00,3200.00,1700.00 -5000.00,3750.00,1250.00,5000.00,3350.00,1650.00 -5100.00,3850.00,1250.00,5100.00,3350.00,1750.00 -5200.00,4000.00,1200.00,5200.00,3400.00,1800.00 -5300.00,4350.00,950.00,5300.00,3500.00,1800.00 -5400.00,4350.00,1050.00,5400.00,3800.00,1600.00 -5500.00,4450.00,1050.00,5500.00,4000.00,1500.00 -5600.00,4800.00,800.00,5600.00,4400.00,1200.00 -5700.00,5100.00,600.00,5700.00,4550.00,1150.00 -5800.00,5300.00,500.00,5800.00,4750.00,1050.00 -5900.00,5450.00,450.00,5900.00,5000.00,900.00 -6000.00,5700.00,300.00,6000.00,5050.00,950.00 -6100.00,5850.00,250.00,6100.00,5350.00,750.00 -6200.00,6100.00,100.00,6200.00,5600.00,600.00 -6300.00,6200.00,100.00,6300.00,5500.00,800.00 -6400.00,6100.00,300.00,6400.00,5300.00,1100.00 -6500.00,6350.00,150.00,6500.00,5400.00,1100.00 -6600.00,6350.00,250.00,6600.00,5300.00,1300.00 -6700.00,6250.00,450.00,6700.00,5500.00,1200.00 -6800.00,6450.00,350.00,6800.00,5700.00,1100.00 -6900.00,6600.00,300.00,6900.00,6000.00,900.00 -7000.00,6750.00,250.00,7000.00,6100.00,900.00 -7100.00,6900.00,200.00,7100.00,6100.00,1000.00 -7200.00,6900.00,300.00,7200.00,6450.00,750.00 -7300.00,7050.00,250.00,7300.00,6850.00,450.00 -7400.00,7250.00,150.00,7400.00,7000.00,400.00 -7500.00,7200.00,300.00,7500.00,6950.00,550.00 -7600.00,7100.00,500.00,7600.00,6750.00,850.00 -7700.00,7300.00,400.00,7700.00,7000.00,700.00 -7800.00,7700.00,100.00,7800.00,6900.00,900.00 -7900.00,7850.00,50.00,7900.00,6900.00,1000.00 -8000.00,8100.00,-100.00,8000.00,6900.00,1100.00 -8100.00,8000.00,100.00,8100.00,7300.00,800.00 -8200.00,7900.00,300.00,8200.00,7200.00,1000.00 -8300.00,7750.00,550.00,8300.00,7600.00,700.00 -8400.00,8100.00,300.00,8400.00,7800.00,600.00 -8500.00,7950.00,550.00,8500.00,7750.00,750.00 -8600.00,8150.00,450.00,8600.00,7650.00,950.00 -8700.00,8450.00,250.00,8700.00,8350.00,350.00 -8800.00,9000.00,-200.00,8800.00,8750.00,50.00 -8900.00,8850.00,50.00,8900.00,8700.00,200.00 -9000.00,9300.00,-300.00,9000.00,8700.00,300.00 -9100.00,9500.00,-400.00,9100.00,8750.00,350.00 -9200.00,9050.00,150.00,9200.00,8150.00,1050.00 -9300.00,9350.00,-50.00,9300.00,8400.00,900.00 -9400.00,11000.00,-1600.00,9400.00,10300.00,-900.00 -9500.00,9200.00,300.00,9500.00,8500.00,1000.00 -9600.00,9450.00,150.00,9600.00,8750.00,850.00 -9700.00,9850.00,-150.00,9700.00,8850.00,850.00 -9800.00,9800.00,0.00,9800.00,8800.00,1000.00 -9900.00,10150.00,-250.00,9900.00,9400.00,500.00 -10000.00,10300.00,-300.00,10000.00,10100.00,-100.00 -10100.00,10500.00,-400.00,10100.00,10200.00,-100.00 -10200.00,10050.00,150.00,10200.00,9600.00,600.00 -10300.00,10500.00,-200.00,10300.00,9700.00,600.00 -10400.00,10700.00,-300.00,10400.00,10000.00,400.00 -10500.00,10700.00,-200.00,10500.00,9900.00,600.00 -10600.00,10600.00,0.00,10600.00,9650.00,950.00 -10700.00,10900.00,-200.00,10700.00,9950.00,750.00 -10800.00,11750.00,-950.00,10800.00,10950.00,-150.00 -10900.00,12000.00,-1100.00,10900.00,11150.00,-250.00 -11000.00,11250.00,-250.00,11000.00,10800.00,200.00 -11100.00,11150.00,-50.00,11100.00,10900.00,200.00 -11200.00,12050.00,-850.00,11200.00,11650.00,-450.00 -11300.00,12150.00,-850.00,11300.00,11700.00,-400.00 -11400.00,12150.00,-750.00,11400.00,11500.00,-100.00 -11500.00,12200.00,-700.00,11500.00,11500.00,0.00 -11600.00,11750.00,-150.00,11600.00,11050.00,550.00 -11700.00,12350.00,-650.00,11700.00,11550.00,150.00 -11800.00,12500.00,-700.00,11800.00,11700.00,100.00 -11900.00,12650.00,-750.00,11900.00,12100.00,-200.00 -12000.00,12150.00,-150.00,12000.00,11550.00,450.00 -12100.00,12950.00,-850.00,12100.00,12550.00,-450.00 -12200.00,13200.00,-1000.00,12200.00,12650.00,-450.00 -12300.00,12600.00,-300.00,12300.00,12100.00,200.00 -12400.00,13550.00,-1150.00,12400.00,13100.00,-700.00 -12500.00,14000.00,-1500.00,12500.00,13500.00,-1000.00 -12600.00,13650.00,-1050.00,12600.00,13000.00,-400.00 -12700.00,13300.00,-600.00,12700.00,12850.00,-150.00 -12800.00,13700.00,-900.00,12800.00,13300.00,-500.00 -12900.00,13900.00,-1000.00,12900.00,13350.00,-450.00 -13000.00,13800.00,-800.00,13000.00,13200.00,-200.00 -13100.00,13850.00,-750.00,13100.00,13350.00,-250.00 -13200.00,13400.00,-200.00,13200.00,13050.00,150.00 -13300.00,14150.00,-850.00,13300.00,13850.00,-550.00 -13400.00,14700.00,-1300.00,13400.00,14200.00,-800.00 -13500.00,14750.00,-1250.00,13500.00,14300.00,-800.00 -13600.00,14800.00,-1200.00,13600.00,14050.00,-450.00 -13700.00,14750.00,-1050.00,13700.00,13800.00,-100.00 -13800.00,14600.00,-800.00,13800.00,13800.00,0.00 -13900.00,14550.00,-650.00,13900.00,13800.00,100.00 -14000.00,15450.00,-1450.00,14000.00,14300.00,-300.00 -14100.00,15600.00,-1500.00,14100.00,14900.00,-800.00 -14200.00,15650.00,-1450.00,14200.00,15300.00,-1100.00 -14300.00,15300.00,-1000.00,14300.00,14800.00,-500.00 -14400.00,15250.00,-850.00,14400.00,14200.00,200.00 -14500.00,15800.00,-1300.00,14500.00,14600.00,-100.00 -14600.00,16350.00,-1750.00,14600.00,15300.00,-700.00 -14700.00,16050.00,-1350.00,14700.00,15150.00,-450.00 -14800.00,15800.00,-1000.00,14800.00,15450.00,-650.00 -14900.00,16350.00,-1450.00,14900.00,16000.00,-1100.00 -15000.00,17150.00,-2150.00,15000.00,16200.00,-1200.00 -15100.00,16450.00,-1350.00,15100.00,15200.00,-100.00 -15200.00,16550.00,-1350.00,15200.00,15500.00,-300.00 -15300.00,16950.00,-1650.00,15300.00,16150.00,-850.00 -15400.00,16900.00,-1500.00,15400.00,16750.00,-1350.00 -15500.00,16500.00,-1000.00,15500.00,16650.00,-1150.00 -15600.00,16800.00,-1200.00,15600.00,16550.00,-950.00 -15700.00,17000.00,-1300.00,15700.00,16350.00,-650.00 -15800.00,17350.00,-1550.00,15800.00,17000.00,-1200.00 -15900.00,17750.00,-1850.00,15900.00,16850.00,-950.00 -16000.00,18000.00,-2000.00,16000.00,17250.00,-1250.00 -16100.00,17950.00,-1850.00,16100.00,17150.00,-1050.00 -16200.00,17750.00,-1550.00,16200.00,17100.00,-900.00 -16300.00,18050.00,-1750.00,16300.00,17550.00,-1250.00 -16400.00,17750.00,-1350.00,16400.00,17350.00,-950.00 -16500.00,17850.00,-1350.00,16500.00,17350.00,-850.00 -16600.00,18650.00,-2050.00,16600.00,18250.00,-1650.00 -16700.00,18300.00,-1600.00,16700.00,17950.00,-1250.00 -16800.00,18100.00,-1300.00,16800.00,17650.00,-850.00 -16900.00,21450.00,-4550.00,16900.00,20700.00,-3800.00 -17000.00,18150.00,-1150.00,17000.00,17500.00,-500.00 -17100.00,18200.00,-1100.00,17100.00,18100.00,-1000.00 -17200.00,18950.00,-1750.00,17200.00,19150.00,-1950.00 -17300.00,18850.00,-1550.00,17195.22,18350.00,-1154.78 -17400.00,19200.00,-1800.00,17095.22,18350.00,-1254.78 -17500.00,19650.00,-2150.00,16995.22,18750.00,-1754.78 -17600.00,19550.00,-1950.00,16895.22,18500.00,-1604.78 -17549.96,19700.00,-2150.04,16795.22,18900.00,-2104.78 -17449.96,19500.00,-2050.04,16695.22,18200.00,-1504.78 -17349.96,19500.00,-2150.04,16595.22,18100.00,-1504.78 -17249.96,19950.00,-2700.04,16495.22,18550.00,-2054.78 -17149.96,20050.00,-2900.04,16395.22,18650.00,-2254.78 -17049.96,19000.00,-1950.04,16295.22,17800.00,-1504.78 -16949.96,19300.00,-2350.04,16195.22,18100.00,-1904.78 -16849.96,20200.00,-3350.04,16095.22,18050.00,-1954.78 -16749.96,19500.00,-2750.04,15995.22,17200.00,-1204.78 -16649.96,19000.00,-2350.04,15895.22,17450.00,-1554.78 -16549.96,18800.00,-2250.04,15795.22,17700.00,-1904.78 -16449.96,18900.00,-2450.04,15695.22,18000.00,-2304.78 -16349.96,18600.00,-2250.04,15595.22,17750.00,-2154.78 -16249.96,17850.00,-1600.04,15495.22,16600.00,-1104.78 -16149.96,18500.00,-2350.04,15395.22,17350.00,-1954.78 -16049.96,19200.00,-3150.04,15295.22,17400.00,-2104.78 -15949.96,18050.00,-2100.04,15195.22,16550.00,-1354.78 -15849.96,17950.00,-2100.04,15095.22,16600.00,-1504.78 -15749.96,17950.00,-2200.04,14995.22,16450.00,-1454.78 -15649.96,17950.00,-2300.04,14895.22,16150.00,-1254.78 -15549.96,17900.00,-2350.04,14795.22,16450.00,-1654.78 -15449.96,16700.00,-1250.04,14695.22,15600.00,-904.78 -15349.96,16700.00,-1350.04,14595.22,15800.00,-1204.78 -15249.96,16650.00,-1400.04,14495.22,15950.00,-1454.78 -15149.96,17300.00,-2150.04,14395.22,16500.00,-2104.78 -15049.96,17150.00,-2100.04,14295.22,15750.00,-1454.78 -14949.96,16550.00,-1600.04,14195.22,15100.00,-904.78 -14849.96,17200.00,-2350.04,14095.22,15800.00,-1704.78 -14749.96,17350.00,-2600.04,13995.22,16050.00,-2054.78 -14649.96,16350.00,-1700.04,13895.22,15400.00,-1504.78 -14549.96,16300.00,-1750.04,13795.22,15500.00,-1704.78 -14449.96,16800.00,-2350.04,13695.22,15450.00,-1754.78 -14349.96,16350.00,-2000.04,13595.22,14850.00,-1254.78 -14249.96,16000.00,-1750.04,13495.22,14650.00,-1154.78 -14149.96,16000.00,-1850.04,13395.22,14100.00,-704.78 -14049.96,15650.00,-1600.04,13295.22,14150.00,-854.78 -13949.96,14400.00,-450.04,13195.22,13550.00,-354.78 -13849.96,14900.00,-1050.04,13095.22,14100.00,-1004.78 -13749.96,15300.00,-1550.04,12995.22,13900.00,-904.78 -13649.96,14400.00,-750.04,12895.22,13000.00,-104.78 -13549.96,14900.00,-1350.04,12795.22,13500.00,-704.78 -13449.96,14800.00,-1350.04,12695.22,14400.00,-1704.78 -13349.96,13450.00,-100.04,12595.22,14000.00,-1404.78 -13249.96,12750.00,499.96,12495.22,13100.00,-604.78 -13149.96,13950.00,-800.04,12395.22,12900.00,-504.78 -13049.96,14700.00,-1650.04,12295.22,12600.00,-304.78 -12949.96,15100.00,-2150.04,12195.22,12700.00,-504.78 -12849.96,15100.00,-2250.04,12095.22,12950.00,-854.78 -12749.96,15000.00,-2250.04,11995.22,13050.00,-1054.78 -12649.96,14000.00,-1350.04,11895.22,12250.00,-354.78 -12549.96,13850.00,-1300.04,11795.22,12150.00,-354.78 -12449.96,14200.00,-1750.04,11695.22,12800.00,-1104.78 -12349.96,13950.00,-1600.04,11595.22,12600.00,-1004.78 -12249.96,13050.00,-800.04,11495.22,11500.00,-4.78 -12149.96,13900.00,-1750.04,11395.22,12400.00,-1004.78 -12049.96,13950.00,-1900.04,11295.22,12250.00,-954.78 -11949.96,13200.00,-1250.04,11195.22,11600.00,-404.78 -11849.96,13500.00,-1650.04,11095.22,11750.00,-654.78 -11749.96,13750.00,-2000.04,10995.22,12000.00,-1004.78 -11649.96,13300.00,-1650.04,10895.22,11650.00,-754.78 -11549.96,11850.00,-300.04,10795.22,10350.00,445.22 -11449.96,12300.00,-850.04,10695.22,11100.00,-404.78 -11349.96,12850.00,-1500.04,10595.22,11550.00,-954.78 -11249.96,12800.00,-1550.04,10495.22,11400.00,-904.78 -11149.96,11950.00,-800.04,10395.22,10450.00,-54.78 -11049.96,12000.00,-950.04,10295.22,10750.00,-454.78 -10949.96,12250.00,-1300.04,10195.22,10850.00,-654.78 -10849.96,14650.00,-3800.04,10095.22,13050.00,-2954.78 -10749.96,11350.00,-600.04,9995.22,9950.00,45.22 -10649.96,10100.00,549.96,9895.22,8800.00,1095.22 -10549.96,11300.00,-750.04,9795.22,10350.00,-554.78 -10449.96,11700.00,-1250.04,9695.22,11050.00,-1354.78 -10349.96,10750.00,-400.04,9595.22,9100.00,495.22 -10249.96,10550.00,-300.04,9495.22,8850.00,645.22 -10149.96,11200.00,-1050.04,9395.22,9550.00,-154.78 -10049.96,11350.00,-1300.04,9295.22,9700.00,-404.78 -9949.96,10650.00,-700.04,9195.22,9050.00,145.22 -9849.96,10950.00,-1100.04,9095.22,9550.00,-454.78 -9749.96,11200.00,-1450.04,8995.22,9900.00,-904.78 -9649.96,10100.00,-450.04,8895.22,8850.00,45.22 -9549.96,10450.00,-900.04,8795.22,9350.00,-554.78 -9449.96,11000.00,-1550.04,8695.22,9400.00,-704.78 -9349.96,10900.00,-1550.04,8595.22,8950.00,-354.78 -9249.96,10250.00,-1000.04,8495.22,8450.00,45.22 -9149.96,9750.00,-600.04,8395.22,7950.00,445.22 -9049.96,9550.00,-500.04,8295.22,8050.00,245.22 -8949.96,9100.00,-150.04,8195.22,7650.00,545.22 -8849.96,9150.00,-300.04,8095.22,7650.00,445.22 -8749.96,9350.00,-600.04,7995.22,8100.00,-104.78 -8649.96,9800.00,-1150.04,7895.22,8400.00,-504.78 -8549.96,9350.00,-800.04,7795.22,7950.00,-154.78 -8449.96,9050.00,-600.04,7695.22,7900.00,-204.78 -8349.96,9800.00,-1450.04,7595.22,8250.00,-654.78 -8249.96,8750.00,-500.04,7495.22,7300.00,195.22 -8149.96,7500.00,649.96,7395.22,6750.00,645.22 -8049.96,8500.00,-450.04,7295.22,6850.00,445.22 -7949.96,8050.00,-100.04,7195.22,6600.00,595.22 -7849.96,7400.00,449.96,7095.22,6150.00,945.22 -7749.96,7450.00,299.96,6995.22,6350.00,645.22 -7649.96,7500.00,149.96,6895.22,6450.00,445.22 -7549.96,7600.00,-50.04,6795.22,6350.00,445.22 -7449.96,7850.00,-400.04,6695.22,6400.00,295.22 -7349.96,7950.00,-600.04,6595.22,6400.00,195.22 -7249.96,7750.00,-500.04,6495.22,6150.00,345.22 -7149.96,7300.00,-150.04,6395.22,5900.00,495.22 -7049.96,7400.00,-350.04,6295.22,5950.00,345.22 -6949.96,7400.00,-450.04,6195.22,6150.00,45.22 -6849.96,6850.00,-0.04,6095.22,5450.00,645.22 -6749.96,6100.00,649.96,5995.22,4600.00,1395.22 -6649.96,6700.00,-50.04,5895.22,5500.00,395.22 -6549.96,6150.00,399.96,5795.22,4700.00,1095.22 -6449.96,5800.00,649.96,5695.22,4400.00,1295.22 -6349.96,6100.00,249.96,5595.22,4600.00,995.22 -6249.96,5950.00,299.96,5495.22,4600.00,895.22 -6149.96,5700.00,449.96,5395.22,4400.00,995.22 -6049.96,5650.00,399.96,5295.22,4300.00,995.22 -5949.96,5550.00,399.96,5195.22,4200.00,995.22 -5849.96,5350.00,499.96,5095.22,4000.00,1095.22 -5749.96,5150.00,599.96,4995.22,3900.00,1095.22 -5649.96,5250.00,399.96,4895.22,4000.00,895.22 -5549.96,5150.00,399.96,4795.22,3950.00,845.22 -5449.96,4800.00,649.96,4695.22,3350.00,1345.22 -5349.96,4250.00,1099.96,4595.22,3100.00,1495.22 -5249.96,4700.00,549.96,4495.22,3600.00,895.22 -5149.96,3950.00,1199.96,4395.22,2750.00,1645.22 -5049.96,3450.00,1599.96,4295.22,2250.00,2045.22 -4949.96,4200.00,749.96,4195.22,3500.00,695.22 -4849.96,3250.00,1599.96,4095.22,2100.00,1995.22 -4749.96,2800.00,1949.96,3995.22,2450.00,1545.22 -4649.96,4350.00,299.96,3895.22,2950.00,945.22 -4549.96,2900.00,1649.96,3795.22,2250.00,1545.22 -4449.96,2850.00,1599.96,3695.22,1450.00,2245.22 -4349.96,4000.00,349.96,3595.22,3100.00,495.22 -4249.96,2650.00,1599.96,3495.22,2000.00,1495.22 -4149.96,2200.00,1949.96,3395.22,550.00,2845.22 -4049.96,3250.00,799.96,3295.22,1650.00,1645.22 -3949.96,2600.00,1349.96,3195.22,2400.00,795.22 -3849.96,1900.00,1949.96,3095.22,-250.00,3345.22 -3749.96,1100.00,2649.96,2995.22,1200.00,1795.22 -3649.96,2350.00,1299.96,2895.22,2450.00,445.22 -3549.96,700.00,2849.96,2795.22,-200.00,2995.22 -3449.96,1350.00,2099.96,2695.22,200.00,2495.22 -3349.96,1950.00,1399.96,2595.22,2800.00,-204.78 -3249.96,1250.00,1999.96,2495.22,200.00,2295.22 -3149.96,1500.00,1649.96,2395.22,-250.00,2645.22 -3049.96,650.00,2399.96,2295.22,550.00,1745.22 -2949.96,700.00,2249.96,2195.22,1500.00,695.22 -2849.96,800.00,2049.96,2095.22,250.00,1845.22 -2749.96,800.00,1949.96,1995.22,50.00,1945.22 -2649.96,-300.00,2949.96,1895.22,0.00,1895.22 -2549.96,550.00,1999.96,1795.22,0.00,1795.22 -2449.96,-350.00,2799.96,1695.22,0.00,1695.22 -2349.96,50.00,2299.96,1595.22,0.00,1595.22 -2249.96,0.00,2249.96,1495.22,0.00,1495.22 -2149.96,-500.00,2649.96,1395.22,0.00,1395.22 -2049.96,600.00,1449.96,1295.22,0.00,1295.22 -1949.96,-250.00,2199.96,1195.22,-50.00,1245.22 -1849.96,-200.00,2049.96,1095.22,50.00,1045.22 -1749.96,50.00,1699.96,995.22,0.00,995.22 -1649.96,-50.00,1699.96,895.22,0.00,895.22 -1549.96,0.00,1549.96,795.22,0.00,795.22 -1449.96,0.00,1449.96,695.22,0.00,695.22 -1349.96,0.00,1349.96,595.22,0.00,595.22 -1249.96,0.00,1249.96,495.22,0.00,495.22 -1149.96,0.00,1149.96,395.22,0.00,395.22 -1049.96,0.00,1049.96,295.22,0.00,295.22 -949.96,0.00,949.96,195.22,0.00,195.22 -849.96,0.00,849.96,95.22,0.00,95.22 -749.96,0.00,749.96,0.00,0.00,0.00 -649.96,0.00,649.96,0.00,0.00,0.00 -549.96,0.00,549.96,0.00,0.00,0.00 -449.96,0.00,449.96,0.00,0.00,0.00 -349.96,0.00,349.96,0.00,0.00,0.00 -249.96,0.00,249.96,0.00,0.00,0.00 -149.96,0.00,149.96,0.00,0.00,0.00 -49.96,0.00,49.96,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 --100.00,0.00,-100.00,-100.00,0.00,-100.00 --200.00,0.00,-200.00,-200.00,0.00,-200.00 --300.00,0.00,-300.00,-300.00,0.00,-300.00 --400.00,0.00,-400.00,-400.00,0.00,-400.00 --500.00,0.00,-500.00,-500.00,0.00,-500.00 --600.00,0.00,-600.00,-600.00,0.00,-600.00 --700.00,0.00,-700.00,-700.00,0.00,-700.00 --800.00,0.00,-800.00,-800.00,0.00,-800.00 --900.00,0.00,-900.00,-900.00,0.00,-900.00 --1000.00,0.00,-1000.00,-1000.00,0.00,-1000.00 --1100.00,0.00,-1100.00,-1100.00,0.00,-1100.00 --1200.00,0.00,-1200.00,-1200.00,0.00,-1200.00 --1300.00,0.00,-1300.00,-1300.00,0.00,-1300.00 --1400.00,0.00,-1400.00,-1400.00,0.00,-1400.00 --1500.00,0.00,-1500.00,-1500.00,0.00,-1500.00 --1600.00,0.00,-1600.00,-1600.00,0.00,-1600.00 --1700.00,0.00,-1700.00,-1700.00,0.00,-1700.00 --1800.00,0.00,-1800.00,-1800.00,0.00,-1800.00 --1900.00,0.00,-1900.00,-1900.00,0.00,-1900.00 --2000.00,0.00,-2000.00,-2000.00,0.00,-2000.00 --2100.00,0.00,-2100.00,-2100.00,0.00,-2100.00 --2200.00,0.00,-2200.00,-2200.00,0.00,-2200.00 --2300.00,0.00,-2300.00,-2300.00,0.00,-2300.00 --2400.00,0.00,-2400.00,-2400.00,0.00,-2400.00 --2500.00,-350.00,-2150.00,-2500.00,-350.00,-2150.00 --2600.00,-300.00,-2300.00,-2600.00,-550.00,-2050.00 --2700.00,350.00,-3050.00,-2700.00,800.00,-3500.00 --2800.00,-950.00,-1850.00,-2800.00,-600.00,-2200.00 --2900.00,-750.00,-2150.00,-2900.00,-1750.00,-1150.00 --3000.00,-1000.00,-2000.00,-3000.00,-850.00,-2150.00 --3100.00,-1400.00,-1700.00,-3100.00,-750.00,-2350.00 --3200.00,-1350.00,-1850.00,-3200.00,-450.00,-2750.00 --3300.00,-1350.00,-1950.00,-3300.00,-750.00,-2550.00 --3400.00,-900.00,-2500.00,-3400.00,-1250.00,-2150.00 --3500.00,-1300.00,-2200.00,-3500.00,-1300.00,-2200.00 --3600.00,-1800.00,-1800.00,-3600.00,-1300.00,-2300.00 --3700.00,-2100.00,-1600.00,-3700.00,-1550.00,-2150.00 --3800.00,-1950.00,-1850.00,-3800.00,-1450.00,-2350.00 --3900.00,-2500.00,-1400.00,-3900.00,-1900.00,-2000.00 --4000.00,-2150.00,-1850.00,-4000.00,-1700.00,-2300.00 --4100.00,-2350.00,-1750.00,-4100.00,-2000.00,-2100.00 --4200.00,-2550.00,-1650.00,-4200.00,-2300.00,-1900.00 --4300.00,-2850.00,-1450.00,-4300.00,-2200.00,-2100.00 --4400.00,-2950.00,-1450.00,-4400.00,-2350.00,-2050.00 --4500.00,-2900.00,-1600.00,-4500.00,-2650.00,-1850.00 --4600.00,-3200.00,-1400.00,-4600.00,-2900.00,-1700.00 --4700.00,-3250.00,-1450.00,-4700.00,-2800.00,-1900.00 --4800.00,-3600.00,-1200.00,-4800.00,-2750.00,-2050.00 --4900.00,-3700.00,-1200.00,-4900.00,-3050.00,-1850.00 --5000.00,-3700.00,-1300.00,-5000.00,-3250.00,-1750.00 --5100.00,-3800.00,-1300.00,-5100.00,-3400.00,-1700.00 --5200.00,-4000.00,-1200.00,-5200.00,-3650.00,-1550.00 --5300.00,-4200.00,-1100.00,-5300.00,-4000.00,-1300.00 --5400.00,-4400.00,-1000.00,-5400.00,-4100.00,-1300.00 --5500.00,-4350.00,-1150.00,-5500.00,-4050.00,-1450.00 --5600.00,-4600.00,-1000.00,-5600.00,-4200.00,-1400.00 --5700.00,-4700.00,-1000.00,-5700.00,-4450.00,-1250.00 --5800.00,-4700.00,-1100.00,-5800.00,-4350.00,-1450.00 --5900.00,-4950.00,-950.00,-5900.00,-4350.00,-1550.00 --6000.00,-5150.00,-850.00,-6000.00,-4800.00,-1200.00 --6100.00,-5350.00,-750.00,-6100.00,-4800.00,-1300.00 --6200.00,-5400.00,-800.00,-6200.00,-5100.00,-1100.00 --6300.00,-5650.00,-650.00,-6300.00,-5300.00,-1000.00 --6400.00,-5950.00,-450.00,-6400.00,-5300.00,-1100.00 --6500.00,-5950.00,-550.00,-6500.00,-5300.00,-1200.00 --6600.00,-5950.00,-650.00,-6600.00,-5500.00,-1100.00 --6700.00,-6100.00,-600.00,-6700.00,-5650.00,-1050.00 --6800.00,-6100.00,-700.00,-6800.00,-5750.00,-1050.00 --6900.00,-6150.00,-750.00,-6900.00,-5900.00,-1000.00 --7000.00,-6200.00,-800.00,-7000.00,-6100.00,-900.00 --7100.00,-6100.00,-1000.00,-7100.00,-5900.00,-1200.00 --7200.00,-6700.00,-500.00,-7200.00,-6250.00,-950.00 --7300.00,-6950.00,-350.00,-7300.00,-6500.00,-800.00 --7400.00,-7050.00,-350.00,-7400.00,-6350.00,-1050.00 --7500.00,-6950.00,-550.00,-7500.00,-6600.00,-900.00 --7600.00,-7050.00,-550.00,-7600.00,-7050.00,-550.00 --7700.00,-6950.00,-750.00,-7700.00,-7350.00,-350.00 --7800.00,-7000.00,-800.00,-7800.00,-7350.00,-450.00 --7900.00,-7300.00,-600.00,-7900.00,-7600.00,-300.00 --8000.00,-7850.00,-150.00,-8000.00,-7950.00,-50.00 --8100.00,-8100.00,0.00,-8100.00,-7850.00,-250.00 --8200.00,-8300.00,100.00,-8200.00,-7200.00,-1000.00 --8300.00,-8500.00,200.00,-8300.00,-7200.00,-1100.00 --8400.00,-8650.00,250.00,-8400.00,-7600.00,-800.00 --8500.00,-8050.00,-450.00,-8500.00,-7650.00,-850.00 --8600.00,-7900.00,-700.00,-8600.00,-8150.00,-450.00 --8700.00,-8100.00,-600.00,-8700.00,-8650.00,-50.00 --8800.00,-8100.00,-700.00,-8800.00,-8300.00,-500.00 --8900.00,-8300.00,-600.00,-8900.00,-8700.00,-200.00 --9000.00,-8600.00,-400.00,-9000.00,-8800.00,-200.00 --9100.00,-8600.00,-500.00,-9100.00,-8850.00,-250.00 --9200.00,-8900.00,-300.00,-9200.00,-8900.00,-300.00 --9300.00,-9350.00,50.00,-9300.00,-9150.00,-150.00 --9400.00,-11250.00,1850.00,-9400.00,-11100.00,1700.00 --9500.00,-9300.00,-200.00,-9500.00,-9050.00,-450.00 --9600.00,-9600.00,0.00,-9600.00,-9300.00,-300.00 --9700.00,-9750.00,50.00,-9700.00,-9250.00,-450.00 --9800.00,-9500.00,-300.00,-9800.00,-9000.00,-800.00 --9900.00,-9650.00,-250.00,-9900.00,-9450.00,-450.00 --10000.00,-10650.00,650.00,-10000.00,-10250.00,250.00 --10100.00,-10700.00,600.00,-10100.00,-10200.00,100.00 --10200.00,-10800.00,600.00,-10200.00,-10250.00,50.00 --10300.00,-10750.00,450.00,-10300.00,-10250.00,-50.00 --10400.00,-10500.00,100.00,-10400.00,-10100.00,-300.00 --10500.00,-10650.00,150.00,-10500.00,-10250.00,-250.00 --10600.00,-10650.00,50.00,-10600.00,-10550.00,-50.00 --10700.00,-10900.00,200.00,-10700.00,-10850.00,150.00 --10800.00,-11150.00,350.00,-10800.00,-11100.00,300.00 --10900.00,-11350.00,450.00,-10900.00,-10700.00,-200.00 --11000.00,-11650.00,650.00,-11000.00,-11000.00,0.00 --11100.00,-12050.00,950.00,-11100.00,-11600.00,500.00 --11200.00,-12200.00,1000.00,-11200.00,-12050.00,850.00 --11300.00,-11650.00,350.00,-11300.00,-11500.00,200.00 --11400.00,-11950.00,550.00,-11400.00,-11450.00,50.00 --11500.00,-12700.00,1200.00,-11500.00,-12250.00,750.00 --11600.00,-12650.00,1050.00,-11600.00,-12200.00,600.00 --11700.00,-12250.00,550.00,-11700.00,-11850.00,150.00 --11800.00,-12950.00,1150.00,-11800.00,-12650.00,850.00 --11900.00,-13600.00,1700.00,-11900.00,-13000.00,1100.00 --12000.00,-12900.00,900.00,-12000.00,-12250.00,250.00 --12100.00,-13250.00,1150.00,-12100.00,-12550.00,450.00 --12200.00,-13600.00,1400.00,-12200.00,-12600.00,400.00 --12300.00,-13400.00,1100.00,-12300.00,-12400.00,100.00 --12400.00,-13650.00,1250.00,-12400.00,-12900.00,500.00 --12500.00,-13600.00,1100.00,-12500.00,-13050.00,550.00 --12600.00,-13000.00,400.00,-12600.00,-12600.00,0.00 --12700.00,-13750.00,1050.00,-12700.00,-13250.00,550.00 --12800.00,-14250.00,1450.00,-12800.00,-13150.00,350.00 --12900.00,-12700.00,-200.00,-12900.00,-11350.00,-1550.00 --13000.00,-11850.00,-1150.00,-13000.00,-10700.00,-2300.00 --13100.00,-14400.00,1300.00,-13100.00,-13650.00,550.00 --13200.00,-15500.00,2300.00,-13200.00,-15100.00,1900.00 --13300.00,-13900.00,600.00,-13300.00,-13250.00,-50.00 --13400.00,-14350.00,950.00,-13400.00,-13900.00,500.00 --13500.00,-15800.00,2300.00,-13500.00,-15750.00,2250.00 --13600.00,-16000.00,2400.00,-13600.00,-15150.00,1550.00 --13700.00,-14800.00,1100.00,-13700.00,-14300.00,600.00 --13800.00,-15000.00,1200.00,-13800.00,-14750.00,950.00 --13900.00,-15500.00,1600.00,-13900.00,-15350.00,1450.00 --14000.00,-15150.00,1150.00,-14000.00,-14500.00,500.00 --14100.00,-15500.00,1400.00,-14100.00,-15150.00,1050.00 --14200.00,-15550.00,1350.00,-14200.00,-15250.00,1050.00 --14300.00,-15500.00,1200.00,-14300.00,-14800.00,500.00 --14400.00,-16250.00,1850.00,-14400.00,-15000.00,600.00 --14500.00,-16150.00,1650.00,-14500.00,-15400.00,900.00 --14600.00,-16300.00,1700.00,-14600.00,-15550.00,950.00 --14700.00,-15750.00,1050.00,-14700.00,-15150.00,450.00 --14800.00,-15150.00,350.00,-14800.00,-15100.00,300.00 --14900.00,-16950.00,2050.00,-14900.00,-17300.00,2400.00 --15000.00,-17400.00,2400.00,-15000.00,-16600.00,1600.00 --15100.00,-16700.00,1600.00,-15100.00,-15900.00,800.00 --15200.00,-16400.00,1200.00,-15200.00,-15700.00,500.00 --15300.00,-16750.00,1450.00,-15300.00,-15800.00,500.00 --15400.00,-17300.00,1900.00,-15400.00,-16650.00,1250.00 --15500.00,-17450.00,1950.00,-15500.00,-17050.00,1550.00 --15600.00,-17300.00,1700.00,-15600.00,-16550.00,950.00 --15700.00,-17350.00,1650.00,-15700.00,-16650.00,950.00 --15800.00,-17950.00,2150.00,-15800.00,-17400.00,1600.00 --15900.00,-17950.00,2050.00,-15900.00,-17600.00,1700.00 --16000.00,-18250.00,2250.00,-16000.00,-17900.00,1900.00 --16100.00,-18350.00,2250.00,-16100.00,-17800.00,1700.00 --16200.00,-18350.00,2150.00,-16200.00,-17150.00,950.00 --16300.00,-18250.00,1950.00,-16300.00,-17250.00,950.00 --16400.00,-18400.00,2000.00,-16400.00,-17800.00,1400.00 --16500.00,-18600.00,2100.00,-16500.00,-18200.00,1700.00 --16600.00,-18850.00,2250.00,-16600.00,-18400.00,1800.00 --16700.00,-18900.00,2200.00,-16700.00,-18200.00,1500.00 --16800.00,-21850.00,5050.00,-16800.00,-21100.00,4300.00 --16900.00,-18000.00,1100.00,-16900.00,-17450.00,550.00 --17000.00,-18000.00,1000.00,-17000.00,-17750.00,750.00 --17100.00,-19650.00,2550.00,-17035.03,-18700.00,1664.97 --17200.00,-19200.00,2000.00,-16935.03,-18900.00,1964.97 --17300.00,-18950.00,1650.00,-16835.03,-18350.00,1514.97 --17400.00,-19200.00,1800.00,-16735.03,-18400.00,1664.97 --17448.25,-19250.00,1801.75,-16635.03,-18050.00,1414.97 --17348.25,-19750.00,2401.75,-16535.03,-18700.00,2164.97 --17248.25,-20500.00,3251.75,-16435.03,-18850.00,2414.97 --17148.25,-19500.00,2351.75,-16335.03,-17750.00,1414.97 --17048.25,-19400.00,2351.75,-16235.03,-17500.00,1264.97 --16948.25,-19550.00,2601.75,-16135.03,-17600.00,1464.97 --16848.25,-19450.00,2601.75,-16035.03,-17900.00,1864.97 --16748.25,-19250.00,2501.75,-15935.03,-18100.00,2164.97 --16648.25,-19300.00,2651.75,-15835.03,-18100.00,2264.97 --16548.25,-18750.00,2201.75,-15735.03,-17200.00,1464.97 --16448.25,-19000.00,2551.75,-15635.03,-17150.00,1514.97 --16348.25,-18700.00,2351.75,-15535.03,-17350.00,1814.97 --16248.25,-18800.00,2551.75,-15435.03,-17300.00,1864.97 --16148.25,-18750.00,2601.75,-15335.03,-17400.00,2064.97 --16048.25,-18500.00,2451.75,-15235.03,-17400.00,2164.97 --15948.25,-18500.00,2551.75,-15135.03,-17100.00,1964.97 --15848.25,-17850.00,2001.75,-15035.03,-16900.00,1864.97 --15748.25,-17900.00,2151.75,-14935.03,-17000.00,2064.97 --15648.25,-18100.00,2451.75,-14835.03,-17100.00,2264.97 --15548.25,-17800.00,2251.75,-14735.03,-16950.00,2214.97 --15448.25,-17800.00,2351.75,-14635.03,-16600.00,1964.97 --15348.25,-17450.00,2101.75,-14535.03,-16050.00,1514.97 --15248.25,-17350.00,2101.75,-14435.03,-16000.00,1564.97 --15148.25,-17250.00,2101.75,-14335.03,-15900.00,1564.97 --15048.25,-17150.00,2101.75,-14235.03,-16100.00,1864.97 --14948.25,-16700.00,1751.75,-14135.03,-15900.00,1764.97 --14848.25,-16600.00,1751.75,-14035.03,-15450.00,1414.97 --14748.25,-16950.00,2201.75,-13935.03,-15400.00,1464.97 --14648.25,-16600.00,1951.75,-13835.03,-14850.00,1014.97 --14548.25,-16500.00,1951.75,-13735.03,-14850.00,1114.97 --14448.25,-16600.00,2151.75,-13635.03,-15350.00,1714.97 --14348.25,-16200.00,1851.75,-13535.03,-15600.00,2064.97 --14248.25,-15600.00,1351.75,-13435.03,-14850.00,1414.97 --14148.25,-16200.00,2051.75,-13335.03,-14700.00,1364.97 --14048.25,-15700.00,1651.75,-13235.03,-14250.00,1014.97 --13948.25,-15350.00,1401.75,-13135.03,-13700.00,564.97 --13848.25,-15650.00,1801.75,-13035.03,-14200.00,1164.97 --13748.25,-16100.00,2351.75,-12935.03,-14800.00,1864.97 --13648.25,-14600.00,951.75,-12835.03,-13200.00,364.97 --13548.25,-14300.00,751.75,-12735.03,-13100.00,364.97 --13448.25,-15850.00,2401.75,-12635.03,-14300.00,1664.97 --13348.25,-15250.00,1901.75,-12535.03,-12550.00,14.97 --13248.25,-14400.00,1151.75,-12435.03,-13200.00,764.97 --13148.25,-14550.00,1401.75,-12335.03,-12850.00,514.97 --13048.25,-14200.00,1151.75,-12235.03,-12950.00,714.97 --12948.25,-14400.00,1451.75,-12135.03,-12950.00,814.97 --12848.25,-14400.00,1551.75,-12035.03,-12850.00,814.97 --12748.25,-14350.00,1601.75,-11935.03,-12750.00,814.97 --12648.25,-13750.00,1101.75,-11835.03,-12100.00,264.97 --12548.25,-13950.00,1401.75,-11735.03,-12200.00,464.97 --12448.25,-14050.00,1601.75,-11635.03,-12350.00,714.97 --12348.25,-13750.00,1401.75,-11535.03,-12100.00,564.97 --12248.25,-13350.00,1101.75,-11435.03,-11550.00,114.97 --12148.25,-13650.00,1501.75,-11335.03,-12200.00,864.97 --12048.25,-13950.00,1901.75,-11235.03,-12300.00,1064.97 --11948.25,-12800.00,851.75,-11135.03,-11200.00,64.97 --11848.25,-12450.00,601.75,-11035.03,-10900.00,-135.03 --11748.25,-13100.00,1351.75,-10935.03,-11600.00,664.97 --11648.25,-12750.00,1101.75,-10835.03,-11950.00,1114.97 --11548.25,-12600.00,1051.75,-10735.03,-11650.00,914.97 --11448.25,-12450.00,1001.75,-10635.03,-11600.00,964.97 --11348.25,-12350.00,1001.75,-10535.03,-11250.00,714.97 --11248.25,-12100.00,851.75,-10435.03,-11150.00,714.97 --11148.25,-12050.00,901.75,-10335.03,-11550.00,1214.97 --11048.25,-12050.00,1001.75,-10235.03,-10850.00,614.97 --10948.25,-11750.00,801.75,-10135.03,-10150.00,14.97 --10848.25,-11650.00,801.75,-10035.03,-9950.00,-85.03 --10748.25,-13700.00,2951.75,-9935.03,-11950.00,2014.97 --10648.25,-10550.00,-98.25,-9835.03,-9850.00,14.97 --10548.25,-9500.00,-1048.25,-9735.03,-9750.00,14.97 --10448.25,-11650.00,1201.75,-9635.03,-10000.00,364.97 --10348.25,-11550.00,1201.75,-9535.03,-10350.00,814.97 --10248.25,-11100.00,851.75,-9435.03,-9350.00,-85.03 --10148.25,-10950.00,801.75,-9335.03,-9500.00,164.97 --10048.25,-10900.00,851.75,-9235.03,-9350.00,114.97 --9948.25,-10250.00,301.75,-9135.03,-8750.00,-385.03 --9848.25,-9850.00,1.75,-9035.03,-8750.00,-285.03 --9748.25,-10300.00,551.75,-8935.03,-9100.00,164.97 --9648.25,-10450.00,801.75,-8835.03,-8850.00,14.97 --9548.25,-10350.00,801.75,-8735.03,-8850.00,114.97 --9448.25,-10550.00,1101.75,-8635.03,-8900.00,264.97 --9348.25,-10150.00,801.75,-8535.03,-8600.00,64.97 --9248.25,-9750.00,501.75,-8435.03,-8500.00,64.97 --9148.25,-10250.00,1101.75,-8335.03,-9150.00,814.97 --9048.25,-9900.00,851.75,-8235.03,-8650.00,414.97 --8948.25,-9400.00,451.75,-8135.03,-8300.00,164.97 --8848.25,-9300.00,451.75,-8035.03,-8100.00,64.97 --8748.25,-9250.00,501.75,-7935.03,-7650.00,-285.03 --8648.25,-9250.00,601.75,-7835.03,-7500.00,-335.03 --8548.25,-9400.00,851.75,-7735.03,-7500.00,-235.03 --8448.25,-9050.00,601.75,-7635.03,-7400.00,-235.03 --8348.25,-8800.00,451.75,-7535.03,-7550.00,14.97 --8248.25,-8600.00,351.75,-7435.03,-7400.00,-35.03 --8148.25,-8050.00,-98.25,-7335.03,-6900.00,-435.03 --8048.25,-8250.00,201.75,-7235.03,-7000.00,-235.03 --7948.25,-8000.00,51.75,-7135.03,-6800.00,-335.03 --7848.25,-8000.00,151.75,-7035.03,-6650.00,-385.03 --7748.25,-7800.00,51.75,-6935.03,-6750.00,-185.03 --7648.25,-7650.00,1.75,-6835.03,-6400.00,-435.03 --7548.25,-7450.00,-98.25,-6735.03,-6200.00,-535.03 --7448.25,-7900.00,451.75,-6635.03,-6150.00,-485.03 --7348.25,-7150.00,-198.25,-6535.03,-5450.00,-1085.03 --7248.25,-6900.00,-348.25,-6435.03,-5400.00,-1035.03 --7148.25,-6950.00,-198.25,-6335.03,-5200.00,-1135.03 --7048.25,-6900.00,-148.25,-6235.03,-5250.00,-985.03 --6948.25,-6850.00,-98.25,-6135.03,-5250.00,-885.03 --6848.25,-6650.00,-198.25,-6035.03,-5050.00,-985.03 --6748.25,-6450.00,-298.25,-5935.03,-5000.00,-935.03 --6648.25,-6500.00,-148.25,-5835.03,-5250.00,-585.03 --6548.25,-6300.00,-248.25,-5735.03,-5100.00,-635.03 --6448.25,-6200.00,-248.25,-5635.03,-5050.00,-585.03 --6348.25,-6000.00,-348.25,-5535.03,-4950.00,-585.03 --6248.25,-5950.00,-298.25,-5435.03,-4850.00,-585.03 --6148.25,-6050.00,-98.25,-5335.03,-4700.00,-635.03 --6048.25,-5400.00,-648.25,-5235.03,-4450.00,-785.03 --5948.25,-5100.00,-848.25,-5135.03,-4300.00,-835.03 --5848.25,-5250.00,-598.25,-5035.03,-4300.00,-735.03 --5748.25,-5300.00,-448.25,-4935.03,-4100.00,-835.03 --5648.25,-5200.00,-448.25,-4835.03,-3900.00,-935.03 --5548.25,-5250.00,-298.25,-4735.03,-3900.00,-835.03 --5448.25,-4700.00,-748.25,-4635.03,-3400.00,-1235.03 --5348.25,-4250.00,-1098.25,-4535.03,-3200.00,-1335.03 --5248.25,-4250.00,-998.25,-4435.03,-3300.00,-1135.03 --5148.25,-3900.00,-1248.25,-4335.03,-2800.00,-1535.03 --5048.25,-3900.00,-1148.25,-4235.03,-2800.00,-1435.03 --4948.25,-4050.00,-898.25,-4135.03,-2650.00,-1485.03 --4848.25,-3950.00,-898.25,-4035.03,-2300.00,-1735.03 --4748.25,-3700.00,-1048.25,-3935.03,-2500.00,-1435.03 --4648.25,-3700.00,-948.25,-3835.03,-2600.00,-1235.03 --4548.25,-3000.00,-1548.25,-3735.03,-1750.00,-1985.03 --4448.25,-2450.00,-1998.25,-3635.03,-2100.00,-1535.03 --4348.25,-3000.00,-1348.25,-3535.03,-1700.00,-1835.03 --4248.25,-2800.00,-1448.25,-3435.03,-1700.00,-1735.03 --4148.25,-2750.00,-1398.25,-3335.03,-1400.00,-1935.03 --4048.25,-3000.00,-1048.25,-3235.03,-1800.00,-1435.03 --3948.25,-2150.00,-1798.25,-3135.03,-1450.00,-1685.03 --3848.25,-1850.00,-1998.25,-3035.03,-1200.00,-1835.03 --3748.25,-2400.00,-1348.25,-2935.03,-250.00,-2685.03 --3648.25,-2000.00,-1648.25,-2835.03,-200.00,-2635.03 --3548.25,-1750.00,-1798.25,-2735.03,-1800.00,-935.03 --3448.25,-2050.00,-1398.25,-2635.03,-1200.00,-1435.03 --3348.25,-1000.00,-2348.25,-2535.03,50.00,-2585.03 --3248.25,-700.00,-2548.25,-2435.03,-350.00,-2085.03 --3148.25,-2300.00,-848.25,-2335.03,-1250.00,-1085.03 --3048.25,-1150.00,-1898.25,-2235.03,-250.00,-1985.03 --2948.25,-450.00,-2498.25,-2135.03,-50.00,-2085.03 --2848.25,-950.00,-1898.25,-2035.03,-300.00,-1735.03 --2748.25,-700.00,-2048.25,-1935.03,-250.00,-1685.03 --2648.25,250.00,-2898.25,-1835.03,-200.00,-1635.03 --2548.25,-650.00,-1898.25,-1735.03,-350.00,-1385.03 --2448.25,50.00,-2498.25,-1635.03,-150.00,-1485.03 --2348.25,350.00,-2698.25,-1535.03,100.00,-1635.03 --2248.25,-1050.00,-1198.25,-1435.03,0.00,-1435.03 --2148.25,-150.00,-1998.25,-1335.03,50.00,-1385.03 --2048.25,50.00,-2098.25,-1235.03,-50.00,-1185.03 --1948.25,0.00,-1948.25,-1135.03,0.00,-1135.03 --1848.25,150.00,-1998.25,-1035.03,0.00,-1035.03 --1748.25,550.00,-2298.25,-935.03,0.00,-935.03 --1648.25,950.00,-2598.25,-835.03,0.00,-835.03 --1548.25,-200.00,-1348.25,-735.03,0.00,-735.03 --1448.25,-50.00,-1398.25,-635.03,0.00,-635.03 --1348.25,0.00,-1348.25,-535.03,0.00,-535.03 --1248.25,0.00,-1248.25,-435.03,0.00,-435.03 --1148.25,0.00,-1148.25,-335.03,0.00,-335.03 --1048.25,0.00,-1048.25,-235.03,0.00,-235.03 --948.25,0.00,-948.25,-135.03,0.00,-135.03 --848.25,0.00,-848.25,-35.03,0.00,-35.03 --748.25,0.00,-748.25,0.00,0.00,0.00 --648.25,0.00,-648.25,0.00,0.00,0.00 --548.25,0.00,-548.25,0.00,0.00,0.00 --448.25,0.00,-448.25,0.00,0.00,0.00 --348.25,0.00,-348.25,0.00,0.00,0.00 --248.25,0.00,-248.25,0.00,0.00,0.00 --148.25,0.00,-148.25,0.00,0.00,0.00 --48.25,0.00,-48.25,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 -0.00,0.00,0.00,0.00,0.00,0.00 \ No newline at end of file +LeftSetpoint,LeftVelocity,LeftError,RightSetpoint,RightVelocity,RightError,Heading +0.00,0.00,0.00,0.00,0.00,0.00,221.03 +0.00,0.00,0.00,0.00,0.00,0.00,221.03 +0.00,0.00,0.00,0.00,0.00,0.00,220.77 +0.00,0.00,0.00,0.00,0.00,0.00,220.63 +0.00,0.00,0.00,0.00,0.00,0.00,220.63 +0.00,0.00,0.00,0.00,0.00,0.00,221.08 +0.00,0.00,0.00,0.00,0.00,0.00,220.77 +0.00,0.00,0.00,0.00,0.00,0.00,220.77 +0.00,0.00,0.00,0.00,0.00,0.00,220.90 +0.00,0.00,0.00,0.00,0.00,0.00,220.74 +0.00,0.00,0.00,0.00,0.00,0.00,220.74 +0.00,0.00,0.00,0.00,0.00,0.00,220.86 +0.00,0.00,0.00,0.00,0.00,0.00,220.90 +0.00,0.00,0.00,0.00,0.00,0.00,220.90 +0.00,0.00,0.00,0.00,0.00,0.00,220.72 +0.00,0.00,0.00,0.00,0.00,0.00,221.12 +0.00,0.00,0.00,0.00,0.00,0.00,221.12 +0.00,0.00,0.00,0.00,0.00,0.00,221.09 +0.00,0.00,0.00,0.00,0.00,0.00,220.94 +0.00,0.00,0.00,0.00,0.00,0.00,220.92 +0.00,0.00,0.00,0.00,0.00,0.00,220.92 +0.00,0.00,0.00,0.00,0.00,0.00,221.17 +0.00,0.00,0.00,0.00,0.00,0.00,221.07 +0.00,0.00,0.00,0.00,0.00,0.00,221.07 +0.00,0.00,0.00,0.00,0.00,0.00,220.83 +0.00,0.00,0.00,0.00,0.00,0.00,220.93 +0.00,0.00,0.00,0.00,0.00,0.00,220.93 +0.00,0.00,0.00,0.00,0.00,0.00,221.38 +0.00,0.00,0.00,0.00,0.00,0.00,221.15 +0.00,0.00,0.00,0.00,0.00,0.00,220.72 +0.00,0.00,0.00,0.00,0.00,0.00,220.72 +0.00,0.00,0.00,0.00,0.00,0.00,221.12 +-200.00,0.00,-200.00,-200.00,0.00,-200.00,221.16 +-400.00,0.00,-400.00,-400.00,0.00,-400.00,221.16 +-600.00,0.00,-600.00,-600.00,0.00,-600.00,220.43 +-800.00,0.00,-800.00,-800.00,0.00,-800.00,220.85 +-1000.00,0.00,-1000.00,-1000.00,0.00,-1000.00,220.85 +-1200.00,0.00,-1200.00,-1200.00,0.00,-1200.00,220.83 +-1400.00,0.00,-1400.00,-1400.00,0.00,-1400.00,220.95 +-1600.00,0.00,-1600.00,-1600.00,0.00,-1600.00,220.45 +-1800.00,0.00,-1800.00,-1800.00,0.00,-1800.00,220.45 +-2000.00,0.00,-2000.00,-2000.00,0.00,-2000.00,220.83 +-2200.00,0.00,-2200.00,-2200.00,0.00,-2200.00,221.02 +-2400.00,0.00,-2400.00,-2400.00,0.00,-2400.00,221.02 +-2600.00,0.00,-2600.00,-2600.00,0.00,-2600.00,220.84 +-2800.00,0.00,-2800.00,-2800.00,0.00,-2800.00,220.62 +-3000.00,0.00,-3000.00,-3000.00,0.00,-3000.00,220.96 +-3200.00,0.00,-3200.00,-3200.00,0.00,-3200.00,220.96 +-3400.00,0.00,-3400.00,-3400.00,0.00,-3400.00,221.11 +-3600.00,0.00,-3600.00,-3600.00,0.00,-3600.00,220.88 +-3800.00,0.00,-3800.00,-3800.00,0.00,-3800.00,220.88 +-4000.00,0.00,-4000.00,-4000.00,0.00,-4000.00,220.78 +-4200.00,0.00,-4200.00,-4200.00,0.00,-4200.00,221.04 +-4400.00,0.00,-4400.00,-4400.00,0.00,-4400.00,221.04 +-4600.00,0.00,-4600.00,-4600.00,0.00,-4600.00,220.71 +-4800.00,-400.00,-4400.00,-4800.00,-400.00,-4400.00,220.73 +-5000.00,-1050.00,-3950.00,-5000.00,-1000.00,-4000.00,222.67 +-5200.00,-2050.00,-3150.00,-5200.00,-1900.00,-3300.00,222.67 +-5400.00,-700.00,-4700.00,-5400.00,-850.00,-4550.00,221.18 +-5600.00,-150.00,-5450.00,-5600.00,200.00,-5800.00,220.35 +-5800.00,-2050.00,-3750.00,-5800.00,-1500.00,-4300.00,220.35 +-6000.00,-3750.00,-2250.00,-6000.00,-3100.00,-2900.00,221.60 +-6200.00,-4200.00,-2000.00,-6200.00,-3350.00,-2850.00,221.05 +-6400.00,-3300.00,-3100.00,-6400.00,-2400.00,-4000.00,221.66 +-6600.00,-3050.00,-3550.00,-6600.00,-1650.00,-4950.00,221.66 +-6800.00,-3800.00,-3000.00,-6800.00,-3250.00,-3550.00,221.92 +-7000.00,-4750.00,-2250.00,-7000.00,-4750.00,-2250.00,221.88 +-7200.00,-5300.00,-1900.00,-7200.00,-4800.00,-2400.00,221.88 +-7400.00,-3900.00,-3500.00,-7400.00,-3950.00,-3450.00,221.67 +-7600.00,-3900.00,-3700.00,-7600.00,-4450.00,-3150.00,221.56 +-7800.00,-4900.00,-2900.00,-7800.00,-5000.00,-2800.00,221.78 +-8000.00,-5950.00,-2050.00,-8000.00,-5650.00,-2350.00,221.78 +-8200.00,-6900.00,-1300.00,-8200.00,-6100.00,-2100.00,221.36 +-8400.00,-6800.00,-1600.00,-8400.00,-6050.00,-2350.00,221.84 +-8600.00,-6050.00,-2550.00,-8600.00,-6350.00,-2250.00,221.84 +-8800.00,-6900.00,-1900.00,-8800.00,-6900.00,-1900.00,222.03 +-9000.00,-7350.00,-1650.00,-9000.00,-6900.00,-2100.00,222.03 +-9200.00,-8050.00,-1150.00,-9200.00,-7400.00,-1800.00,221.63 +-9400.00,-8550.00,-850.00,-9400.00,-7600.00,-1800.00,221.63 +-9600.00,-8750.00,-850.00,-9600.00,-7900.00,-1700.00,221.25 +-9800.00,-8900.00,-900.00,-9800.00,-8050.00,-1750.00,221.63 +-10000.00,-8750.00,-1250.00,-10000.00,-7950.00,-2050.00,221.63 +-10200.00,-9300.00,-900.00,-10200.00,-8600.00,-1600.00,221.90 +-10400.00,-9700.00,-700.00,-10400.00,-8800.00,-1600.00,221.59 +-10600.00,-9850.00,-750.00,-10600.00,-9100.00,-1500.00,221.51 +-10800.00,-10200.00,-600.00,-10800.00,-9350.00,-1450.00,221.51 +-11000.00,-10250.00,-750.00,-11000.00,-9650.00,-1350.00,221.42 +-11200.00,-10550.00,-650.00,-11200.00,-9800.00,-1400.00,221.27 +-11400.00,-10800.00,-600.00,-11400.00,-10100.00,-1300.00,221.27 +-11600.00,-10950.00,-650.00,-11600.00,-10250.00,-1350.00,221.32 +-11800.00,-11100.00,-700.00,-11800.00,-10500.00,-1300.00,221.12 +-12000.00,-11450.00,-550.00,-12000.00,-10800.00,-1200.00,220.94 +-12200.00,-11700.00,-500.00,-12200.00,-11150.00,-1050.00,220.94 +-12400.00,-11900.00,-500.00,-12400.00,-11250.00,-1150.00,221.20 +-12600.00,-12100.00,-500.00,-12600.00,-11550.00,-1050.00,221.09 +-12800.00,-12250.00,-550.00,-12800.00,-11700.00,-1100.00,221.04 +-13000.00,-12550.00,-450.00,-13000.00,-11950.00,-1050.00,221.04 +-13200.00,-12800.00,-400.00,-13200.00,-12150.00,-1050.00,220.94 +-13400.00,-12550.00,-850.00,-13400.00,-11950.00,-1450.00,220.88 +-13600.00,-13200.00,-400.00,-13600.00,-12650.00,-950.00,220.88 +-13800.00,-13500.00,-300.00,-13800.00,-13050.00,-750.00,220.60 +-14000.00,-13700.00,-300.00,-14000.00,-13150.00,-850.00,220.47 +-14200.00,-13950.00,-250.00,-14200.00,-13500.00,-700.00,220.29 +-14400.00,-14000.00,-400.00,-14400.00,-13700.00,-700.00,220.29 +-14600.00,-14150.00,-450.00,-14600.00,-13950.00,-650.00,220.52 +-14800.00,-14350.00,-450.00,-14800.00,-14200.00,-600.00,220.63 +-15000.00,-14600.00,-400.00,-15000.00,-14350.00,-650.00,221.10 +-15200.00,-14950.00,-250.00,-15200.00,-14550.00,-650.00,221.10 +-15400.00,-15250.00,-150.00,-15400.00,-14850.00,-550.00,221.38 +-15600.00,-18150.00,2550.00,-15600.00,-17700.00,2100.00,220.75 +-15800.00,-15550.00,-250.00,-15800.00,-15100.00,-700.00,221.06 +-16000.00,-15250.00,-750.00,-16000.00,-14900.00,-1100.00,221.06 +-16200.00,-15500.00,-700.00,-16200.00,-15100.00,-1100.00,220.84 +-16400.00,-16000.00,-400.00,-16400.00,-15500.00,-900.00,221.07 +-16600.00,-16550.00,-50.00,-16600.00,-16000.00,-600.00,221.07 +-16800.00,-16800.00,0.00,-16800.00,-16200.00,-600.00,221.03 +-17000.00,-17050.00,50.00,-17000.00,-16500.00,-500.00,221.26 +-17200.00,-17250.00,50.00,-17200.00,-16750.00,-450.00,221.05 +-17400.00,-17500.00,100.00,-17400.00,-16900.00,-500.00,221.05 +-17600.00,-17900.00,300.00,-17600.00,-17100.00,-500.00,221.35 +-17800.00,-18200.00,400.00,-17800.00,-17450.00,-350.00,221.61 +-18000.00,-18300.00,300.00,-18000.00,-17650.00,-350.00,221.43 +-18200.00,-18550.00,350.00,-18200.00,-17750.00,-450.00,221.43 +-18400.00,-18750.00,350.00,-18400.00,-18000.00,-400.00,221.05 +-18600.00,-19650.00,1050.00,-18600.00,-18900.00,300.00,221.02 +-18800.00,-19250.00,450.00,-18800.00,-18450.00,-350.00,221.02 +-19000.00,-19300.00,300.00,-19000.00,-18650.00,-350.00,221.30 +-19200.00,-19550.00,350.00,-19200.00,-18700.00,-500.00,221.37 +-19400.00,-19800.00,400.00,-19400.00,-18900.00,-500.00,221.20 +-19600.00,-19950.00,350.00,-19600.00,-19200.00,-400.00,221.20 +-19800.00,-20300.00,500.00,-19800.00,-19500.00,-300.00,220.71 +-20000.00,-20400.00,400.00,-20000.00,-19800.00,-200.00,220.65 +-20200.00,-20600.00,400.00,-20200.00,-19900.00,-300.00,220.71 +-20400.00,-21600.00,1200.00,-20400.00,-20900.00,500.00,220.71 +-20600.00,-21000.00,400.00,-20600.00,-20400.00,-200.00,220.44 +-20800.00,-21850.00,1050.00,-20800.00,-21150.00,350.00,220.61 +-21000.00,-21250.00,250.00,-21000.00,-20750.00,-250.00,220.61 +-21200.00,-22250.00,1050.00,-21200.00,-21600.00,400.00,220.68 +-21400.00,-21700.00,300.00,-21400.00,-21250.00,-150.00,220.30 +-21600.00,-21800.00,200.00,-21600.00,-21450.00,-150.00,220.71 +-21800.00,-22950.00,1150.00,-21800.00,-22600.00,800.00,220.71 +-22000.00,-22350.00,350.00,-22000.00,-22200.00,200.00,221.00 +-22200.00,-22650.00,450.00,-22200.00,-22200.00,0.00,221.13 +-22400.00,-22850.00,450.00,-22400.00,-22500.00,100.00,220.68 +-22600.00,-23450.00,850.00,-22600.00,-22700.00,100.00,220.68 +-22800.00,-23500.00,700.00,-22800.00,-23050.00,250.00,221.56 +-23000.00,-24650.00,1650.00,-23000.00,-24000.00,1000.00,221.36 +-23200.00,-24750.00,1550.00,-23200.00,-24200.00,1000.00,221.33 +-23400.00,-24000.00,600.00,-23334.14,-23250.00,-84.14,221.33 +-23600.00,-25100.00,1500.00,-23134.14,-24200.00,1065.86,221.70 +-23723.05,-25250.00,1526.95,-22934.14,-24300.00,1365.86,221.14 +-23523.05,-24500.00,976.95,-22734.14,-23450.00,715.86,220.94 +-23323.05,-24800.00,1476.95,-22534.14,-23250.00,715.86,220.94 +-23123.05,-24650.00,1526.95,-22334.14,-23150.00,815.86,221.25 +-22923.05,-24750.00,1826.95,-22134.14,-23150.00,1015.86,220.90 +-22723.05,-25400.00,2676.95,-21934.14,-23900.00,1965.86,220.90 +-22523.05,-24500.00,1976.95,-21734.14,-22900.00,1165.86,220.55 +-22323.05,-23750.00,1426.95,-21534.14,-22450.00,915.86,220.64 +-22123.05,-23650.00,1526.95,-21334.14,-22200.00,865.86,220.79 +-21923.05,-23450.00,1526.95,-21134.14,-22050.00,915.86,220.79 +-21723.05,-23350.00,1626.95,-20934.14,-21900.00,965.86,220.73 +-21523.05,-23250.00,1726.95,-20734.14,-21600.00,865.86,220.30 +-21323.05,-22950.00,1626.95,-20534.14,-21500.00,965.86,220.37 +-21123.05,-22750.00,1626.95,-20334.14,-21500.00,1165.86,220.37 +-20923.05,-23100.00,2176.95,-20134.14,-22000.00,1865.86,220.46 +-20723.05,-22250.00,1526.95,-19934.14,-21000.00,1065.86,220.55 +-20523.05,-21600.00,1076.95,-19734.14,-20600.00,865.86,220.55 +-20323.05,-21700.00,1376.95,-19534.14,-20500.00,965.86,220.64 +-20123.05,-21600.00,1476.95,-19334.14,-20350.00,1015.86,220.78 +-19923.05,-21400.00,1476.95,-19134.14,-20250.00,1115.86,221.21 +-19723.05,-21400.00,1676.95,-18934.14,-20050.00,1115.86,221.21 +-19523.05,-21150.00,1626.95,-18734.14,-19700.00,965.86,220.91 +-19323.05,-20800.00,1476.95,-18534.14,-19400.00,865.86,220.73 +-19123.05,-20650.00,1526.95,-18334.14,-19150.00,815.86,220.78 +-18923.05,-20450.00,1526.95,-18134.14,-18900.00,765.86,220.78 +-18723.05,-20300.00,1576.95,-17934.14,-18750.00,815.86,221.03 +-18523.05,-20100.00,1576.95,-17734.14,-18400.00,665.86,220.85 +-18323.05,-19850.00,1526.95,-17534.14,-18150.00,615.86,220.85 +-18123.05,-23000.00,4876.95,-17334.14,-20850.00,3515.86,220.95 +-17923.05,-19100.00,1176.95,-17134.14,-17350.00,215.86,220.85 +-17723.05,-18200.00,476.95,-16934.14,-16750.00,-184.14,220.65 +-17523.05,-18350.00,826.95,-16734.14,-16650.00,-84.14,220.65 +-17323.05,-18350.00,1026.95,-16534.14,-16800.00,265.86,220.96 +-17123.05,-18250.00,1126.95,-16334.14,-16850.00,515.86,220.90 +-16923.05,-18050.00,1126.95,-16134.14,-16750.00,615.86,220.94 +-16723.05,-17950.00,1226.95,-15934.14,-16400.00,465.86,220.94 +-16523.05,-17750.00,1226.95,-15734.14,-16200.00,465.86,220.76 +-16323.05,-17350.00,1026.95,-15534.14,-16000.00,465.86,220.88 +-16123.05,-17150.00,1026.95,-15334.14,-15800.00,465.86,220.99 +-15923.05,-16950.00,1026.95,-15134.14,-15750.00,615.86,220.99 +-15723.05,-16800.00,1076.95,-14934.14,-15400.00,465.86,220.43 +-15523.05,-16550.00,1026.95,-14734.14,-15050.00,315.86,220.59 +-15323.05,-16300.00,976.95,-14534.14,-14800.00,265.86,220.59 +-15123.05,-16100.00,976.95,-14334.14,-14750.00,415.86,220.59 +-14923.05,-15950.00,1026.95,-14134.14,-14450.00,315.86,220.63 +-14723.05,-15550.00,826.95,-13934.14,-14300.00,365.86,220.95 +-14523.05,-15400.00,876.95,-13734.14,-14050.00,315.86,220.95 +-14323.05,-15100.00,776.95,-13534.14,-13850.00,315.86,220.70 +-14123.05,-14850.00,726.95,-13334.14,-13600.00,265.86,220.80 +-13923.05,-14750.00,826.95,-13134.14,-13400.00,265.86,221.13 +-13723.05,-14450.00,726.95,-12934.14,-13300.00,365.86,221.13 +-13523.05,-14350.00,826.95,-12734.14,-13150.00,415.86,220.94 +-13323.05,-13500.00,176.95,-12534.14,-12500.00,-34.14,221.28 +-13123.05,-13900.00,776.95,-12334.14,-12800.00,465.86,221.28 +-12923.05,-13900.00,976.95,-12134.14,-12600.00,465.86,220.79 +-12723.05,-13500.00,776.95,-11934.14,-12350.00,415.86,221.00 +-12523.05,-13300.00,776.95,-11734.14,-12000.00,265.86,221.05 +-12323.05,-13100.00,776.95,-11534.14,-11850.00,315.86,221.05 +-12123.05,-12450.00,326.95,-11334.14,-11250.00,-84.14,221.04 +-11923.05,-12700.00,776.95,-11134.14,-11400.00,265.86,221.05 +-11723.05,-12600.00,876.95,-10934.14,-11100.00,165.86,221.05 +-11523.05,-12300.00,776.95,-10734.14,-10900.00,165.86,221.30 +-11323.05,-12050.00,726.95,-10534.14,-10700.00,165.86,221.74 +-11123.05,-11850.00,726.95,-10334.14,-10350.00,15.86,221.96 +-10923.05,-11550.00,626.95,-10134.14,-10150.00,15.86,221.96 +-10723.05,-11350.00,626.95,-9934.14,-9850.00,-84.14,221.04 +-10523.05,-10650.00,126.95,-9734.14,-9300.00,-434.14,221.56 +-10323.05,-8950.00,-1373.05,-9534.14,-7650.00,-1884.14,221.56 +-10123.05,-9650.00,-473.05,-9334.14,-8400.00,-934.14,221.69 +-9923.05,-9800.00,-123.05,-9134.14,-8500.00,-634.14,221.60 +-9723.05,-9600.00,-123.05,-8934.14,-8250.00,-684.14,221.72 +-9523.05,-7950.00,-1573.05,-8734.14,-6800.00,-1934.14,221.72 +-9323.05,-7100.00,-2223.05,-8534.14,-5700.00,-2834.14,221.74 +-9123.05,-7700.00,-1423.05,-8334.14,-6250.00,-2084.14,221.14 +-8923.05,-8550.00,-373.05,-8134.14,-7050.00,-1084.14,221.57 +-8723.05,-8300.00,-423.05,-7934.14,-6650.00,-1284.14,221.57 +-8523.05,-7150.00,-1373.05,-7734.14,-5800.00,-1934.14,221.55 +-8323.05,-6600.00,-1723.05,-7534.14,-5000.00,-2534.14,221.78 +-8123.05,-6900.00,-1223.05,-7334.14,-5150.00,-2184.14,221.78 +-7923.05,-6950.00,-973.05,-7134.14,-5500.00,-1634.14,221.27 +-7723.05,-5750.00,-1973.05,-6934.14,-5550.00,-1384.14,221.92 +-7523.05,-5450.00,-2073.05,-6734.14,-4550.00,-2184.14,221.34 +-7323.05,-5800.00,-1523.05,-6534.14,-3250.00,-3284.14,221.34 +-7123.05,-5750.00,-1373.05,-6334.14,-2450.00,-3884.14,221.06 +-6923.05,-4950.00,-1973.05,-6134.14,-3500.00,-2634.14,221.21 +-6723.05,-3900.00,-2823.05,-5934.14,-4100.00,-1834.14,221.21 +-6523.05,-3850.00,-2673.05,-5734.14,-3000.00,-2734.14,221.75 +-6323.05,-4150.00,-2173.05,-5534.14,-1850.00,-3684.14,221.41 +-6123.05,-2850.00,-3273.05,-5334.14,-1900.00,-3434.14,222.11 +-5923.05,-2850.00,-3073.05,-5134.14,-1950.00,-3184.14,222.11 +-5723.05,-3100.00,-2623.05,-4934.14,-1350.00,-3584.14,221.27 +-5523.05,-2350.00,-3173.05,-4734.14,350.00,-5084.14,221.04 +-5323.05,-850.00,-4473.05,-4534.14,-300.00,-4234.14,221.04 +-5123.05,-1300.00,-3823.05,-4334.14,-500.00,-3834.14,221.31 +-4923.05,-2200.00,-2723.05,-4134.14,750.00,-4884.14,220.41 +-4723.05,-1850.00,-2873.05,-3934.14,-100.00,-3834.14,220.81 +-4523.05,-300.00,-4223.05,-3734.14,-650.00,-3084.14,220.81 +-4323.05,950.00,-5273.05,-3534.14,900.00,-4434.14,220.67 +-4123.05,-750.00,-3373.05,-3334.14,200.00,-3534.14,219.77 +-3923.05,-1000.00,-2923.05,-3134.14,-50.00,-3084.14,220.88 +-3723.05,0.00,-3723.05,-2934.14,0.00,-2934.14,220.88 +-3523.05,50.00,-3573.05,-2734.14,0.00,-2734.14,220.98 +-3323.05,0.00,-3323.05,-2534.14,0.00,-2534.14,220.92 +-3123.05,0.00,-3123.05,-2334.14,0.00,-2334.14,220.92 +-2923.05,0.00,-2923.05,-2134.14,0.00,-2134.14,220.88 +-2723.05,0.00,-2723.05,-1934.14,0.00,-1934.14,221.08 +-2523.05,0.00,-2523.05,-1734.14,0.00,-1734.14,221.25 +-2323.05,0.00,-2323.05,-1534.14,0.00,-1534.14,221.25 +-2123.05,0.00,-2123.05,-1334.14,0.00,-1334.14,221.05 +-1923.05,0.00,-1923.05,-1134.14,0.00,-1134.14,221.02 +-1723.05,0.00,-1723.05,-934.14,0.00,-934.14,221.02 +-1523.05,0.00,-1523.05,-734.14,0.00,-734.14,220.87 +-1323.05,0.00,-1323.05,-534.14,0.00,-534.14,220.39 +-1123.05,0.00,-1123.05,-334.14,0.00,-334.14,220.39 +-923.05,0.00,-923.05,-134.14,0.00,-134.14,220.99 +-723.05,0.00,-723.05,0.00,0.00,0.00,220.82 +-523.05,0.00,-523.05,0.00,0.00,0.00,221.14 +-323.05,0.00,-323.05,0.00,0.00,0.00,221.14 +-123.05,0.00,-123.05,0.00,0.00,0.00,221.06 +0.00,0.00,0.00,0.00,0.00,0.00,220.87 +0.00,0.00,0.00,0.00,0.00,0.00,220.87 +0.00,0.00,0.00,0.00,0.00,0.00,220.54 +0.00,0.00,0.00,0.00,0.00,0.00,221.22 +0.00,0.00,0.00,0.00,0.00,0.00,221.22 +0.00,0.00,0.00,0.00,0.00,0.00,221.18 +0.00,0.00,0.00,0.00,0.00,0.00,220.86 +0.00,0.00,0.00,0.00,0.00,0.00,220.86 +0.00,0.00,0.00,0.00,0.00,0.00,220.45 +0.00,0.00,0.00,0.00,0.00,0.00,220.94 +0.00,0.00,0.00,0.00,0.00,0.00,220.94 +0.00,0.00,0.00,0.00,0.00,0.00,220.68 +0.00,0.00,0.00,0.00,0.00,0.00,220.62 +0.00,0.00,0.00,0.00,0.00,0.00,220.66 +0.00,0.00,0.00,0.00,0.00,0.00,220.66 +0.00,0.00,0.00,0.00,0.00,0.00,220.36 +0.00,0.00,0.00,0.00,0.00,0.00,220.26 +0.00,0.00,0.00,0.00,0.00,0.00,220.26 +0.00,0.00,0.00,0.00,0.00,0.00,220.65 +0.00,0.00,0.00,0.00,0.00,0.00,220.80 +0.00,0.00,0.00,0.00,0.00,0.00,220.80 +0.00,0.00,0.00,0.00,0.00,0.00,220.35 +0.00,0.00,0.00,0.00,0.00,0.00,220.46 +0.00,0.00,0.00,0.00,0.00,0.00,220.69 +0.00,0.00,0.00,0.00,0.00,0.00,220.69 +0.00,0.00,0.00,0.00,0.00,0.00,220.78 +0.00,0.00,0.00,0.00,0.00,0.00,220.50 +0.00,0.00,0.00,0.00,0.00,0.00,220.50 +0.00,0.00,0.00,0.00,0.00,0.00,220.88 +0.00,0.00,0.00,0.00,0.00,0.00,220.90 +0.00,0.00,0.00,0.00,0.00,0.00,220.90 +0.00,0.00,0.00,0.00,0.00,0.00,220.95 +0.00,0.00,0.00,0.00,0.00,0.00,221.08 +0.00,0.00,0.00,0.00,0.00,0.00,221.08 +0.00,0.00,0.00,0.00,0.00,0.00,221.06 +0.00,0.00,0.00,0.00,0.00,0.00,220.44 +0.00,0.00,0.00,0.00,0.00,0.00,220.62 +0.00,0.00,0.00,0.00,0.00,0.00,220.62 +0.00,0.00,0.00,0.00,0.00,0.00,220.60 +0.00,0.00,0.00,0.00,0.00,0.00,220.66 +0.00,0.00,0.00,0.00,0.00,0.00,220.66 +0.00,0.00,0.00,0.00,0.00,0.00,220.40 +0.00,0.00,0.00,0.00,0.00,0.00,221.17 +0.00,0.00,0.00,0.00,0.00,0.00,221.17 +0.00,0.00,0.00,0.00,0.00,0.00,220.69 +0.00,0.00,0.00,0.00,0.00,0.00,220.99 +0.00,0.00,0.00,0.00,0.00,0.00,220.99 +0.00,0.00,0.00,0.00,0.00,0.00,220.95 +0.00,0.00,0.00,0.00,0.00,0.00,220.54 +0.00,0.00,0.00,0.00,0.00,0.00,220.62 +0.00,0.00,0.00,0.00,0.00,0.00,220.62 +0.00,0.00,0.00,0.00,0.00,0.00,220.87 +0.00,0.00,0.00,0.00,0.00,0.00,220.73 +0.00,0.00,0.00,0.00,0.00,0.00,220.73 +0.00,0.00,0.00,0.00,0.00,0.00,220.82 +0.00,0.00,0.00,0.00,0.00,0.00,220.81 +0.00,0.00,0.00,0.00,0.00,0.00,221.15 +0.00,0.00,0.00,0.00,0.00,0.00,221.15 +0.00,0.00,0.00,0.00,0.00,0.00,221.08 +0.00,0.00,0.00,0.00,0.00,0.00,220.86 +0.00,0.00,0.00,0.00,0.00,0.00,220.86 +0.00,0.00,0.00,0.00,0.00,0.00,220.94 +0.00,0.00,0.00,0.00,0.00,0.00,221.10 +0.00,0.00,0.00,0.00,0.00,0.00,221.10 +0.00,0.00,0.00,0.00,0.00,0.00,220.86 +0.00,0.00,0.00,0.00,0.00,0.00,220.85 +0.00,0.00,0.00,0.00,0.00,0.00,220.85 +0.00,0.00,0.00,0.00,0.00,0.00,220.77 +0.00,0.00,0.00,0.00,0.00,0.00,220.95 +0.00,0.00,0.00,0.00,0.00,0.00,220.27 +0.00,0.00,0.00,0.00,0.00,0.00,220.27 +0.00,0.00,0.00,0.00,0.00,0.00,220.59 +0.00,0.00,0.00,0.00,0.00,0.00,220.84 +0.00,0.00,0.00,0.00,0.00,0.00,220.84 +0.00,0.00,0.00,0.00,0.00,0.00,220.88 +0.00,0.00,0.00,0.00,0.00,0.00,220.83 +0.00,0.00,0.00,0.00,0.00,0.00,220.83 +0.00,0.00,0.00,0.00,0.00,0.00,220.43 +0.00,0.00,0.00,0.00,0.00,0.00,220.42 +0.00,0.00,0.00,0.00,0.00,0.00,220.42 +0.00,0.00,0.00,0.00,0.00,0.00,220.51 +0.00,0.00,0.00,0.00,0.00,0.00,220.52 +0.00,0.00,0.00,0.00,0.00,0.00,220.58 +0.00,0.00,0.00,0.00,0.00,0.00,220.58 +0.00,0.00,0.00,0.00,0.00,0.00,220.81 +0.00,0.00,0.00,0.00,0.00,0.00,220.52 +0.00,0.00,0.00,0.00,0.00,0.00,220.52 +0.00,0.00,0.00,0.00,0.00,0.00,220.69 +0.00,0.00,0.00,0.00,0.00,0.00,220.79 +0.00,0.00,0.00,0.00,0.00,0.00,220.79 +0.00,0.00,0.00,0.00,0.00,0.00,220.19 +0.00,0.00,0.00,0.00,0.00,0.00,220.34 +0.00,0.00,0.00,0.00,0.00,0.00,220.34 +0.00,0.00,0.00,0.00,0.00,0.00,220.61 +0.00,0.00,0.00,0.00,0.00,0.00,220.90 +0.00,0.00,0.00,0.00,0.00,0.00,220.51 +0.00,0.00,0.00,0.00,0.00,0.00,220.51 +0.00,0.00,0.00,0.00,0.00,0.00,220.68 +0.00,0.00,0.00,0.00,0.00,0.00,220.87 +0.00,0.00,0.00,0.00,0.00,0.00,220.87 +0.00,0.00,0.00,0.00,0.00,0.00,221.11 +0.00,0.00,0.00,0.00,0.00,0.00,220.77 +0.00,0.00,0.00,0.00,0.00,0.00,220.77 +0.00,0.00,0.00,0.00,0.00,0.00,220.87 +0.00,0.00,0.00,0.00,0.00,0.00,220.82 +0.00,0.00,0.00,0.00,0.00,0.00,220.74 +0.00,0.00,0.00,0.00,0.00,0.00,220.74 +0.00,0.00,0.00,0.00,0.00,0.00,220.82 +0.00,0.00,0.00,0.00,0.00,0.00,221.13 +0.00,0.00,0.00,0.00,0.00,0.00,221.13 +0.00,0.00,0.00,0.00,0.00,0.00,221.15 +0.00,0.00,0.00,0.00,0.00,0.00,220.98 +0.00,0.00,0.00,0.00,0.00,0.00,220.98 +0.00,0.00,0.00,0.00,0.00,0.00,221.16 +0.00,0.00,0.00,0.00,0.00,0.00,221.10 +0.00,0.00,0.00,0.00,0.00,0.00,220.85 +0.00,0.00,0.00,0.00,0.00,0.00,220.85 +0.00,0.00,0.00,0.00,0.00,0.00,220.73 +0.00,0.00,0.00,0.00,0.00,0.00,220.54 +0.00,0.00,0.00,0.00,0.00,0.00,220.54 +0.00,0.00,0.00,0.00,0.00,0.00,220.60 +0.00,0.00,0.00,0.00,0.00,0.00,221.06 +0.00,0.00,0.00,0.00,0.00,0.00,221.06 +0.00,0.00,0.00,0.00,0.00,0.00,220.69 +0.00,0.00,0.00,0.00,0.00,0.00,220.90 +0.00,0.00,0.00,0.00,0.00,0.00,220.84 +0.00,0.00,0.00,0.00,0.00,0.00,220.84 +0.00,0.00,0.00,0.00,0.00,0.00,220.99 +0.00,0.00,0.00,0.00,0.00,0.00,220.75 +0.00,0.00,0.00,0.00,0.00,0.00,220.75 +0.00,0.00,0.00,0.00,0.00,0.00,221.20 +0.00,0.00,0.00,0.00,0.00,0.00,220.90 +0.00,0.00,0.00,0.00,0.00,0.00,220.90 +0.00,0.00,0.00,0.00,0.00,0.00,220.78 +0.00,0.00,0.00,0.00,0.00,0.00,220.44 +0.00,0.00,0.00,0.00,0.00,0.00,220.44 +0.00,0.00,0.00,0.00,0.00,0.00,220.93 +0.00,0.00,0.00,0.00,0.00,0.00,220.63 +0.00,0.00,0.00,0.00,0.00,0.00,220.88 +0.00,0.00,0.00,0.00,0.00,0.00,220.88 +0.00,0.00,0.00,0.00,0.00,0.00,220.45 +0.00,0.00,0.00,0.00,0.00,0.00,220.23 +0.00,0.00,0.00,0.00,0.00,0.00,220.23 +0.00,0.00,0.00,0.00,0.00,0.00,220.74 +0.00,0.00,0.00,0.00,0.00,0.00,220.55 +0.00,0.00,0.00,0.00,0.00,0.00,220.55 +0.00,0.00,0.00,0.00,0.00,0.00,220.56 +0.00,0.00,0.00,0.00,0.00,0.00,220.37 +0.00,0.00,0.00,0.00,0.00,0.00,220.59 +0.00,0.00,0.00,0.00,0.00,0.00,220.59 +0.00,0.00,0.00,0.00,0.00,0.00,220.09 +0.00,0.00,0.00,0.00,0.00,0.00,220.26 +0.00,0.00,0.00,0.00,0.00,0.00,220.26 +0.00,0.00,0.00,0.00,0.00,0.00,220.21 +0.00,0.00,0.00,0.00,0.00,0.00,220.86 +0.00,0.00,0.00,0.00,0.00,0.00,220.86 +0.00,0.00,0.00,0.00,0.00,0.00,220.88 +0.00,0.00,0.00,0.00,0.00,0.00,220.56 +0.00,0.00,0.00,0.00,0.00,0.00,220.56 +0.00,0.00,0.00,0.00,0.00,0.00,220.82 +0.00,0.00,0.00,0.00,0.00,0.00,220.44 +0.00,0.00,0.00,0.00,0.00,0.00,220.72 +0.00,0.00,0.00,0.00,0.00,0.00,220.72 +0.00,0.00,0.00,0.00,0.00,0.00,220.29 +0.00,0.00,0.00,0.00,0.00,0.00,220.26 +0.00,0.00,0.00,0.00,0.00,0.00,220.26 +0.00,0.00,0.00,0.00,0.00,0.00,220.45 +0.00,0.00,0.00,0.00,0.00,0.00,220.56 +0.00,0.00,0.00,0.00,0.00,0.00,220.56 +0.00,0.00,0.00,0.00,0.00,0.00,220.30 +0.00,0.00,0.00,0.00,0.00,0.00,220.41 +0.00,0.00,0.00,0.00,0.00,0.00,221.04 +0.00,0.00,0.00,0.00,0.00,0.00,221.04 +0.00,0.00,0.00,0.00,0.00,0.00,220.58 +0.00,0.00,0.00,0.00,0.00,0.00,220.74 +0.00,0.00,0.00,0.00,0.00,0.00,220.74 +0.00,0.00,0.00,0.00,0.00,0.00,220.43 +0.00,0.00,0.00,0.00,0.00,0.00,220.70 +0.00,0.00,0.00,0.00,0.00,0.00,220.70 +0.00,0.00,0.00,0.00,0.00,0.00,220.89 +0.00,0.00,0.00,0.00,0.00,0.00,220.55 +0.00,0.00,0.00,0.00,0.00,0.00,220.55 +0.00,0.00,0.00,0.00,0.00,0.00,220.69 +0.00,0.00,0.00,0.00,0.00,0.00,220.62 +0.00,0.00,0.00,0.00,0.00,0.00,220.62 +0.00,0.00,0.00,0.00,0.00,0.00,220.42 +200.00,0.00,200.00,200.00,0.00,200.00,220.62 +400.00,0.00,400.00,400.00,0.00,400.00,220.39 +600.00,0.00,600.00,600.00,0.00,600.00,220.39 +800.00,0.00,800.00,800.00,0.00,800.00,220.65 +1000.00,0.00,1000.00,1000.00,0.00,1000.00,221.22 +1200.00,0.00,1200.00,1200.00,0.00,1200.00,221.22 +1400.00,0.00,1400.00,1400.00,0.00,1400.00,221.12 +1600.00,0.00,1600.00,1600.00,0.00,1600.00,221.23 +1800.00,0.00,1800.00,1800.00,0.00,1800.00,221.23 +2000.00,0.00,2000.00,2000.00,0.00,2000.00,220.89 +2200.00,0.00,2200.00,2200.00,0.00,2200.00,220.74 +2400.00,0.00,2400.00,2400.00,0.00,2400.00,220.55 +2600.00,0.00,2600.00,2600.00,0.00,2600.00,220.55 +2800.00,0.00,2800.00,2800.00,0.00,2800.00,220.50 +3000.00,0.00,3000.00,3000.00,0.00,3000.00,220.87 +3200.00,0.00,3200.00,3200.00,0.00,3200.00,220.87 +3400.00,0.00,3400.00,3400.00,0.00,3400.00,220.84 +3600.00,0.00,3600.00,3600.00,0.00,3600.00,220.73 +3800.00,0.00,3800.00,3800.00,0.00,3800.00,220.57 +4000.00,0.00,4000.00,4000.00,0.00,4000.00,220.57 +4200.00,0.00,4200.00,4200.00,0.00,4200.00,220.63 +4400.00,0.00,4400.00,4400.00,0.00,4400.00,220.80 +4600.00,0.00,4600.00,4600.00,0.00,4600.00,220.80 +4800.00,500.00,4300.00,4800.00,350.00,4450.00,220.97 +5000.00,2450.00,2550.00,5000.00,1050.00,3950.00,220.88 +5200.00,2850.00,2350.00,5200.00,1600.00,3600.00,220.88 +5400.00,1500.00,3900.00,5400.00,900.00,4500.00,220.68 +5600.00,2200.00,3400.00,5600.00,0.00,5600.00,219.66 +5800.00,2350.00,3450.00,5800.00,1400.00,4400.00,219.66 +6000.00,1400.00,4600.00,6000.00,3100.00,2900.00,220.45 +6200.00,2800.00,3400.00,6200.00,3250.00,2950.00,221.57 +6400.00,4050.00,2350.00,6400.00,2350.00,4050.00,221.57 +6600.00,4500.00,2100.00,6600.00,1600.00,5000.00,220.62 +6800.00,3400.00,3400.00,6800.00,3100.00,3700.00,220.53 +7000.00,3200.00,3800.00,7000.00,4600.00,2400.00,221.47 +7200.00,4150.00,3050.00,7200.00,4600.00,2600.00,221.47 +7400.00,5050.00,2350.00,7400.00,3950.00,3450.00,221.32 +7600.00,5750.00,1850.00,7600.00,4450.00,3150.00,220.87 +7800.00,5550.00,2250.00,7800.00,5000.00,2800.00,220.87 +8000.00,4850.00,3150.00,8000.00,5400.00,2600.00,221.20 +8200.00,5800.00,2400.00,8200.00,5750.00,2450.00,221.05 +8400.00,6200.00,2200.00,8400.00,6050.00,2350.00,221.05 +8600.00,6650.00,1950.00,8600.00,6350.00,2250.00,221.17 +8800.00,7350.00,1450.00,8800.00,6800.00,2000.00,221.22 +9000.00,7650.00,1350.00,9000.00,7050.00,1950.00,221.22 +9200.00,7650.00,1550.00,9200.00,7050.00,2150.00,220.66 +9400.00,7850.00,1550.00,9400.00,7350.00,2050.00,220.78 +9600.00,8100.00,1500.00,9600.00,7650.00,1950.00,220.78 +9800.00,8350.00,1450.00,9800.00,7950.00,1850.00,221.04 +10000.00,8550.00,1450.00,10000.00,8100.00,1900.00,221.34 +10200.00,9050.00,1150.00,10200.00,8700.00,1500.00,221.21 +10400.00,8950.00,1450.00,10400.00,8600.00,1800.00,221.21 +10600.00,9450.00,1150.00,10600.00,9150.00,1450.00,221.46 +10800.00,9700.00,1100.00,10800.00,9350.00,1450.00,220.90 +11000.00,9950.00,1050.00,11000.00,9500.00,1500.00,220.90 +11200.00,10100.00,1100.00,11200.00,9800.00,1400.00,221.04 +11400.00,10300.00,1100.00,11400.00,9900.00,1500.00,221.39 +11600.00,10450.00,1150.00,11600.00,10150.00,1450.00,221.39 +11800.00,10750.00,1050.00,11800.00,10350.00,1450.00,221.18 +12000.00,10950.00,1050.00,12000.00,10600.00,1400.00,221.05 +12200.00,11300.00,900.00,12200.00,10900.00,1300.00,221.05 +12400.00,11550.00,850.00,12400.00,11050.00,1350.00,220.65 +12600.00,11800.00,800.00,12600.00,11250.00,1350.00,220.93 +12800.00,12100.00,700.00,12800.00,11700.00,1100.00,220.94 +13000.00,12300.00,700.00,13000.00,11850.00,1150.00,220.94 +13200.00,12450.00,750.00,13200.00,11900.00,1300.00,221.15 +13400.00,12650.00,750.00,13400.00,12100.00,1300.00,220.63 +13600.00,12950.00,650.00,13600.00,12350.00,1250.00,220.63 +13800.00,13200.00,600.00,13800.00,12650.00,1150.00,221.14 +14000.00,13350.00,650.00,14000.00,12750.00,1250.00,220.89 +14200.00,13650.00,550.00,14200.00,12950.00,1250.00,220.89 +14400.00,13950.00,450.00,14400.00,13150.00,1250.00,221.05 +14600.00,14050.00,550.00,14600.00,13450.00,1150.00,220.88 +14800.00,14300.00,500.00,14800.00,13600.00,1200.00,220.85 +15000.00,14550.00,450.00,15000.00,13750.00,1250.00,220.85 +15200.00,14800.00,400.00,15200.00,13900.00,1300.00,220.83 +15400.00,15000.00,400.00,15400.00,14200.00,1200.00,220.77 +15600.00,15300.00,300.00,15600.00,14500.00,1100.00,220.77 +15800.00,15550.00,250.00,15800.00,14750.00,1050.00,220.86 +16000.00,15750.00,250.00,16000.00,15000.00,1000.00,221.00 +16200.00,16550.00,-350.00,16200.00,15800.00,400.00,220.55 +16400.00,19700.00,-3300.00,16400.00,18850.00,-2450.00,220.55 +16600.00,16600.00,0.00,16600.00,16200.00,400.00,220.60 +16800.00,16050.00,750.00,16800.00,15750.00,1050.00,220.80 +17000.00,16100.00,900.00,17000.00,15600.00,1400.00,220.71 +17200.00,16550.00,650.00,17200.00,16100.00,1100.00,220.71 +17400.00,16850.00,550.00,17400.00,16500.00,900.00,220.92 +17600.00,17250.00,350.00,17600.00,16900.00,700.00,220.99 +17800.00,17450.00,350.00,17800.00,17200.00,600.00,220.99 +18000.00,17750.00,250.00,18000.00,17450.00,550.00,221.58 +18200.00,17950.00,250.00,18200.00,17700.00,500.00,221.40 +18400.00,18800.00,-400.00,18400.00,18600.00,-200.00,221.40 +18600.00,18350.00,250.00,18600.00,18000.00,600.00,221.31 +18800.00,19100.00,-300.00,18800.00,19000.00,-200.00,221.49 +19000.00,19400.00,-400.00,19000.00,19150.00,-150.00,221.72 +19200.00,18850.00,350.00,19200.00,18400.00,800.00,221.72 +19400.00,19600.00,-200.00,19400.00,19550.00,-150.00,221.62 +19600.00,19900.00,-300.00,19600.00,19700.00,-100.00,221.66 +19800.00,20100.00,-300.00,19800.00,19900.00,-100.00,220.94 +20000.00,20150.00,-150.00,20000.00,20000.00,0.00,220.94 +20200.00,20450.00,-250.00,20200.00,20000.00,200.00,221.49 +20400.00,20600.00,-200.00,20400.00,20300.00,100.00,220.95 +20600.00,20900.00,-300.00,20600.00,20450.00,150.00,220.95 +20800.00,21150.00,-350.00,20800.00,20450.00,350.00,221.12 +21000.00,21400.00,-400.00,21000.00,20900.00,100.00,221.24 +21200.00,21800.00,-600.00,21200.00,21100.00,100.00,221.17 +21400.00,21800.00,-400.00,21400.00,21300.00,100.00,221.17 +21600.00,22100.00,-500.00,21600.00,21600.00,0.00,220.86 +21800.00,21650.00,150.00,21800.00,21400.00,400.00,220.87 +22000.00,22800.00,-800.00,22000.00,22350.00,-350.00,220.87 +22200.00,23250.00,-1050.00,22200.00,22650.00,-450.00,220.88 +22400.00,23050.00,-650.00,22400.00,22450.00,-50.00,221.11 +22600.00,23300.00,-700.00,22600.00,22900.00,-300.00,221.20 +22800.00,23300.00,-500.00,22800.00,23200.00,-400.00,221.20 +23000.00,23700.00,-700.00,23000.00,23350.00,-350.00,220.83 +23200.00,23850.00,-650.00,23200.00,23600.00,-400.00,221.40 +23400.00,24050.00,-650.00,23400.00,23750.00,-350.00,221.28 +23600.00,24200.00,-600.00,23388.51,23850.00,-461.49,221.28 +23800.00,24450.00,-650.00,23188.51,24200.00,-1011.49,221.48 +23786.61,24600.00,-813.39,22988.51,24300.00,-1311.49,221.53 +23586.61,24850.00,-1263.39,22788.51,24200.00,-1411.49,221.53 +23386.61,24600.00,-1213.39,22588.51,24050.00,-1461.49,221.35 +23186.61,24500.00,-1313.39,22388.51,23950.00,-1561.49,221.55 +22986.61,24450.00,-1463.39,22188.51,23700.00,-1511.49,221.79 +22786.61,24500.00,-1713.39,21988.51,23350.00,-1361.49,221.79 +22586.61,24200.00,-1613.39,21788.51,23150.00,-1361.49,221.66 +22386.61,23850.00,-1463.39,21588.51,22900.00,-1311.49,221.51 +22186.61,23850.00,-1663.39,21388.51,22700.00,-1311.49,221.45 +21986.61,23650.00,-1663.39,21188.51,22350.00,-1161.49,221.45 +21786.61,23300.00,-1513.39,20988.51,22050.00,-1061.49,221.13 +21586.61,23150.00,-1563.39,20788.51,21850.00,-1061.49,221.44 +21386.61,23000.00,-1613.39,20588.51,21700.00,-1111.49,221.44 +21186.61,22600.00,-1413.39,20388.51,21250.00,-861.49,220.83 +20986.61,22550.00,-1563.39,20188.51,21200.00,-1011.49,220.90 +20786.61,21650.00,-863.39,19988.51,20200.00,-211.49,221.04 +20586.61,22250.00,-1663.39,19788.51,20850.00,-1061.49,221.04 +20386.61,22300.00,-1913.39,19588.51,20750.00,-1161.49,220.68 +20186.61,21950.00,-1763.39,19388.51,20600.00,-1211.49,220.92 +19986.61,21550.00,-1563.39,19188.51,19900.00,-711.49,220.92 +19786.61,21100.00,-1313.39,18988.51,20100.00,-1111.49,220.48 +19586.61,21050.00,-1463.39,18788.51,19800.00,-1011.49,220.80 +19386.61,20850.00,-1463.39,18588.51,19400.00,-811.49,221.40 +19186.61,20650.00,-1463.39,18388.51,19400.00,-1011.49,221.40 +18986.61,20150.00,-1163.39,18188.51,19000.00,-811.49,221.43 +18786.61,19400.00,-613.39,17988.51,18200.00,-211.49,221.80 +18586.61,19850.00,-1263.39,17788.51,18750.00,-961.49,221.62 +18386.61,19700.00,-1313.39,17588.51,18400.00,-811.49,221.62 +18186.61,18850.00,-663.39,17388.51,17700.00,-311.49,221.84 +17986.61,19250.00,-1263.39,17188.51,18100.00,-911.49,221.58 +17786.61,19200.00,-1413.39,16988.51,17750.00,-761.49,221.58 +17586.61,18800.00,-1213.39,16788.51,17700.00,-911.49,221.39 +17386.61,21600.00,-4213.39,16588.51,19900.00,-3311.49,221.62 +17186.61,17900.00,-713.39,16388.51,16800.00,-411.49,221.36 +16986.61,16600.00,386.61,16188.51,15500.00,688.51,221.36 +16786.61,16750.00,36.61,15988.51,15400.00,588.51,221.73 +16586.61,17550.00,-963.39,15788.51,16250.00,-461.49,221.70 +16386.61,17550.00,-1163.39,15588.51,16350.00,-761.49,221.37 +16186.61,17400.00,-1213.39,15388.51,16100.00,-711.49,221.37 +15986.61,16550.00,-563.39,15188.51,15250.00,-61.49,221.18 +15786.61,16850.00,-1063.39,14988.51,15650.00,-661.49,221.37 +15586.61,16750.00,-1163.39,14788.51,15350.00,-561.49,221.37 +15386.61,16000.00,-613.39,14588.51,14600.00,-11.49,221.21 +15186.61,16300.00,-1113.39,14388.51,14850.00,-461.49,221.13 +14986.61,16100.00,-1113.39,14188.51,14600.00,-411.49,220.88 +14786.61,15400.00,-613.39,13988.51,13900.00,88.51,220.88 +14586.61,15700.00,-1113.39,13788.51,14100.00,-311.49,220.58 +14386.61,15550.00,-1163.39,13588.51,13950.00,-361.49,220.36 +14186.61,14800.00,-613.39,13388.51,13200.00,188.51,220.36 +13986.61,14550.00,-563.39,13188.51,13000.00,188.51,220.37 +13786.61,14400.00,-613.39,12988.51,12850.00,138.51,220.65 +13586.61,14750.00,-1163.39,12788.51,13150.00,-361.49,220.77 +13386.61,14450.00,-1063.39,12588.51,12850.00,-261.49,220.77 +13186.61,13550.00,-363.39,12388.51,12150.00,238.51,220.46 +12986.61,13400.00,-413.39,12188.51,11950.00,238.51,220.81 +12786.61,13400.00,-613.39,11988.51,11800.00,188.51,220.81 +12586.61,13250.00,-663.39,11788.51,11600.00,188.51,220.20 +12386.61,12850.00,-463.39,11588.51,11450.00,138.51,220.73 +12186.61,12650.00,-463.39,11388.51,11250.00,138.51,220.73 +11986.61,12550.00,-563.39,11188.51,11150.00,38.51,220.51 +11786.61,12150.00,-363.39,10988.51,10850.00,138.51,220.91 +11586.61,11900.00,-313.39,10788.51,10550.00,238.51,221.04 +11386.61,11800.00,-413.39,10588.51,10300.00,288.51,221.04 +11186.61,11700.00,-513.39,10388.51,10150.00,238.51,220.83 +10986.61,11300.00,-313.39,10188.51,9900.00,288.51,221.14 +10786.61,11450.00,-663.39,9988.51,10000.00,-11.49,221.14 +10586.61,10650.00,-63.39,9788.51,9400.00,388.51,221.26 +10386.61,8800.00,1586.61,9588.51,7700.00,1888.51,221.43 +10186.61,9150.00,1036.61,9388.51,8150.00,1238.51,221.33 +9986.61,9400.00,586.61,9188.51,8100.00,1088.51,221.33 +9786.61,9500.00,286.61,8988.51,8350.00,638.51,221.18 +9586.61,9200.00,386.61,8788.51,7700.00,1088.51,221.62 +9386.61,8950.00,436.61,8588.51,6900.00,1688.51,221.62 +9186.61,7400.00,1786.61,8388.51,7300.00,1088.51,221.43 +8986.61,6400.00,2586.61,8188.51,6350.00,1838.51,221.05 +8786.61,7250.00,1536.61,7988.51,6100.00,1888.51,221.05 +8586.61,7550.00,1036.61,7788.51,6450.00,1338.51,221.44 +8386.61,7750.00,636.61,7588.51,6200.00,1388.51,221.30 +8186.61,6450.00,1736.61,7388.51,5100.00,2288.51,221.30 +7986.61,5950.00,2036.61,7188.51,4700.00,2488.51,221.44 +7786.61,6250.00,1536.61,6988.51,5200.00,1788.51,221.57 +7586.61,6350.00,1236.61,6788.51,5000.00,1788.51,221.36 +7386.61,5100.00,2286.61,6588.51,3900.00,2688.51,221.36 +7186.61,4950.00,2236.61,6388.51,3050.00,3338.51,221.68 +6986.61,4950.00,2036.61,6188.51,2900.00,3288.51,221.59 +6786.61,3800.00,2986.61,5988.51,3550.00,2438.51,221.59 +6586.61,3600.00,2986.61,5788.51,3700.00,2088.51,221.69 +6386.61,4500.00,1886.61,5588.51,2800.00,2788.51,221.60 +6186.61,4550.00,1636.61,5388.51,2050.00,3338.51,221.60 +5986.61,3850.00,2136.61,5188.51,450.00,4738.51,221.56 +5786.61,3000.00,2786.61,4988.51,200.00,4788.51,221.93 +5586.61,2300.00,3286.61,4788.51,2400.00,2388.51,221.93 +5386.61,1000.00,4386.61,4588.51,2700.00,1888.51,221.02 +5186.61,650.00,4536.61,4388.51,1800.00,2588.51,222.40 +4986.61,2550.00,2436.61,4188.51,1300.00,2888.51,222.40 +4786.61,3250.00,1536.61,3988.51,1050.00,2938.51,221.88 +4586.61,2650.00,1936.61,3788.51,-600.00,4388.51,221.71 +4386.61,1050.00,3336.61,3588.51,-150.00,3738.51,221.98 +4186.61,650.00,3536.61,3388.51,0.00,3388.51,221.98 +3986.61,1050.00,2936.61,3188.51,0.00,3188.51,221.31 +3786.61,100.00,3686.61,2988.51,0.00,2988.51,220.91 +3586.61,-100.00,3686.61,2788.51,0.00,2788.51,220.91 +3386.61,0.00,3386.61,2588.51,0.00,2588.51,221.35 +3186.61,0.00,3186.61,2388.51,0.00,2388.51,220.72 +2986.61,0.00,2986.61,2188.51,0.00,2188.51,220.62 +2786.61,0.00,2786.61,1988.51,0.00,1988.51,220.62 +2586.61,0.00,2586.61,1788.51,0.00,1788.51,220.88 +2386.61,0.00,2386.61,1588.51,0.00,1588.51,221.06 +2186.61,0.00,2186.61,1388.51,0.00,1388.51,221.06 +1986.61,0.00,1986.61,1188.51,0.00,1188.51,220.99 +1786.61,0.00,1786.61,988.51,0.00,988.51,220.77 +1586.61,0.00,1586.61,788.51,0.00,788.51,220.77 +1386.61,0.00,1386.61,588.51,0.00,588.51,220.73 +1186.61,0.00,1186.61,388.51,0.00,388.51,220.52 +986.61,0.00,986.61,188.51,0.00,188.51,220.52 +786.61,0.00,786.61,0.00,0.00,0.00,220.94 +586.61,0.00,586.61,0.00,0.00,0.00,221.05 +386.61,0.00,386.61,0.00,0.00,0.00,221.20 +186.61,0.00,186.61,0.00,0.00,0.00,221.20 +0.00,0.00,0.00,0.00,0.00,0.00,221.03 +0.00,0.00,0.00,0.00,0.00,0.00,221.16 +0.00,0.00,0.00,0.00,0.00,0.00,221.16 +0.00,0.00,0.00,0.00,0.00,0.00,220.68 +0.00,0.00,0.00,0.00,0.00,0.00,221.08 +0.00,0.00,0.00,0.00,0.00,0.00,221.08 +0.00,0.00,0.00,0.00,0.00,0.00,220.48 +0.00,0.00,0.00,0.00,0.00,0.00,220.21 +0.00,0.00,0.00,0.00,0.00,0.00,220.21 +0.00,0.00,0.00,0.00,0.00,0.00,220.58 +0.00,0.00,0.00,0.00,0.00,0.00,220.51 +0.00,0.00,0.00,0.00,0.00,0.00,220.51 +0.00,0.00,0.00,0.00,0.00,0.00,220.60 +0.00,0.00,0.00,0.00,0.00,0.00,220.66 +0.00,0.00,0.00,0.00,0.00,0.00,220.45 +0.00,0.00,0.00,0.00,0.00,0.00,220.45 +0.00,0.00,0.00,0.00,0.00,0.00,220.25 +0.00,0.00,0.00,0.00,0.00,0.00,220.38 +0.00,0.00,0.00,0.00,0.00,0.00,220.38 +0.00,0.00,0.00,0.00,0.00,0.00,220.32 +0.00,0.00,0.00,0.00,0.00,0.00,220.39 +0.00,0.00,0.00,0.00,0.00,0.00,220.39 diff --git a/src/robot/control.cpp b/src/robot/control.cpp index 420667e..f539089 100644 --- a/src/robot/control.cpp +++ b/src/robot/control.cpp @@ -26,13 +26,14 @@ #include "robot/profiledPIDController.h" #include "robot/trapezoidalProfileNew.h" -//PLEASE ONLY USE CHESSBOT #4 FOR TESTING -TrapezoidProfile::Constraints profileConstraints(MAX_VELOCITY_TPS, MAX_ACCELERATION_TPSPS); + +// pid constants +TrapezoidProfile::Constraints profileConstraints(VELOCITY_LIMIT_TPS, ACCELERATION_LIMIT_TPSPS); TrapezoidProfile leftProfile(profileConstraints); TrapezoidProfile rightProfile(profileConstraints); TrapezoidProfile::State leftSetpoint, rightSetpoint; -PIDController encoderAVelocityController(0.00004, 0.000005, 0.00000, -1, +1); // Blue -PIDController encoderBVelocityController(0.00004, 0.000005, 0.00000, -1, +1); //Red +PIDController encoderAVelocityController(0.00002, 0.000000, 0.00000, -1, +1); // Blue +PIDController encoderBVelocityController(0.00002, 0.000000, 0.00000, -1, +1); //Red //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; @@ -269,8 +270,8 @@ void controlLoop(int loopDelayMs, int8_t framesUntilPrint) { prevPositionA = currentPositionEncoderA; prevPositionB = currentPositionEncoderB; - double leftFeedForward = leftSetpoint.velocity / MAX_VELOCITY_TPS; - double rightFeedForward = rightSetpoint.velocity / MAX_VELOCITY_TPS; + double leftFeedForward = leftSetpoint.velocity / THEORETICAL_MAX_VELOCITY_TPS; + double rightFeedForward = rightSetpoint.velocity / THEORETICAL_MAX_VELOCITY_TPS; double leftMotorPower = encoderAVelocityController.Compute(leftSetpoint.velocity, currentVelocityA, loopDelaySeconds) + leftFeedForward; double rightMotorPower = encoderBVelocityController.Compute(rightSetpoint.velocity, currentVelocityB, loopDelaySeconds) + rightFeedForward; diff --git a/src/utils/config.cpp b/src/utils/config.cpp index 6049e39..7929814 100644 --- a/src/utils/config.cpp +++ b/src/utils/config.cpp @@ -37,8 +37,10 @@ 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 = 63000; +float THEORETICAL_MAX_ACCELERATION_TPSPS = 16000; +float VELOCITY_LIMIT_TPS = 40000; +float ACCELERATION_LIMIT_TPSPS = 10000; float TILES_TO_TICKS = 2*12*TICKS_PER_ROTATION/(WHEEL_DIAMETER_INCHES*M_PI); float PID_POSITION_TOLERANCE = 100; @@ -68,8 +70,8 @@ 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"]; serialLogln("Config Set!", 2); } From d6bc7da7d22b8522c5a3aed19af65eaa7f0bdb35 Mon Sep 17 00:00:00 2001 From: democat Date: Mon, 29 Sep 2025 23:02:12 -0500 Subject: [PATCH 20/47] More tuning? --- src/robot/control.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/robot/control.cpp b/src/robot/control.cpp index f539089..e8e8dc2 100644 --- a/src/robot/control.cpp +++ b/src/robot/control.cpp @@ -32,8 +32,8 @@ TrapezoidProfile::Constraints profileConstraints(VELOCITY_LIMIT_TPS, ACCELERATIO TrapezoidProfile leftProfile(profileConstraints); TrapezoidProfile rightProfile(profileConstraints); TrapezoidProfile::State leftSetpoint, rightSetpoint; -PIDController encoderAVelocityController(0.00002, 0.000000, 0.00000, -1, +1); // Blue -PIDController encoderBVelocityController(0.00002, 0.000000, 0.00000, -1, +1); //Red +PIDController encoderAVelocityController(0.00004, 0.000000, 0.00000, -1, +1); // Blue +PIDController encoderBVelocityController(0.00004, 0.000000, 0.00000, -1, +1); //Red //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; From d24d5583a25dafe986810cebd261b123004991c2 Mon Sep 17 00:00:00 2001 From: democat Date: Mon, 29 Sep 2025 21:50:18 -0500 Subject: [PATCH 21/47] Ensure no state changes (it really didn't before anyway, might revert later) --- include/robot/trapezoidalProfileNew.h | 15 +---- src/robot/trapezoidalProfileNew.cpp | 83 +++------------------------ 2 files changed, 10 insertions(+), 88 deletions(-) diff --git a/include/robot/trapezoidalProfileNew.h b/include/robot/trapezoidalProfileNew.h index 855a180..67e551b 100644 --- a/include/robot/trapezoidalProfileNew.h +++ b/include/robot/trapezoidalProfileNew.h @@ -40,15 +40,11 @@ class TrapezoidProfile }; TrapezoidProfile(const Constraints& constraints) - : m_constraints(constraints), m_direction(1), m_endAccel(0), m_endFullSpeed(0), m_endDecel(0) {} + : m_constraints(constraints) {} State calculate(double t, const State& current, const State& goal); - double timeLeftUntil(double target); - - double totalTime() const { return m_endDecel; } - - bool isFinished(double t) const { return t >= totalTime(); } + // bool isFinished(double t) const { return t >= totalTime(); } private: static bool shouldFlipAcceleration(const State& initial, const State& goal) @@ -56,17 +52,12 @@ class TrapezoidProfile return initial.position > goal.position; } - State direct(const State& in) const + State direct(const State& in, int m_direction) const { return State(in.position * m_direction, in.velocity * m_direction); } - int m_direction; Constraints m_constraints; - State m_current; - double m_endAccel; - double m_endFullSpeed; - double m_endDecel; }; #endif \ No newline at end of file diff --git a/src/robot/trapezoidalProfileNew.cpp b/src/robot/trapezoidalProfileNew.cpp index 5a75c3c..962fe6f 100644 --- a/src/robot/trapezoidalProfileNew.cpp +++ b/src/robot/trapezoidalProfileNew.cpp @@ -2,9 +2,9 @@ TrapezoidProfile::State TrapezoidProfile::calculate(double t, const State ¤t, const State &goal) { - m_direction = shouldFlipAcceleration(current, goal) ? -1 : 1; - m_current = direct(current); - State goalDir = direct(goal); + int m_direction = shouldFlipAcceleration(current, goal) ? -1 : 1; + State m_current = direct(current, m_direction); + State goalDir = direct(goal, m_direction); if (std::abs(m_current.velocity) > m_constraints.maxVelocity) { @@ -28,9 +28,9 @@ TrapezoidProfile::State TrapezoidProfile::calculate(double t, const State &curre fullSpeedDist = 0; } - m_endAccel = accelerationTime - cutoffBegin; - m_endFullSpeed = m_endAccel + fullSpeedDist / m_constraints.maxVelocity; - m_endDecel = m_endFullSpeed + accelerationTime - cutoffEnd; + 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) @@ -57,74 +57,5 @@ TrapezoidProfile::State TrapezoidProfile::calculate(double t, const State &curre result = goalDir; } - return direct(result); + return direct(result, m_direction); } - -double TrapezoidProfile::timeLeftUntil(double target) -{ - double position = m_current.position * m_direction; - double velocity = m_current.velocity * m_direction; - - double endAccel = m_endAccel * m_direction; - double endFullSpeed = m_endFullSpeed * m_direction - endAccel; - - if (target < position) - { - endAccel = -endAccel; - endFullSpeed = -endFullSpeed; - velocity = -velocity; - } - - endAccel = std::max(endAccel, 0.0); - endFullSpeed = std::max(endFullSpeed, 0.0); - - const double acceleration = m_constraints.maxAcceleration; - const double deceleration = -m_constraints.maxAcceleration; - - double distToTarget = std::abs(target - position); - if (distToTarget < 1e-6) - { - return 0; - } - - double accelDist = velocity * endAccel + 0.5 * acceleration * endAccel * endAccel; - - double decelVelocity; - if (endAccel > 0) - { - decelVelocity = std::sqrt(std::abs(velocity * velocity + 2 * acceleration * accelDist)); - } - else - { - decelVelocity = velocity; - } - - double fullSpeedDist = m_constraints.maxVelocity * endFullSpeed; - double decelDist; - - if (accelDist > distToTarget) - { - accelDist = distToTarget; - fullSpeedDist = 0; - decelDist = 0; - } - else if (accelDist + fullSpeedDist > distToTarget) - { - fullSpeedDist = distToTarget - accelDist; - decelDist = 0; - } - else - { - decelDist = distToTarget - fullSpeedDist - accelDist; - } - - double accelTime = - (-velocity + std::sqrt(std::abs(velocity * velocity + 2 * acceleration * accelDist))) / acceleration; - - double decelTime = - (-decelVelocity + std::sqrt(std::abs(decelVelocity * decelVelocity + 2 * deceleration * decelDist))) / deceleration; - - double fullSpeedTime = fullSpeedDist / m_constraints.maxVelocity; - - return accelTime + fullSpeedTime + decelTime; -} \ No newline at end of file From c9138e0a55f15bcb2b7ad185467d1bc105e1ca72 Mon Sep 17 00:00:00 2001 From: democat Date: Mon, 29 Sep 2025 21:50:30 -0500 Subject: [PATCH 22/47] Add minimum motor power config value --- include/utils/config.h | 1 + src/robot/control.cpp | 5 ++--- src/utils/config.cpp | 2 ++ 3 files changed, 5 insertions(+), 3 deletions(-) diff --git a/include/utils/config.h b/include/utils/config.h index 743a031..803c9b3 100644 --- a/include/utils/config.h +++ b/include/utils/config.h @@ -37,6 +37,7 @@ 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 TILES_TO_TICKS; extern float PID_POSITION_TOLERANCE; diff --git a/src/robot/control.cpp b/src/robot/control.cpp index e8e8dc2..d33ef9a 100644 --- a/src/robot/control.cpp +++ b/src/robot/control.cpp @@ -559,10 +559,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; } diff --git a/src/utils/config.cpp b/src/utils/config.cpp index 7929814..2f9aebc 100644 --- a/src/utils/config.cpp +++ b/src/utils/config.cpp @@ -41,6 +41,7 @@ float THEORETICAL_MAX_VELOCITY_TPS = 63000; float THEORETICAL_MAX_ACCELERATION_TPSPS = 16000; float VELOCITY_LIMIT_TPS = 40000; float ACCELERATION_LIMIT_TPSPS = 10000; +float MIN_MOTOR_POWER = 0.12; // Minimum motor power to elicit motor response, empirically determined float TILES_TO_TICKS = 2*12*TICKS_PER_ROTATION/(WHEEL_DIAMETER_INCHES*M_PI); float PID_POSITION_TOLERANCE = 100; @@ -72,6 +73,7 @@ void setConfig(JsonObject config) { if (config["WHEEL_DIAMETER_INCHES"].is()) WHEEL_DIAMETER_INCHES = config["WHEEL_DIAMETER_INCHES"]; 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"]; serialLogln("Config Set!", 2); } From fab9398fe07e03d82670dcf6b4ce781ccd5acf9e Mon Sep 17 00:00:00 2001 From: democat Date: Mon, 29 Sep 2025 23:20:20 -0500 Subject: [PATCH 23/47] Increase BMM350 Data Rate --- src/robot/magnet.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/robot/magnet.cpp b/src/robot/magnet.cpp index 20495db..543e411 100644 --- a/src/robot/magnet.cpp +++ b/src/robot/magnet.cpp @@ -10,7 +10,7 @@ Magnet::Magnet() Wire.begin(SDA_PIN, SCL_PIN); bmm350.begin(); bmm350.setOperationMode(eBmm350NormalMode); - bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY, BMM350_DATA_RATE_25HZ); + bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY, BMM350_DATA_RATE_100HZ); bmm350.setMeasurementXYZ(); } From 4dfffb0b99e69014c700bcc4235f76de3005198b Mon Sep 17 00:00:00 2001 From: democat Date: Mon, 29 Sep 2025 23:42:21 -0500 Subject: [PATCH 24/47] Tune PID some more --- src/robot/control.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/robot/control.cpp b/src/robot/control.cpp index d33ef9a..abf3d4a 100644 --- a/src/robot/control.cpp +++ b/src/robot/control.cpp @@ -32,8 +32,8 @@ TrapezoidProfile::Constraints profileConstraints(VELOCITY_LIMIT_TPS, ACCELERATIO TrapezoidProfile leftProfile(profileConstraints); TrapezoidProfile rightProfile(profileConstraints); TrapezoidProfile::State leftSetpoint, rightSetpoint; -PIDController encoderAVelocityController(0.00004, 0.000000, 0.00000, -1, +1); // Blue -PIDController encoderBVelocityController(0.00004, 0.000000, 0.00000, -1, +1); //Red +PIDController encoderAVelocityController(0.00006, 0.000001, 0.00000, -1, +1); // Blue +PIDController encoderBVelocityController(0.00006, 0.000001, 0.00000, -1, +1); //Red //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; From 07b01f7b8f71b0b0a303a20fca121c646f5e8124 Mon Sep 17 00:00:00 2001 From: democat Date: Tue, 30 Sep 2025 01:45:13 -0500 Subject: [PATCH 25/47] comment out heading reading... looks like its blocking the main thread slightly and causing PID oscillations --- src/robot/control.cpp | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/src/robot/control.cpp b/src/robot/control.cpp index 5176834..426a0e9 100644 --- a/src/robot/control.cpp +++ b/src/robot/control.cpp @@ -35,8 +35,8 @@ TrapezoidProfile::Constraints profileConstraints(VELOCITY_LIMIT_TPS, ACCELERATIO TrapezoidProfile leftProfile(profileConstraints); TrapezoidProfile rightProfile(profileConstraints); TrapezoidProfile::State leftSetpoint, rightSetpoint; -PIDController encoderAVelocityController(0.00006, 0.000001, 0.00000, -1, +1); // Blue -PIDController encoderBVelocityController(0.00006, 0.000001, 0.00000, -1, +1); //Red +PIDController encoderAVelocityController(0.00006, 0.000000, 0.00000, -1, +1); // Blue +PIDController encoderBVelocityController(0.00006, 0.000000, 0.00000, -1, +1); //Red //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; @@ -339,8 +339,9 @@ void controlLoop(int loopDelayMs, int8_t framesUntilPrint) { serialLog(rightSetpoint.velocity - currentVelocityB, 3); serialLog(",", 3); // test magnet data - float heading = magnet->readDegrees(); - serialLogln(heading, 3); + // float heading = magnet->readDegrees(); + // serialLogln(heading, 3); + serialLogln(0, 3); #endif From 75cb0c376c8b9df438d57e009c95335e8ec5083a Mon Sep 17 00:00:00 2001 From: democat Date: Tue, 30 Sep 2025 01:45:20 -0500 Subject: [PATCH 26/47] new graph --- pid_test.csv | 1463 ++++++++++++++++++++++++++------------------------ 1 file changed, 748 insertions(+), 715 deletions(-) diff --git a/pid_test.csv b/pid_test.csv index e9dd924..71be961 100644 --- a/pid_test.csv +++ b/pid_test.csv @@ -1,716 +1,749 @@ LeftSetpoint,LeftVelocity,LeftError,RightSetpoint,RightVelocity,RightError,Heading -0.00,0.00,0.00,0.00,0.00,0.00,221.03 -0.00,0.00,0.00,0.00,0.00,0.00,221.03 -0.00,0.00,0.00,0.00,0.00,0.00,220.77 -0.00,0.00,0.00,0.00,0.00,0.00,220.63 -0.00,0.00,0.00,0.00,0.00,0.00,220.63 -0.00,0.00,0.00,0.00,0.00,0.00,221.08 -0.00,0.00,0.00,0.00,0.00,0.00,220.77 -0.00,0.00,0.00,0.00,0.00,0.00,220.77 -0.00,0.00,0.00,0.00,0.00,0.00,220.90 -0.00,0.00,0.00,0.00,0.00,0.00,220.74 -0.00,0.00,0.00,0.00,0.00,0.00,220.74 -0.00,0.00,0.00,0.00,0.00,0.00,220.86 -0.00,0.00,0.00,0.00,0.00,0.00,220.90 -0.00,0.00,0.00,0.00,0.00,0.00,220.90 -0.00,0.00,0.00,0.00,0.00,0.00,220.72 -0.00,0.00,0.00,0.00,0.00,0.00,221.12 -0.00,0.00,0.00,0.00,0.00,0.00,221.12 -0.00,0.00,0.00,0.00,0.00,0.00,221.09 -0.00,0.00,0.00,0.00,0.00,0.00,220.94 -0.00,0.00,0.00,0.00,0.00,0.00,220.92 -0.00,0.00,0.00,0.00,0.00,0.00,220.92 -0.00,0.00,0.00,0.00,0.00,0.00,221.17 -0.00,0.00,0.00,0.00,0.00,0.00,221.07 -0.00,0.00,0.00,0.00,0.00,0.00,221.07 -0.00,0.00,0.00,0.00,0.00,0.00,220.83 -0.00,0.00,0.00,0.00,0.00,0.00,220.93 -0.00,0.00,0.00,0.00,0.00,0.00,220.93 -0.00,0.00,0.00,0.00,0.00,0.00,221.38 -0.00,0.00,0.00,0.00,0.00,0.00,221.15 -0.00,0.00,0.00,0.00,0.00,0.00,220.72 -0.00,0.00,0.00,0.00,0.00,0.00,220.72 -0.00,0.00,0.00,0.00,0.00,0.00,221.12 --200.00,0.00,-200.00,-200.00,0.00,-200.00,221.16 --400.00,0.00,-400.00,-400.00,0.00,-400.00,221.16 --600.00,0.00,-600.00,-600.00,0.00,-600.00,220.43 --800.00,0.00,-800.00,-800.00,0.00,-800.00,220.85 --1000.00,0.00,-1000.00,-1000.00,0.00,-1000.00,220.85 --1200.00,0.00,-1200.00,-1200.00,0.00,-1200.00,220.83 --1400.00,0.00,-1400.00,-1400.00,0.00,-1400.00,220.95 --1600.00,0.00,-1600.00,-1600.00,0.00,-1600.00,220.45 --1800.00,0.00,-1800.00,-1800.00,0.00,-1800.00,220.45 --2000.00,0.00,-2000.00,-2000.00,0.00,-2000.00,220.83 --2200.00,0.00,-2200.00,-2200.00,0.00,-2200.00,221.02 --2400.00,0.00,-2400.00,-2400.00,0.00,-2400.00,221.02 --2600.00,0.00,-2600.00,-2600.00,0.00,-2600.00,220.84 --2800.00,0.00,-2800.00,-2800.00,0.00,-2800.00,220.62 --3000.00,0.00,-3000.00,-3000.00,0.00,-3000.00,220.96 --3200.00,0.00,-3200.00,-3200.00,0.00,-3200.00,220.96 --3400.00,0.00,-3400.00,-3400.00,0.00,-3400.00,221.11 --3600.00,0.00,-3600.00,-3600.00,0.00,-3600.00,220.88 --3800.00,0.00,-3800.00,-3800.00,0.00,-3800.00,220.88 --4000.00,0.00,-4000.00,-4000.00,0.00,-4000.00,220.78 --4200.00,0.00,-4200.00,-4200.00,0.00,-4200.00,221.04 --4400.00,0.00,-4400.00,-4400.00,0.00,-4400.00,221.04 --4600.00,0.00,-4600.00,-4600.00,0.00,-4600.00,220.71 --4800.00,-400.00,-4400.00,-4800.00,-400.00,-4400.00,220.73 --5000.00,-1050.00,-3950.00,-5000.00,-1000.00,-4000.00,222.67 --5200.00,-2050.00,-3150.00,-5200.00,-1900.00,-3300.00,222.67 --5400.00,-700.00,-4700.00,-5400.00,-850.00,-4550.00,221.18 --5600.00,-150.00,-5450.00,-5600.00,200.00,-5800.00,220.35 --5800.00,-2050.00,-3750.00,-5800.00,-1500.00,-4300.00,220.35 --6000.00,-3750.00,-2250.00,-6000.00,-3100.00,-2900.00,221.60 --6200.00,-4200.00,-2000.00,-6200.00,-3350.00,-2850.00,221.05 --6400.00,-3300.00,-3100.00,-6400.00,-2400.00,-4000.00,221.66 --6600.00,-3050.00,-3550.00,-6600.00,-1650.00,-4950.00,221.66 --6800.00,-3800.00,-3000.00,-6800.00,-3250.00,-3550.00,221.92 --7000.00,-4750.00,-2250.00,-7000.00,-4750.00,-2250.00,221.88 --7200.00,-5300.00,-1900.00,-7200.00,-4800.00,-2400.00,221.88 --7400.00,-3900.00,-3500.00,-7400.00,-3950.00,-3450.00,221.67 --7600.00,-3900.00,-3700.00,-7600.00,-4450.00,-3150.00,221.56 --7800.00,-4900.00,-2900.00,-7800.00,-5000.00,-2800.00,221.78 --8000.00,-5950.00,-2050.00,-8000.00,-5650.00,-2350.00,221.78 --8200.00,-6900.00,-1300.00,-8200.00,-6100.00,-2100.00,221.36 --8400.00,-6800.00,-1600.00,-8400.00,-6050.00,-2350.00,221.84 --8600.00,-6050.00,-2550.00,-8600.00,-6350.00,-2250.00,221.84 --8800.00,-6900.00,-1900.00,-8800.00,-6900.00,-1900.00,222.03 --9000.00,-7350.00,-1650.00,-9000.00,-6900.00,-2100.00,222.03 --9200.00,-8050.00,-1150.00,-9200.00,-7400.00,-1800.00,221.63 --9400.00,-8550.00,-850.00,-9400.00,-7600.00,-1800.00,221.63 --9600.00,-8750.00,-850.00,-9600.00,-7900.00,-1700.00,221.25 --9800.00,-8900.00,-900.00,-9800.00,-8050.00,-1750.00,221.63 --10000.00,-8750.00,-1250.00,-10000.00,-7950.00,-2050.00,221.63 --10200.00,-9300.00,-900.00,-10200.00,-8600.00,-1600.00,221.90 --10400.00,-9700.00,-700.00,-10400.00,-8800.00,-1600.00,221.59 --10600.00,-9850.00,-750.00,-10600.00,-9100.00,-1500.00,221.51 --10800.00,-10200.00,-600.00,-10800.00,-9350.00,-1450.00,221.51 --11000.00,-10250.00,-750.00,-11000.00,-9650.00,-1350.00,221.42 --11200.00,-10550.00,-650.00,-11200.00,-9800.00,-1400.00,221.27 --11400.00,-10800.00,-600.00,-11400.00,-10100.00,-1300.00,221.27 --11600.00,-10950.00,-650.00,-11600.00,-10250.00,-1350.00,221.32 --11800.00,-11100.00,-700.00,-11800.00,-10500.00,-1300.00,221.12 --12000.00,-11450.00,-550.00,-12000.00,-10800.00,-1200.00,220.94 --12200.00,-11700.00,-500.00,-12200.00,-11150.00,-1050.00,220.94 --12400.00,-11900.00,-500.00,-12400.00,-11250.00,-1150.00,221.20 --12600.00,-12100.00,-500.00,-12600.00,-11550.00,-1050.00,221.09 --12800.00,-12250.00,-550.00,-12800.00,-11700.00,-1100.00,221.04 --13000.00,-12550.00,-450.00,-13000.00,-11950.00,-1050.00,221.04 --13200.00,-12800.00,-400.00,-13200.00,-12150.00,-1050.00,220.94 --13400.00,-12550.00,-850.00,-13400.00,-11950.00,-1450.00,220.88 --13600.00,-13200.00,-400.00,-13600.00,-12650.00,-950.00,220.88 --13800.00,-13500.00,-300.00,-13800.00,-13050.00,-750.00,220.60 --14000.00,-13700.00,-300.00,-14000.00,-13150.00,-850.00,220.47 --14200.00,-13950.00,-250.00,-14200.00,-13500.00,-700.00,220.29 --14400.00,-14000.00,-400.00,-14400.00,-13700.00,-700.00,220.29 --14600.00,-14150.00,-450.00,-14600.00,-13950.00,-650.00,220.52 --14800.00,-14350.00,-450.00,-14800.00,-14200.00,-600.00,220.63 --15000.00,-14600.00,-400.00,-15000.00,-14350.00,-650.00,221.10 --15200.00,-14950.00,-250.00,-15200.00,-14550.00,-650.00,221.10 --15400.00,-15250.00,-150.00,-15400.00,-14850.00,-550.00,221.38 --15600.00,-18150.00,2550.00,-15600.00,-17700.00,2100.00,220.75 --15800.00,-15550.00,-250.00,-15800.00,-15100.00,-700.00,221.06 --16000.00,-15250.00,-750.00,-16000.00,-14900.00,-1100.00,221.06 --16200.00,-15500.00,-700.00,-16200.00,-15100.00,-1100.00,220.84 --16400.00,-16000.00,-400.00,-16400.00,-15500.00,-900.00,221.07 --16600.00,-16550.00,-50.00,-16600.00,-16000.00,-600.00,221.07 --16800.00,-16800.00,0.00,-16800.00,-16200.00,-600.00,221.03 --17000.00,-17050.00,50.00,-17000.00,-16500.00,-500.00,221.26 --17200.00,-17250.00,50.00,-17200.00,-16750.00,-450.00,221.05 --17400.00,-17500.00,100.00,-17400.00,-16900.00,-500.00,221.05 --17600.00,-17900.00,300.00,-17600.00,-17100.00,-500.00,221.35 --17800.00,-18200.00,400.00,-17800.00,-17450.00,-350.00,221.61 --18000.00,-18300.00,300.00,-18000.00,-17650.00,-350.00,221.43 --18200.00,-18550.00,350.00,-18200.00,-17750.00,-450.00,221.43 --18400.00,-18750.00,350.00,-18400.00,-18000.00,-400.00,221.05 --18600.00,-19650.00,1050.00,-18600.00,-18900.00,300.00,221.02 --18800.00,-19250.00,450.00,-18800.00,-18450.00,-350.00,221.02 --19000.00,-19300.00,300.00,-19000.00,-18650.00,-350.00,221.30 --19200.00,-19550.00,350.00,-19200.00,-18700.00,-500.00,221.37 --19400.00,-19800.00,400.00,-19400.00,-18900.00,-500.00,221.20 --19600.00,-19950.00,350.00,-19600.00,-19200.00,-400.00,221.20 --19800.00,-20300.00,500.00,-19800.00,-19500.00,-300.00,220.71 --20000.00,-20400.00,400.00,-20000.00,-19800.00,-200.00,220.65 --20200.00,-20600.00,400.00,-20200.00,-19900.00,-300.00,220.71 --20400.00,-21600.00,1200.00,-20400.00,-20900.00,500.00,220.71 --20600.00,-21000.00,400.00,-20600.00,-20400.00,-200.00,220.44 --20800.00,-21850.00,1050.00,-20800.00,-21150.00,350.00,220.61 --21000.00,-21250.00,250.00,-21000.00,-20750.00,-250.00,220.61 --21200.00,-22250.00,1050.00,-21200.00,-21600.00,400.00,220.68 --21400.00,-21700.00,300.00,-21400.00,-21250.00,-150.00,220.30 --21600.00,-21800.00,200.00,-21600.00,-21450.00,-150.00,220.71 --21800.00,-22950.00,1150.00,-21800.00,-22600.00,800.00,220.71 --22000.00,-22350.00,350.00,-22000.00,-22200.00,200.00,221.00 --22200.00,-22650.00,450.00,-22200.00,-22200.00,0.00,221.13 --22400.00,-22850.00,450.00,-22400.00,-22500.00,100.00,220.68 --22600.00,-23450.00,850.00,-22600.00,-22700.00,100.00,220.68 --22800.00,-23500.00,700.00,-22800.00,-23050.00,250.00,221.56 --23000.00,-24650.00,1650.00,-23000.00,-24000.00,1000.00,221.36 --23200.00,-24750.00,1550.00,-23200.00,-24200.00,1000.00,221.33 --23400.00,-24000.00,600.00,-23334.14,-23250.00,-84.14,221.33 --23600.00,-25100.00,1500.00,-23134.14,-24200.00,1065.86,221.70 --23723.05,-25250.00,1526.95,-22934.14,-24300.00,1365.86,221.14 --23523.05,-24500.00,976.95,-22734.14,-23450.00,715.86,220.94 --23323.05,-24800.00,1476.95,-22534.14,-23250.00,715.86,220.94 --23123.05,-24650.00,1526.95,-22334.14,-23150.00,815.86,221.25 --22923.05,-24750.00,1826.95,-22134.14,-23150.00,1015.86,220.90 --22723.05,-25400.00,2676.95,-21934.14,-23900.00,1965.86,220.90 --22523.05,-24500.00,1976.95,-21734.14,-22900.00,1165.86,220.55 --22323.05,-23750.00,1426.95,-21534.14,-22450.00,915.86,220.64 --22123.05,-23650.00,1526.95,-21334.14,-22200.00,865.86,220.79 --21923.05,-23450.00,1526.95,-21134.14,-22050.00,915.86,220.79 --21723.05,-23350.00,1626.95,-20934.14,-21900.00,965.86,220.73 --21523.05,-23250.00,1726.95,-20734.14,-21600.00,865.86,220.30 --21323.05,-22950.00,1626.95,-20534.14,-21500.00,965.86,220.37 --21123.05,-22750.00,1626.95,-20334.14,-21500.00,1165.86,220.37 --20923.05,-23100.00,2176.95,-20134.14,-22000.00,1865.86,220.46 --20723.05,-22250.00,1526.95,-19934.14,-21000.00,1065.86,220.55 --20523.05,-21600.00,1076.95,-19734.14,-20600.00,865.86,220.55 --20323.05,-21700.00,1376.95,-19534.14,-20500.00,965.86,220.64 --20123.05,-21600.00,1476.95,-19334.14,-20350.00,1015.86,220.78 --19923.05,-21400.00,1476.95,-19134.14,-20250.00,1115.86,221.21 --19723.05,-21400.00,1676.95,-18934.14,-20050.00,1115.86,221.21 --19523.05,-21150.00,1626.95,-18734.14,-19700.00,965.86,220.91 --19323.05,-20800.00,1476.95,-18534.14,-19400.00,865.86,220.73 --19123.05,-20650.00,1526.95,-18334.14,-19150.00,815.86,220.78 --18923.05,-20450.00,1526.95,-18134.14,-18900.00,765.86,220.78 --18723.05,-20300.00,1576.95,-17934.14,-18750.00,815.86,221.03 --18523.05,-20100.00,1576.95,-17734.14,-18400.00,665.86,220.85 --18323.05,-19850.00,1526.95,-17534.14,-18150.00,615.86,220.85 --18123.05,-23000.00,4876.95,-17334.14,-20850.00,3515.86,220.95 --17923.05,-19100.00,1176.95,-17134.14,-17350.00,215.86,220.85 --17723.05,-18200.00,476.95,-16934.14,-16750.00,-184.14,220.65 --17523.05,-18350.00,826.95,-16734.14,-16650.00,-84.14,220.65 --17323.05,-18350.00,1026.95,-16534.14,-16800.00,265.86,220.96 --17123.05,-18250.00,1126.95,-16334.14,-16850.00,515.86,220.90 --16923.05,-18050.00,1126.95,-16134.14,-16750.00,615.86,220.94 --16723.05,-17950.00,1226.95,-15934.14,-16400.00,465.86,220.94 --16523.05,-17750.00,1226.95,-15734.14,-16200.00,465.86,220.76 --16323.05,-17350.00,1026.95,-15534.14,-16000.00,465.86,220.88 --16123.05,-17150.00,1026.95,-15334.14,-15800.00,465.86,220.99 --15923.05,-16950.00,1026.95,-15134.14,-15750.00,615.86,220.99 --15723.05,-16800.00,1076.95,-14934.14,-15400.00,465.86,220.43 --15523.05,-16550.00,1026.95,-14734.14,-15050.00,315.86,220.59 --15323.05,-16300.00,976.95,-14534.14,-14800.00,265.86,220.59 --15123.05,-16100.00,976.95,-14334.14,-14750.00,415.86,220.59 --14923.05,-15950.00,1026.95,-14134.14,-14450.00,315.86,220.63 --14723.05,-15550.00,826.95,-13934.14,-14300.00,365.86,220.95 --14523.05,-15400.00,876.95,-13734.14,-14050.00,315.86,220.95 --14323.05,-15100.00,776.95,-13534.14,-13850.00,315.86,220.70 --14123.05,-14850.00,726.95,-13334.14,-13600.00,265.86,220.80 --13923.05,-14750.00,826.95,-13134.14,-13400.00,265.86,221.13 --13723.05,-14450.00,726.95,-12934.14,-13300.00,365.86,221.13 --13523.05,-14350.00,826.95,-12734.14,-13150.00,415.86,220.94 --13323.05,-13500.00,176.95,-12534.14,-12500.00,-34.14,221.28 --13123.05,-13900.00,776.95,-12334.14,-12800.00,465.86,221.28 --12923.05,-13900.00,976.95,-12134.14,-12600.00,465.86,220.79 --12723.05,-13500.00,776.95,-11934.14,-12350.00,415.86,221.00 --12523.05,-13300.00,776.95,-11734.14,-12000.00,265.86,221.05 --12323.05,-13100.00,776.95,-11534.14,-11850.00,315.86,221.05 --12123.05,-12450.00,326.95,-11334.14,-11250.00,-84.14,221.04 --11923.05,-12700.00,776.95,-11134.14,-11400.00,265.86,221.05 --11723.05,-12600.00,876.95,-10934.14,-11100.00,165.86,221.05 --11523.05,-12300.00,776.95,-10734.14,-10900.00,165.86,221.30 --11323.05,-12050.00,726.95,-10534.14,-10700.00,165.86,221.74 --11123.05,-11850.00,726.95,-10334.14,-10350.00,15.86,221.96 --10923.05,-11550.00,626.95,-10134.14,-10150.00,15.86,221.96 --10723.05,-11350.00,626.95,-9934.14,-9850.00,-84.14,221.04 --10523.05,-10650.00,126.95,-9734.14,-9300.00,-434.14,221.56 --10323.05,-8950.00,-1373.05,-9534.14,-7650.00,-1884.14,221.56 --10123.05,-9650.00,-473.05,-9334.14,-8400.00,-934.14,221.69 --9923.05,-9800.00,-123.05,-9134.14,-8500.00,-634.14,221.60 --9723.05,-9600.00,-123.05,-8934.14,-8250.00,-684.14,221.72 --9523.05,-7950.00,-1573.05,-8734.14,-6800.00,-1934.14,221.72 --9323.05,-7100.00,-2223.05,-8534.14,-5700.00,-2834.14,221.74 --9123.05,-7700.00,-1423.05,-8334.14,-6250.00,-2084.14,221.14 --8923.05,-8550.00,-373.05,-8134.14,-7050.00,-1084.14,221.57 --8723.05,-8300.00,-423.05,-7934.14,-6650.00,-1284.14,221.57 --8523.05,-7150.00,-1373.05,-7734.14,-5800.00,-1934.14,221.55 --8323.05,-6600.00,-1723.05,-7534.14,-5000.00,-2534.14,221.78 --8123.05,-6900.00,-1223.05,-7334.14,-5150.00,-2184.14,221.78 --7923.05,-6950.00,-973.05,-7134.14,-5500.00,-1634.14,221.27 --7723.05,-5750.00,-1973.05,-6934.14,-5550.00,-1384.14,221.92 --7523.05,-5450.00,-2073.05,-6734.14,-4550.00,-2184.14,221.34 --7323.05,-5800.00,-1523.05,-6534.14,-3250.00,-3284.14,221.34 --7123.05,-5750.00,-1373.05,-6334.14,-2450.00,-3884.14,221.06 --6923.05,-4950.00,-1973.05,-6134.14,-3500.00,-2634.14,221.21 --6723.05,-3900.00,-2823.05,-5934.14,-4100.00,-1834.14,221.21 --6523.05,-3850.00,-2673.05,-5734.14,-3000.00,-2734.14,221.75 --6323.05,-4150.00,-2173.05,-5534.14,-1850.00,-3684.14,221.41 --6123.05,-2850.00,-3273.05,-5334.14,-1900.00,-3434.14,222.11 --5923.05,-2850.00,-3073.05,-5134.14,-1950.00,-3184.14,222.11 --5723.05,-3100.00,-2623.05,-4934.14,-1350.00,-3584.14,221.27 --5523.05,-2350.00,-3173.05,-4734.14,350.00,-5084.14,221.04 --5323.05,-850.00,-4473.05,-4534.14,-300.00,-4234.14,221.04 --5123.05,-1300.00,-3823.05,-4334.14,-500.00,-3834.14,221.31 --4923.05,-2200.00,-2723.05,-4134.14,750.00,-4884.14,220.41 --4723.05,-1850.00,-2873.05,-3934.14,-100.00,-3834.14,220.81 --4523.05,-300.00,-4223.05,-3734.14,-650.00,-3084.14,220.81 --4323.05,950.00,-5273.05,-3534.14,900.00,-4434.14,220.67 --4123.05,-750.00,-3373.05,-3334.14,200.00,-3534.14,219.77 --3923.05,-1000.00,-2923.05,-3134.14,-50.00,-3084.14,220.88 --3723.05,0.00,-3723.05,-2934.14,0.00,-2934.14,220.88 --3523.05,50.00,-3573.05,-2734.14,0.00,-2734.14,220.98 --3323.05,0.00,-3323.05,-2534.14,0.00,-2534.14,220.92 --3123.05,0.00,-3123.05,-2334.14,0.00,-2334.14,220.92 --2923.05,0.00,-2923.05,-2134.14,0.00,-2134.14,220.88 --2723.05,0.00,-2723.05,-1934.14,0.00,-1934.14,221.08 --2523.05,0.00,-2523.05,-1734.14,0.00,-1734.14,221.25 --2323.05,0.00,-2323.05,-1534.14,0.00,-1534.14,221.25 --2123.05,0.00,-2123.05,-1334.14,0.00,-1334.14,221.05 --1923.05,0.00,-1923.05,-1134.14,0.00,-1134.14,221.02 --1723.05,0.00,-1723.05,-934.14,0.00,-934.14,221.02 --1523.05,0.00,-1523.05,-734.14,0.00,-734.14,220.87 --1323.05,0.00,-1323.05,-534.14,0.00,-534.14,220.39 --1123.05,0.00,-1123.05,-334.14,0.00,-334.14,220.39 --923.05,0.00,-923.05,-134.14,0.00,-134.14,220.99 --723.05,0.00,-723.05,0.00,0.00,0.00,220.82 --523.05,0.00,-523.05,0.00,0.00,0.00,221.14 --323.05,0.00,-323.05,0.00,0.00,0.00,221.14 --123.05,0.00,-123.05,0.00,0.00,0.00,221.06 -0.00,0.00,0.00,0.00,0.00,0.00,220.87 -0.00,0.00,0.00,0.00,0.00,0.00,220.87 -0.00,0.00,0.00,0.00,0.00,0.00,220.54 -0.00,0.00,0.00,0.00,0.00,0.00,221.22 -0.00,0.00,0.00,0.00,0.00,0.00,221.22 -0.00,0.00,0.00,0.00,0.00,0.00,221.18 -0.00,0.00,0.00,0.00,0.00,0.00,220.86 -0.00,0.00,0.00,0.00,0.00,0.00,220.86 -0.00,0.00,0.00,0.00,0.00,0.00,220.45 -0.00,0.00,0.00,0.00,0.00,0.00,220.94 -0.00,0.00,0.00,0.00,0.00,0.00,220.94 -0.00,0.00,0.00,0.00,0.00,0.00,220.68 -0.00,0.00,0.00,0.00,0.00,0.00,220.62 -0.00,0.00,0.00,0.00,0.00,0.00,220.66 -0.00,0.00,0.00,0.00,0.00,0.00,220.66 -0.00,0.00,0.00,0.00,0.00,0.00,220.36 -0.00,0.00,0.00,0.00,0.00,0.00,220.26 -0.00,0.00,0.00,0.00,0.00,0.00,220.26 -0.00,0.00,0.00,0.00,0.00,0.00,220.65 -0.00,0.00,0.00,0.00,0.00,0.00,220.80 -0.00,0.00,0.00,0.00,0.00,0.00,220.80 -0.00,0.00,0.00,0.00,0.00,0.00,220.35 -0.00,0.00,0.00,0.00,0.00,0.00,220.46 -0.00,0.00,0.00,0.00,0.00,0.00,220.69 -0.00,0.00,0.00,0.00,0.00,0.00,220.69 -0.00,0.00,0.00,0.00,0.00,0.00,220.78 -0.00,0.00,0.00,0.00,0.00,0.00,220.50 -0.00,0.00,0.00,0.00,0.00,0.00,220.50 -0.00,0.00,0.00,0.00,0.00,0.00,220.88 -0.00,0.00,0.00,0.00,0.00,0.00,220.90 -0.00,0.00,0.00,0.00,0.00,0.00,220.90 -0.00,0.00,0.00,0.00,0.00,0.00,220.95 -0.00,0.00,0.00,0.00,0.00,0.00,221.08 -0.00,0.00,0.00,0.00,0.00,0.00,221.08 -0.00,0.00,0.00,0.00,0.00,0.00,221.06 -0.00,0.00,0.00,0.00,0.00,0.00,220.44 -0.00,0.00,0.00,0.00,0.00,0.00,220.62 -0.00,0.00,0.00,0.00,0.00,0.00,220.62 -0.00,0.00,0.00,0.00,0.00,0.00,220.60 -0.00,0.00,0.00,0.00,0.00,0.00,220.66 -0.00,0.00,0.00,0.00,0.00,0.00,220.66 -0.00,0.00,0.00,0.00,0.00,0.00,220.40 -0.00,0.00,0.00,0.00,0.00,0.00,221.17 -0.00,0.00,0.00,0.00,0.00,0.00,221.17 -0.00,0.00,0.00,0.00,0.00,0.00,220.69 -0.00,0.00,0.00,0.00,0.00,0.00,220.99 -0.00,0.00,0.00,0.00,0.00,0.00,220.99 -0.00,0.00,0.00,0.00,0.00,0.00,220.95 -0.00,0.00,0.00,0.00,0.00,0.00,220.54 -0.00,0.00,0.00,0.00,0.00,0.00,220.62 -0.00,0.00,0.00,0.00,0.00,0.00,220.62 -0.00,0.00,0.00,0.00,0.00,0.00,220.87 -0.00,0.00,0.00,0.00,0.00,0.00,220.73 -0.00,0.00,0.00,0.00,0.00,0.00,220.73 -0.00,0.00,0.00,0.00,0.00,0.00,220.82 -0.00,0.00,0.00,0.00,0.00,0.00,220.81 -0.00,0.00,0.00,0.00,0.00,0.00,221.15 -0.00,0.00,0.00,0.00,0.00,0.00,221.15 -0.00,0.00,0.00,0.00,0.00,0.00,221.08 -0.00,0.00,0.00,0.00,0.00,0.00,220.86 -0.00,0.00,0.00,0.00,0.00,0.00,220.86 -0.00,0.00,0.00,0.00,0.00,0.00,220.94 -0.00,0.00,0.00,0.00,0.00,0.00,221.10 -0.00,0.00,0.00,0.00,0.00,0.00,221.10 -0.00,0.00,0.00,0.00,0.00,0.00,220.86 -0.00,0.00,0.00,0.00,0.00,0.00,220.85 -0.00,0.00,0.00,0.00,0.00,0.00,220.85 -0.00,0.00,0.00,0.00,0.00,0.00,220.77 -0.00,0.00,0.00,0.00,0.00,0.00,220.95 -0.00,0.00,0.00,0.00,0.00,0.00,220.27 -0.00,0.00,0.00,0.00,0.00,0.00,220.27 -0.00,0.00,0.00,0.00,0.00,0.00,220.59 -0.00,0.00,0.00,0.00,0.00,0.00,220.84 -0.00,0.00,0.00,0.00,0.00,0.00,220.84 -0.00,0.00,0.00,0.00,0.00,0.00,220.88 -0.00,0.00,0.00,0.00,0.00,0.00,220.83 -0.00,0.00,0.00,0.00,0.00,0.00,220.83 -0.00,0.00,0.00,0.00,0.00,0.00,220.43 -0.00,0.00,0.00,0.00,0.00,0.00,220.42 -0.00,0.00,0.00,0.00,0.00,0.00,220.42 -0.00,0.00,0.00,0.00,0.00,0.00,220.51 -0.00,0.00,0.00,0.00,0.00,0.00,220.52 -0.00,0.00,0.00,0.00,0.00,0.00,220.58 -0.00,0.00,0.00,0.00,0.00,0.00,220.58 -0.00,0.00,0.00,0.00,0.00,0.00,220.81 -0.00,0.00,0.00,0.00,0.00,0.00,220.52 -0.00,0.00,0.00,0.00,0.00,0.00,220.52 -0.00,0.00,0.00,0.00,0.00,0.00,220.69 -0.00,0.00,0.00,0.00,0.00,0.00,220.79 -0.00,0.00,0.00,0.00,0.00,0.00,220.79 -0.00,0.00,0.00,0.00,0.00,0.00,220.19 -0.00,0.00,0.00,0.00,0.00,0.00,220.34 -0.00,0.00,0.00,0.00,0.00,0.00,220.34 -0.00,0.00,0.00,0.00,0.00,0.00,220.61 -0.00,0.00,0.00,0.00,0.00,0.00,220.90 -0.00,0.00,0.00,0.00,0.00,0.00,220.51 -0.00,0.00,0.00,0.00,0.00,0.00,220.51 -0.00,0.00,0.00,0.00,0.00,0.00,220.68 -0.00,0.00,0.00,0.00,0.00,0.00,220.87 -0.00,0.00,0.00,0.00,0.00,0.00,220.87 -0.00,0.00,0.00,0.00,0.00,0.00,221.11 -0.00,0.00,0.00,0.00,0.00,0.00,220.77 -0.00,0.00,0.00,0.00,0.00,0.00,220.77 -0.00,0.00,0.00,0.00,0.00,0.00,220.87 -0.00,0.00,0.00,0.00,0.00,0.00,220.82 -0.00,0.00,0.00,0.00,0.00,0.00,220.74 -0.00,0.00,0.00,0.00,0.00,0.00,220.74 -0.00,0.00,0.00,0.00,0.00,0.00,220.82 -0.00,0.00,0.00,0.00,0.00,0.00,221.13 -0.00,0.00,0.00,0.00,0.00,0.00,221.13 -0.00,0.00,0.00,0.00,0.00,0.00,221.15 -0.00,0.00,0.00,0.00,0.00,0.00,220.98 -0.00,0.00,0.00,0.00,0.00,0.00,220.98 -0.00,0.00,0.00,0.00,0.00,0.00,221.16 -0.00,0.00,0.00,0.00,0.00,0.00,221.10 -0.00,0.00,0.00,0.00,0.00,0.00,220.85 -0.00,0.00,0.00,0.00,0.00,0.00,220.85 -0.00,0.00,0.00,0.00,0.00,0.00,220.73 -0.00,0.00,0.00,0.00,0.00,0.00,220.54 -0.00,0.00,0.00,0.00,0.00,0.00,220.54 -0.00,0.00,0.00,0.00,0.00,0.00,220.60 -0.00,0.00,0.00,0.00,0.00,0.00,221.06 -0.00,0.00,0.00,0.00,0.00,0.00,221.06 -0.00,0.00,0.00,0.00,0.00,0.00,220.69 -0.00,0.00,0.00,0.00,0.00,0.00,220.90 -0.00,0.00,0.00,0.00,0.00,0.00,220.84 -0.00,0.00,0.00,0.00,0.00,0.00,220.84 -0.00,0.00,0.00,0.00,0.00,0.00,220.99 -0.00,0.00,0.00,0.00,0.00,0.00,220.75 -0.00,0.00,0.00,0.00,0.00,0.00,220.75 -0.00,0.00,0.00,0.00,0.00,0.00,221.20 -0.00,0.00,0.00,0.00,0.00,0.00,220.90 -0.00,0.00,0.00,0.00,0.00,0.00,220.90 -0.00,0.00,0.00,0.00,0.00,0.00,220.78 -0.00,0.00,0.00,0.00,0.00,0.00,220.44 -0.00,0.00,0.00,0.00,0.00,0.00,220.44 -0.00,0.00,0.00,0.00,0.00,0.00,220.93 -0.00,0.00,0.00,0.00,0.00,0.00,220.63 -0.00,0.00,0.00,0.00,0.00,0.00,220.88 -0.00,0.00,0.00,0.00,0.00,0.00,220.88 -0.00,0.00,0.00,0.00,0.00,0.00,220.45 -0.00,0.00,0.00,0.00,0.00,0.00,220.23 -0.00,0.00,0.00,0.00,0.00,0.00,220.23 -0.00,0.00,0.00,0.00,0.00,0.00,220.74 -0.00,0.00,0.00,0.00,0.00,0.00,220.55 -0.00,0.00,0.00,0.00,0.00,0.00,220.55 -0.00,0.00,0.00,0.00,0.00,0.00,220.56 -0.00,0.00,0.00,0.00,0.00,0.00,220.37 -0.00,0.00,0.00,0.00,0.00,0.00,220.59 -0.00,0.00,0.00,0.00,0.00,0.00,220.59 -0.00,0.00,0.00,0.00,0.00,0.00,220.09 -0.00,0.00,0.00,0.00,0.00,0.00,220.26 -0.00,0.00,0.00,0.00,0.00,0.00,220.26 -0.00,0.00,0.00,0.00,0.00,0.00,220.21 -0.00,0.00,0.00,0.00,0.00,0.00,220.86 -0.00,0.00,0.00,0.00,0.00,0.00,220.86 -0.00,0.00,0.00,0.00,0.00,0.00,220.88 -0.00,0.00,0.00,0.00,0.00,0.00,220.56 -0.00,0.00,0.00,0.00,0.00,0.00,220.56 -0.00,0.00,0.00,0.00,0.00,0.00,220.82 -0.00,0.00,0.00,0.00,0.00,0.00,220.44 -0.00,0.00,0.00,0.00,0.00,0.00,220.72 -0.00,0.00,0.00,0.00,0.00,0.00,220.72 -0.00,0.00,0.00,0.00,0.00,0.00,220.29 -0.00,0.00,0.00,0.00,0.00,0.00,220.26 -0.00,0.00,0.00,0.00,0.00,0.00,220.26 -0.00,0.00,0.00,0.00,0.00,0.00,220.45 -0.00,0.00,0.00,0.00,0.00,0.00,220.56 -0.00,0.00,0.00,0.00,0.00,0.00,220.56 -0.00,0.00,0.00,0.00,0.00,0.00,220.30 -0.00,0.00,0.00,0.00,0.00,0.00,220.41 -0.00,0.00,0.00,0.00,0.00,0.00,221.04 -0.00,0.00,0.00,0.00,0.00,0.00,221.04 -0.00,0.00,0.00,0.00,0.00,0.00,220.58 -0.00,0.00,0.00,0.00,0.00,0.00,220.74 -0.00,0.00,0.00,0.00,0.00,0.00,220.74 -0.00,0.00,0.00,0.00,0.00,0.00,220.43 -0.00,0.00,0.00,0.00,0.00,0.00,220.70 -0.00,0.00,0.00,0.00,0.00,0.00,220.70 -0.00,0.00,0.00,0.00,0.00,0.00,220.89 -0.00,0.00,0.00,0.00,0.00,0.00,220.55 -0.00,0.00,0.00,0.00,0.00,0.00,220.55 -0.00,0.00,0.00,0.00,0.00,0.00,220.69 -0.00,0.00,0.00,0.00,0.00,0.00,220.62 -0.00,0.00,0.00,0.00,0.00,0.00,220.62 -0.00,0.00,0.00,0.00,0.00,0.00,220.42 -200.00,0.00,200.00,200.00,0.00,200.00,220.62 -400.00,0.00,400.00,400.00,0.00,400.00,220.39 -600.00,0.00,600.00,600.00,0.00,600.00,220.39 -800.00,0.00,800.00,800.00,0.00,800.00,220.65 -1000.00,0.00,1000.00,1000.00,0.00,1000.00,221.22 -1200.00,0.00,1200.00,1200.00,0.00,1200.00,221.22 -1400.00,0.00,1400.00,1400.00,0.00,1400.00,221.12 -1600.00,0.00,1600.00,1600.00,0.00,1600.00,221.23 -1800.00,0.00,1800.00,1800.00,0.00,1800.00,221.23 -2000.00,0.00,2000.00,2000.00,0.00,2000.00,220.89 -2200.00,0.00,2200.00,2200.00,0.00,2200.00,220.74 -2400.00,0.00,2400.00,2400.00,0.00,2400.00,220.55 -2600.00,0.00,2600.00,2600.00,0.00,2600.00,220.55 -2800.00,0.00,2800.00,2800.00,0.00,2800.00,220.50 -3000.00,0.00,3000.00,3000.00,0.00,3000.00,220.87 -3200.00,0.00,3200.00,3200.00,0.00,3200.00,220.87 -3400.00,0.00,3400.00,3400.00,0.00,3400.00,220.84 -3600.00,0.00,3600.00,3600.00,0.00,3600.00,220.73 -3800.00,0.00,3800.00,3800.00,0.00,3800.00,220.57 -4000.00,0.00,4000.00,4000.00,0.00,4000.00,220.57 -4200.00,0.00,4200.00,4200.00,0.00,4200.00,220.63 -4400.00,0.00,4400.00,4400.00,0.00,4400.00,220.80 -4600.00,0.00,4600.00,4600.00,0.00,4600.00,220.80 -4800.00,500.00,4300.00,4800.00,350.00,4450.00,220.97 -5000.00,2450.00,2550.00,5000.00,1050.00,3950.00,220.88 -5200.00,2850.00,2350.00,5200.00,1600.00,3600.00,220.88 -5400.00,1500.00,3900.00,5400.00,900.00,4500.00,220.68 -5600.00,2200.00,3400.00,5600.00,0.00,5600.00,219.66 -5800.00,2350.00,3450.00,5800.00,1400.00,4400.00,219.66 -6000.00,1400.00,4600.00,6000.00,3100.00,2900.00,220.45 -6200.00,2800.00,3400.00,6200.00,3250.00,2950.00,221.57 -6400.00,4050.00,2350.00,6400.00,2350.00,4050.00,221.57 -6600.00,4500.00,2100.00,6600.00,1600.00,5000.00,220.62 -6800.00,3400.00,3400.00,6800.00,3100.00,3700.00,220.53 -7000.00,3200.00,3800.00,7000.00,4600.00,2400.00,221.47 -7200.00,4150.00,3050.00,7200.00,4600.00,2600.00,221.47 -7400.00,5050.00,2350.00,7400.00,3950.00,3450.00,221.32 -7600.00,5750.00,1850.00,7600.00,4450.00,3150.00,220.87 -7800.00,5550.00,2250.00,7800.00,5000.00,2800.00,220.87 -8000.00,4850.00,3150.00,8000.00,5400.00,2600.00,221.20 -8200.00,5800.00,2400.00,8200.00,5750.00,2450.00,221.05 -8400.00,6200.00,2200.00,8400.00,6050.00,2350.00,221.05 -8600.00,6650.00,1950.00,8600.00,6350.00,2250.00,221.17 -8800.00,7350.00,1450.00,8800.00,6800.00,2000.00,221.22 -9000.00,7650.00,1350.00,9000.00,7050.00,1950.00,221.22 -9200.00,7650.00,1550.00,9200.00,7050.00,2150.00,220.66 -9400.00,7850.00,1550.00,9400.00,7350.00,2050.00,220.78 -9600.00,8100.00,1500.00,9600.00,7650.00,1950.00,220.78 -9800.00,8350.00,1450.00,9800.00,7950.00,1850.00,221.04 -10000.00,8550.00,1450.00,10000.00,8100.00,1900.00,221.34 -10200.00,9050.00,1150.00,10200.00,8700.00,1500.00,221.21 -10400.00,8950.00,1450.00,10400.00,8600.00,1800.00,221.21 -10600.00,9450.00,1150.00,10600.00,9150.00,1450.00,221.46 -10800.00,9700.00,1100.00,10800.00,9350.00,1450.00,220.90 -11000.00,9950.00,1050.00,11000.00,9500.00,1500.00,220.90 -11200.00,10100.00,1100.00,11200.00,9800.00,1400.00,221.04 -11400.00,10300.00,1100.00,11400.00,9900.00,1500.00,221.39 -11600.00,10450.00,1150.00,11600.00,10150.00,1450.00,221.39 -11800.00,10750.00,1050.00,11800.00,10350.00,1450.00,221.18 -12000.00,10950.00,1050.00,12000.00,10600.00,1400.00,221.05 -12200.00,11300.00,900.00,12200.00,10900.00,1300.00,221.05 -12400.00,11550.00,850.00,12400.00,11050.00,1350.00,220.65 -12600.00,11800.00,800.00,12600.00,11250.00,1350.00,220.93 -12800.00,12100.00,700.00,12800.00,11700.00,1100.00,220.94 -13000.00,12300.00,700.00,13000.00,11850.00,1150.00,220.94 -13200.00,12450.00,750.00,13200.00,11900.00,1300.00,221.15 -13400.00,12650.00,750.00,13400.00,12100.00,1300.00,220.63 -13600.00,12950.00,650.00,13600.00,12350.00,1250.00,220.63 -13800.00,13200.00,600.00,13800.00,12650.00,1150.00,221.14 -14000.00,13350.00,650.00,14000.00,12750.00,1250.00,220.89 -14200.00,13650.00,550.00,14200.00,12950.00,1250.00,220.89 -14400.00,13950.00,450.00,14400.00,13150.00,1250.00,221.05 -14600.00,14050.00,550.00,14600.00,13450.00,1150.00,220.88 -14800.00,14300.00,500.00,14800.00,13600.00,1200.00,220.85 -15000.00,14550.00,450.00,15000.00,13750.00,1250.00,220.85 -15200.00,14800.00,400.00,15200.00,13900.00,1300.00,220.83 -15400.00,15000.00,400.00,15400.00,14200.00,1200.00,220.77 -15600.00,15300.00,300.00,15600.00,14500.00,1100.00,220.77 -15800.00,15550.00,250.00,15800.00,14750.00,1050.00,220.86 -16000.00,15750.00,250.00,16000.00,15000.00,1000.00,221.00 -16200.00,16550.00,-350.00,16200.00,15800.00,400.00,220.55 -16400.00,19700.00,-3300.00,16400.00,18850.00,-2450.00,220.55 -16600.00,16600.00,0.00,16600.00,16200.00,400.00,220.60 -16800.00,16050.00,750.00,16800.00,15750.00,1050.00,220.80 -17000.00,16100.00,900.00,17000.00,15600.00,1400.00,220.71 -17200.00,16550.00,650.00,17200.00,16100.00,1100.00,220.71 -17400.00,16850.00,550.00,17400.00,16500.00,900.00,220.92 -17600.00,17250.00,350.00,17600.00,16900.00,700.00,220.99 -17800.00,17450.00,350.00,17800.00,17200.00,600.00,220.99 -18000.00,17750.00,250.00,18000.00,17450.00,550.00,221.58 -18200.00,17950.00,250.00,18200.00,17700.00,500.00,221.40 -18400.00,18800.00,-400.00,18400.00,18600.00,-200.00,221.40 -18600.00,18350.00,250.00,18600.00,18000.00,600.00,221.31 -18800.00,19100.00,-300.00,18800.00,19000.00,-200.00,221.49 -19000.00,19400.00,-400.00,19000.00,19150.00,-150.00,221.72 -19200.00,18850.00,350.00,19200.00,18400.00,800.00,221.72 -19400.00,19600.00,-200.00,19400.00,19550.00,-150.00,221.62 -19600.00,19900.00,-300.00,19600.00,19700.00,-100.00,221.66 -19800.00,20100.00,-300.00,19800.00,19900.00,-100.00,220.94 -20000.00,20150.00,-150.00,20000.00,20000.00,0.00,220.94 -20200.00,20450.00,-250.00,20200.00,20000.00,200.00,221.49 -20400.00,20600.00,-200.00,20400.00,20300.00,100.00,220.95 -20600.00,20900.00,-300.00,20600.00,20450.00,150.00,220.95 -20800.00,21150.00,-350.00,20800.00,20450.00,350.00,221.12 -21000.00,21400.00,-400.00,21000.00,20900.00,100.00,221.24 -21200.00,21800.00,-600.00,21200.00,21100.00,100.00,221.17 -21400.00,21800.00,-400.00,21400.00,21300.00,100.00,221.17 -21600.00,22100.00,-500.00,21600.00,21600.00,0.00,220.86 -21800.00,21650.00,150.00,21800.00,21400.00,400.00,220.87 -22000.00,22800.00,-800.00,22000.00,22350.00,-350.00,220.87 -22200.00,23250.00,-1050.00,22200.00,22650.00,-450.00,220.88 -22400.00,23050.00,-650.00,22400.00,22450.00,-50.00,221.11 -22600.00,23300.00,-700.00,22600.00,22900.00,-300.00,221.20 -22800.00,23300.00,-500.00,22800.00,23200.00,-400.00,221.20 -23000.00,23700.00,-700.00,23000.00,23350.00,-350.00,220.83 -23200.00,23850.00,-650.00,23200.00,23600.00,-400.00,221.40 -23400.00,24050.00,-650.00,23400.00,23750.00,-350.00,221.28 -23600.00,24200.00,-600.00,23388.51,23850.00,-461.49,221.28 -23800.00,24450.00,-650.00,23188.51,24200.00,-1011.49,221.48 -23786.61,24600.00,-813.39,22988.51,24300.00,-1311.49,221.53 -23586.61,24850.00,-1263.39,22788.51,24200.00,-1411.49,221.53 -23386.61,24600.00,-1213.39,22588.51,24050.00,-1461.49,221.35 -23186.61,24500.00,-1313.39,22388.51,23950.00,-1561.49,221.55 -22986.61,24450.00,-1463.39,22188.51,23700.00,-1511.49,221.79 -22786.61,24500.00,-1713.39,21988.51,23350.00,-1361.49,221.79 -22586.61,24200.00,-1613.39,21788.51,23150.00,-1361.49,221.66 -22386.61,23850.00,-1463.39,21588.51,22900.00,-1311.49,221.51 -22186.61,23850.00,-1663.39,21388.51,22700.00,-1311.49,221.45 -21986.61,23650.00,-1663.39,21188.51,22350.00,-1161.49,221.45 -21786.61,23300.00,-1513.39,20988.51,22050.00,-1061.49,221.13 -21586.61,23150.00,-1563.39,20788.51,21850.00,-1061.49,221.44 -21386.61,23000.00,-1613.39,20588.51,21700.00,-1111.49,221.44 -21186.61,22600.00,-1413.39,20388.51,21250.00,-861.49,220.83 -20986.61,22550.00,-1563.39,20188.51,21200.00,-1011.49,220.90 -20786.61,21650.00,-863.39,19988.51,20200.00,-211.49,221.04 -20586.61,22250.00,-1663.39,19788.51,20850.00,-1061.49,221.04 -20386.61,22300.00,-1913.39,19588.51,20750.00,-1161.49,220.68 -20186.61,21950.00,-1763.39,19388.51,20600.00,-1211.49,220.92 -19986.61,21550.00,-1563.39,19188.51,19900.00,-711.49,220.92 -19786.61,21100.00,-1313.39,18988.51,20100.00,-1111.49,220.48 -19586.61,21050.00,-1463.39,18788.51,19800.00,-1011.49,220.80 -19386.61,20850.00,-1463.39,18588.51,19400.00,-811.49,221.40 -19186.61,20650.00,-1463.39,18388.51,19400.00,-1011.49,221.40 -18986.61,20150.00,-1163.39,18188.51,19000.00,-811.49,221.43 -18786.61,19400.00,-613.39,17988.51,18200.00,-211.49,221.80 -18586.61,19850.00,-1263.39,17788.51,18750.00,-961.49,221.62 -18386.61,19700.00,-1313.39,17588.51,18400.00,-811.49,221.62 -18186.61,18850.00,-663.39,17388.51,17700.00,-311.49,221.84 -17986.61,19250.00,-1263.39,17188.51,18100.00,-911.49,221.58 -17786.61,19200.00,-1413.39,16988.51,17750.00,-761.49,221.58 -17586.61,18800.00,-1213.39,16788.51,17700.00,-911.49,221.39 -17386.61,21600.00,-4213.39,16588.51,19900.00,-3311.49,221.62 -17186.61,17900.00,-713.39,16388.51,16800.00,-411.49,221.36 -16986.61,16600.00,386.61,16188.51,15500.00,688.51,221.36 -16786.61,16750.00,36.61,15988.51,15400.00,588.51,221.73 -16586.61,17550.00,-963.39,15788.51,16250.00,-461.49,221.70 -16386.61,17550.00,-1163.39,15588.51,16350.00,-761.49,221.37 -16186.61,17400.00,-1213.39,15388.51,16100.00,-711.49,221.37 -15986.61,16550.00,-563.39,15188.51,15250.00,-61.49,221.18 -15786.61,16850.00,-1063.39,14988.51,15650.00,-661.49,221.37 -15586.61,16750.00,-1163.39,14788.51,15350.00,-561.49,221.37 -15386.61,16000.00,-613.39,14588.51,14600.00,-11.49,221.21 -15186.61,16300.00,-1113.39,14388.51,14850.00,-461.49,221.13 -14986.61,16100.00,-1113.39,14188.51,14600.00,-411.49,220.88 -14786.61,15400.00,-613.39,13988.51,13900.00,88.51,220.88 -14586.61,15700.00,-1113.39,13788.51,14100.00,-311.49,220.58 -14386.61,15550.00,-1163.39,13588.51,13950.00,-361.49,220.36 -14186.61,14800.00,-613.39,13388.51,13200.00,188.51,220.36 -13986.61,14550.00,-563.39,13188.51,13000.00,188.51,220.37 -13786.61,14400.00,-613.39,12988.51,12850.00,138.51,220.65 -13586.61,14750.00,-1163.39,12788.51,13150.00,-361.49,220.77 -13386.61,14450.00,-1063.39,12588.51,12850.00,-261.49,220.77 -13186.61,13550.00,-363.39,12388.51,12150.00,238.51,220.46 -12986.61,13400.00,-413.39,12188.51,11950.00,238.51,220.81 -12786.61,13400.00,-613.39,11988.51,11800.00,188.51,220.81 -12586.61,13250.00,-663.39,11788.51,11600.00,188.51,220.20 -12386.61,12850.00,-463.39,11588.51,11450.00,138.51,220.73 -12186.61,12650.00,-463.39,11388.51,11250.00,138.51,220.73 -11986.61,12550.00,-563.39,11188.51,11150.00,38.51,220.51 -11786.61,12150.00,-363.39,10988.51,10850.00,138.51,220.91 -11586.61,11900.00,-313.39,10788.51,10550.00,238.51,221.04 -11386.61,11800.00,-413.39,10588.51,10300.00,288.51,221.04 -11186.61,11700.00,-513.39,10388.51,10150.00,238.51,220.83 -10986.61,11300.00,-313.39,10188.51,9900.00,288.51,221.14 -10786.61,11450.00,-663.39,9988.51,10000.00,-11.49,221.14 -10586.61,10650.00,-63.39,9788.51,9400.00,388.51,221.26 -10386.61,8800.00,1586.61,9588.51,7700.00,1888.51,221.43 -10186.61,9150.00,1036.61,9388.51,8150.00,1238.51,221.33 -9986.61,9400.00,586.61,9188.51,8100.00,1088.51,221.33 -9786.61,9500.00,286.61,8988.51,8350.00,638.51,221.18 -9586.61,9200.00,386.61,8788.51,7700.00,1088.51,221.62 -9386.61,8950.00,436.61,8588.51,6900.00,1688.51,221.62 -9186.61,7400.00,1786.61,8388.51,7300.00,1088.51,221.43 -8986.61,6400.00,2586.61,8188.51,6350.00,1838.51,221.05 -8786.61,7250.00,1536.61,7988.51,6100.00,1888.51,221.05 -8586.61,7550.00,1036.61,7788.51,6450.00,1338.51,221.44 -8386.61,7750.00,636.61,7588.51,6200.00,1388.51,221.30 -8186.61,6450.00,1736.61,7388.51,5100.00,2288.51,221.30 -7986.61,5950.00,2036.61,7188.51,4700.00,2488.51,221.44 -7786.61,6250.00,1536.61,6988.51,5200.00,1788.51,221.57 -7586.61,6350.00,1236.61,6788.51,5000.00,1788.51,221.36 -7386.61,5100.00,2286.61,6588.51,3900.00,2688.51,221.36 -7186.61,4950.00,2236.61,6388.51,3050.00,3338.51,221.68 -6986.61,4950.00,2036.61,6188.51,2900.00,3288.51,221.59 -6786.61,3800.00,2986.61,5988.51,3550.00,2438.51,221.59 -6586.61,3600.00,2986.61,5788.51,3700.00,2088.51,221.69 -6386.61,4500.00,1886.61,5588.51,2800.00,2788.51,221.60 -6186.61,4550.00,1636.61,5388.51,2050.00,3338.51,221.60 -5986.61,3850.00,2136.61,5188.51,450.00,4738.51,221.56 -5786.61,3000.00,2786.61,4988.51,200.00,4788.51,221.93 -5586.61,2300.00,3286.61,4788.51,2400.00,2388.51,221.93 -5386.61,1000.00,4386.61,4588.51,2700.00,1888.51,221.02 -5186.61,650.00,4536.61,4388.51,1800.00,2588.51,222.40 -4986.61,2550.00,2436.61,4188.51,1300.00,2888.51,222.40 -4786.61,3250.00,1536.61,3988.51,1050.00,2938.51,221.88 -4586.61,2650.00,1936.61,3788.51,-600.00,4388.51,221.71 -4386.61,1050.00,3336.61,3588.51,-150.00,3738.51,221.98 -4186.61,650.00,3536.61,3388.51,0.00,3388.51,221.98 -3986.61,1050.00,2936.61,3188.51,0.00,3188.51,221.31 -3786.61,100.00,3686.61,2988.51,0.00,2988.51,220.91 -3586.61,-100.00,3686.61,2788.51,0.00,2788.51,220.91 -3386.61,0.00,3386.61,2588.51,0.00,2588.51,221.35 -3186.61,0.00,3186.61,2388.51,0.00,2388.51,220.72 -2986.61,0.00,2986.61,2188.51,0.00,2188.51,220.62 -2786.61,0.00,2786.61,1988.51,0.00,1988.51,220.62 -2586.61,0.00,2586.61,1788.51,0.00,1788.51,220.88 -2386.61,0.00,2386.61,1588.51,0.00,1588.51,221.06 -2186.61,0.00,2186.61,1388.51,0.00,1388.51,221.06 -1986.61,0.00,1986.61,1188.51,0.00,1188.51,220.99 -1786.61,0.00,1786.61,988.51,0.00,988.51,220.77 -1586.61,0.00,1586.61,788.51,0.00,788.51,220.77 -1386.61,0.00,1386.61,588.51,0.00,588.51,220.73 -1186.61,0.00,1186.61,388.51,0.00,388.51,220.52 -986.61,0.00,986.61,188.51,0.00,188.51,220.52 -786.61,0.00,786.61,0.00,0.00,0.00,220.94 -586.61,0.00,586.61,0.00,0.00,0.00,221.05 -386.61,0.00,386.61,0.00,0.00,0.00,221.20 -186.61,0.00,186.61,0.00,0.00,0.00,221.20 -0.00,0.00,0.00,0.00,0.00,0.00,221.03 -0.00,0.00,0.00,0.00,0.00,0.00,221.16 -0.00,0.00,0.00,0.00,0.00,0.00,221.16 -0.00,0.00,0.00,0.00,0.00,0.00,220.68 -0.00,0.00,0.00,0.00,0.00,0.00,221.08 -0.00,0.00,0.00,0.00,0.00,0.00,221.08 -0.00,0.00,0.00,0.00,0.00,0.00,220.48 -0.00,0.00,0.00,0.00,0.00,0.00,220.21 -0.00,0.00,0.00,0.00,0.00,0.00,220.21 -0.00,0.00,0.00,0.00,0.00,0.00,220.58 -0.00,0.00,0.00,0.00,0.00,0.00,220.51 -0.00,0.00,0.00,0.00,0.00,0.00,220.51 -0.00,0.00,0.00,0.00,0.00,0.00,220.60 -0.00,0.00,0.00,0.00,0.00,0.00,220.66 -0.00,0.00,0.00,0.00,0.00,0.00,220.45 -0.00,0.00,0.00,0.00,0.00,0.00,220.45 -0.00,0.00,0.00,0.00,0.00,0.00,220.25 -0.00,0.00,0.00,0.00,0.00,0.00,220.38 -0.00,0.00,0.00,0.00,0.00,0.00,220.38 -0.00,0.00,0.00,0.00,0.00,0.00,220.32 -0.00,0.00,0.00,0.00,0.00,0.00,220.39 -0.00,0.00,0.00,0.00,0.00,0.00,220.39 \ No newline at end of file +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +-200.00,0.00,-200.00,-200.00,0.00,-200.00,0 +-400.00,0.00,-400.00,-400.00,0.00,-400.00,0 +-600.00,0.00,-600.00,-600.00,0.00,-600.00,0 +-800.00,0.00,-800.00,-800.00,0.00,-800.00,0 +-1000.00,0.00,-1000.00,-1000.00,0.00,-1000.00,0 +-1200.00,0.00,-1200.00,-1200.00,0.00,-1200.00,0 +-1400.00,0.00,-1400.00,-1400.00,0.00,-1400.00,0 +-1600.00,0.00,-1600.00,-1600.00,0.00,-1600.00,0 +-1800.00,-100.00,-1700.00,-1800.00,-250.00,-1550.00,0 +-2000.00,-350.00,-1650.00,-2000.00,-300.00,-1700.00,0 +-2200.00,-150.00,-2050.00,-2200.00,0.00,-2200.00,0 +-2400.00,-350.00,-2050.00,-2400.00,-100.00,-2300.00,0 +-2600.00,-1550.00,-1050.00,-2600.00,-200.00,-2400.00,0 +-2800.00,-2150.00,-650.00,-2800.00,-450.00,-2350.00,0 +-3000.00,-600.00,-2400.00,-3000.00,-700.00,-2300.00,0 +-3200.00,-1450.00,-1750.00,-3200.00,-1400.00,-1800.00,0 +-3400.00,-3050.00,-350.00,-3400.00,-1250.00,-2150.00,0 +-3600.00,-2650.00,-950.00,-3600.00,-1350.00,-2250.00,0 +-3800.00,-1200.00,-2600.00,-3800.00,-1350.00,-2450.00,0 +-4000.00,-450.00,-3550.00,-4000.00,-1350.00,-2650.00,0 +-4200.00,-3150.00,-1050.00,-4200.00,-2050.00,-2150.00,0 +-4400.00,-4250.00,-150.00,-4400.00,-2100.00,-2300.00,0 +-4600.00,-2000.00,-2600.00,-4600.00,-2100.00,-2500.00,0 +-4800.00,-950.00,-3850.00,-4800.00,-2500.00,-2300.00,0 +-5000.00,-4250.00,-750.00,-5000.00,-3300.00,-1700.00,0 +-5200.00,-5050.00,-150.00,-5200.00,-3500.00,-1700.00,0 +-5400.00,-2550.00,-2850.00,-5400.00,-3100.00,-2300.00,0 +-5600.00,-3000.00,-2600.00,-5600.00,-3250.00,-2350.00,0 +-5800.00,-5900.00,100.00,-5800.00,-4300.00,-1500.00,0 +-6000.00,-5250.00,-750.00,-6000.00,-4300.00,-1700.00,0 +-6200.00,-3600.00,-2600.00,-6200.00,-4150.00,-2050.00,0 +-6400.00,-4650.00,-1750.00,-6400.00,-4350.00,-2050.00,0 +-6600.00,-6150.00,-450.00,-6600.00,-4700.00,-1900.00,0 +-6800.00,-5500.00,-1300.00,-6800.00,-4650.00,-2150.00,0 +-7000.00,-4900.00,-2100.00,-7000.00,-4650.00,-2350.00,0 +-7200.00,-7050.00,-150.00,-7200.00,-6200.00,-1000.00,0 +-7400.00,-6050.00,-1350.00,-7400.00,-4950.00,-2450.00,0 +-7600.00,-5950.00,-1650.00,-7600.00,-5300.00,-2300.00,0 +-7800.00,-6600.00,-1200.00,-7800.00,-5800.00,-2000.00,0 +-8000.00,-6800.00,-1200.00,-8000.00,-6000.00,-2000.00,0 +-8200.00,-6550.00,-1650.00,-8200.00,-6150.00,-2050.00,0 +-8400.00,-6400.00,-2000.00,-8400.00,-6300.00,-2100.00,0 +-8600.00,-6850.00,-1750.00,-8600.00,-6650.00,-1950.00,0 +-8800.00,-7450.00,-1350.00,-8800.00,-6800.00,-2000.00,0 +-9000.00,-7600.00,-1400.00,-9000.00,-6900.00,-2100.00,0 +-9200.00,-7550.00,-1650.00,-9200.00,-7000.00,-2200.00,0 +-9400.00,-7600.00,-1800.00,-9400.00,-7400.00,-2000.00,0 +-9600.00,-7800.00,-1800.00,-9600.00,-7700.00,-1900.00,0 +-9800.00,-8450.00,-1350.00,-9800.00,-7950.00,-1850.00,0 +-10000.00,-8900.00,-1100.00,-10000.00,-8150.00,-1850.00,0 +-10200.00,-8850.00,-1350.00,-10200.00,-7850.00,-2350.00,0 +-10400.00,-8950.00,-1450.00,-10400.00,-8150.00,-2250.00,0 +-10600.00,-9200.00,-1400.00,-10600.00,-8800.00,-1800.00,0 +-10800.00,-9400.00,-1400.00,-10800.00,-9200.00,-1600.00,0 +-11000.00,-9850.00,-1150.00,-11000.00,-9700.00,-1300.00,0 +-11200.00,-9850.00,-1350.00,-11200.00,-9350.00,-1850.00,0 +-11400.00,-10000.00,-1400.00,-11400.00,-9550.00,-1850.00,0 +-11600.00,-10150.00,-1450.00,-11600.00,-9500.00,-2100.00,0 +-11800.00,-10350.00,-1450.00,-11800.00,-10000.00,-1800.00,0 +-12000.00,-10900.00,-1100.00,-12000.00,-10700.00,-1300.00,0 +-12200.00,-10750.00,-1450.00,-12200.00,-10550.00,-1650.00,0 +-12400.00,-10650.00,-1750.00,-12400.00,-10500.00,-1900.00,0 +-12600.00,-11600.00,-1000.00,-12600.00,-11350.00,-1250.00,0 +-12800.00,-11800.00,-1000.00,-12800.00,-10850.00,-1950.00,0 +-13000.00,-11400.00,-1600.00,-13000.00,-10800.00,-2200.00,0 +-13200.00,-12300.00,-900.00,-13200.00,-11700.00,-1500.00,0 +-13400.00,-12700.00,-700.00,-13400.00,-12100.00,-1300.00,0 +-13600.00,-12700.00,-900.00,-13600.00,-12150.00,-1450.00,0 +-13800.00,-12050.00,-1750.00,-13800.00,-11850.00,-1950.00,0 +-14000.00,-12750.00,-1250.00,-14000.00,-12350.00,-1650.00,0 +-14200.00,-13100.00,-1100.00,-14200.00,-12500.00,-1700.00,0 +-14400.00,-13700.00,-700.00,-14400.00,-12900.00,-1500.00,0 +-14600.00,-13450.00,-1150.00,-14600.00,-12800.00,-1800.00,0 +-14800.00,-14100.00,-700.00,-14800.00,-13650.00,-1150.00,0 +-15000.00,-14300.00,-700.00,-15000.00,-13250.00,-1750.00,0 +-15200.00,-14000.00,-1200.00,-15200.00,-13500.00,-1700.00,0 +-15400.00,-15000.00,-400.00,-15400.00,-14800.00,-600.00,0 +-15600.00,-14750.00,-850.00,-15600.00,-14700.00,-900.00,0 +-15800.00,-13900.00,-1900.00,-15800.00,-13550.00,-2250.00,0 +-16000.00,-14550.00,-1450.00,-16000.00,-14050.00,-1950.00,0 +-16200.00,-16400.00,200.00,-16200.00,-15200.00,-1000.00,0 +-16400.00,-16200.00,-200.00,-16400.00,-15400.00,-1000.00,0 +-16600.00,-15250.00,-1350.00,-16600.00,-14500.00,-2100.00,0 +-16800.00,-16250.00,-550.00,-16800.00,-15650.00,-1150.00,0 +-17000.00,-16500.00,-500.00,-17000.00,-15900.00,-1100.00,0 +-17200.00,-15850.00,-1350.00,-17200.00,-15250.00,-1950.00,0 +-17400.00,-15650.00,-1750.00,-17400.00,-15650.00,-1750.00,0 +-17600.00,-16700.00,-900.00,-17600.00,-16400.00,-1200.00,0 +-17800.00,-17700.00,-100.00,-17800.00,-16950.00,-850.00,0 +-18000.00,-17500.00,-500.00,-18000.00,-16900.00,-1100.00,0 +-18200.00,-17550.00,-650.00,-18200.00,-17550.00,-650.00,0 +-18400.00,-18050.00,-350.00,-18400.00,-16650.00,-1750.00,0 +-18600.00,-17550.00,-1050.00,-18600.00,-16600.00,-2000.00,0 +-18800.00,-18300.00,-500.00,-18800.00,-17700.00,-1100.00,0 +-19000.00,-18000.00,-1000.00,-19000.00,-17050.00,-1950.00,0 +-19200.00,-18550.00,-650.00,-19200.00,-18350.00,-850.00,0 +-19400.00,-19000.00,-400.00,-19400.00,-18200.00,-1200.00,0 +-19600.00,-18250.00,-1350.00,-19600.00,-17200.00,-2400.00,0 +-19800.00,-19350.00,-450.00,-19800.00,-18600.00,-1200.00,0 +-20000.00,-20100.00,100.00,-20000.00,-19000.00,-1000.00,0 +-20200.00,-18700.00,-1500.00,-20200.00,-18200.00,-2000.00,0 +-20400.00,-19850.00,-550.00,-20400.00,-19850.00,-550.00,0 +-20600.00,-20250.00,-350.00,-20600.00,-19050.00,-1550.00,0 +-20800.00,-19950.00,-850.00,-20800.00,-19200.00,-1600.00,0 +-21000.00,-20700.00,-300.00,-21000.00,-20100.00,-900.00,0 +-21200.00,-20500.00,-700.00,-21200.00,-19800.00,-1400.00,0 +-21400.00,-20150.00,-1250.00,-21400.00,-19850.00,-1550.00,0 +-21600.00,-21000.00,-600.00,-21600.00,-20100.00,-1500.00,0 +-21800.00,-21500.00,-300.00,-21800.00,-19900.00,-1900.00,0 +-22000.00,-21050.00,-950.00,-22000.00,-20400.00,-1600.00,0 +-22200.00,-21350.00,-850.00,-22200.00,-21250.00,-950.00,0 +-22400.00,-26300.00,3900.00,-22400.00,-26000.00,3600.00,0 +-22600.00,-21400.00,-1200.00,-22600.00,-19700.00,-2900.00,0 +-22800.00,-20000.00,-2800.00,-22800.00,-20000.00,-2800.00,0 +-23000.00,-23250.00,250.00,-23000.00,-23000.00,0.00,0 +-23200.00,-23600.00,400.00,-23200.00,-21650.00,-1550.00,0 +-23400.00,-21200.00,-2200.00,-23184.98,-21850.00,-1334.98,0 +-23371.48,-22400.00,-971.48,-22984.98,-21550.00,-1434.98,0 +-23171.48,-23950.00,778.52,-22784.98,-22850.00,65.02,0 +-22971.48,-23600.00,628.52,-22584.98,-21600.00,-984.98,0 +-22771.48,-22200.00,-571.48,-22384.98,-21800.00,-584.98,0 +-22571.48,-22400.00,-171.48,-22184.98,-22950.00,765.02,0 +-22371.48,-22350.00,-21.48,-21984.98,-20150.00,-1834.98,0 +-22171.48,-23300.00,1128.52,-21784.98,-21400.00,-384.98,0 +-21971.48,-23050.00,1078.52,-21584.98,-22000.00,415.02,0 +-21771.48,-22150.00,378.52,-21384.98,-20050.00,-1334.98,0 +-21571.48,-21800.00,228.52,-21184.98,-21000.00,-184.98,0 +-21371.48,-21400.00,28.52,-20984.98,-20150.00,-834.98,0 +-21171.48,-21300.00,128.52,-20784.98,-20300.00,-484.98,0 +-20971.48,-21100.00,128.52,-20584.98,-20200.00,-384.98,0 +-20771.48,-20100.00,-671.48,-20384.98,-19100.00,-1284.98,0 +-20571.48,-20750.00,178.52,-20184.98,-19700.00,-484.98,0 +-20371.48,-20400.00,28.52,-19984.98,-19100.00,-884.98,0 +-20171.48,-19050.00,-1121.48,-19784.98,-18250.00,-1534.98,0 +-19971.48,-20250.00,278.52,-19584.98,-19850.00,265.02,0 +-19771.48,-20200.00,428.52,-19384.98,-18300.00,-1084.98,0 +-19571.48,-19050.00,-521.48,-19184.98,-17600.00,-1584.98,0 +-19371.48,-19950.00,578.52,-18984.98,-18900.00,-84.98,0 +-19171.48,-20250.00,1078.52,-18784.98,-18500.00,-284.98,0 +-18971.48,-18200.00,-771.48,-18584.98,-17750.00,-834.98,0 +-18771.48,-18900.00,128.52,-18384.98,-19050.00,665.02,0 +-18571.48,-19250.00,678.52,-18184.98,-16650.00,-1534.98,0 +-18371.48,-19400.00,1028.52,-17984.98,-17200.00,-784.98,0 +-18171.48,-18400.00,228.52,-17784.98,-18900.00,1115.02,0 +-17971.48,-17000.00,-971.48,-17584.98,-16050.00,-1534.98,0 +-17771.48,-16800.00,-971.48,-17384.98,-15900.00,-1484.98,0 +-17571.48,-18500.00,928.52,-17184.98,-18400.00,1215.02,0 +-17371.48,-17550.00,178.52,-16984.98,-16100.00,-884.98,0 +-17171.48,-16300.00,-871.48,-16784.98,-15300.00,-1484.98,0 +-16971.48,-17050.00,78.52,-16584.98,-17400.00,815.02,0 +-16771.48,-17650.00,878.52,-16384.98,-16900.00,515.02,0 +-16571.48,-16500.00,-71.48,-16184.98,-15400.00,-784.98,0 +-16371.48,-16150.00,-221.48,-15984.98,-16050.00,65.02,0 +-16171.48,-16150.00,-21.48,-15784.98,-16350.00,565.02,0 +-15971.48,-15850.00,-121.48,-15584.98,-14450.00,-1134.98,0 +-15771.48,-15800.00,28.52,-15384.98,-14000.00,-1384.98,0 +-15571.48,-16300.00,728.52,-15184.98,-15550.00,365.02,0 +-15371.48,-15600.00,228.52,-14984.98,-14300.00,-684.98,0 +-15171.48,-15450.00,278.52,-14784.98,-14300.00,-484.98,0 +-14971.48,-14650.00,-321.48,-14584.98,-14050.00,-534.98,0 +-14771.48,-15000.00,228.52,-14384.98,-13900.00,-484.98,0 +-14571.48,-14400.00,-171.48,-14184.98,-13300.00,-884.98,0 +-14371.48,-14400.00,28.52,-13984.98,-13250.00,-734.98,0 +-14171.48,-13550.00,-621.48,-13784.98,-13000.00,-784.98,0 +-13971.48,-13750.00,-221.48,-13584.98,-13150.00,-434.98,0 +-13771.48,-14300.00,528.52,-13384.98,-13250.00,-134.98,0 +-13571.48,-13600.00,28.52,-13184.98,-12650.00,-534.98,0 +-13371.48,-12700.00,-671.48,-12984.98,-12100.00,-884.98,0 +-13171.48,-13650.00,478.52,-12784.98,-12650.00,-134.98,0 +-12971.48,-12750.00,-221.48,-12584.98,-11850.00,-734.98,0 +-12771.48,-12450.00,-321.48,-12384.98,-11950.00,-434.98,0 +-12571.48,-12750.00,178.52,-12184.98,-11500.00,-684.98,0 +-12371.48,-12100.00,-271.48,-11984.98,-10850.00,-1134.98,0 +-12171.48,-11950.00,-221.48,-11784.98,-11150.00,-634.98,0 +-11971.48,-12400.00,428.52,-11584.98,-11300.00,-284.98,0 +-11771.48,-11350.00,-421.48,-11384.98,-10450.00,-934.98,0 +-11571.48,-11350.00,-221.48,-11184.98,-10500.00,-684.98,0 +-11371.48,-10650.00,-721.48,-10984.98,-9800.00,-1184.98,0 +-11171.48,-10450.00,-721.48,-10784.98,-9700.00,-1084.98,0 +-10971.48,-10400.00,-571.48,-10584.98,-9350.00,-1234.98,0 +-10771.48,-10500.00,-271.48,-10384.98,-9200.00,-1184.98,0 +-10571.48,-10450.00,-121.48,-10184.98,-8900.00,-1284.98,0 +-10371.48,-9800.00,-571.48,-9984.98,-8800.00,-1184.98,0 +-10171.48,-9650.00,-521.48,-9784.98,-9100.00,-684.98,0 +-9971.48,-9800.00,-171.48,-9584.98,-9100.00,-484.98,0 +-9771.48,-9950.00,178.52,-9384.98,-9300.00,-84.98,0 +-9571.48,-9600.00,28.52,-9184.98,-8500.00,-684.98,0 +-9371.48,-11000.00,1628.52,-8984.98,-10250.00,1265.02,0 +-9171.48,-8350.00,-821.48,-8784.98,-7750.00,-1034.98,0 +-8971.48,-7350.00,-1621.48,-8584.98,-6850.00,-1734.98,0 +-8771.48,-8350.00,-421.48,-8384.98,-8050.00,-334.98,0 +-8571.48,-8250.00,-321.48,-8184.98,-7850.00,-334.98,0 +-8371.48,-7750.00,-621.48,-7984.98,-6850.00,-1134.98,0 +-8171.48,-7550.00,-621.48,-7784.98,-6800.00,-984.98,0 +-7971.48,-7750.00,-221.48,-7584.98,-6950.00,-634.98,0 +-7771.48,-7550.00,-221.48,-7384.98,-6800.00,-584.98,0 +-7571.48,-7200.00,-371.48,-7184.98,-6450.00,-734.98,0 +-7371.48,-6850.00,-521.48,-6984.98,-6100.00,-884.98,0 +-7171.48,-6700.00,-471.48,-6784.98,-5800.00,-984.98,0 +-6971.48,-6350.00,-621.48,-6584.98,-5700.00,-884.98,0 +-6771.48,-5800.00,-971.48,-6384.98,-5350.00,-1034.98,0 +-6571.48,-6000.00,-571.48,-6184.98,-5450.00,-734.98,0 +-6371.48,-6000.00,-371.48,-5984.98,-5350.00,-634.98,0 +-6171.48,-5600.00,-571.48,-5784.98,-4700.00,-1084.98,0 +-5971.48,-4900.00,-1071.48,-5584.98,-4300.00,-1284.98,0 +-5771.48,-5050.00,-721.48,-5384.98,-4250.00,-1134.98,0 +-5571.48,-4850.00,-721.48,-5184.98,-4250.00,-934.98,0 +-5371.48,-4500.00,-871.48,-4984.98,-3900.00,-1084.98,0 +-5171.48,-4400.00,-771.48,-4784.98,-3650.00,-1134.98,0 +-4971.48,-4050.00,-921.48,-4584.98,-3400.00,-1184.98,0 +-4771.48,-3800.00,-971.48,-4384.98,-3250.00,-1134.98,0 +-4571.48,-3750.00,-821.48,-4184.98,-3200.00,-984.98,0 +-4371.48,-3550.00,-821.48,-3984.98,-3200.00,-784.98,0 +-4171.48,-3100.00,-1071.48,-3784.98,-2900.00,-884.98,0 +-3971.48,-2600.00,-1371.48,-3584.98,-2100.00,-1484.98,0 +-3771.48,-3150.00,-621.48,-3384.98,-1450.00,-1934.98,0 +-3571.48,-2800.00,-771.48,-3184.98,-3100.00,-84.98,0 +-3371.48,-1200.00,-2171.48,-2984.98,-2400.00,-584.98,0 +-3171.48,-1950.00,-1221.48,-2784.98,0.00,-2784.98,0 +-2971.48,-2750.00,-221.48,-2584.98,-1700.00,-884.98,0 +-2771.48,-1850.00,-921.48,-2384.98,-1900.00,-484.98,0 +-2571.48,-1100.00,-1471.48,-2184.98,800.00,-2984.98,0 +-2371.48,-950.00,-1421.48,-1984.98,-1200.00,-784.98,0 +-2171.48,-350.00,-1821.48,-1784.98,-1900.00,115.02,0 +-1971.48,0.00,-1971.48,-1584.98,50.00,-1634.98,0 +-1771.48,-250.00,-1521.48,-1384.98,-200.00,-1184.98,0 +-1571.48,-200.00,-1371.48,-1184.98,-150.00,-1034.98,0 +-1371.48,100.00,-1471.48,-984.98,300.00,-1284.98,0 +-1171.48,500.00,-1671.48,-784.98,0.00,-784.98,0 +-971.48,1100.00,-2071.48,-584.98,0.00,-584.98,0 +-771.48,-350.00,-421.48,-384.98,0.00,-384.98,0 +-571.48,-400.00,-171.48,-184.98,0.00,-184.98,0 +-371.48,850.00,-1221.48,0.00,0.00,0.00,0 +-171.48,-200.00,28.52,0.00,0.00,0.00,0 +0.00,-200.00,200.00,0.00,0.00,0.00,0 +0.00,100.00,-100.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +200.00,0.00,200.00,200.00,0.00,200.00,0 +400.00,0.00,400.00,400.00,0.00,400.00,0 +600.00,0.00,600.00,600.00,0.00,600.00,0 +800.00,0.00,800.00,800.00,0.00,800.00,0 +1000.00,0.00,1000.00,1000.00,0.00,1000.00,0 +1200.00,0.00,1200.00,1200.00,0.00,1200.00,0 +1400.00,0.00,1400.00,1400.00,0.00,1400.00,0 +1600.00,0.00,1600.00,1600.00,0.00,1600.00,0 +1800.00,200.00,1600.00,1800.00,200.00,1600.00,0 +2000.00,400.00,1600.00,2000.00,500.00,1500.00,0 +2200.00,50.00,2150.00,2200.00,0.00,2200.00,0 +2400.00,250.00,2150.00,2400.00,100.00,2300.00,0 +2600.00,900.00,1700.00,2600.00,200.00,2400.00,0 +2800.00,2300.00,500.00,2800.00,300.00,2500.00,0 +3000.00,1200.00,1800.00,3000.00,600.00,2400.00,0 +3200.00,1000.00,2200.00,3200.00,1250.00,1950.00,0 +3400.00,1800.00,1600.00,3400.00,1350.00,2050.00,0 +3600.00,1850.00,1750.00,3600.00,1550.00,2050.00,0 +3800.00,1600.00,2200.00,3800.00,1350.00,2450.00,0 +4000.00,2300.00,1700.00,4000.00,1700.00,2300.00,0 +4200.00,2300.00,1900.00,4200.00,1700.00,2500.00,0 +4400.00,2100.00,2300.00,4400.00,1950.00,2450.00,0 +4600.00,2800.00,1800.00,4600.00,2200.00,2400.00,0 +4800.00,3000.00,1800.00,4800.00,2550.00,2250.00,0 +5000.00,2500.00,2500.00,5000.00,2750.00,2250.00,0 +5200.00,3100.00,2100.00,5200.00,2850.00,2350.00,0 +5400.00,3650.00,1750.00,5400.00,3100.00,2300.00,0 +5600.00,3700.00,1900.00,5600.00,3400.00,2200.00,0 +5800.00,3950.00,1850.00,5800.00,3600.00,2200.00,0 +6000.00,4100.00,1900.00,6000.00,3900.00,2100.00,0 +6200.00,4550.00,1650.00,6200.00,4250.00,1950.00,0 +6400.00,4700.00,1700.00,6400.00,4450.00,1950.00,0 +6600.00,4950.00,1650.00,6600.00,4650.00,1950.00,0 +6800.00,5100.00,1700.00,6800.00,4650.00,2150.00,0 +7000.00,5300.00,1700.00,7000.00,5150.00,1850.00,0 +7200.00,5800.00,1400.00,7200.00,5250.00,1950.00,0 +7400.00,5950.00,1450.00,7400.00,5600.00,1800.00,0 +7600.00,6150.00,1450.00,7600.00,5750.00,1850.00,0 +7800.00,6150.00,1650.00,7800.00,5450.00,2350.00,0 +8000.00,7500.00,500.00,8000.00,7100.00,900.00,0 +8200.00,6350.00,1850.00,8200.00,5900.00,2300.00,0 +8400.00,6400.00,2000.00,8400.00,6300.00,2100.00,0 +8600.00,7050.00,1550.00,8600.00,6400.00,2200.00,0 +8800.00,7100.00,1700.00,8800.00,6600.00,2200.00,0 +9000.00,7250.00,1750.00,9000.00,6900.00,2100.00,0 +9200.00,7450.00,1750.00,9200.00,6950.00,2250.00,0 +9400.00,7600.00,1800.00,9400.00,7350.00,2050.00,0 +9600.00,7750.00,1850.00,9600.00,7500.00,2100.00,0 +9800.00,8100.00,1700.00,9800.00,7950.00,1850.00,0 +10000.00,8600.00,1400.00,10000.00,8050.00,1950.00,0 +10200.00,8900.00,1300.00,10200.00,8350.00,1850.00,0 +10400.00,9150.00,1250.00,10400.00,8250.00,2150.00,0 +10600.00,9250.00,1350.00,10600.00,8400.00,2200.00,0 +10800.00,9250.00,1550.00,10800.00,8550.00,2250.00,0 +11000.00,9250.00,1750.00,11000.00,8600.00,2400.00,0 +11200.00,9450.00,1750.00,11200.00,9000.00,2200.00,0 +11400.00,9650.00,1750.00,11400.00,9250.00,2150.00,0 +11600.00,9800.00,1800.00,11600.00,9800.00,1800.00,0 +11800.00,9800.00,2000.00,11800.00,9950.00,1850.00,0 +12000.00,10150.00,1850.00,12000.00,10100.00,1900.00,0 +12200.00,10450.00,1750.00,12200.00,10350.00,1850.00,0 +12400.00,10950.00,1450.00,12400.00,10550.00,1850.00,0 +12600.00,11400.00,1200.00,12600.00,10750.00,1850.00,0 +12800.00,11600.00,1200.00,12800.00,11000.00,1800.00,0 +13000.00,11600.00,1400.00,13000.00,11050.00,1950.00,0 +13200.00,11650.00,1550.00,13200.00,11250.00,1950.00,0 +13400.00,12550.00,850.00,13400.00,12200.00,1200.00,0 +13600.00,11850.00,1750.00,13600.00,11550.00,2050.00,0 +13800.00,11800.00,2000.00,13800.00,11750.00,2050.00,0 +14000.00,12250.00,1750.00,14000.00,11900.00,2100.00,0 +14200.00,12550.00,1650.00,14200.00,12300.00,1900.00,0 +14400.00,12850.00,1550.00,14400.00,12700.00,1700.00,0 +14600.00,13550.00,1050.00,14600.00,13000.00,1600.00,0 +14800.00,13550.00,1250.00,14800.00,13100.00,1700.00,0 +15000.00,13800.00,1200.00,15000.00,13500.00,1500.00,0 +15200.00,13950.00,1250.00,15200.00,13450.00,1750.00,0 +15400.00,14550.00,850.00,15400.00,14050.00,1350.00,0 +15600.00,14200.00,1400.00,15600.00,13900.00,1700.00,0 +15800.00,14750.00,1050.00,15800.00,14350.00,1450.00,0 +16000.00,14400.00,1600.00,16000.00,13950.00,2050.00,0 +16200.00,15550.00,650.00,16200.00,14850.00,1350.00,0 +16400.00,15600.00,800.00,16400.00,14850.00,1550.00,0 +16600.00,14950.00,1650.00,16600.00,14700.00,1900.00,0 +16800.00,15800.00,1000.00,16800.00,15350.00,1450.00,0 +17000.00,15550.00,1450.00,17000.00,15100.00,1900.00,0 +17200.00,15350.00,1850.00,17200.00,15650.00,1550.00,0 +17400.00,16550.00,850.00,17400.00,16350.00,1050.00,0 +17600.00,16800.00,800.00,17600.00,16200.00,1400.00,0 +17800.00,16800.00,1000.00,17800.00,15950.00,1850.00,0 +18000.00,17200.00,800.00,18000.00,16450.00,1550.00,0 +18200.00,17550.00,650.00,18200.00,17150.00,1050.00,0 +18400.00,17100.00,1300.00,18400.00,16800.00,1600.00,0 +18600.00,17250.00,1350.00,18600.00,16700.00,1900.00,0 +18800.00,17800.00,1000.00,18800.00,17250.00,1550.00,0 +19000.00,17200.00,1800.00,19000.00,17150.00,1850.00,0 +19200.00,18450.00,750.00,19200.00,17600.00,1600.00,0 +19400.00,18650.00,750.00,19400.00,18400.00,1000.00,0 +19600.00,18550.00,1050.00,19600.00,18400.00,1200.00,0 +19800.00,18800.00,1000.00,19800.00,18700.00,1100.00,0 +20000.00,18900.00,1100.00,20000.00,18350.00,1650.00,0 +20200.00,19350.00,850.00,20200.00,19350.00,850.00,0 +20400.00,19450.00,950.00,20400.00,18500.00,1900.00,0 +20600.00,20100.00,500.00,20600.00,19750.00,850.00,0 +20800.00,20550.00,250.00,20800.00,19350.00,1450.00,0 +21000.00,18750.00,2250.00,21000.00,18900.00,2100.00,0 +21200.00,19650.00,1550.00,21200.00,20000.00,1200.00,0 +21400.00,21100.00,300.00,21400.00,20300.00,1100.00,0 +21600.00,20400.00,1200.00,21600.00,20200.00,1400.00,0 +21800.00,20750.00,1050.00,21800.00,19950.00,1850.00,0 +22000.00,21450.00,550.00,22000.00,20850.00,1150.00,0 +22200.00,20850.00,1350.00,22200.00,20600.00,1600.00,0 +22400.00,21250.00,1150.00,22400.00,21950.00,450.00,0 +22600.00,22200.00,400.00,22600.00,21450.00,1150.00,0 +22800.00,22200.00,600.00,22800.00,21600.00,1200.00,0 +23000.00,21600.00,1400.00,23000.00,21400.00,1600.00,0 +23200.00,21950.00,1250.00,23200.00,21800.00,1400.00,0 +23400.00,22300.00,1100.00,23279.76,22300.00,979.76,0 +23600.00,22150.00,1450.00,23079.76,22350.00,729.76,0 +23760.91,27800.00,-4039.09,22879.76,27300.00,-4420.24,0 +23560.91,22100.00,1460.91,22679.76,20200.00,2479.76,0 +23360.91,20200.00,3160.91,22479.76,18450.00,4029.76,0 +23160.91,23500.00,-339.09,22279.76,23450.00,-1170.24,0 +22960.91,26200.00,-3239.09,22079.76,21900.00,179.76,0 +22760.91,22050.00,710.91,21879.76,19950.00,1929.76,0 +22560.91,20400.00,2160.91,21679.76,21900.00,-220.24,0 +22360.91,22450.00,-89.09,21479.76,23000.00,-1520.24,0 +22160.91,24950.00,-2789.09,21279.76,20900.00,379.76,0 +21960.91,21500.00,460.91,21079.76,18900.00,2179.76,0 +21760.91,19950.00,1810.91,20879.76,21600.00,-720.24,0 +21560.91,21600.00,-39.09,20679.76,20650.00,29.76,0 +21360.91,23100.00,-1739.09,20479.76,19150.00,1329.76,0 +21160.91,22350.00,-1189.09,20279.76,20600.00,-320.24,0 +20960.91,21300.00,-339.09,20079.76,21850.00,-1770.24,0 +20760.91,19850.00,910.91,19879.76,18250.00,1629.76,0 +20560.91,20100.00,460.91,19679.76,18150.00,1529.76,0 +20360.91,20550.00,-189.09,19479.76,20200.00,-720.24,0 +20160.91,20200.00,-39.09,19279.76,18250.00,1029.76,0 +19960.91,19550.00,410.91,19079.76,17600.00,1479.76,0 +19760.91,19450.00,310.91,18879.76,18800.00,79.76,0 +19560.91,19800.00,-239.09,18679.76,18300.00,379.76,0 +19360.91,19550.00,-189.09,18479.76,17100.00,1379.76,0 +19160.91,18600.00,560.91,18279.76,18100.00,179.76,0 +18960.91,18500.00,460.91,18079.76,18600.00,-520.24,0 +18760.91,18800.00,-39.09,17879.76,17000.00,879.76,0 +18560.91,18400.00,160.91,17679.76,17150.00,529.76,0 +18360.91,17800.00,560.91,17479.76,16950.00,529.76,0 +18160.91,16850.00,1310.91,17279.76,15850.00,1429.76,0 +17960.91,17100.00,860.91,17079.76,16550.00,529.76,0 +17760.91,18150.00,-389.09,16879.76,16800.00,79.76,0 +17560.91,17650.00,-89.09,16679.76,16450.00,229.76,0 +17360.91,16900.00,460.91,16479.76,16050.00,429.76,0 +17160.91,16950.00,210.91,16279.76,16000.00,279.76,0 +16960.91,16950.00,10.91,16079.76,15600.00,479.76,0 +16760.91,16550.00,210.91,15879.76,15600.00,279.76,0 +16560.91,16350.00,210.91,15679.76,15200.00,479.76,0 +16360.91,16300.00,60.91,15479.76,14900.00,579.76,0 +16160.91,15400.00,760.91,15279.76,14300.00,979.76,0 +15960.91,15200.00,760.91,15079.76,14400.00,679.76,0 +15760.91,15550.00,210.91,14879.76,14650.00,229.76,0 +15560.91,15050.00,510.91,14679.76,14650.00,29.76,0 +15360.91,15000.00,360.91,14479.76,14500.00,-20.24,0 +15160.91,15200.00,-39.09,14279.76,13850.00,429.76,0 +14960.91,14900.00,60.91,14079.76,13350.00,729.76,0 +14760.91,14700.00,60.91,13879.76,13400.00,479.76,0 +14560.91,14700.00,-139.09,13679.76,12800.00,879.76,0 +14360.91,14100.00,260.91,13479.76,13050.00,429.76,0 +14160.91,13150.00,1010.91,13279.76,13200.00,79.76,0 +13960.91,12800.00,1160.91,13079.76,12350.00,729.76,0 +13760.91,12700.00,1060.91,12879.76,12000.00,879.76,0 +13560.91,13200.00,360.91,12679.76,12200.00,479.76,0 +13360.91,13450.00,-89.09,12479.76,11900.00,579.76,0 +13160.91,12750.00,410.91,12279.76,11650.00,629.76,0 +12960.91,12650.00,310.91,12079.76,11450.00,629.76,0 +12760.91,12550.00,210.91,11879.76,11150.00,729.76,0 +12560.91,12200.00,360.91,11679.76,11450.00,229.76,0 +12360.91,11750.00,610.91,11479.76,10800.00,679.76,0 +12160.91,11450.00,710.91,11279.76,10600.00,679.76,0 +11960.91,11600.00,360.91,11079.76,10650.00,429.76,0 +11760.91,11600.00,160.91,10879.76,9650.00,1229.76,0 +11560.91,11100.00,460.91,10679.76,9850.00,829.76,0 +11360.91,10650.00,710.91,10479.76,9550.00,929.76,0 +11160.91,10250.00,910.91,10279.76,9150.00,1129.76,0 +10960.91,9550.00,1410.91,10079.76,8900.00,1179.76,0 +10760.91,9600.00,1160.91,9879.76,8800.00,1079.76,0 +10560.91,9450.00,1110.91,9679.76,8650.00,1029.76,0 +10360.91,9400.00,960.91,9479.76,8900.00,579.76,0 +10160.91,10000.00,160.91,9279.76,9100.00,179.76,0 +9960.91,9150.00,810.91,9079.76,8250.00,829.76,0 +9760.91,8600.00,1160.91,8879.76,7950.00,929.76,0 +9560.91,8600.00,960.91,8679.76,7750.00,929.76,0 +9360.91,8200.00,1160.91,8479.76,7400.00,1079.76,0 +9160.91,8200.00,960.91,8279.76,7150.00,1129.76,0 +8960.91,7900.00,1060.91,8079.76,6900.00,1179.76,0 +8760.91,8150.00,610.91,7879.76,7100.00,779.76,0 +8560.91,7950.00,610.91,7679.76,6850.00,829.76,0 +8360.91,7450.00,910.91,7479.76,6850.00,629.76,0 +8160.91,8700.00,-539.09,7279.76,7750.00,-470.24,0 +7960.91,6800.00,1160.91,7079.76,6250.00,829.76,0 +7760.91,5950.00,1810.91,6879.76,5350.00,1529.76,0 +7560.91,6550.00,1010.91,6679.76,6050.00,629.76,0 +7360.91,6100.00,1260.91,6479.76,5700.00,779.76,0 +7160.91,5850.00,1310.91,6279.76,5000.00,1279.76,0 +6960.91,6000.00,960.91,6079.76,5550.00,529.76,0 +6760.91,5600.00,1160.91,5879.76,5200.00,679.76,0 +6560.91,5300.00,1260.91,5679.76,4350.00,1329.76,0 +6360.91,5150.00,1210.91,5479.76,4600.00,879.76,0 +6160.91,5050.00,1110.91,5279.76,4550.00,729.76,0 +5960.91,4550.00,1410.91,5079.76,3950.00,1129.76,0 +5760.91,4500.00,1260.91,4879.76,3900.00,979.76,0 +5560.91,4250.00,1310.91,4679.76,3600.00,1079.76,0 +5360.91,4000.00,1360.91,4479.76,3300.00,1179.76,0 +5160.91,3650.00,1510.91,4279.76,3200.00,1079.76,0 +4960.91,3450.00,1510.91,4079.76,2900.00,1179.76,0 +4760.91,3300.00,1460.91,3879.76,2800.00,1079.76,0 +4560.91,3000.00,1560.91,3679.76,2400.00,1279.76,0 +4360.91,2850.00,1510.91,3479.76,2250.00,1229.76,0 +4160.91,2750.00,1410.91,3279.76,2350.00,929.76,0 +3960.91,2350.00,1610.91,3079.76,1300.00,1779.76,0 +3760.91,2350.00,1410.91,2879.76,1750.00,1129.76,0 +3560.91,2450.00,1110.91,2679.76,1900.00,779.76,0 +3360.91,1900.00,1460.91,2479.76,1050.00,1429.76,0 +3160.91,1650.00,1510.91,2279.76,500.00,1779.76,0 +2960.91,1600.00,1360.91,2079.76,150.00,1929.76,0 +2760.91,1550.00,1210.91,1879.76,400.00,1479.76,0 +2560.91,300.00,2260.91,1679.76,350.00,1329.76,0 +2360.91,200.00,2160.91,1479.76,-100.00,1579.76,0 +2160.91,2200.00,-39.09,1279.76,-200.00,1479.76,0 +1960.91,550.00,1410.91,1079.76,-600.00,1679.76,0 +1760.91,-1000.00,2760.91,879.76,-500.00,1379.76,0 +1560.91,250.00,1310.91,679.76,0.00,679.76,0 +1360.91,1100.00,260.91,479.76,0.00,479.76,0 +1160.91,-950.00,2110.91,279.76,0.00,279.76,0 +960.91,-450.00,1410.91,79.76,0.00,79.76,0 +760.91,650.00,110.91,0.00,0.00,0.00,0 +560.91,-800.00,1360.91,0.00,0.00,0.00,0 +360.91,50.00,310.91,0.00,0.00,0.00,0 +160.91,300.00,-139.09,0.00,0.00,0.00,0 +0.00,-150.00,150.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 \ No newline at end of file From 2f518ba227c8b9e77624b5f20c9fbe9d8510331a Mon Sep 17 00:00:00 2001 From: democat Date: Tue, 30 Sep 2025 23:58:29 -0500 Subject: [PATCH 27/47] Temp fix for now to hopefully prevent blocking the thread? unsure --- src/robot/magnet.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/src/robot/magnet.cpp b/src/robot/magnet.cpp index 543e411..ada8c31 100644 --- a/src/robot/magnet.cpp +++ b/src/robot/magnet.cpp @@ -10,7 +10,7 @@ Magnet::Magnet() Wire.begin(SDA_PIN, SCL_PIN); bmm350.begin(); bmm350.setOperationMode(eBmm350NormalMode); - bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY, BMM350_DATA_RATE_100HZ); + bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY, BMM350_DATA_RATE_50HZ); bmm350.setMeasurementXYZ(); } @@ -62,6 +62,9 @@ float Magnet::readDegreesRaw() { } float Magnet::readDegrees() { + if (!bmm350.getDataReadyState()) { + return previousReading; // Return the last reading if data is not ready + } float currentReading = readDegreesRaw(); // Handle wrap-around if (currentReading - previousReading > 180) { From 795a9e2c322b11c5adb035ace2225adc15d08c00 Mon Sep 17 00:00:00 2001 From: democat Date: Tue, 30 Sep 2025 23:59:57 -0500 Subject: [PATCH 28/47] nvm only works if data ready interrupt pin is enabled --- src/robot/magnet.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/src/robot/magnet.cpp b/src/robot/magnet.cpp index ada8c31..a8a8289 100644 --- a/src/robot/magnet.cpp +++ b/src/robot/magnet.cpp @@ -62,9 +62,10 @@ float Magnet::readDegreesRaw() { } float Magnet::readDegrees() { - if (!bmm350.getDataReadyState()) { - return previousReading; // Return the last reading if data is not ready - } + // Only works if data ready interrupt is enabled + // if (!bmm350.getDataReadyState()) { + // return previousReading; // Return the last reading if data is not ready + // } float currentReading = readDegreesRaw(); // Handle wrap-around if (currentReading - previousReading > 180) { From 3955e966feb2c15b0a70767767e100d17555924e Mon Sep 17 00:00:00 2001 From: democat Date: Tue, 7 Oct 2025 01:54:02 -0500 Subject: [PATCH 29/47] add todo, commented out interrupt code --- src/main.cpp | 1 + src/robot/magnet.cpp | 15 +++++++++++++-- 2 files changed, 14 insertions(+), 2 deletions(-) diff --git a/src/main.cpp b/src/main.cpp index 6aa163c..f6aad9f 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -68,6 +68,7 @@ void loop() { } // Run control loop + // TODO change time parameter to be actual delta time, not just delay between loops controlLoop(loopDelayMilliseconds, framesUntilPrint); // This delay determines how often the code in loop is run diff --git a/src/robot/magnet.cpp b/src/robot/magnet.cpp index a8a8289..0b463b1 100644 --- a/src/robot/magnet.cpp +++ b/src/robot/magnet.cpp @@ -2,7 +2,15 @@ #include "robot/magnet.h" #define SDA_PIN 8 -#define SCL_PIN 9 +#define SCL_PIN 9 + +// volatile uint8_t interruptFlag = 0; +// void Magnet::updateReadings(void) +// { +// // interruptFlag = 1; // Interrupt flag +// // detachInterrupt(13); // Detach interrupt +// currentRaw = readDegreesRaw(); +// } Magnet::Magnet() : bmm350(&Wire, 0x14) @@ -10,8 +18,11 @@ Magnet::Magnet() Wire.begin(SDA_PIN, SCL_PIN); bmm350.begin(); bmm350.setOperationMode(eBmm350NormalMode); - bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY, BMM350_DATA_RATE_50HZ); + bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY, BMM350_DATA_RATE_12_5HZ); bmm350.setMeasurementXYZ(); + // bmm350.setDataReadyPin(BMM350_ENABLE_INTERRUPT, BMM350_ACTIVE_LOW); + // pinMode(/*Pin */ 13, INPUT_PULLUP); + // attachInterrupt(/*interput io*/ 13, [this](){ this->updateReadings(); }, ONLOW); } void Magnet::set_hard_iron_offset(float x, float y, float z) { From 54ce47fb16cf4a8cc6c700903c572d70128d8d20 Mon Sep 17 00:00:00 2001 From: democat Date: Wed, 8 Oct 2025 17:59:14 -0500 Subject: [PATCH 30/47] 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 --- pid_test.csv | 4989 ++++++++++++++++++++++++++++++++++++++++- src/main.cpp | 7 +- src/robot/control.cpp | 6 +- 3 files changed, 4997 insertions(+), 5 deletions(-) diff --git a/pid_test.csv b/pid_test.csv index 71be961..d888e93 100644 --- a/pid_test.csv +++ b/pid_test.csv @@ -746,4 +746,4991 @@ LeftSetpoint,LeftVelocity,LeftError,RightSetpoint,RightVelocity,RightError,Headi 0.00,0.00,0.00,0.00,0.00,0.00,0 0.00,0.00,0.00,0.00,0.00,0.00,0 0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 \ No newline at end of file +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,290.55 +0.00,0.00,0.00,0.00,0.00,0.00,290.55 +0.00,0.00,0.00,0.00,0.00,0.00,290.55 +0.00,0.00,0.00,0.00,0.00,0.00,290.57 +0.00,0.00,0.00,0.00,0.00,0.00,290.56 +0.00,0.00,0.00,0.00,0.00,0.00,290.52 +0.00,0.00,0.00,0.00,0.00,0.00,290.51 +0.00,0.00,0.00,0.00,0.00,0.00,290.51 +0.00,0.00,0.00,0.00,0.00,0.00,290.55 +0.00,0.00,0.00,0.00,0.00,0.00,290.56 +0.00,0.00,0.00,0.00,0.00,0.00,290.57 +0.00,0.00,0.00,0.00,0.00,0.00,290.59 +0.00,0.00,0.00,0.00,0.00,0.00,290.60 +0.00,0.00,0.00,0.00,0.00,0.00,290.59 +0.00,0.00,0.00,0.00,0.00,0.00,290.55 +0.00,0.00,0.00,0.00,0.00,0.00,290.54 +0.00,0.00,0.00,0.00,0.00,0.00,290.54 +0.00,0.00,0.00,0.00,0.00,0.00,290.56 +0.00,0.00,0.00,0.00,0.00,0.00,290.56 +-200.00,0.00,-200.00,-200.00,0.00,-200.00,290.53 +-400.00,0.00,-400.00,-400.00,0.00,-400.00,290.58 +-600.00,0.00,-600.00,-600.00,0.00,-600.00,290.56 +-800.00,0.00,-800.00,-800.00,0.00,-800.00,290.56 +-1000.00,0.00,-1000.00,-1000.00,0.00,-1000.00,290.53 +-1200.00,0.00,-1200.00,-1200.00,0.00,-1200.00,290.47 +-1400.00,0.00,-1400.00,-1400.00,0.00,-1400.00,290.47 +-1600.00,0.00,-1600.00,-1600.00,0.00,-1600.00,290.48 +-1800.00,-250.00,-1550.00,-1800.00,-150.00,-1650.00,290.49 +-2000.00,-350.00,-1650.00,-2000.00,-250.00,-1750.00,290.47 +-2200.00,0.00,-2200.00,-2200.00,0.00,-2200.00,290.52 +-2400.00,-300.00,-2100.00,-2400.00,-200.00,-2200.00,290.52 +-2600.00,-1050.00,-1550.00,-2600.00,-550.00,-2050.00,290.45 +-2800.00,-2950.00,150.00,-2800.00,-1600.00,-1200.00,290.56 +-3000.00,-3100.00,100.00,-3000.00,-2050.00,-950.00,290.48 +-3200.00,-2000.00,-1200.00,-3200.00,-500.00,-2700.00,290.42 +-3400.00,-1250.00,-2150.00,-3400.00,-1200.00,-2200.00,290.49 +-3600.00,-2050.00,-1550.00,-3600.00,-3400.00,-200.00,290.49 +-3800.00,-4150.00,350.00,-3800.00,-3900.00,100.00,290.42 +-4000.00,-3900.00,-100.00,-4000.00,-2300.00,-1700.00,290.43 +-4200.00,-2850.00,-1350.00,-4200.00,-1550.00,-2650.00,290.48 +-4400.00,-1850.00,-2550.00,-4400.00,-2350.00,-2050.00,290.61 +-4600.00,-4000.00,-600.00,-4600.00,-4550.00,-50.00,290.55 +-4800.00,-5550.00,750.00,-4800.00,-4700.00,-100.00,290.58 +-5000.00,-4100.00,-900.00,-5000.00,-3400.00,-1600.00,290.55 +-5200.00,-3150.00,-2050.00,-5200.00,-2450.00,-2750.00,290.49 +-5400.00,-4400.00,-1000.00,-5400.00,-3850.00,-1550.00,290.53 +-5600.00,-6150.00,550.00,-5600.00,-6100.00,500.00,290.58 +-5800.00,-5750.00,-50.00,-5800.00,-6150.00,350.00,290.59 +-6000.00,-4300.00,-1700.00,-6000.00,-4750.00,-1250.00,290.59 +-6200.00,-3900.00,-2300.00,-6200.00,-3750.00,-2450.00,290.71 +-6400.00,-6300.00,-100.00,-6400.00,-4700.00,-1700.00,290.81 +-6600.00,-7700.00,1100.00,-6600.00,-6750.00,150.00,290.77 +-6800.00,-5850.00,-950.00,-6800.00,-7150.00,350.00,290.79 +-7000.00,-4900.00,-2100.00,-7000.00,-5800.00,-1200.00,290.74 +-7200.00,-6350.00,-850.00,-7200.00,-4800.00,-2400.00,290.68 +-7400.00,-8450.00,1050.00,-7400.00,-5900.00,-1500.00,290.69 +-7600.00,-8150.00,550.00,-7600.00,-8050.00,450.00,290.71 +-7800.00,-6300.00,-1500.00,-7800.00,-8350.00,550.00,290.65 +-8000.00,-5450.00,-2550.00,-8000.00,-6700.00,-1300.00,290.62 +-8200.00,-8150.00,-50.00,-8200.00,-6150.00,-2050.00,290.63 +-8400.00,-10550.00,2150.00,-8400.00,-7000.00,-1400.00,290.62 +-8600.00,-9300.00,700.00,-8600.00,-8750.00,150.00,290.61 +-8800.00,-7050.00,-1750.00,-8800.00,-9200.00,400.00,290.54 +-9000.00,-6650.00,-2350.00,-9000.00,-8450.00,-550.00,290.49 +-9200.00,-9600.00,400.00,-9200.00,-7150.00,-2050.00,290.49 +-9400.00,-11300.00,1900.00,-9400.00,-7800.00,-1600.00,290.52 +-9600.00,-9950.00,350.00,-9600.00,-10100.00,500.00,290.53 +-9800.00,-8050.00,-1750.00,-9800.00,-10500.00,700.00,290.52 +-10000.00,-8550.00,-1450.00,-10000.00,-9450.00,-550.00,290.43 +-10200.00,-10400.00,200.00,-10200.00,-7950.00,-2250.00,290.44 +-10400.00,-11150.00,750.00,-10400.00,-8950.00,-1450.00,290.46 +-10600.00,-10800.00,200.00,-10600.00,-11050.00,450.00,290.40 +-10800.00,-10100.00,-700.00,-10800.00,-11700.00,900.00,290.36 +-11000.00,-10350.00,-650.00,-11000.00,-10900.00,-100.00,290.29 +-11200.00,-10950.00,-250.00,-11200.00,-9000.00,-2200.00,290.25 +-11400.00,-11600.00,200.00,-11400.00,-9950.00,-1450.00,290.24 +-11600.00,-11650.00,50.00,-11600.00,-12100.00,500.00,290.17 +-11800.00,-11150.00,-650.00,-11800.00,-12550.00,750.00,290.14 +-12000.00,-11750.00,-250.00,-12000.00,-12300.00,300.00,290.05 +-12200.00,-11950.00,-250.00,-12200.00,-11300.00,-900.00,289.96 +-12400.00,-12200.00,-200.00,-12400.00,-11050.00,-1350.00,289.93 +-12600.00,-12400.00,-200.00,-12600.00,-11950.00,-650.00,289.98 +-12800.00,-12900.00,100.00,-12800.00,-13350.00,550.00,289.99 +-13000.00,-12650.00,-350.00,-13000.00,-13050.00,50.00,289.99 +-13200.00,-12700.00,-500.00,-13200.00,-12600.00,-600.00,289.95 +-13400.00,-13700.00,300.00,-13400.00,-12850.00,-550.00,290.02 +-13600.00,-14100.00,500.00,-13600.00,-13350.00,-250.00,290.06 +-13800.00,-13950.00,150.00,-13800.00,-13700.00,-100.00,290.09 +-14000.00,-13400.00,-600.00,-14000.00,-13300.00,-700.00,290.09 +-14200.00,-14300.00,100.00,-14200.00,-14000.00,-200.00,290.11 +-14400.00,-14600.00,200.00,-14400.00,-14050.00,-350.00,290.14 +-14600.00,-14400.00,-200.00,-14600.00,-14100.00,-500.00,290.14 +-14800.00,-15000.00,200.00,-14800.00,-14750.00,-50.00,290.15 +-15000.00,-14850.00,-150.00,-15000.00,-14600.00,-400.00,290.17 +-15200.00,-15600.00,400.00,-15200.00,-14900.00,-300.00,290.19 +-15400.00,-15350.00,-50.00,-15400.00,-14700.00,-700.00,290.24 +-15600.00,-17950.00,2350.00,-15600.00,-17450.00,1850.00,290.28 +-15800.00,-14700.00,-1100.00,-15800.00,-15050.00,-750.00,290.27 +-16000.00,-12700.00,-3300.00,-16000.00,-14550.00,-1450.00,290.33 +-16200.00,-16650.00,450.00,-16200.00,-15400.00,-800.00,290.39 +-16400.00,-20900.00,4500.00,-16400.00,-16850.00,450.00,290.48 +-16600.00,-17600.00,1000.00,-16600.00,-16700.00,100.00,290.51 +-16800.00,-14000.00,-2800.00,-16800.00,-16950.00,150.00,290.55 +-17000.00,-15800.00,-1200.00,-17000.00,-16900.00,-100.00,290.57 +-17200.00,-21000.00,3800.00,-17200.00,-16850.00,-350.00,290.62 +-17400.00,-19950.00,2550.00,-17400.00,-16650.00,-750.00,290.62 +-17600.00,-15100.00,-2500.00,-17600.00,-17950.00,350.00,290.54 +-17800.00,-14950.00,-2850.00,-17800.00,-18550.00,750.00,290.45 +-18000.00,-20800.00,2800.00,-18000.00,-18350.00,350.00,290.33 +-18200.00,-21250.00,3050.00,-18200.00,-17250.00,-950.00,290.26 +-18400.00,-15000.00,-3400.00,-18400.00,-17500.00,-900.00,290.26 +-18600.00,-14000.00,-4600.00,-18600.00,-19400.00,800.00,290.18 +-18800.00,-23150.00,4350.00,-18800.00,-20250.00,1450.00,290.13 +-19000.00,-26850.00,7850.00,-19000.00,-19550.00,550.00,290.06 +-19200.00,-16400.00,-2800.00,-19200.00,-18150.00,-1050.00,290.00 +-19400.00,-10250.00,-9150.00,-19400.00,-18800.00,-600.00,289.96 +-19600.00,-21400.00,1800.00,-19600.00,-19650.00,50.00,290.08 +-19800.00,-32250.00,12450.00,-19800.00,-22050.00,2250.00,289.97 +-20000.00,-20450.00,450.00,-20000.00,-19700.00,-300.00,290.21 +-20200.00,-10800.00,-9400.00,-20200.00,-19250.00,-950.00,290.08 +-20400.00,-14900.00,-5500.00,-20400.00,-20400.00,0.00,289.84 +-20600.00,-29600.00,9000.00,-20600.00,-23350.00,2750.00,289.97 +-20800.00,-29950.00,9150.00,-20800.00,-19900.00,-900.00,290.20 +-21000.00,-14000.00,-7000.00,-21000.00,-18300.00,-2700.00,290.13 +-21200.00,-11800.00,-9400.00,-21200.00,-20050.00,-1150.00,290.32 +-21400.00,-23950.00,2550.00,-21400.00,-24400.00,3000.00,290.31 +-21600.00,-33050.00,11450.00,-21600.00,-23950.00,2350.00,290.52 +-21800.00,-24950.00,3150.00,-21800.00,-20200.00,-1600.00,290.56 +-22000.00,-12000.00,-10000.00,-22000.00,-19300.00,-2700.00,290.36 +-22200.00,-16750.00,-5450.00,-22200.00,-22400.00,200.00,290.44 +-22400.00,-30150.00,7750.00,-22400.00,-26700.00,4300.00,290.48 +-22600.00,-32100.00,9500.00,-22600.00,-21700.00,-900.00,290.50 +-22800.00,-21300.00,-1500.00,-22800.00,-17300.00,-5500.00,290.51 +-23000.00,-14750.00,-8250.00,-23000.00,-21500.00,-1500.00,290.56 +-23200.00,-22350.00,-850.00,-23200.00,-29550.00,6350.00,290.69 +-23400.00,-29700.00,6300.00,-23400.00,-29050.00,5650.00,290.60 +-23600.00,-28050.00,4450.00,-23600.00,-19650.00,-3950.00,290.50 +-23800.00,-20700.00,-3100.00,-23554.83,-17150.00,-6404.83,290.43 +-23916.18,-19800.00,-4116.18,-23354.83,-25150.00,1795.17,290.52 +-23716.18,-27050.00,3333.82,-23154.83,-32750.00,9595.17,290.43 +-23516.18,-28350.00,4833.82,-22954.83,-27050.00,4095.17,290.35 +-23316.18,-23100.00,-216.18,-22754.83,-14550.00,-8204.83,290.28 +-23116.18,-19000.00,-4116.18,-22554.83,-13300.00,-9254.83,290.41 +-22916.18,-24000.00,1083.82,-22354.83,-28400.00,6045.17,290.30 +-22716.18,-26100.00,3383.82,-22154.83,-33500.00,11345.17,290.15 +-22516.18,-22750.00,233.82,-21954.83,-22500.00,545.17,290.19 +-22316.18,-20050.00,-2266.18,-21754.83,-9200.00,-12554.83,289.99 +-22116.18,-22500.00,383.82,-21554.83,-13500.00,-8054.83,290.29 +-21916.18,-25700.00,3783.82,-21354.83,-29400.00,8045.17,290.45 +-21716.18,-22700.00,983.82,-21154.83,-32000.00,10845.17,290.32 +-21516.18,-20200.00,-1316.18,-20954.83,-18650.00,-2304.83,290.21 +-21316.18,-20450.00,-866.18,-20754.83,-7050.00,-13704.83,290.18 +-21116.18,-22400.00,1283.82,-20554.83,-14700.00,-5854.83,290.39 +-20916.18,-23600.00,2683.82,-20354.83,-29250.00,8895.17,290.50 +-20716.18,-20650.00,-66.18,-20154.83,-29300.00,9145.17,290.39 +-20516.18,-20200.00,-316.18,-19954.83,-16050.00,-3904.83,290.32 +-20316.18,-21600.00,1283.82,-19754.83,-7700.00,-12054.83,290.49 +-20116.18,-20650.00,533.82,-19554.83,-16600.00,-2954.83,290.54 +-19916.18,-21250.00,1333.82,-19354.83,-31000.00,11645.17,290.60 +-19716.18,-20300.00,583.82,-19154.83,-27250.00,8095.17,290.47 +-19516.18,-22400.00,2883.82,-18954.83,-10300.00,-8654.83,290.46 +-19316.18,-18900.00,-416.18,-18754.83,-4350.00,-14404.83,290.71 +-19116.18,-18550.00,-566.18,-18554.83,-19600.00,1045.17,290.75 +-18916.18,-18300.00,-616.18,-18354.83,-29800.00,11445.17,290.69 +-18716.18,-19450.00,733.82,-18154.83,-24200.00,6045.17,290.53 +-18516.18,-19250.00,733.82,-17954.83,-8450.00,-9504.83,290.51 +-18316.18,-19650.00,1333.82,-17754.83,-9050.00,-8704.83,290.59 +-18116.18,-19150.00,1033.82,-17554.83,-22800.00,5245.17,290.57 +-17916.18,-17650.00,-266.18,-17354.83,-29200.00,11845.17,290.46 +-17716.18,-17500.00,-216.18,-17154.83,-19400.00,2245.17,290.31 +-17516.18,-18150.00,633.82,-16954.83,-3600.00,-13354.83,290.36 +-17316.18,-17950.00,633.82,-16754.83,-5950.00,-10804.83,290.35 +-17116.18,-17850.00,733.82,-16554.83,-21650.00,5095.17,290.32 +-16916.18,-16450.00,-466.18,-16354.83,-28850.00,12495.17,290.17 +-16716.18,-16700.00,-16.18,-16154.83,-19150.00,2995.17,290.05 +-16516.18,-17100.00,583.82,-15954.83,-2400.00,-13554.83,290.09 +-16316.18,-16750.00,433.82,-15754.83,-3650.00,-12104.83,290.17 +-16116.18,-16150.00,33.82,-15554.83,-19250.00,3695.17,290.24 +-15916.18,-15900.00,-16.18,-15354.83,-27800.00,12445.17,290.26 +-15716.18,-15800.00,83.82,-15154.83,-17400.00,2245.17,290.12 +-15516.18,-16000.00,483.82,-14954.83,-1750.00,-13204.83,290.00 +-15316.18,-15800.00,483.82,-14754.83,-3300.00,-11454.83,290.11 +-15116.18,-16000.00,883.82,-14554.83,-19250.00,4695.17,290.19 +-14916.18,-14950.00,33.82,-14354.83,-27700.00,13345.17,290.12 +-14716.18,-14400.00,-316.18,-14154.83,-17000.00,2845.17,290.15 +-14516.18,-14450.00,-66.18,-13954.83,500.00,-14454.83,290.22 +-14316.18,-14450.00,133.82,-13754.83,-1700.00,-12054.83,290.35 +-14116.18,-14400.00,283.82,-13554.83,-17350.00,3795.17,290.41 +-13916.18,-13600.00,-316.18,-13354.83,-25550.00,12195.17,290.28 +-13716.18,-14050.00,333.82,-13154.83,-16500.00,3345.17,290.18 +-13516.18,-13700.00,183.82,-12954.83,-800.00,-12154.83,290.16 +-13316.18,-13550.00,233.82,-12754.83,-3650.00,-9104.83,290.27 +-13116.18,-13400.00,283.82,-12554.83,-18300.00,5745.17,290.41 +-12916.18,-12550.00,-366.18,-12354.83,-23200.00,10845.17,290.38 +-12716.18,-12700.00,-16.18,-12154.83,-11750.00,-404.83,290.33 +-12516.18,-13200.00,683.82,-11954.83,-200.00,-11754.83,290.45 +-12316.18,-13050.00,733.82,-11754.83,-6000.00,-5754.83,290.57 +-12116.18,-12700.00,583.82,-11554.83,-19750.00,8195.17,290.62 +-11916.18,-11450.00,-466.18,-11354.83,-20350.00,8995.17,290.54 +-11716.18,-11450.00,-266.18,-11154.83,-5850.00,-5304.83,290.53 +-11516.18,-12700.00,1183.82,-10954.83,1850.00,-12804.83,290.44 +-11316.18,-11500.00,183.82,-10754.83,-10000.00,-754.83,290.59 +-11116.18,-9700.00,-1416.18,-10554.83,-22800.00,12245.17,290.62 +-10916.18,-9750.00,-1166.18,-10354.83,-16900.00,6545.17,290.49 +-10716.18,-11350.00,633.82,-10154.83,-300.00,-9854.83,290.43 +-10516.18,-11400.00,883.82,-9954.83,700.00,-10654.83,290.54 +-10316.18,-10750.00,433.82,-9754.83,-14000.00,4245.17,290.71 +-10116.18,-8300.00,-1816.18,-9554.83,-21750.00,12195.17,290.62 +-9916.18,-8600.00,-1316.18,-9354.83,-13750.00,4395.17,290.54 +-9716.18,-10050.00,333.82,-9154.83,1500.00,-10654.83,290.57 +-9516.18,-10450.00,933.82,-8954.83,-1400.00,-7554.83,290.64 +-9316.18,-9900.00,583.82,-8754.83,-15150.00,6395.17,290.63 +-9116.18,-7750.00,-1366.18,-8554.83,-19250.00,10695.17,290.46 +-8916.18,-6950.00,-1966.18,-8354.83,-6300.00,-2054.83,290.37 +-8716.18,-8700.00,-16.18,-8154.83,4400.00,-12554.83,290.31 +-8516.18,-9850.00,1333.82,-7954.83,-3550.00,-4404.83,290.45 +-8316.18,-9450.00,1133.82,-7754.83,-17150.00,9395.17,290.44 +-8116.18,-7250.00,-866.18,-7554.83,-15400.00,7845.17,290.34 +-7916.18,-6400.00,-1516.18,-7354.83,-300.00,-7054.83,290.33 +-7716.18,-7300.00,-416.18,-7154.83,3700.00,-10854.83,290.40 +-7516.18,-8050.00,533.82,-6954.83,-8150.00,1195.17,290.53 +-7316.18,-7500.00,183.82,-6754.83,-17500.00,10745.17,290.46 +-7116.18,-6150.00,-966.18,-6554.83,-10700.00,4145.17,290.24 +-6916.18,-5350.00,-1566.18,-6354.83,3150.00,-9504.83,290.18 +-6716.18,-6150.00,-566.18,-6154.83,700.00,-6854.83,290.37 +-6516.18,-8100.00,1583.82,-5954.83,-15300.00,9345.17,290.38 +-6316.18,-6600.00,283.82,-5754.83,-15900.00,10145.17,290.27 +-6116.18,-5300.00,-816.18,-5554.83,-50.00,-5504.83,289.98 +-5916.18,-4650.00,-1266.18,-5354.83,7000.00,-12354.83,289.97 +-5716.18,-5100.00,-616.18,-5154.83,-4950.00,-204.83,289.98 +-5516.18,-5300.00,-216.18,-4954.83,-16000.00,11045.17,290.03 +-5316.18,-4950.00,-366.18,-4754.83,-9450.00,4695.17,289.89 +-5116.18,-4000.00,-1116.18,-4554.83,5300.00,-9854.83,289.82 +-4916.18,-3250.00,-1666.18,-4354.83,3300.00,-7654.83,289.92 +-4716.18,-3900.00,-816.18,-4154.83,-10000.00,5845.17,289.99 +-4516.18,-4600.00,83.82,-3954.83,-14450.00,10495.17,289.97 +-4316.18,-4700.00,383.82,-3754.83,-2250.00,-1504.83,289.78 +-4116.18,-3650.00,-466.18,-3554.83,7450.00,-11004.83,289.76 +-3916.18,-2650.00,-1266.18,-3354.83,500.00,-3854.83,289.97 +-3716.18,-2100.00,-1616.18,-3154.83,-12450.00,9295.17,290.00 +-3516.18,-3100.00,-416.18,-2954.83,-10450.00,7495.17,289.96 +-3316.18,-3300.00,-16.18,-2754.83,4500.00,-7254.83,289.95 +-3116.18,-2500.00,-616.18,-2554.83,7400.00,-9954.83,290.09 +-2916.18,-750.00,-2166.18,-2354.83,-6600.00,4245.17,290.07 +-2716.18,-850.00,-1866.18,-2154.83,-14900.00,12745.17,290.01 +-2516.18,-3650.00,1133.82,-1954.83,-2950.00,995.17,289.95 +-2316.18,-3750.00,1433.82,-1754.83,9950.00,-11704.83,289.94 +-2116.18,-2100.00,-16.18,-1554.83,4900.00,-6454.83,290.11 +-1916.18,-1700.00,-216.18,-1354.83,-10300.00,8945.17,290.24 +-1716.18,50.00,-1766.18,-1154.83,-11400.00,10245.17,290.10 +-1516.18,150.00,-1666.18,-954.83,4100.00,-5054.83,290.14 +-1316.18,-650.00,-666.18,-754.83,11200.00,-11954.83,290.28 +-1116.18,200.00,-1316.18,-554.83,-1000.00,445.17,290.46 +-916.18,950.00,-1866.18,-354.83,-12600.00,12245.17,290.43 +-716.18,-550.00,-166.18,-154.83,-6250.00,6095.17,290.40 +-516.18,-100.00,-416.18,0.00,8950.00,-8950.00,290.40 +-316.18,500.00,-816.18,0.00,9300.00,-9300.00,290.49 +-116.18,-150.00,33.82,0.00,-5900.00,5900.00,290.53 +0.00,0.00,0.00,0.00,-11500.00,11500.00,290.51 +0.00,0.00,0.00,0.00,1750.00,-1750.00,290.56 +0.00,0.00,0.00,0.00,12150.00,-12150.00,290.49 +0.00,0.00,0.00,0.00,6700.00,-6700.00,290.66 +0.00,0.00,0.00,0.00,-6100.00,6100.00,290.79 +0.00,0.00,0.00,0.00,-8200.00,8200.00,290.70 +0.00,0.00,0.00,0.00,3700.00,-3700.00,290.56 +0.00,0.00,0.00,0.00,9650.00,-9650.00,290.56 +0.00,0.00,0.00,0.00,650.00,-650.00,290.53 +0.00,0.00,0.00,0.00,-9150.00,9150.00,290.59 +0.00,0.00,0.00,0.00,-4650.00,4650.00,290.48 +0.00,0.00,0.00,0.00,7200.00,-7200.00,290.36 +0.00,0.00,0.00,0.00,6600.00,-6600.00,290.44 +0.00,0.00,0.00,0.00,-4900.00,4900.00,290.52 +0.00,0.00,0.00,0.00,-7850.00,7850.00,290.32 +0.00,0.00,0.00,0.00,1200.00,-1200.00,290.22 +0.00,0.00,0.00,0.00,8850.00,-8850.00,290.23 +0.00,0.00,0.00,0.00,4500.00,-4500.00,290.24 +0.00,0.00,0.00,0.00,-7100.00,7100.00,290.37 +0.00,0.00,0.00,0.00,-6200.00,6200.00,290.20 +0.00,0.00,0.00,0.00,4800.00,-4800.00,290.27 +0.00,0.00,0.00,0.00,7600.00,-7600.00,290.38 +0.00,0.00,0.00,0.00,-2450.00,2450.00,290.39 +0.00,0.00,0.00,0.00,-8550.00,8550.00,290.37 +0.00,0.00,0.00,0.00,-1250.00,1250.00,290.18 +0.00,0.00,0.00,0.00,7650.00,-7650.00,290.21 +0.00,0.00,0.00,0.00,4000.00,-4000.00,290.32 +0.00,0.00,0.00,0.00,-6100.00,6100.00,290.42 +0.00,0.00,0.00,0.00,-5100.00,5100.00,290.37 +0.00,0.00,0.00,0.00,3900.00,-3900.00,290.27 +0.00,0.00,0.00,0.00,5700.00,-5700.00,290.32 +0.00,0.00,0.00,0.00,-1100.00,1100.00,290.35 +0.00,0.00,0.00,0.00,-6300.00,6300.00,290.33 +0.00,0.00,0.00,0.00,-2800.00,2800.00,290.22 +0.00,0.00,0.00,0.00,4500.00,-4500.00,290.28 +0.00,0.00,0.00,0.00,3300.00,-3300.00,290.36 +0.00,0.00,0.00,0.00,-2100.00,2100.00,290.40 +0.00,0.00,0.00,0.00,-2950.00,2950.00,290.37 +0.00,0.00,0.00,0.00,-150.00,150.00,290.35 +0.00,0.00,0.00,0.00,1200.00,-1200.00,290.37 +0.00,0.00,0.00,0.00,1200.00,-1200.00,290.36 +0.00,0.00,0.00,0.00,0.00,0.00,290.38 +0.00,0.00,0.00,0.00,-50.00,50.00,290.32 +0.00,0.00,0.00,0.00,0.00,0.00,290.33 +0.00,0.00,0.00,0.00,0.00,0.00,290.31 +0.00,0.00,0.00,0.00,0.00,0.00,290.29 +0.00,0.00,0.00,0.00,0.00,0.00,290.30 +0.00,0.00,0.00,0.00,0.00,0.00,290.28 +0.00,0.00,0.00,0.00,0.00,0.00,290.28 +0.00,0.00,0.00,0.00,0.00,0.00,290.34 +0.00,0.00,0.00,0.00,0.00,0.00,290.39 +0.00,0.00,0.00,0.00,0.00,0.00,290.45 +0.00,0.00,0.00,0.00,0.00,0.00,290.42 +0.00,0.00,0.00,0.00,0.00,0.00,290.40 +0.00,0.00,0.00,0.00,0.00,0.00,290.40 +0.00,0.00,0.00,0.00,0.00,0.00,290.38 +0.00,0.00,0.00,0.00,0.00,0.00,290.34 +0.00,0.00,0.00,0.00,0.00,0.00,290.29 +0.00,0.00,0.00,0.00,0.00,0.00,290.27 +0.00,0.00,0.00,0.00,0.00,0.00,290.20 +0.00,0.00,0.00,0.00,0.00,0.00,290.12 +0.00,0.00,0.00,0.00,0.00,0.00,290.11 +0.00,0.00,0.00,0.00,0.00,0.00,290.08 +0.00,0.00,0.00,0.00,0.00,0.00,290.08 +0.00,0.00,0.00,0.00,0.00,0.00,290.10 +0.00,0.00,0.00,0.00,0.00,0.00,290.08 +0.00,0.00,0.00,0.00,0.00,0.00,290.11 +0.00,0.00,0.00,0.00,0.00,0.00,290.14 +0.00,0.00,0.00,0.00,0.00,0.00,290.12 +0.00,0.00,0.00,0.00,0.00,0.00,290.13 +0.00,0.00,0.00,0.00,0.00,0.00,290.15 +0.00,0.00,0.00,0.00,0.00,0.00,290.15 +0.00,0.00,0.00,0.00,0.00,0.00,290.18 +0.00,0.00,0.00,0.00,0.00,0.00,290.23 +0.00,0.00,0.00,0.00,0.00,0.00,290.25 +0.00,0.00,0.00,0.00,0.00,0.00,290.26 +0.00,0.00,0.00,0.00,0.00,0.00,290.28 +0.00,0.00,0.00,0.00,0.00,0.00,290.28 +0.00,0.00,0.00,0.00,0.00,0.00,290.28 +0.00,0.00,0.00,0.00,0.00,0.00,290.23 +0.00,0.00,0.00,0.00,0.00,0.00,290.21 +0.00,0.00,0.00,0.00,0.00,0.00,290.21 +0.00,0.00,0.00,0.00,0.00,0.00,290.26 +0.00,0.00,0.00,0.00,0.00,0.00,290.25 +0.00,0.00,0.00,0.00,0.00,0.00,290.23 +0.00,0.00,0.00,0.00,0.00,0.00,290.22 +0.00,0.00,0.00,0.00,0.00,0.00,290.18 +0.00,0.00,0.00,0.00,0.00,0.00,290.18 +0.00,0.00,0.00,0.00,0.00,0.00,290.23 +0.00,0.00,0.00,0.00,0.00,0.00,290.23 +0.00,0.00,0.00,0.00,0.00,0.00,290.21 +0.00,0.00,0.00,0.00,0.00,0.00,290.22 +0.00,0.00,0.00,0.00,0.00,0.00,290.25 +0.00,0.00,0.00,0.00,0.00,0.00,290.29 +0.00,0.00,0.00,0.00,0.00,0.00,290.30 +0.00,0.00,0.00,0.00,0.00,0.00,290.30 +0.00,0.00,0.00,0.00,0.00,0.00,290.32 +0.00,0.00,0.00,0.00,0.00,0.00,290.32 +0.00,0.00,0.00,0.00,0.00,0.00,290.30 +0.00,0.00,0.00,0.00,0.00,0.00,290.26 +0.00,0.00,0.00,0.00,0.00,0.00,290.25 +0.00,0.00,0.00,0.00,0.00,0.00,290.24 +0.00,0.00,0.00,0.00,0.00,0.00,290.23 +0.00,0.00,0.00,0.00,0.00,0.00,290.25 +0.00,0.00,0.00,0.00,0.00,0.00,290.20 +0.00,0.00,0.00,0.00,0.00,0.00,290.22 +0.00,0.00,0.00,0.00,0.00,0.00,290.20 +0.00,0.00,0.00,0.00,0.00,0.00,290.15 +0.00,0.00,0.00,0.00,0.00,0.00,290.19 +0.00,0.00,0.00,0.00,0.00,0.00,290.15 +0.00,0.00,0.00,0.00,0.00,0.00,290.17 +0.00,0.00,0.00,0.00,0.00,0.00,290.17 +0.00,0.00,0.00,0.00,0.00,0.00,290.19 +0.00,0.00,0.00,0.00,0.00,0.00,290.19 +0.00,0.00,0.00,0.00,0.00,0.00,290.20 +0.00,0.00,0.00,0.00,0.00,0.00,290.23 +0.00,0.00,0.00,0.00,0.00,0.00,290.21 +0.00,0.00,0.00,0.00,0.00,0.00,290.21 +0.00,0.00,0.00,0.00,0.00,0.00,290.20 +0.00,0.00,0.00,0.00,0.00,0.00,290.21 +0.00,0.00,0.00,0.00,0.00,0.00,290.20 +0.00,0.00,0.00,0.00,0.00,0.00,290.24 +0.00,0.00,0.00,0.00,0.00,0.00,290.23 +0.00,0.00,0.00,0.00,0.00,0.00,290.24 +0.00,0.00,0.00,0.00,0.00,0.00,290.27 +0.00,0.00,0.00,0.00,0.00,0.00,290.25 +0.00,0.00,0.00,0.00,0.00,0.00,290.27 +0.00,0.00,0.00,0.00,0.00,0.00,290.31 +0.00,0.00,0.00,0.00,0.00,0.00,290.32 +0.00,0.00,0.00,0.00,0.00,0.00,290.33 +0.00,0.00,0.00,0.00,0.00,0.00,290.31 +0.00,0.00,0.00,0.00,0.00,0.00,290.31 +0.00,0.00,0.00,0.00,0.00,0.00,290.29 +0.00,0.00,0.00,0.00,0.00,0.00,290.31 +0.00,0.00,0.00,0.00,0.00,0.00,290.38 +0.00,0.00,0.00,0.00,0.00,0.00,290.37 +0.00,0.00,0.00,0.00,0.00,0.00,290.38 +0.00,0.00,0.00,0.00,0.00,0.00,290.36 +0.00,0.00,0.00,0.00,0.00,0.00,290.30 +0.00,0.00,0.00,0.00,0.00,0.00,290.27 +0.00,0.00,0.00,0.00,0.00,0.00,290.25 +0.00,0.00,0.00,0.00,0.00,0.00,290.23 +0.00,0.00,0.00,0.00,0.00,0.00,290.27 +0.00,0.00,0.00,0.00,0.00,0.00,290.26 +0.00,0.00,0.00,0.00,0.00,0.00,290.23 +0.00,0.00,0.00,0.00,0.00,0.00,290.24 +0.00,0.00,0.00,0.00,0.00,0.00,290.23 +0.00,0.00,0.00,0.00,0.00,0.00,290.23 +0.00,0.00,0.00,0.00,0.00,0.00,290.24 +0.00,0.00,0.00,0.00,0.00,0.00,290.29 +0.00,0.00,0.00,0.00,0.00,0.00,290.32 +0.00,0.00,0.00,0.00,0.00,0.00,290.28 +0.00,0.00,0.00,0.00,0.00,0.00,290.30 +0.00,0.00,0.00,0.00,0.00,0.00,290.32 +0.00,0.00,0.00,0.00,0.00,0.00,290.27 +0.00,0.00,0.00,0.00,0.00,0.00,290.23 +0.00,0.00,0.00,0.00,0.00,0.00,290.25 +0.00,0.00,0.00,0.00,0.00,0.00,290.23 +0.00,0.00,0.00,0.00,0.00,0.00,290.21 +0.00,0.00,0.00,0.00,0.00,0.00,290.15 +0.00,0.00,0.00,0.00,0.00,0.00,290.13 +0.00,0.00,0.00,0.00,0.00,0.00,290.15 +0.00,0.00,0.00,0.00,0.00,0.00,290.16 +0.00,0.00,0.00,0.00,0.00,0.00,290.14 +200.00,0.00,200.00,200.00,0.00,200.00,290.08 +400.00,0.00,400.00,400.00,0.00,400.00,290.10 +600.00,0.00,600.00,600.00,0.00,600.00,290.09 +800.00,0.00,800.00,800.00,0.00,800.00,290.05 +1000.00,0.00,1000.00,1000.00,0.00,1000.00,290.09 +1200.00,0.00,1200.00,1200.00,0.00,1200.00,290.06 +1400.00,0.00,1400.00,1400.00,0.00,1400.00,290.03 +1600.00,0.00,1600.00,1600.00,0.00,1600.00,290.04 +1800.00,150.00,1650.00,1800.00,150.00,1650.00,290.00 +2000.00,250.00,1750.00,2000.00,150.00,1850.00,289.99 +2200.00,100.00,2100.00,2200.00,50.00,2150.00,289.96 +2400.00,200.00,2200.00,2400.00,150.00,2250.00,289.90 +2600.00,850.00,1750.00,2600.00,550.00,2050.00,289.92 +2800.00,2650.00,150.00,2800.00,1300.00,1500.00,289.99 +3000.00,2800.00,200.00,3000.00,2300.00,700.00,289.97 +3200.00,900.00,2300.00,3200.00,2050.00,1150.00,289.93 +3400.00,50.00,3350.00,3400.00,450.00,2950.00,289.98 +3600.00,3600.00,0.00,3600.00,150.00,3450.00,289.89 +3800.00,6100.00,-2300.00,3800.00,2850.00,950.00,289.90 +4000.00,4100.00,-100.00,4000.00,5100.00,-1100.00,289.89 +4200.00,2500.00,1700.00,4200.00,3850.00,350.00,289.94 +4400.00,1600.00,2800.00,4400.00,2350.00,2050.00,289.95 +4600.00,4350.00,250.00,4600.00,1600.00,3000.00,289.89 +4800.00,6150.00,-1350.00,4800.00,3850.00,950.00,289.89 +5000.00,4400.00,600.00,5000.00,6000.00,-1000.00,289.86 +5200.00,2800.00,2400.00,5200.00,5350.00,-150.00,289.84 +5400.00,2700.00,2700.00,5400.00,3800.00,1600.00,289.94 +5600.00,6250.00,-650.00,5600.00,3000.00,2600.00,289.90 +5800.00,7600.00,-1800.00,5800.00,4300.00,1500.00,289.90 +6000.00,5700.00,300.00,6000.00,6100.00,-100.00,289.97 +6200.00,4550.00,1650.00,6200.00,6050.00,150.00,289.97 +6400.00,4200.00,2200.00,6400.00,4650.00,1750.00,290.05 +6600.00,6150.00,450.00,6600.00,3800.00,2800.00,290.10 +6800.00,7350.00,-550.00,6800.00,5400.00,1400.00,290.08 +7000.00,6900.00,100.00,7000.00,8000.00,-1000.00,290.06 +7200.00,5600.00,1600.00,7200.00,7900.00,-700.00,290.14 +7400.00,5000.00,2400.00,7400.00,6050.00,1350.00,290.17 +7600.00,7300.00,300.00,7600.00,5150.00,2450.00,290.24 +7800.00,8750.00,-950.00,7800.00,6150.00,1650.00,290.26 +8000.00,8000.00,0.00,8000.00,8150.00,-150.00,290.27 +8200.00,7050.00,1150.00,8200.00,8600.00,-400.00,290.28 +8400.00,7400.00,1000.00,8400.00,6850.00,1550.00,290.31 +8600.00,8250.00,350.00,8600.00,5650.00,2950.00,290.26 +8800.00,8600.00,200.00,8800.00,7300.00,1500.00,290.25 +9000.00,8600.00,400.00,9000.00,10100.00,-1100.00,290.28 +9200.00,8650.00,550.00,9200.00,9800.00,-600.00,290.33 +9400.00,8850.00,550.00,9400.00,7800.00,1600.00,290.42 +9600.00,9300.00,300.00,9600.00,7000.00,2600.00,290.46 +9800.00,9950.00,-150.00,9800.00,8950.00,850.00,290.46 +10000.00,10050.00,-50.00,10000.00,11250.00,-1250.00,290.50 +10200.00,9850.00,350.00,10200.00,11000.00,-800.00,290.55 +10400.00,9900.00,500.00,10400.00,8400.00,2000.00,290.63 +10600.00,9950.00,650.00,10600.00,7700.00,2900.00,290.60 +10800.00,10550.00,250.00,10800.00,9950.00,850.00,290.55 +11000.00,11300.00,-300.00,11000.00,13150.00,-2150.00,290.51 +11200.00,10900.00,300.00,11200.00,12050.00,-850.00,290.50 +11400.00,11250.00,150.00,11400.00,10000.00,1400.00,290.52 +11600.00,11100.00,500.00,11600.00,9500.00,2100.00,290.50 +11800.00,11400.00,400.00,11800.00,10700.00,1100.00,290.49 +12000.00,12300.00,-300.00,12000.00,13050.00,-1050.00,290.51 +12200.00,12550.00,-350.00,12200.00,13100.00,-900.00,290.46 +12400.00,11950.00,450.00,12400.00,11600.00,800.00,290.49 +12600.00,12300.00,300.00,12600.00,11550.00,1050.00,290.49 +12800.00,12600.00,200.00,12800.00,11650.00,1150.00,290.52 +13000.00,12900.00,100.00,13000.00,12450.00,550.00,290.55 +13200.00,13150.00,50.00,13200.00,13100.00,100.00,290.59 +13400.00,13350.00,50.00,13400.00,13300.00,100.00,290.57 +13600.00,13400.00,200.00,13600.00,13150.00,450.00,290.52 +13800.00,14000.00,-200.00,13800.00,13600.00,200.00,290.50 +14000.00,13750.00,250.00,14000.00,13300.00,700.00,290.47 +14200.00,13800.00,400.00,14200.00,13500.00,700.00,290.44 +14400.00,14150.00,250.00,14400.00,13850.00,550.00,290.40 +14600.00,14550.00,50.00,14600.00,14150.00,450.00,290.38 +14800.00,14850.00,-50.00,14800.00,14400.00,400.00,290.33 +15000.00,14850.00,150.00,15000.00,14500.00,500.00,290.29 +15200.00,15500.00,-300.00,15200.00,15200.00,0.00,290.26 +15400.00,15150.00,250.00,15400.00,14850.00,550.00,290.23 +15600.00,15150.00,450.00,15600.00,14650.00,950.00,290.19 +15800.00,16200.00,-400.00,15800.00,15850.00,-50.00,290.10 +16000.00,16600.00,-600.00,16000.00,16500.00,-500.00,290.06 +16200.00,16200.00,0.00,16200.00,16450.00,-250.00,290.06 +16400.00,18900.00,-2500.00,16400.00,18550.00,-2150.00,290.05 +16600.00,15350.00,1250.00,16600.00,15300.00,1300.00,289.96 +16800.00,12400.00,4400.00,16800.00,14050.00,2750.00,289.91 +17000.00,16750.00,250.00,17000.00,16100.00,900.00,289.98 +17200.00,21950.00,-4750.00,17200.00,19600.00,-2400.00,289.98 +17400.00,19750.00,-2350.00,17400.00,19700.00,-2300.00,290.04 +17600.00,14800.00,2800.00,17600.00,17300.00,300.00,289.99 +17800.00,15850.00,1950.00,17800.00,16200.00,1600.00,290.04 +18000.00,20450.00,-2450.00,18000.00,16200.00,1800.00,290.00 +18200.00,21550.00,-3350.00,18200.00,18200.00,0.00,290.10 +18400.00,18300.00,100.00,18400.00,20150.00,-1750.00,290.16 +18600.00,14200.00,4400.00,18600.00,19800.00,-1200.00,290.23 +18800.00,17350.00,1450.00,18800.00,17900.00,900.00,290.41 +19000.00,24250.00,-5250.00,19000.00,17300.00,1700.00,290.35 +19200.00,22150.00,-2950.00,19200.00,19400.00,-200.00,290.38 +19400.00,16150.00,3250.00,19400.00,21050.00,-1650.00,290.33 +19600.00,17150.00,2450.00,19600.00,20600.00,-1000.00,290.36 +19800.00,24350.00,-4550.00,19800.00,19400.00,400.00,290.39 +20000.00,24650.00,-4650.00,20000.00,19000.00,1000.00,290.37 +20200.00,16750.00,3450.00,20200.00,19850.00,350.00,290.32 +20400.00,14950.00,5450.00,20400.00,21150.00,-750.00,290.37 +20600.00,24600.00,-4000.00,20600.00,21700.00,-1100.00,290.37 +20800.00,28500.00,-7700.00,20800.00,21000.00,-200.00,290.30 +21000.00,18150.00,2850.00,21000.00,20500.00,500.00,290.27 +21200.00,11850.00,9350.00,21200.00,20400.00,800.00,290.18 +21400.00,23900.00,-2500.00,21400.00,21700.00,-300.00,290.39 +21600.00,33200.00,-11600.00,21600.00,23300.00,-1700.00,290.34 +21800.00,21600.00,200.00,21800.00,21550.00,250.00,290.28 +22000.00,13150.00,8850.00,22000.00,20800.00,1200.00,290.10 +22200.00,17750.00,4450.00,22200.00,21400.00,800.00,290.47 +22400.00,28950.00,-6550.00,22400.00,24200.00,-1800.00,290.61 +22600.00,30100.00,-7500.00,22600.00,22850.00,-250.00,290.19 +22800.00,20950.00,1850.00,22800.00,21900.00,900.00,290.06 +23000.00,17400.00,5600.00,23000.00,21800.00,1200.00,290.14 +23200.00,25550.00,-2350.00,23200.00,23900.00,-700.00,290.13 +23400.00,33300.00,-9900.00,23400.00,25900.00,-2500.00,290.03 +23600.00,23450.00,150.00,23600.00,24100.00,-500.00,290.11 +23800.00,13350.00,10450.00,23800.00,22800.00,1000.00,289.96 +24000.00,22600.00,1400.00,24000.00,22700.00,1300.00,290.33 +24200.00,33700.00,-9500.00,23954.34,26200.00,-2245.66,290.44 +24370.48,27000.00,-2629.52,23754.34,24500.00,-745.66,290.16 +24170.48,18850.00,5320.48,23554.34,23550.00,4.34,290.21 +23970.48,20300.00,3670.48,23354.34,23200.00,154.34,290.52 +23770.48,28200.00,-4429.52,23154.34,23850.00,-695.66,290.60 +23570.48,29000.00,-5429.52,22954.34,24050.00,-1095.66,290.53 +23370.48,20700.00,2670.48,22754.34,23650.00,-895.66,290.51 +23170.48,20150.00,3020.48,22554.34,23050.00,-495.66,290.57 +22970.48,26050.00,-3079.52,22354.34,23000.00,-645.66,290.58 +22770.48,26450.00,-3679.52,22154.34,22650.00,-495.66,290.53 +22570.48,23150.00,-579.52,21954.34,22650.00,-695.66,290.42 +22370.48,20850.00,1520.48,21754.34,22550.00,-795.66,290.48 +22170.48,22800.00,-629.52,21554.34,21800.00,-245.66,290.55 +21970.48,25150.00,-3179.52,21354.34,21750.00,-395.66,290.35 +21770.48,23950.00,-2179.52,21154.34,21850.00,-695.66,290.40 +21570.48,21000.00,570.48,20954.34,21750.00,-795.66,290.22 +21370.48,20600.00,770.48,20754.34,21350.00,-595.66,290.14 +21170.48,22500.00,-1329.52,20554.34,20750.00,-195.66,290.08 +20970.48,23600.00,-2629.52,20354.34,20750.00,-395.66,289.98 +20770.48,21700.00,-929.52,20154.34,20700.00,-545.66,290.00 +20570.48,20000.00,570.48,19954.34,20750.00,-795.66,289.95 +20370.48,20600.00,-229.52,19754.34,20650.00,-895.66,289.94 +20170.48,22100.00,-1929.52,19554.34,20100.00,-545.66,289.94 +19970.48,21900.00,-1929.52,19354.34,19550.00,-195.66,289.96 +19770.48,20200.00,-429.52,19154.34,19250.00,-95.66,289.98 +19570.48,19400.00,170.48,18954.34,19450.00,-495.66,290.06 +19370.48,20200.00,-829.52,18754.34,19450.00,-695.66,290.13 +19170.48,20900.00,-1729.52,18554.34,19100.00,-545.66,290.21 +18970.48,23200.00,-4229.52,18354.34,21750.00,-3395.66,290.30 +18770.48,17550.00,1220.48,18154.34,17150.00,1004.34,290.39 +18570.48,14500.00,4070.48,17954.34,14600.00,3354.34,290.43 +18370.48,19650.00,-1279.52,17754.34,16900.00,854.34,290.47 +18170.48,24950.00,-6779.52,17554.34,21200.00,-3645.66,290.52 +17970.48,21250.00,-3279.52,17354.34,21150.00,-3795.66,290.56 +17770.48,14450.00,3320.48,17154.34,15200.00,1954.34,290.63 +17570.48,13600.00,3970.48,16954.34,12650.00,4304.34,290.71 +17370.48,21700.00,-4329.52,16754.34,17150.00,-395.66,290.68 +17170.48,24050.00,-6879.52,16554.34,21450.00,-4895.66,290.64 +16970.48,15300.00,1670.48,16354.34,20200.00,-3845.66,290.66 +16770.48,8950.00,7820.48,16154.34,15100.00,1054.34,290.61 +16570.48,17400.00,-829.52,15954.34,12400.00,3554.34,290.79 +16370.48,28400.00,-12029.52,15754.34,15000.00,754.34,290.59 +16170.48,18650.00,-2479.52,15554.34,18200.00,-2645.66,290.46 +15970.48,3750.00,12220.48,15354.34,18000.00,-2645.66,290.46 +15770.48,9750.00,6020.48,15154.34,13650.00,1504.34,290.71 +15570.48,27100.00,-11529.52,14954.34,13600.00,1354.34,290.95 +15370.48,24100.00,-8729.52,14754.34,12600.00,2154.34,290.46 +15170.48,6200.00,8970.48,14554.34,14550.00,4.34,290.18 +14970.48,4150.00,10820.48,14354.34,15800.00,-1445.66,290.55 +14770.48,18050.00,-3279.52,14154.34,15950.00,-1795.66,290.58 +14570.48,26200.00,-11629.52,13954.34,13400.00,554.34,290.52 +14370.48,15050.00,-679.52,13754.34,11150.00,2604.34,290.33 +14170.48,4350.00,9820.48,13554.34,12150.00,1404.34,290.46 +13970.48,9000.00,4970.48,13354.34,15050.00,-1695.66,290.45 +13770.48,18250.00,-4479.52,13154.34,15100.00,-1945.66,290.46 +13570.48,22850.00,-9279.52,12954.34,10750.00,2204.34,290.27 +13370.48,13800.00,-429.52,12754.34,10150.00,2604.34,290.32 +13170.48,3900.00,9270.48,12554.34,12650.00,-95.66,290.22 +12970.48,9550.00,3420.48,12354.34,14700.00,-2345.66,290.20 +12770.48,17500.00,-4729.52,12154.34,14000.00,-1845.66,290.39 +12570.48,19800.00,-7229.52,11954.34,10250.00,1704.34,290.30 +12370.48,12750.00,-379.52,11754.34,9200.00,2554.34,290.30 +12170.48,6550.00,5620.48,11554.34,11100.00,454.34,290.43 +11970.48,9500.00,2470.48,11354.34,13450.00,-2095.66,290.37 +11770.48,16950.00,-5179.52,11154.34,13100.00,-1945.66,290.46 +11570.48,14600.00,-3029.52,10954.34,9950.00,1004.34,290.64 +11370.48,8500.00,2870.48,10754.34,8800.00,1954.34,290.54 +11170.48,9900.00,1270.48,10554.34,9600.00,954.34,290.53 +10970.48,14150.00,-3179.52,10354.34,11550.00,-1195.66,290.45 +10770.48,13350.00,-2579.52,10154.34,11000.00,-845.66,290.40 +10570.48,9850.00,720.48,9954.34,9050.00,904.34,290.47 +10370.48,8350.00,2020.48,9754.34,7900.00,1854.34,290.53 +10170.48,9900.00,270.48,9554.34,8600.00,954.34,290.56 +9970.48,12500.00,-2529.52,9354.34,10350.00,-995.66,290.51 +9770.48,11400.00,-1629.52,9154.34,9950.00,-795.66,290.61 +9570.48,9100.00,470.48,8954.34,8100.00,854.34,290.64 +9370.48,7650.00,1720.48,8754.34,6950.00,1804.34,290.65 +9170.48,8900.00,270.48,8554.34,7750.00,804.34,290.68 +8970.48,11100.00,-2129.52,8354.34,9150.00,-795.66,290.66 +8770.48,10200.00,-1429.52,8154.34,9050.00,-895.66,290.71 +8570.48,8100.00,470.48,7954.34,7200.00,754.34,290.71 +8370.48,7000.00,1370.48,7754.34,5950.00,1804.34,290.71 +8170.48,8100.00,70.48,7554.34,6550.00,1004.34,290.70 +7970.48,8800.00,-829.52,7354.34,7700.00,-345.66,290.69 +7770.48,8350.00,-579.52,7154.34,7950.00,-795.66,290.65 +7570.48,6750.00,820.48,6954.34,6150.00,804.34,290.65 +7370.48,6100.00,1270.48,6754.34,5300.00,1454.34,290.72 +7170.48,7150.00,20.48,6554.34,5550.00,1004.34,290.62 +6970.48,7250.00,-279.52,6354.34,6250.00,104.34,290.63 +6770.48,6050.00,720.48,6154.34,6150.00,4.34,290.61 +6570.48,5450.00,1120.48,5954.34,4850.00,1104.34,290.64 +6370.48,6050.00,320.48,5754.34,4150.00,1604.34,290.59 +6170.48,6400.00,-229.52,5554.34,4550.00,1004.34,290.58 +5970.48,6150.00,-179.52,5354.34,5250.00,104.34,290.56 +5770.48,5050.00,720.48,5154.34,5250.00,-95.66,290.55 +5570.48,5200.00,370.48,4954.34,4500.00,454.34,290.51 +5370.48,4300.00,1070.48,4754.34,2500.00,2254.34,290.45 +5170.48,3850.00,1320.48,4554.34,2150.00,2404.34,290.40 +4970.48,4400.00,570.48,4354.34,4550.00,-195.66,290.44 +4770.48,4650.00,120.48,4154.34,5550.00,-1395.66,290.40 +4570.48,3850.00,720.48,3954.34,4450.00,-495.66,290.37 +4370.48,2850.00,1520.48,3754.34,3300.00,454.34,290.45 +4170.48,2600.00,1570.48,3554.34,2500.00,1054.34,290.43 +3970.48,3300.00,670.48,3354.34,700.00,2654.34,290.44 +3770.48,3950.00,-179.52,3154.34,200.00,2954.34,290.39 +3570.48,3100.00,470.48,2954.34,3400.00,-445.66,290.42 +3370.48,2450.00,920.48,2754.34,5000.00,-2245.66,290.47 +3170.48,850.00,2320.48,2554.34,3950.00,-1395.66,290.42 +2970.48,1050.00,1920.48,2354.34,2750.00,-395.66,290.40 +2770.48,3350.00,-579.52,2154.34,1500.00,654.34,290.43 +2570.48,4000.00,-1429.52,1954.34,0.00,1954.34,290.39 +2370.48,3050.00,-679.52,1754.34,100.00,1654.34,290.34 +2170.48,1850.00,320.48,1554.34,1700.00,-145.66,290.35 +1970.48,1250.00,720.48,1354.34,1600.00,-245.66,290.29 +1770.48,800.00,970.48,1154.34,0.00,1154.34,290.30 +1570.48,-550.00,2120.48,954.34,-250.00,1204.34,290.38 +1370.48,550.00,820.48,754.34,-750.00,1504.34,290.38 +1170.48,500.00,670.48,554.34,-550.00,1104.34,290.28 +970.48,-1100.00,2070.48,354.34,50.00,304.34,290.25 +770.48,350.00,420.48,154.34,50.00,104.34,290.24 +570.48,700.00,-129.52,0.00,0.00,0.00,290.17 +370.48,-1050.00,1420.48,0.00,0.00,0.00,290.12 +170.48,50.00,120.48,0.00,0.00,0.00,290.15 +0.00,250.00,-250.00,0.00,0.00,0.00,290.17 +0.00,-100.00,100.00,0.00,0.00,0.00,290.12 +0.00,0.00,0.00,0.00,0.00,0.00,290.13 +0.00,0.00,0.00,0.00,0.00,0.00,290.12 +0.00,0.00,0.00,0.00,0.00,0.00,290.12 +0.00,0.00,0.00,0.00,0.00,0.00,290.13 +0.00,0.00,0.00,0.00,0.00,0.00,290.12 +0.00,0.00,0.00,0.00,0.00,0.00,290.11 +0.00,0.00,0.00,0.00,0.00,0.00,290.11 +0.00,0.00,0.00,0.00,0.00,0.00,290.08 +0.00,0.00,0.00,0.00,0.00,0.00,290.07 +0.00,0.00,0.00,0.00,0.00,0.00,290.07 +0.00,0.00,0.00,0.00,0.00,0.00,290.12 +0.00,0.00,0.00,0.00,0.00,0.00,290.14 +0.00,0.00,0.00,0.00,0.00,0.00,290.09 +0.00,0.00,0.00,0.00,0.00,0.00,290.07 +0.00,0.00,0.00,0.00,0.00,0.00,290.08 +0.00,0.00,0.00,0.00,0.00,0.00,290.13 +0.00,0.00,0.00,0.00,0.00,0.00,290.16 +0.00,0.00,0.00,0.00,0.00,0.00,290.17 +0.00,0.00,0.00,0.00,0.00,0.00,290.17 +0.00,0.00,0.00,0.00,0.00,0.00,290.16 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +-200.00,0.00,-200.00,-200.00,0.00,-200.00,0 +-400.00,0.00,-400.00,-400.00,0.00,-400.00,0 +-600.00,0.00,-600.00,-600.00,0.00,-600.00,0 +-800.00,0.00,-800.00,-800.00,0.00,-800.00,0 +-1000.00,0.00,-1000.00,-1000.00,0.00,-1000.00,0 +-1200.00,0.00,-1200.00,-1200.00,0.00,-1200.00,0 +-1400.00,0.00,-1400.00,-1400.00,0.00,-1400.00,0 +-1600.00,0.00,-1600.00,-1600.00,0.00,-1600.00,0 +-1800.00,-250.00,-1550.00,-1800.00,-150.00,-1650.00,0 +-2000.00,-350.00,-1650.00,-2000.00,-250.00,-1750.00,0 +-2200.00,-50.00,-2150.00,-2200.00,-100.00,-2100.00,0 +-2400.00,-250.00,-2150.00,-2400.00,-150.00,-2250.00,0 +-2600.00,-950.00,-1650.00,-2600.00,-450.00,-2150.00,0 +-2800.00,-2650.00,-150.00,-2800.00,-1400.00,-1400.00,0 +-3000.00,-2650.00,-350.00,-3000.00,-2400.00,-600.00,0 +-3200.00,-1550.00,-1650.00,-3200.00,-2050.00,-1150.00,0 +-3400.00,-2050.00,-1350.00,-3400.00,-500.00,-2900.00,0 +-3600.00,-2900.00,-700.00,-3600.00,-100.00,-3500.00,0 +-3800.00,-2900.00,-900.00,-3800.00,-2700.00,-1100.00,0 +-4000.00,-1750.00,-2250.00,-4000.00,-4700.00,700.00,0 +-4200.00,-1850.00,-2350.00,-4200.00,-3950.00,-250.00,0 +-4400.00,-4350.00,-50.00,-4400.00,-2950.00,-1450.00,0 +-4600.00,-5300.00,700.00,-4600.00,-2300.00,-2300.00,0 +-4800.00,-3900.00,-900.00,-4800.00,-2800.00,-2000.00,0 +-5000.00,-3150.00,-1850.00,-5000.00,-4250.00,-750.00,0 +-5200.00,-4150.00,-1050.00,-5200.00,-4700.00,-500.00,0 +-5400.00,-4900.00,-500.00,-5400.00,-4200.00,-1200.00,0 +-5600.00,-4700.00,-900.00,-5600.00,-3400.00,-2200.00,0 +-5800.00,-4050.00,-1750.00,-5800.00,-3800.00,-2000.00,0 +-6000.00,-4900.00,-1100.00,-6000.00,-5050.00,-950.00,0 +-6200.00,-6250.00,50.00,-6200.00,-5950.00,-250.00,0 +-6400.00,-5800.00,-600.00,-6400.00,-5300.00,-1100.00,0 +-6600.00,-5050.00,-1550.00,-6600.00,-4700.00,-1900.00,0 +-6800.00,-5750.00,-1050.00,-6800.00,-5200.00,-1600.00,0 +-7000.00,-6900.00,-100.00,-7000.00,-6000.00,-1000.00,0 +-7200.00,-6700.00,-500.00,-7200.00,-6600.00,-600.00,0 +-7400.00,-5700.00,-1700.00,-7400.00,-6600.00,-800.00,0 +-7600.00,-6100.00,-1500.00,-7600.00,-6200.00,-1400.00,0 +-7800.00,-7600.00,-200.00,-7800.00,-6800.00,-1000.00,0 +-8000.00,-8250.00,250.00,-8000.00,-7200.00,-800.00,0 +-8200.00,-7450.00,-750.00,-8200.00,-7400.00,-800.00,0 +-8400.00,-6400.00,-2000.00,-8400.00,-7600.00,-800.00,0 +-8600.00,-7450.00,-1150.00,-8600.00,-7700.00,-900.00,0 +-8800.00,-9200.00,400.00,-8800.00,-7900.00,-900.00,0 +-9000.00,-8950.00,-50.00,-9000.00,-8200.00,-800.00,0 +-9200.00,-7450.00,-1750.00,-9200.00,-8350.00,-850.00,0 +-9400.00,-7900.00,-1500.00,-9400.00,-8650.00,-750.00,0 +-9600.00,-9500.00,-100.00,-9600.00,-8850.00,-750.00,0 +-9800.00,-9850.00,50.00,-9800.00,-8950.00,-850.00,0 +-10000.00,-9650.00,-350.00,-10000.00,-9200.00,-800.00,0 +-10200.00,-9600.00,-600.00,-10200.00,-9400.00,-800.00,0 +-10400.00,-9750.00,-650.00,-10400.00,-9650.00,-750.00,0 +-10600.00,-10050.00,-550.00,-10600.00,-9950.00,-650.00,0 +-10800.00,-10350.00,-450.00,-10800.00,-10100.00,-700.00,0 +-11000.00,-10600.00,-400.00,-11000.00,-10300.00,-700.00,0 +-11200.00,-10850.00,-350.00,-11200.00,-10600.00,-600.00,0 +-11400.00,-10950.00,-450.00,-11400.00,-10800.00,-600.00,0 +-11600.00,-11100.00,-500.00,-11600.00,-10950.00,-650.00,0 +-11800.00,-11300.00,-500.00,-11800.00,-11200.00,-600.00,0 +-12000.00,-11650.00,-350.00,-12000.00,-11400.00,-600.00,0 +-12200.00,-11900.00,-300.00,-12200.00,-11650.00,-550.00,0 +-12400.00,-12000.00,-400.00,-12400.00,-11900.00,-500.00,0 +-12600.00,-12100.00,-500.00,-12600.00,-12100.00,-500.00,0 +-12800.00,-12350.00,-450.00,-12800.00,-12300.00,-500.00,0 +-13000.00,-12800.00,-200.00,-13000.00,-12500.00,-500.00,0 +-13200.00,-13050.00,-150.00,-13200.00,-12550.00,-650.00,0 +-13400.00,-13550.00,150.00,-13400.00,-13250.00,-150.00,0 +-13600.00,-13100.00,-500.00,-13600.00,-12900.00,-700.00,0 +-13800.00,-13850.00,50.00,-13800.00,-13400.00,-400.00,0 +-14000.00,-13700.00,-300.00,-14000.00,-13200.00,-800.00,0 +-14200.00,-13900.00,-300.00,-14200.00,-13300.00,-900.00,0 +-14400.00,-14150.00,-250.00,-14400.00,-13800.00,-600.00,0 +-14600.00,-14300.00,-300.00,-14600.00,-14200.00,-400.00,0 +-14800.00,-14450.00,-350.00,-14800.00,-14300.00,-500.00,0 +-15000.00,-14850.00,-150.00,-15000.00,-14450.00,-550.00,0 +-15200.00,-15850.00,650.00,-15200.00,-15050.00,-150.00,0 +-15400.00,-15350.00,-50.00,-15400.00,-14650.00,-750.00,0 +-15600.00,-18400.00,2800.00,-15600.00,-17950.00,2350.00,0 +-15800.00,-14200.00,-1600.00,-15800.00,-14000.00,-1800.00,0 +-16000.00,-12250.00,-3750.00,-16000.00,-12100.00,-3900.00,0 +-16200.00,-16000.00,-200.00,-16200.00,-15000.00,-1200.00,0 +-16400.00,-20350.00,3950.00,-16400.00,-18900.00,2500.00,0 +-16600.00,-17300.00,700.00,-16600.00,-17450.00,850.00,0 +-16800.00,-14000.00,-2800.00,-16800.00,-14500.00,-2300.00,0 +-17000.00,-15100.00,-1900.00,-17000.00,-14050.00,-2950.00,0 +-17200.00,-20100.00,2900.00,-17200.00,-17250.00,50.00,0 +-17400.00,-19900.00,2500.00,-17400.00,-19450.00,2050.00,0 +-17600.00,-14900.00,-2700.00,-17600.00,-18800.00,1200.00,0 +-17800.00,-14500.00,-3300.00,-17800.00,-16500.00,-1300.00,0 +-18000.00,-19450.00,1450.00,-18000.00,-16050.00,-1950.00,0 +-18200.00,-22300.00,4100.00,-18200.00,-17950.00,-250.00,0 +-18400.00,-18050.00,-350.00,-18400.00,-18600.00,200.00,0 +-18600.00,-15050.00,-3550.00,-18600.00,-19400.00,800.00,0 +-18800.00,-17400.00,-1400.00,-18800.00,-18200.00,-600.00,0 +-19000.00,-22850.00,3850.00,-19000.00,-18650.00,-350.00,0 +-19200.00,-21000.00,1800.00,-19200.00,-19150.00,-50.00,0 +-19400.00,-15650.00,-3750.00,-19400.00,-18800.00,-600.00,0 +-19600.00,-16950.00,-2650.00,-19600.00,-19000.00,-600.00,0 +-19800.00,-23700.00,3900.00,-19800.00,-20150.00,350.00,0 +-20000.00,-23400.00,3400.00,-20000.00,-20400.00,400.00,0 +-20200.00,-16050.00,-4150.00,-20200.00,-19550.00,-650.00,0 +-20400.00,-14800.00,-5600.00,-20400.00,-19400.00,-1000.00,0 +-20600.00,-24300.00,3700.00,-20600.00,-20900.00,300.00,0 +-20800.00,-27050.00,6250.00,-20800.00,-21400.00,600.00,0 +-21000.00,-18500.00,-2500.00,-21000.00,-21000.00,0.00,0 +-21200.00,-15500.00,-5700.00,-21200.00,-19950.00,-1250.00,0 +-21400.00,-22800.00,1400.00,-21400.00,-20150.00,-1250.00,0 +-21600.00,-29700.00,8100.00,-21600.00,-22150.00,550.00,0 +-21800.00,-22800.00,1000.00,-21800.00,-21950.00,150.00,0 +-22000.00,-14350.00,-7650.00,-22000.00,-21550.00,-450.00,0 +-22200.00,-19050.00,-3150.00,-22200.00,-22050.00,-150.00,0 +-22400.00,-30950.00,8550.00,-22400.00,-22800.00,400.00,0 +-22600.00,-27650.00,5050.00,-22600.00,-22100.00,-500.00,0 +-22800.00,-15300.00,-7500.00,-22800.00,-22100.00,-700.00,0 +-23000.00,-16300.00,-6700.00,-23000.00,-21800.00,-1200.00,0 +-23200.00,-30250.00,7050.00,-23200.00,-23650.00,450.00,0 +-23400.00,-27950.00,4550.00,-23400.00,-23550.00,150.00,0 +-23600.00,-20100.00,-3500.00,-23600.00,-22400.00,-1200.00,0 +-23800.00,-21100.00,-2700.00,-23800.00,-23700.00,-100.00,0 +-24000.00,-26100.00,2100.00,-23928.70,-24500.00,571.30,0 +-24200.00,-25100.00,900.00,-23728.70,-24400.00,671.30,0 +-24092.89,-24150.00,57.11,-23528.70,-23900.00,371.30,0 +-23892.89,-23600.00,-292.89,-23328.70,-22900.00,-428.70,0 +-23692.89,-25550.00,1857.11,-23128.70,-23700.00,571.30,0 +-23492.89,-24750.00,1257.11,-22928.70,-23300.00,371.30,0 +-23292.89,-24100.00,807.11,-22728.70,-23850.00,1121.30,0 +-23092.89,-23250.00,157.11,-22528.70,-23350.00,821.30,0 +-22892.89,-22350.00,-542.89,-22328.70,-21950.00,-378.70,0 +-22692.89,-23450.00,757.11,-22128.70,-22500.00,371.30,0 +-22492.89,-24350.00,1857.11,-21928.70,-22700.00,771.30,0 +-22292.89,-22900.00,607.11,-21728.70,-21650.00,-78.70,0 +-22092.89,-22650.00,557.11,-21528.70,-22050.00,521.30,0 +-21892.89,-22600.00,707.11,-21328.70,-21950.00,621.30,0 +-21692.89,-22400.00,707.11,-21128.70,-21550.00,421.30,0 +-21492.89,-21450.00,-42.89,-20928.70,-20250.00,-678.70,0 +-21292.89,-21350.00,57.11,-20728.70,-20100.00,-628.70,0 +-21092.89,-22550.00,1457.11,-20528.70,-21400.00,871.30,0 +-20892.89,-22500.00,1607.11,-20328.70,-21300.00,971.30,0 +-20692.89,-20600.00,-92.89,-20128.70,-19800.00,-328.70,0 +-20492.89,-20050.00,-442.89,-19928.70,-19100.00,-828.70,0 +-20292.89,-21350.00,1057.11,-19728.70,-20200.00,471.30,0 +-20092.89,-21200.00,1107.11,-19528.70,-19900.00,371.30,0 +-19892.89,-21200.00,1307.11,-19328.70,-20200.00,871.30,0 +-19692.89,-19700.00,7.11,-19128.70,-18900.00,-228.70,0 +-19492.89,-19250.00,-242.89,-18928.70,-18500.00,-428.70,0 +-19292.89,-19400.00,107.11,-18728.70,-18600.00,-128.70,0 +-19092.89,-19850.00,757.11,-18528.70,-18800.00,271.30,0 +-18892.89,-19650.00,757.11,-18328.70,-18600.00,271.30,0 +-18692.89,-19300.00,607.11,-18128.70,-18250.00,121.30,0 +-18492.89,-18900.00,407.11,-17928.70,-17950.00,21.30,0 +-18292.89,-22000.00,3707.11,-17728.70,-21000.00,3271.30,0 +-18092.89,-17050.00,-1042.89,-17528.70,-16500.00,-1028.70,0 +-17892.89,-14200.00,-3692.89,-17328.70,-14150.00,-3178.70,0 +-17692.89,-17500.00,-192.89,-17128.70,-15850.00,-1278.70,0 +-17492.89,-21900.00,4407.11,-16928.70,-19550.00,2621.30,0 +-17292.89,-18900.00,1607.11,-16728.70,-18200.00,1471.30,0 +-17092.89,-14600.00,-2492.89,-16528.70,-14650.00,-1878.70,0 +-16892.89,-15400.00,-1492.89,-16328.70,-14700.00,-1628.70,0 +-16692.89,-19850.00,3157.11,-16128.70,-17000.00,871.30,0 +-16492.89,-18450.00,1957.11,-15928.70,-16850.00,921.30,0 +-16292.89,-14100.00,-2192.89,-15728.70,-16150.00,421.30,0 +-16092.89,-14300.00,-1792.89,-15528.70,-15550.00,21.30,0 +-15892.89,-17600.00,1707.11,-15328.70,-14850.00,-478.70,0 +-15692.89,-18300.00,2607.11,-15128.70,-14700.00,-428.70,0 +-15492.89,-15550.00,57.11,-14928.70,-14950.00,21.30,0 +-15292.89,-12650.00,-2642.89,-14728.70,-15000.00,271.30,0 +-15092.89,-14400.00,-692.89,-14528.70,-14600.00,71.30,0 +-14892.89,-17300.00,2407.11,-14328.70,-14150.00,-178.70,0 +-14692.89,-16150.00,1457.11,-14128.70,-13850.00,-278.70,0 +-14492.89,-12550.00,-1942.89,-13928.70,-13750.00,-178.70,0 +-14292.89,-12900.00,-1392.89,-13728.70,-13550.00,-178.70,0 +-14092.89,-16050.00,1957.11,-13528.70,-13850.00,321.30,0 +-13892.89,-15300.00,1407.11,-13328.70,-13100.00,-228.70,0 +-13692.89,-12000.00,-1692.89,-13128.70,-12600.00,-528.70,0 +-13492.89,-12050.00,-1442.89,-12928.70,-12500.00,-428.70,0 +-13292.89,-14350.00,1057.11,-12728.70,-12500.00,-228.70,0 +-13092.89,-15000.00,1907.11,-12528.70,-12500.00,-28.70,0 +-12892.89,-13000.00,107.11,-12328.70,-12200.00,-128.70,0 +-12692.89,-10600.00,-2092.89,-12128.70,-11950.00,-178.70,0 +-12492.89,-11700.00,-792.89,-11928.70,-11650.00,-278.70,0 +-12292.89,-14150.00,1857.11,-11728.70,-11600.00,-128.70,0 +-12092.89,-13500.00,1407.11,-11528.70,-11300.00,-228.70,0 +-11892.89,-9650.00,-2242.89,-11328.70,-10700.00,-628.70,0 +-11692.89,-9400.00,-2292.89,-11128.70,-11050.00,-78.70,0 +-11492.89,-12850.00,1357.11,-10928.70,-11000.00,71.30,0 +-11292.89,-12800.00,1507.11,-10728.70,-10350.00,-378.70,0 +-11092.89,-9950.00,-1142.89,-10528.70,-10400.00,-128.70,0 +-10892.89,-8700.00,-2192.89,-10328.70,-10300.00,-28.70,0 +-10692.89,-10750.00,57.11,-10128.70,-10000.00,-128.70,0 +-10492.89,-12500.00,2007.11,-9928.70,-9650.00,-278.70,0 +-10292.89,-10950.00,657.11,-9728.70,-9350.00,-378.70,0 +-10092.89,-8650.00,-1442.89,-9528.70,-8850.00,-678.70,0 +-9892.89,-9250.00,-642.89,-9328.70,-9150.00,-178.70,0 +-9692.89,-10600.00,907.11,-9128.70,-9200.00,71.30,0 +-9492.89,-9850.00,357.11,-8928.70,-8850.00,-78.70,0 +-9292.89,-8250.00,-1042.89,-8728.70,-8350.00,-378.70,0 +-9092.89,-8550.00,-542.89,-8528.70,-8200.00,-328.70,0 +-8892.89,-9500.00,607.11,-8328.70,-8300.00,-28.70,0 +-8692.89,-8700.00,7.11,-8128.70,-7800.00,-328.70,0 +-8492.89,-7550.00,-942.89,-7928.70,-7600.00,-328.70,0 +-8292.89,-7600.00,-692.89,-7728.70,-7450.00,-278.70,0 +-8092.89,-8200.00,107.11,-7528.70,-7250.00,-278.70,0 +-7892.89,-8200.00,307.11,-7328.70,-7150.00,-178.70,0 +-7692.89,-7600.00,-92.89,-7128.70,-6850.00,-278.70,0 +-7492.89,-6650.00,-842.89,-6928.70,-6750.00,-178.70,0 +-7292.89,-6750.00,-542.89,-6728.70,-6500.00,-228.70,0 +-7092.89,-7000.00,-92.89,-6528.70,-6250.00,-278.70,0 +-6892.89,-6800.00,-92.89,-6328.70,-6100.00,-228.70,0 +-6692.89,-5700.00,-992.89,-6128.70,-5750.00,-378.70,0 +-6492.89,-5300.00,-1192.89,-5928.70,-4950.00,-978.70,0 +-6292.89,-6200.00,-92.89,-5728.70,-5000.00,-728.70,0 +-6092.89,-6200.00,107.11,-5528.70,-5250.00,-278.70,0 +-5892.89,-5000.00,-892.89,-5328.70,-5000.00,-328.70,0 +-5692.89,-4400.00,-1292.89,-5128.70,-4000.00,-1128.70,0 +-5492.89,-5500.00,7.11,-4928.70,-3650.00,-1278.70,0 +-5292.89,-5550.00,257.11,-4728.70,-4100.00,-628.70,0 +-5092.89,-4750.00,-342.89,-4528.70,-4100.00,-428.70,0 +-4892.89,-4000.00,-892.89,-4328.70,-3400.00,-928.70,0 +-4692.89,-3500.00,-1192.89,-4128.70,-2650.00,-1478.70,0 +-4492.89,-4300.00,-192.89,-3928.70,-3150.00,-778.70,0 +-4292.89,-4450.00,157.11,-3728.70,-3100.00,-628.70,0 +-4092.89,-3400.00,-692.89,-3528.70,-2450.00,-1078.70,0 +-3892.89,-2950.00,-942.89,-3328.70,-2000.00,-1328.70,0 +-3692.89,-2200.00,-1492.89,-3128.70,-2550.00,-578.70,0 +-3492.89,-2050.00,-1442.89,-2928.70,-2400.00,-528.70,0 +-3292.89,-3400.00,107.11,-2728.70,-2100.00,-628.70,0 +-3092.89,-3100.00,7.11,-2528.70,-300.00,-2228.70,0 +-2892.89,-2450.00,-442.89,-2328.70,200.00,-2528.70,0 +-2692.89,-1250.00,-1442.89,-2128.70,-1550.00,-578.70,0 +-2492.89,-1900.00,-592.89,-1928.70,-2650.00,721.30,0 +-2292.89,-1800.00,-492.89,-1728.70,-1950.00,221.30,0 +-2092.89,-1600.00,-492.89,-1528.70,-850.00,-678.70,0 +-1892.89,300.00,-2192.89,-1328.70,450.00,-1778.70,0 +-1692.89,100.00,-1792.89,-1128.70,400.00,-1528.70,0 +-1492.89,-1100.00,-392.89,-928.70,-200.00,-728.70,0 +-1292.89,-1200.00,-92.89,-728.70,250.00,-978.70,0 +-1092.89,-1300.00,207.11,-528.70,50.00,-578.70,0 +-892.89,400.00,-1292.89,-328.70,0.00,-328.70,0 +-692.89,450.00,-1142.89,-128.70,0.00,-128.70,0 +-492.89,-200.00,-292.89,0.00,0.00,0.00,0 +-292.89,0.00,-292.89,0.00,0.00,0.00,0 +-92.89,0.00,-92.89,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +200.00,0.00,200.00,200.00,0.00,200.00,0 +400.00,0.00,400.00,400.00,0.00,400.00,0 +600.00,0.00,600.00,600.00,0.00,600.00,0 +800.00,0.00,800.00,800.00,0.00,800.00,0 +1000.00,0.00,1000.00,1000.00,0.00,1000.00,0 +1200.00,0.00,1200.00,1200.00,0.00,1200.00,0 +1400.00,0.00,1400.00,1400.00,0.00,1400.00,0 +1600.00,0.00,1600.00,1600.00,0.00,1600.00,0 +1800.00,250.00,1550.00,1800.00,150.00,1650.00,0 +2000.00,250.00,1750.00,2000.00,300.00,1700.00,0 +2200.00,0.00,2200.00,2200.00,0.00,2200.00,0 +2400.00,200.00,2200.00,2400.00,200.00,2200.00,0 +2600.00,750.00,1850.00,2600.00,550.00,2050.00,0 +2800.00,2350.00,450.00,2800.00,1450.00,1350.00,0 +3000.00,2650.00,350.00,3000.00,2300.00,700.00,0 +3200.00,1500.00,1700.00,3200.00,2100.00,1100.00,0 +3400.00,500.00,2900.00,3400.00,550.00,2850.00,0 +3600.00,3000.00,600.00,3600.00,100.00,3500.00,0 +3800.00,4000.00,-200.00,3800.00,2850.00,950.00,0 +4000.00,2850.00,1150.00,4000.00,4700.00,-700.00,0 +4200.00,2350.00,1850.00,4200.00,3750.00,450.00,0 +4400.00,2950.00,1450.00,4400.00,2700.00,1700.00,0 +4600.00,3700.00,900.00,4600.00,2100.00,2500.00,0 +4800.00,4000.00,800.00,4800.00,3000.00,1800.00,0 +5000.00,4200.00,800.00,5000.00,4650.00,350.00,0 +5200.00,4300.00,900.00,5200.00,4550.00,650.00,0 +5400.00,4450.00,950.00,5400.00,3800.00,1600.00,0 +5600.00,4600.00,1000.00,5600.00,3950.00,1650.00,0 +5800.00,5000.00,800.00,5800.00,4400.00,1400.00,0 +6000.00,5050.00,950.00,6000.00,4900.00,1100.00,0 +6200.00,5400.00,800.00,6200.00,5200.00,1000.00,0 +6400.00,5600.00,800.00,6400.00,5400.00,1000.00,0 +6600.00,5750.00,850.00,6600.00,5300.00,1300.00,0 +6800.00,5900.00,900.00,6800.00,5600.00,1200.00,0 +7000.00,6150.00,850.00,7000.00,5850.00,1150.00,0 +7200.00,6400.00,800.00,7200.00,6100.00,1100.00,0 +7400.00,6650.00,750.00,7400.00,6400.00,1000.00,0 +7600.00,6900.00,700.00,7600.00,6450.00,1150.00,0 +7800.00,7050.00,750.00,7800.00,6700.00,1100.00,0 +8000.00,7250.00,750.00,8000.00,7050.00,950.00,0 +8200.00,7450.00,750.00,8200.00,7250.00,950.00,0 +8400.00,7700.00,700.00,8400.00,7350.00,1050.00,0 +8600.00,8000.00,600.00,8600.00,7550.00,1050.00,0 +8800.00,8200.00,600.00,8800.00,7800.00,1000.00,0 +9000.00,8500.00,500.00,9000.00,8000.00,1000.00,0 +9200.00,8650.00,550.00,9200.00,8150.00,1050.00,0 +9400.00,8700.00,700.00,9400.00,8350.00,1050.00,0 +9600.00,9050.00,550.00,9600.00,8500.00,1100.00,0 +9800.00,9600.00,200.00,9800.00,9200.00,600.00,0 +10000.00,9500.00,500.00,10000.00,9000.00,1000.00,0 +10200.00,9500.00,700.00,10200.00,9100.00,1100.00,0 +10400.00,10200.00,200.00,10400.00,9800.00,600.00,0 +10600.00,10150.00,450.00,10600.00,9700.00,900.00,0 +10800.00,10200.00,600.00,10800.00,9800.00,1000.00,0 +11000.00,10500.00,500.00,11000.00,10150.00,850.00,0 +11200.00,10800.00,400.00,11200.00,10350.00,850.00,0 +11400.00,11050.00,350.00,11400.00,10600.00,800.00,0 +11600.00,11700.00,-100.00,11600.00,11400.00,200.00,0 +11800.00,11350.00,450.00,11800.00,10900.00,900.00,0 +12000.00,11700.00,300.00,12000.00,11350.00,650.00,0 +12200.00,11500.00,700.00,12200.00,11150.00,1050.00,0 +12400.00,11750.00,650.00,12400.00,11450.00,950.00,0 +12600.00,12300.00,300.00,12600.00,11850.00,750.00,0 +12800.00,12700.00,100.00,12800.00,12150.00,650.00,0 +13000.00,12700.00,300.00,13000.00,12400.00,600.00,0 +13200.00,12750.00,450.00,13200.00,12500.00,700.00,0 +13400.00,12950.00,450.00,13400.00,12650.00,750.00,0 +13600.00,13350.00,250.00,13600.00,12750.00,850.00,0 +13800.00,13650.00,150.00,13800.00,12950.00,850.00,0 +14000.00,13650.00,350.00,14000.00,13250.00,750.00,0 +14200.00,14300.00,-100.00,14200.00,14150.00,50.00,0 +14400.00,14500.00,-100.00,14400.00,14100.00,300.00,0 +14600.00,13850.00,750.00,14600.00,13500.00,1100.00,0 +14800.00,14550.00,250.00,14800.00,14200.00,600.00,0 +15000.00,15150.00,-150.00,15000.00,14800.00,200.00,0 +15200.00,14700.00,500.00,15200.00,14100.00,1100.00,0 +15400.00,15300.00,100.00,15400.00,15100.00,300.00,0 +15600.00,15100.00,500.00,15600.00,15000.00,600.00,0 +15800.00,15200.00,600.00,15800.00,14950.00,850.00,0 +16000.00,16100.00,-100.00,16000.00,15800.00,200.00,0 +16200.00,16400.00,-200.00,16200.00,16150.00,50.00,0 +16400.00,16250.00,150.00,16400.00,16000.00,400.00,0 +16600.00,16150.00,450.00,16600.00,15950.00,650.00,0 +16800.00,19400.00,-2600.00,16800.00,19300.00,-2500.00,0 +17000.00,15500.00,1500.00,17000.00,15150.00,1850.00,0 +17200.00,13200.00,4000.00,17200.00,13700.00,3500.00,0 +17400.00,16450.00,950.00,17400.00,15750.00,1650.00,0 +17600.00,20750.00,-3150.00,17600.00,19450.00,-1850.00,0 +17800.00,18550.00,-750.00,17800.00,19800.00,-2000.00,0 +18000.00,14550.00,3450.00,18000.00,17900.00,100.00,0 +18200.00,16750.00,1450.00,18200.00,17100.00,1100.00,0 +18400.00,20500.00,-2100.00,18400.00,16300.00,2100.00,0 +18600.00,21500.00,-2900.00,18600.00,18350.00,250.00,0 +18800.00,18200.00,600.00,18800.00,18850.00,-50.00,0 +19000.00,17300.00,1700.00,19000.00,19500.00,-500.00,0 +19200.00,19000.00,200.00,19200.00,19200.00,0.00,0 +19400.00,19800.00,-400.00,19400.00,18250.00,1150.00,0 +19600.00,20200.00,-600.00,19600.00,19200.00,400.00,0 +19800.00,19000.00,800.00,19800.00,19250.00,550.00,0 +20000.00,19950.00,50.00,20000.00,20300.00,-300.00,0 +20200.00,20800.00,-600.00,20200.00,20150.00,50.00,0 +20400.00,20750.00,-350.00,20400.00,20150.00,250.00,0 +20600.00,20400.00,200.00,20600.00,20200.00,400.00,0 +20800.00,20500.00,300.00,20800.00,20300.00,500.00,0 +21000.00,21150.00,-150.00,21000.00,20800.00,200.00,0 +21200.00,21300.00,-100.00,21200.00,21300.00,-100.00,0 +21400.00,21400.00,0.00,21400.00,21100.00,300.00,0 +21600.00,20750.00,850.00,21600.00,20500.00,1100.00,0 +21800.00,21050.00,750.00,21800.00,20800.00,1000.00,0 +22000.00,22700.00,-700.00,22000.00,22500.00,-500.00,0 +22200.00,23050.00,-850.00,22200.00,22900.00,-700.00,0 +22400.00,22400.00,0.00,22400.00,22400.00,0.00,0 +22600.00,22200.00,400.00,22600.00,22000.00,600.00,0 +22800.00,22800.00,0.00,22800.00,22300.00,500.00,0 +23000.00,23050.00,-50.00,23000.00,22750.00,250.00,0 +23200.00,22950.00,250.00,23200.00,23050.00,150.00,0 +23400.00,23650.00,-250.00,23400.00,23400.00,0.00,0 +23600.00,24100.00,-500.00,23600.00,23600.00,0.00,0 +23800.00,24000.00,-200.00,23800.00,23800.00,0.00,0 +24000.00,23950.00,50.00,24000.00,23800.00,200.00,0 +24200.00,24050.00,150.00,23842.48,24050.00,-207.52,0 +24117.63,24400.00,-282.37,23642.48,24050.00,-407.52,0 +23917.63,25650.00,-1732.37,23442.48,24700.00,-1257.52,0 +23717.63,24250.00,-532.37,23242.48,23250.00,-7.52,0 +23517.63,23650.00,-132.37,23042.48,22700.00,342.48,0 +23317.63,23650.00,-332.37,22842.48,22950.00,-107.52,0 +23117.63,24100.00,-982.37,22642.48,23200.00,-557.52,0 +22917.63,23800.00,-882.37,22442.48,22900.00,-457.52,0 +22717.63,23150.00,-432.37,22242.48,22450.00,-207.52,0 +22517.63,22850.00,-332.37,22042.48,22350.00,-307.52,0 +22317.63,22950.00,-632.37,21842.48,22150.00,-307.52,0 +22117.63,22950.00,-832.37,21642.48,22250.00,-607.52,0 +21917.63,22350.00,-432.37,21442.48,21800.00,-357.52,0 +21717.63,22100.00,-382.37,21242.48,21550.00,-307.52,0 +21517.63,22000.00,-482.37,21042.48,21200.00,-157.52,0 +21317.63,21800.00,-482.37,20842.48,21050.00,-207.52,0 +21117.63,21450.00,-332.37,20642.48,20600.00,42.48,0 +20917.63,21400.00,-482.37,20442.48,20650.00,-207.52,0 +20717.63,21300.00,-582.37,20242.48,20700.00,-457.52,0 +20517.63,20800.00,-282.37,20042.48,20450.00,-407.52,0 +20317.63,20550.00,-232.37,19842.48,20100.00,-257.52,0 +20117.63,20600.00,-482.37,19642.48,19500.00,142.48,0 +19917.63,19750.00,167.63,19442.48,19000.00,442.48,0 +19717.63,20400.00,-682.37,19242.48,19800.00,-557.52,0 +19517.63,20600.00,-1082.37,19042.48,19850.00,-807.52,0 +19317.63,19800.00,-482.37,18842.48,19400.00,-557.52,0 +19117.63,19300.00,-182.37,18642.48,18750.00,-107.52,0 +18917.63,19300.00,-382.37,18442.48,18350.00,92.48,0 +18717.63,19250.00,-532.37,18242.48,18250.00,-7.52,0 +18517.63,19100.00,-582.37,18042.48,18150.00,-107.52,0 +18317.63,18900.00,-582.37,17842.48,18050.00,-207.52,0 +18117.63,18750.00,-632.37,17642.48,18000.00,-357.52,0 +17917.63,18450.00,-532.37,17442.48,17650.00,-207.52,0 +17717.63,18150.00,-432.37,17242.48,17400.00,-157.52,0 +17517.63,17850.00,-332.37,17042.48,17150.00,-107.52,0 +17317.63,17650.00,-332.37,16842.48,16850.00,-7.52,0 +17117.63,16950.00,167.63,16642.48,16100.00,542.48,0 +16917.63,17700.00,-782.37,16442.48,16500.00,-57.52,0 +16717.63,21000.00,-4282.37,16242.48,19800.00,-3557.52,0 +16517.63,16050.00,467.63,16042.48,15550.00,492.48,0 +16317.63,12650.00,3667.63,15842.48,12550.00,3292.48,0 +16117.63,15150.00,967.63,15642.48,14000.00,1642.48,0 +15917.63,18900.00,-2982.37,15442.48,16550.00,-1107.52,0 +15717.63,17650.00,-1932.37,15242.48,17700.00,-2457.52,0 +15517.63,13100.00,2417.63,15042.48,15000.00,42.48,0 +15317.63,13450.00,1867.63,14842.48,12700.00,2142.48,0 +15117.63,16650.00,-1532.37,14642.48,12900.00,1742.48,0 +14917.63,17350.00,-2432.37,14442.48,14650.00,-207.52,0 +14717.63,15100.00,-382.37,14242.48,15950.00,-1707.52,0 +14517.63,12100.00,2417.63,14042.48,15100.00,-1057.52,0 +14317.63,12900.00,1417.63,13842.48,13300.00,542.48,0 +14117.63,15650.00,-1532.37,13642.48,12600.00,1042.48,0 +13917.63,15450.00,-1532.37,13442.48,12850.00,592.48,0 +13717.63,14050.00,-332.37,13242.48,13750.00,-507.52,0 +13517.63,12650.00,867.63,13042.48,13100.00,-57.52,0 +13317.63,12950.00,367.63,12842.48,12700.00,142.48,0 +13117.63,14050.00,-932.37,12642.48,12750.00,-107.52,0 +12917.63,13350.00,-432.37,12442.48,12150.00,292.48,0 +12717.63,13100.00,-382.37,12242.48,12400.00,-157.52,0 +12517.63,12250.00,267.63,12042.48,11650.00,392.48,0 +12317.63,12500.00,-182.37,11842.48,11850.00,-7.52,0 +12117.63,12500.00,-382.37,11642.48,11700.00,-57.52,0 +11917.63,12200.00,-282.37,11442.48,11450.00,-7.52,0 +11717.63,11900.00,-182.37,11242.48,11050.00,192.48,0 +11517.63,11550.00,-32.37,11042.48,10800.00,242.48,0 +11317.63,11100.00,217.63,10842.48,10300.00,542.48,0 +11117.63,11550.00,-432.37,10642.48,10700.00,-57.52,0 +10917.63,11350.00,-432.37,10442.48,10550.00,-107.52,0 +10717.63,10550.00,167.63,10242.48,9800.00,442.48,0 +10517.63,10300.00,217.63,10042.48,9550.00,492.48,0 +10317.63,10450.00,-132.37,9842.48,9400.00,442.48,0 +10117.63,10850.00,-732.37,9642.48,9800.00,-157.52,0 +9917.63,10100.00,-182.37,9442.48,9600.00,-157.52,0 +9717.63,8500.00,1217.63,9242.48,9050.00,192.48,0 +9517.63,9000.00,517.63,9042.48,8650.00,392.48,0 +9317.63,9750.00,-432.37,8842.48,8100.00,742.48,0 +9117.63,9600.00,-482.37,8642.48,8250.00,392.48,0 +8917.63,8600.00,317.63,8442.48,8200.00,242.48,0 +8717.63,7500.00,1217.63,8242.48,8050.00,192.48,0 +8517.63,8200.00,317.63,8042.48,7800.00,242.48,0 +8317.63,9100.00,-782.37,7842.48,7450.00,392.48,0 +8117.63,8500.00,-382.37,7642.48,7300.00,342.48,0 +7917.63,6900.00,1017.63,7442.48,7150.00,292.48,0 +7717.63,6350.00,1367.63,7242.48,6900.00,342.48,0 +7517.63,7400.00,117.63,7042.48,6650.00,392.48,0 +7317.63,8150.00,-832.37,6842.48,6450.00,392.48,0 +7117.63,7500.00,-382.37,6642.48,6100.00,542.48,0 +6917.63,6050.00,867.63,6442.48,6000.00,442.48,0 +6717.63,5600.00,1117.63,6242.48,5800.00,442.48,0 +6517.63,6450.00,67.63,6042.48,5550.00,492.48,0 +6317.63,6800.00,-482.37,5842.48,5350.00,492.48,0 +6117.63,5850.00,267.63,5642.48,5200.00,442.48,0 +5917.63,4900.00,1017.63,5442.48,4600.00,842.48,0 +5717.63,4550.00,1167.63,5242.48,3950.00,1292.48,0 +5517.63,5350.00,167.63,5042.48,4100.00,942.48,0 +5317.63,5650.00,-332.37,4842.48,4400.00,442.48,0 +5117.63,4350.00,767.63,4642.48,4050.00,592.48,0 +4917.63,3950.00,967.63,4442.48,3250.00,1192.48,0 +4717.63,4600.00,117.63,4242.48,2550.00,1692.48,0 +4517.63,4750.00,-232.37,4042.48,2900.00,1142.48,0 +4317.63,3800.00,517.63,3842.48,3450.00,392.48,0 +4117.63,2950.00,1167.63,3642.48,3100.00,542.48,0 +3917.63,2750.00,1167.63,3442.48,2250.00,1192.48,0 +3717.63,3600.00,117.63,3242.48,1950.00,1292.48,0 +3517.63,3550.00,-32.37,3042.48,1900.00,1142.48,0 +3317.63,2750.00,567.63,2842.48,1800.00,1042.48,0 +3117.63,2150.00,967.63,2642.48,550.00,2092.48,0 +2917.63,1350.00,1567.63,2442.48,1300.00,1142.48,0 +2717.63,950.00,1767.63,2242.48,1300.00,942.48,0 +2517.63,2550.00,-32.37,2042.48,100.00,1942.48,0 +2317.63,2650.00,-332.37,1842.48,50.00,1792.48,0 +2117.63,1750.00,367.63,1642.48,1350.00,292.48,0 +1917.63,1650.00,267.63,1442.48,1600.00,-157.52,0 +1717.63,0.00,1717.63,1242.48,-200.00,1442.48,0 +1517.63,-250.00,1767.63,1042.48,-800.00,1842.48,0 +1317.63,300.00,1017.63,842.48,350.00,492.48,0 +1117.63,400.00,717.63,642.48,350.00,292.48,0 +917.63,-200.00,1117.63,442.48,-650.00,1092.48,0 +717.63,-550.00,1267.63,242.48,-100.00,342.48,0 +517.63,-1050.00,1567.63,42.48,50.00,-7.52,0 +317.63,150.00,167.63,0.00,0.00,0.00,0 +117.63,200.00,-82.37,0.00,0.00,0.00,0 +0.00,-50.00,50.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +-200.00,0.00,-200.00,-200.00,0.00,-200.00,0 +-400.00,0.00,-400.00,-400.00,0.00,-400.00,0 +-600.00,0.00,-600.00,-600.00,0.00,-600.00,0 +-800.00,0.00,-800.00,-800.00,0.00,-800.00,0 +-1000.00,0.00,-1000.00,-1000.00,0.00,-1000.00,0 +-1200.00,0.00,-1200.00,-1200.00,0.00,-1200.00,0 +-1400.00,0.00,-1400.00,-1400.00,0.00,-1400.00,0 +-1600.00,0.00,-1600.00,-1600.00,0.00,-1600.00,0 +-1800.00,-150.00,-1650.00,-1800.00,-200.00,-1600.00,0 +-2000.00,-350.00,-1650.00,-2000.00,-400.00,-1600.00,0 +-2200.00,0.00,-2200.00,-2200.00,-50.00,-2150.00,0 +-2400.00,-200.00,-2200.00,-2400.00,-100.00,-2300.00,0 +-2600.00,-650.00,-1950.00,-2600.00,-600.00,-2000.00,0 +-2800.00,-2050.00,-750.00,-2800.00,-1500.00,-1300.00,0 +-3000.00,-2450.00,-550.00,-3000.00,-1950.00,-1050.00,0 +-3200.00,-1650.00,-1550.00,-3200.00,-1350.00,-1850.00,0 +-3400.00,-200.00,-3200.00,-3400.00,-1350.00,-2050.00,0 +-3600.00,-1550.00,-2050.00,-3600.00,-1350.00,-2250.00,0 +-3800.00,-4600.00,800.00,-3800.00,-2400.00,-1400.00,0 +-4000.00,-4600.00,600.00,-4000.00,-2900.00,-1100.00,0 +-4200.00,-3200.00,-1000.00,-4200.00,-2900.00,-1300.00,0 +-4400.00,-2600.00,-1800.00,-4400.00,-2700.00,-1700.00,0 +-4600.00,-3150.00,-1450.00,-4600.00,-2950.00,-1650.00,0 +-4800.00,-4200.00,-600.00,-4800.00,-3100.00,-1700.00,0 +-5000.00,-4050.00,-950.00,-5000.00,-3450.00,-1550.00,0 +-5200.00,-3550.00,-1650.00,-5200.00,-3800.00,-1400.00,0 +-5400.00,-4250.00,-1150.00,-5400.00,-4000.00,-1400.00,0 +-5600.00,-4850.00,-750.00,-5600.00,-4100.00,-1500.00,0 +-5800.00,-4900.00,-900.00,-5800.00,-4150.00,-1650.00,0 +-6000.00,-5250.00,-750.00,-6000.00,-4650.00,-1350.00,0 +-6200.00,-5450.00,-750.00,-6200.00,-4950.00,-1250.00,0 +-6400.00,-5550.00,-850.00,-6400.00,-5150.00,-1250.00,0 +-6600.00,-5700.00,-900.00,-6600.00,-5300.00,-1300.00,0 +-6800.00,-5900.00,-900.00,-6800.00,-5600.00,-1200.00,0 +-7000.00,-6100.00,-900.00,-7000.00,-5750.00,-1250.00,0 +-7200.00,-6350.00,-850.00,-7200.00,-6050.00,-1150.00,0 +-7400.00,-6750.00,-650.00,-7400.00,-6350.00,-1050.00,0 +-7600.00,-6950.00,-650.00,-7600.00,-6550.00,-1050.00,0 +-7800.00,-7050.00,-750.00,-7800.00,-6700.00,-1100.00,0 +-8000.00,-7250.00,-750.00,-8000.00,-6900.00,-1100.00,0 +-8200.00,-7500.00,-700.00,-8200.00,-7100.00,-1100.00,0 +-8400.00,-7750.00,-650.00,-8400.00,-7450.00,-950.00,0 +-8600.00,-7950.00,-650.00,-8600.00,-7600.00,-1000.00,0 +-8800.00,-8150.00,-650.00,-8800.00,-7850.00,-950.00,0 +-9000.00,-8400.00,-600.00,-9000.00,-8100.00,-900.00,0 +-9200.00,-8550.00,-650.00,-9200.00,-8250.00,-950.00,0 +-9400.00,-8800.00,-600.00,-9400.00,-8400.00,-1000.00,0 +-9600.00,-8900.00,-700.00,-9600.00,-8550.00,-1050.00,0 +-9800.00,-9100.00,-700.00,-9800.00,-8800.00,-1000.00,0 +-10000.00,-9450.00,-550.00,-10000.00,-9050.00,-950.00,0 +-10200.00,-9650.00,-550.00,-10200.00,-9350.00,-850.00,0 +-10400.00,-9850.00,-550.00,-10400.00,-9600.00,-800.00,0 +-10600.00,-10050.00,-550.00,-10600.00,-9800.00,-800.00,0 +-10800.00,-10150.00,-650.00,-10800.00,-10050.00,-750.00,0 +-11000.00,-10200.00,-800.00,-11000.00,-10150.00,-850.00,0 +-11200.00,-10450.00,-750.00,-11200.00,-10450.00,-750.00,0 +-11400.00,-10850.00,-550.00,-11400.00,-10650.00,-750.00,0 +-11600.00,-11050.00,-550.00,-11600.00,-10900.00,-700.00,0 +-11800.00,-11300.00,-500.00,-11800.00,-11000.00,-800.00,0 +-12000.00,-11400.00,-600.00,-12000.00,-11250.00,-750.00,0 +-12200.00,-12000.00,-200.00,-12200.00,-11950.00,-250.00,0 +-12400.00,-11650.00,-750.00,-12400.00,-11650.00,-750.00,0 +-12600.00,-12250.00,-350.00,-12600.00,-12200.00,-400.00,0 +-12800.00,-12100.00,-700.00,-12800.00,-11950.00,-850.00,0 +-13000.00,-12250.00,-750.00,-13000.00,-12050.00,-950.00,0 +-13200.00,-13150.00,-50.00,-13200.00,-12950.00,-250.00,0 +-13400.00,-13450.00,50.00,-13400.00,-13200.00,-200.00,0 +-13600.00,-12800.00,-800.00,-13600.00,-12600.00,-1000.00,0 +-13800.00,-13300.00,-500.00,-13800.00,-13200.00,-600.00,0 +-14000.00,-13750.00,-250.00,-14000.00,-13400.00,-600.00,0 +-14200.00,-14000.00,-200.00,-14200.00,-13650.00,-550.00,0 +-14400.00,-14050.00,-350.00,-14400.00,-13750.00,-650.00,0 +-14600.00,-14100.00,-500.00,-14600.00,-13800.00,-800.00,0 +-14800.00,-14450.00,-350.00,-14800.00,-14150.00,-650.00,0 +-15000.00,-14750.00,-250.00,-15000.00,-14400.00,-600.00,0 +-15200.00,-14400.00,-800.00,-15200.00,-14050.00,-1150.00,0 +-15400.00,-14650.00,-750.00,-15400.00,-14400.00,-1000.00,0 +-15600.00,-15850.00,250.00,-15600.00,-15600.00,0.00,0 +-15800.00,-15750.00,-50.00,-15800.00,-15250.00,-550.00,0 +-16000.00,-19050.00,3050.00,-16000.00,-18550.00,2550.00,0 +-16200.00,-14500.00,-1700.00,-16200.00,-14000.00,-2200.00,0 +-16400.00,-12950.00,-3450.00,-16400.00,-12950.00,-3450.00,0 +-16600.00,-16450.00,-150.00,-16600.00,-15700.00,-900.00,0 +-16800.00,-19650.00,2850.00,-16800.00,-18150.00,1350.00,0 +-17000.00,-17250.00,250.00,-17000.00,-17750.00,750.00,0 +-17200.00,-13350.00,-3850.00,-17200.00,-15950.00,-1250.00,0 +-17400.00,-16000.00,-1400.00,-17400.00,-16200.00,-1200.00,0 +-17600.00,-20550.00,2950.00,-17600.00,-16950.00,-650.00,0 +-17800.00,-19250.00,1450.00,-17800.00,-17500.00,-300.00,0 +-18000.00,-14300.00,-3700.00,-18000.00,-16950.00,-1050.00,0 +-18200.00,-15500.00,-2700.00,-18200.00,-17150.00,-1050.00,0 +-18400.00,-21200.00,2800.00,-18400.00,-18450.00,50.00,0 +-18600.00,-22150.00,3550.00,-18600.00,-18700.00,100.00,0 +-18800.00,-17400.00,-1400.00,-18800.00,-17900.00,-900.00,0 +-19000.00,-15050.00,-3950.00,-19000.00,-18550.00,-450.00,0 +-19200.00,-18000.00,-1200.00,-19200.00,-18350.00,-850.00,0 +-19400.00,-23250.00,3850.00,-19400.00,-19400.00,0.00,0 +-19600.00,-20350.00,750.00,-19600.00,-19000.00,-600.00,0 +-19800.00,-16450.00,-3350.00,-19800.00,-19800.00,0.00,0 +-20000.00,-18250.00,-1750.00,-20000.00,-19900.00,-100.00,0 +-20200.00,-22750.00,2550.00,-20200.00,-19900.00,-300.00,0 +-20400.00,-23000.00,2600.00,-20400.00,-19950.00,-450.00,0 +-20600.00,-20150.00,-450.00,-20600.00,-20200.00,-400.00,0 +-20800.00,-18950.00,-1850.00,-20800.00,-20450.00,-350.00,0 +-21000.00,-20450.00,-550.00,-21000.00,-20750.00,-250.00,0 +-21200.00,-21950.00,750.00,-21200.00,-20850.00,-350.00,0 +-21400.00,-21900.00,500.00,-21400.00,-21000.00,-400.00,0 +-21600.00,-21400.00,-200.00,-21600.00,-21150.00,-450.00,0 +-21800.00,-21400.00,-400.00,-21800.00,-21350.00,-450.00,0 +-22000.00,-22150.00,150.00,-22000.00,-21650.00,-350.00,0 +-22200.00,-22550.00,350.00,-22200.00,-21700.00,-500.00,0 +-22400.00,-22650.00,250.00,-22400.00,-21950.00,-450.00,0 +-22600.00,-22650.00,50.00,-22600.00,-22200.00,-400.00,0 +-22800.00,-22500.00,-300.00,-22800.00,-22450.00,-350.00,0 +-23000.00,-22850.00,-150.00,-23000.00,-22650.00,-350.00,0 +-23200.00,-23150.00,-50.00,-23200.00,-22700.00,-500.00,0 +-23400.00,-23650.00,250.00,-23400.00,-23000.00,-400.00,0 +-23600.00,-24000.00,400.00,-23600.00,-23250.00,-350.00,0 +-23800.00,-23950.00,150.00,-23722.21,-23550.00,-172.21,0 +-24000.00,-23150.00,-850.00,-23522.21,-22900.00,-622.21,0 +-23982.98,-24550.00,567.02,-23322.21,-23750.00,427.79,0 +-23782.98,-25400.00,1617.02,-23122.21,-23900.00,777.79,0 +-23582.98,-24700.00,1117.02,-22922.21,-23650.00,727.79,0 +-23382.98,-23600.00,217.02,-22722.21,-22900.00,177.79,0 +-23182.98,-23300.00,117.02,-22522.21,-22500.00,-22.21,0 +-22982.98,-23350.00,367.02,-22322.21,-22500.00,177.79,0 +-22782.98,-22450.00,-332.98,-22122.21,-21600.00,-522.21,0 +-22582.98,-23350.00,767.02,-21922.21,-22500.00,577.79,0 +-22382.98,-23450.00,1067.02,-21722.21,-22600.00,877.79,0 +-22182.98,-22900.00,717.02,-21522.21,-22050.00,527.79,0 +-21982.98,-21400.00,-582.98,-21322.21,-20550.00,-772.21,0 +-21782.98,-22300.00,517.02,-21122.21,-21100.00,-22.21,0 +-21582.98,-22500.00,917.02,-20922.21,-21500.00,577.79,0 +-21382.98,-22050.00,667.02,-20722.21,-21300.00,577.79,0 +-21182.98,-20800.00,-382.98,-20522.21,-19900.00,-622.21,0 +-20982.98,-21700.00,717.02,-20322.21,-20350.00,27.79,0 +-20782.98,-21300.00,517.02,-20122.21,-19850.00,-272.21,0 +-20582.98,-21650.00,1067.02,-19922.21,-20300.00,377.79,0 +-20382.98,-21200.00,817.02,-19722.21,-20200.00,477.79,0 +-20182.98,-19750.00,-432.98,-19522.21,-19000.00,-522.21,0 +-19982.98,-20350.00,367.02,-19322.21,-19300.00,-22.21,0 +-19782.98,-20500.00,717.02,-19122.21,-19400.00,277.79,0 +-19582.98,-20250.00,667.02,-18922.21,-19100.00,177.79,0 +-19382.98,-19200.00,-182.98,-18722.21,-17900.00,-822.21,0 +-19182.98,-19700.00,517.02,-18522.21,-18550.00,27.79,0 +-18982.98,-19800.00,817.02,-18322.21,-18700.00,377.79,0 +-18782.98,-19450.00,667.02,-18122.21,-18450.00,327.79,0 +-18582.98,-18950.00,367.02,-17922.21,-17900.00,-22.21,0 +-18382.98,-18650.00,267.02,-17722.21,-17500.00,-222.21,0 +-18182.98,-18600.00,417.02,-17522.21,-17400.00,-122.21,0 +-17982.98,-17900.00,-82.98,-17322.21,-16700.00,-622.21,0 +-17782.98,-17650.00,-132.98,-17122.21,-16700.00,-422.21,0 +-17582.98,-17750.00,167.02,-16922.21,-17000.00,77.79,0 +-17382.98,-17450.00,67.02,-16722.21,-16900.00,177.79,0 +-17182.98,-21600.00,4417.02,-16522.21,-20400.00,3877.79,0 +-16982.98,-16350.00,-632.98,-16322.21,-15200.00,-1122.21,0 +-16782.98,-13500.00,-3282.98,-16122.21,-13050.00,-3072.21,0 +-16582.98,-16450.00,-132.98,-15922.21,-15250.00,-672.21,0 +-16382.98,-19000.00,2617.02,-15722.21,-17500.00,1777.79,0 +-16182.98,-16650.00,467.02,-15522.21,-16600.00,1077.79,0 +-15982.98,-13500.00,-2482.98,-15322.21,-15200.00,-122.21,0 +-15782.98,-15050.00,-732.98,-15122.21,-15100.00,-22.21,0 +-15582.98,-17700.00,2117.02,-14922.21,-15250.00,327.79,0 +-15382.98,-16550.00,1167.02,-14722.21,-14100.00,-622.21,0 +-15182.98,-15450.00,267.02,-14522.21,-14450.00,-72.21,0 +-14982.98,-14800.00,-182.98,-14322.21,-14600.00,277.79,0 +-14782.98,-14400.00,-382.98,-14122.21,-13800.00,-322.21,0 +-14582.98,-15150.00,567.02,-13922.21,-13950.00,27.79,0 +-14382.98,-14550.00,167.02,-13722.21,-13350.00,-372.21,0 +-14182.98,-14650.00,467.02,-13522.21,-13800.00,277.79,0 +-13982.98,-14000.00,17.02,-13322.21,-13050.00,-272.21,0 +-13782.98,-14350.00,567.02,-13122.21,-13150.00,27.79,0 +-13582.98,-13850.00,267.02,-12922.21,-12450.00,-472.21,0 +-13382.98,-13800.00,417.02,-12722.21,-12650.00,-72.21,0 +-13182.98,-12850.00,-332.98,-12522.21,-12000.00,-522.21,0 +-12982.98,-13200.00,217.02,-12322.21,-12200.00,-122.21,0 +-12782.98,-13300.00,517.02,-12122.21,-12100.00,-22.21,0 +-12582.98,-12550.00,-32.98,-11922.21,-11300.00,-622.21,0 +-12382.98,-12650.00,267.02,-11722.21,-11500.00,-222.21,0 +-12182.98,-12550.00,367.02,-11522.21,-11400.00,-122.21,0 +-11982.98,-11850.00,-132.98,-11322.21,-10650.00,-672.21,0 +-11782.98,-12000.00,217.02,-11122.21,-10800.00,-322.21,0 +-11582.98,-11600.00,17.02,-10922.21,-10450.00,-472.21,0 +-11382.98,-11350.00,-32.98,-10722.21,-10300.00,-422.21,0 +-11182.98,-11600.00,417.02,-10522.21,-10550.00,27.79,0 +-10982.98,-11000.00,17.02,-10322.21,-9950.00,-372.21,0 +-10782.98,-10600.00,-182.98,-10122.21,-9700.00,-422.21,0 +-10582.98,-10550.00,-32.98,-9922.21,-9500.00,-422.21,0 +-10382.98,-10900.00,517.02,-9722.21,-9750.00,27.79,0 +-10182.98,-10250.00,67.02,-9522.21,-9200.00,-322.21,0 +-9982.98,-9800.00,-182.98,-9322.21,-8800.00,-522.21,0 +-9782.98,-10100.00,317.02,-9122.21,-9000.00,-122.21,0 +-9582.98,-9600.00,17.02,-8922.21,-8550.00,-372.21,0 +-9382.98,-9350.00,-32.98,-8722.21,-8250.00,-472.21,0 +-9182.98,-9100.00,-82.98,-8522.21,-8050.00,-472.21,0 +-8982.98,-8900.00,-82.98,-8322.21,-8050.00,-272.21,0 +-8782.98,-8700.00,-82.98,-8122.21,-7850.00,-272.21,0 +-8582.98,-8300.00,-282.98,-7922.21,-7600.00,-322.21,0 +-8382.98,-8450.00,67.02,-7722.21,-7650.00,-72.21,0 +-8182.98,-8000.00,-182.98,-7522.21,-6950.00,-572.21,0 +-7982.98,-7750.00,-232.98,-7322.21,-6700.00,-622.21,0 +-7782.98,-7650.00,-132.98,-7122.21,-6700.00,-422.21,0 +-7582.98,-7750.00,167.02,-6922.21,-6750.00,-172.21,0 +-7382.98,-7000.00,-382.98,-6722.21,-6350.00,-372.21,0 +-7182.98,-6150.00,-1032.98,-6522.21,-6100.00,-422.21,0 +-6982.98,-6350.00,-632.98,-6322.21,-5850.00,-472.21,0 +-6782.98,-6650.00,-132.98,-6122.21,-5650.00,-472.21,0 +-6582.98,-6400.00,-182.98,-5922.21,-5550.00,-372.21,0 +-6382.98,-5450.00,-932.98,-5722.21,-5150.00,-572.21,0 +-6182.98,-4700.00,-1482.98,-5522.21,-4300.00,-1222.21,0 +-5982.98,-5400.00,-582.98,-5322.21,-4450.00,-872.21,0 +-5782.98,-5900.00,117.02,-5122.21,-4850.00,-272.21,0 +-5582.98,-5650.00,67.02,-4922.21,-4600.00,-322.21,0 +-5382.98,-4750.00,-632.98,-4722.21,-3650.00,-1072.21,0 +-5182.98,-4150.00,-1032.98,-4522.21,-3150.00,-1372.21,0 +-4982.98,-4400.00,-582.98,-4322.21,-3550.00,-772.21,0 +-4782.98,-4150.00,-632.98,-4122.21,-3500.00,-622.21,0 +-4582.98,-3350.00,-1232.98,-3922.21,-2750.00,-1172.21,0 +-4382.98,-3000.00,-1382.98,-3722.21,-2050.00,-1672.21,0 +-4182.98,-3500.00,-682.98,-3522.21,-2750.00,-772.21,0 +-3982.98,-3600.00,-382.98,-3322.21,-2700.00,-622.21,0 +-3782.98,-2800.00,-982.98,-3122.21,-2100.00,-1022.21,0 +-3582.98,-2150.00,-1432.98,-2922.21,-500.00,-2422.21,0 +-3382.98,-1250.00,-2132.98,-2722.21,-500.00,-2222.21,0 +-3182.98,-2450.00,-732.98,-2522.21,-2600.00,77.79,0 +-2982.98,-3100.00,117.02,-2322.21,-3000.00,677.79,0 +-2782.98,-2050.00,-732.98,-2122.21,-1850.00,-272.21,0 +-2582.98,-1400.00,-1182.98,-1922.21,-1750.00,-172.21,0 +-2382.98,-100.00,-2282.98,-1722.21,-50.00,-1672.21,0 +-2182.98,-500.00,-1682.98,-1522.21,450.00,-1972.21,0 +-1982.98,-2400.00,417.02,-1322.21,-200.00,-1122.21,0 +-1782.98,-2650.00,867.02,-1122.21,200.00,-1322.21,0 +-1582.98,-1000.00,-582.98,-922.21,450.00,-1372.21,0 +-1382.98,50.00,-1432.98,-722.21,0.00,-722.21,0 +-1182.98,400.00,-1582.98,-522.21,0.00,-522.21,0 +-982.98,850.00,-1832.98,-322.21,0.00,-322.21,0 +-782.98,150.00,-932.98,-122.21,0.00,-122.21,0 +-582.98,-450.00,-132.98,0.00,0.00,0.00,0 +-382.98,450.00,-832.98,0.00,0.00,0.00,0 +-182.98,0.00,-182.98,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +200.00,0.00,200.00,200.00,0.00,200.00,0 +400.00,0.00,400.00,400.00,0.00,400.00,0 +600.00,0.00,600.00,600.00,0.00,600.00,0 +800.00,0.00,800.00,800.00,0.00,800.00,0 +1000.00,0.00,1000.00,1000.00,0.00,1000.00,0 +1200.00,0.00,1200.00,1200.00,0.00,1200.00,0 +1400.00,0.00,1400.00,1400.00,0.00,1400.00,0 +1600.00,0.00,1600.00,1600.00,0.00,1600.00,0 +1800.00,200.00,1600.00,1800.00,150.00,1650.00,0 +2000.00,250.00,1750.00,2000.00,200.00,1800.00,0 +2200.00,0.00,2200.00,2200.00,0.00,2200.00,0 +2400.00,250.00,2150.00,2400.00,200.00,2200.00,0 +2600.00,500.00,2100.00,2600.00,200.00,2400.00,0 +2800.00,1700.00,1100.00,2800.00,600.00,2200.00,0 +3000.00,2300.00,700.00,3000.00,1400.00,1600.00,0 +3200.00,1800.00,1400.00,3200.00,2200.00,1000.00,0 +3400.00,850.00,2550.00,3400.00,1900.00,1500.00,0 +3600.00,1800.00,1800.00,3600.00,1100.00,2500.00,0 +3800.00,3950.00,-150.00,3800.00,1000.00,2800.00,0 +4000.00,3950.00,50.00,4000.00,2750.00,1250.00,0 +4200.00,2800.00,1400.00,4200.00,3650.00,550.00,0 +4400.00,2000.00,2400.00,4400.00,3250.00,1150.00,0 +4600.00,3250.00,1350.00,4600.00,2550.00,2050.00,0 +4800.00,4450.00,350.00,4800.00,2700.00,2100.00,0 +5000.00,4500.00,500.00,5000.00,3500.00,1500.00,0 +5200.00,3400.00,1800.00,5200.00,4000.00,1200.00,0 +5400.00,3150.00,2250.00,5400.00,4050.00,1350.00,0 +5600.00,4900.00,700.00,5600.00,4300.00,1300.00,0 +5800.00,5850.00,-50.00,5800.00,4300.00,1500.00,0 +6000.00,5350.00,650.00,6000.00,4350.00,1650.00,0 +6200.00,4400.00,1800.00,6200.00,4700.00,1500.00,0 +6400.00,4950.00,1450.00,6400.00,5000.00,1400.00,0 +6600.00,6000.00,600.00,6600.00,5300.00,1300.00,0 +6800.00,6250.00,550.00,6800.00,5550.00,1250.00,0 +7000.00,6150.00,850.00,7000.00,5700.00,1300.00,0 +7200.00,6250.00,950.00,7200.00,5800.00,1400.00,0 +7400.00,6800.00,600.00,7400.00,6300.00,1100.00,0 +7600.00,6750.00,850.00,7600.00,6250.00,1350.00,0 +7800.00,6850.00,950.00,7800.00,6400.00,1400.00,0 +8000.00,7500.00,500.00,8000.00,7000.00,1000.00,0 +8200.00,7400.00,800.00,8200.00,7000.00,1200.00,0 +8400.00,7500.00,900.00,8400.00,7000.00,1400.00,0 +8600.00,7800.00,800.00,8600.00,7200.00,1400.00,0 +8800.00,8150.00,650.00,8800.00,7600.00,1200.00,0 +9000.00,8650.00,350.00,9000.00,8200.00,800.00,0 +9200.00,8400.00,800.00,9200.00,8050.00,1150.00,0 +9400.00,8400.00,1000.00,9400.00,8050.00,1350.00,0 +9600.00,8800.00,800.00,9600.00,8300.00,1300.00,0 +9800.00,9600.00,200.00,9800.00,8900.00,900.00,0 +10000.00,9400.00,600.00,10000.00,8900.00,1100.00,0 +10200.00,9700.00,500.00,10200.00,9350.00,850.00,0 +10400.00,9850.00,550.00,10400.00,9550.00,850.00,0 +10600.00,9700.00,900.00,10600.00,9250.00,1350.00,0 +10800.00,10450.00,350.00,10800.00,9850.00,950.00,0 +11000.00,10600.00,400.00,11000.00,10200.00,800.00,0 +11200.00,10800.00,400.00,11200.00,10350.00,850.00,0 +11400.00,10850.00,550.00,11400.00,10350.00,1050.00,0 +11600.00,11050.00,550.00,11600.00,10450.00,1150.00,0 +11800.00,10800.00,1000.00,11800.00,10300.00,1500.00,0 +12000.00,11550.00,450.00,12000.00,11150.00,850.00,0 +12200.00,12050.00,150.00,12200.00,11700.00,500.00,0 +12400.00,12050.00,350.00,12400.00,11700.00,700.00,0 +12600.00,11600.00,1000.00,12600.00,11200.00,1400.00,0 +12800.00,12300.00,500.00,12800.00,11900.00,900.00,0 +13000.00,12250.00,750.00,13000.00,11900.00,1100.00,0 +13200.00,12450.00,750.00,13200.00,12000.00,1200.00,0 +13400.00,13250.00,150.00,13400.00,12950.00,450.00,0 +13600.00,13350.00,250.00,13600.00,13250.00,350.00,0 +13800.00,12800.00,1000.00,13800.00,12600.00,1200.00,0 +14000.00,13500.00,500.00,14000.00,13200.00,800.00,0 +14200.00,14000.00,200.00,14200.00,13600.00,600.00,0 +14400.00,14100.00,300.00,14400.00,13750.00,650.00,0 +14600.00,13550.00,1050.00,14600.00,13250.00,1350.00,0 +14800.00,14350.00,450.00,14800.00,14100.00,700.00,0 +15000.00,14850.00,150.00,15000.00,14500.00,500.00,0 +15200.00,14900.00,300.00,15200.00,14600.00,600.00,0 +15400.00,14950.00,450.00,15400.00,14600.00,800.00,0 +15600.00,14650.00,950.00,15600.00,14150.00,1450.00,0 +15800.00,15800.00,0.00,15800.00,15150.00,650.00,0 +16000.00,16100.00,-100.00,16000.00,15700.00,300.00,0 +16200.00,15850.00,350.00,16200.00,15500.00,700.00,0 +16400.00,15250.00,1150.00,16400.00,15200.00,1200.00,0 +16600.00,16350.00,250.00,16600.00,16050.00,550.00,0 +16800.00,20200.00,-3400.00,16800.00,19650.00,-2850.00,0 +17000.00,15700.00,1300.00,17000.00,15300.00,1700.00,0 +17200.00,13250.00,3950.00,17200.00,13450.00,3750.00,0 +17400.00,16700.00,700.00,17400.00,15950.00,1450.00,0 +17600.00,20400.00,-2800.00,17600.00,18600.00,-1000.00,0 +17800.00,18600.00,-800.00,17800.00,18750.00,-950.00,0 +18000.00,14400.00,3600.00,18000.00,17700.00,300.00,0 +18200.00,15900.00,2300.00,18200.00,17000.00,1200.00,0 +18400.00,19600.00,-1200.00,18400.00,16350.00,2050.00,0 +18600.00,20250.00,-1650.00,18600.00,17250.00,1350.00,0 +18800.00,19200.00,-400.00,18800.00,19100.00,-300.00,0 +19000.00,17850.00,1150.00,19000.00,19400.00,-400.00,0 +19200.00,18250.00,950.00,19200.00,18950.00,250.00,0 +19400.00,19650.00,-250.00,19400.00,18500.00,900.00,0 +19600.00,20150.00,-550.00,19600.00,18500.00,1100.00,0 +19800.00,19500.00,300.00,19800.00,18900.00,900.00,0 +20000.00,19400.00,600.00,20000.00,19550.00,450.00,0 +20200.00,19750.00,450.00,20200.00,19900.00,300.00,0 +20400.00,20150.00,250.00,20400.00,19900.00,500.00,0 +20600.00,20350.00,250.00,20600.00,19950.00,650.00,0 +20800.00,20500.00,300.00,20800.00,20200.00,600.00,0 +21000.00,20700.00,300.00,21000.00,20400.00,600.00,0 +21200.00,20950.00,250.00,21200.00,20600.00,600.00,0 +21400.00,21250.00,150.00,21400.00,21150.00,250.00,0 +21600.00,21400.00,200.00,21600.00,21250.00,350.00,0 +21800.00,21700.00,100.00,21800.00,21300.00,500.00,0 +22000.00,21850.00,150.00,22000.00,21400.00,600.00,0 +22200.00,22150.00,50.00,22200.00,21650.00,550.00,0 +22400.00,22100.00,300.00,22400.00,21650.00,750.00,0 +22600.00,21900.00,700.00,22600.00,22300.00,300.00,0 +22800.00,22650.00,150.00,22800.00,22550.00,250.00,0 +23000.00,23050.00,-50.00,23000.00,22650.00,350.00,0 +23200.00,22900.00,300.00,23200.00,22500.00,700.00,0 +23400.00,23300.00,100.00,23400.00,22900.00,500.00,0 +23600.00,23750.00,-150.00,23600.00,23250.00,350.00,0 +23800.00,23850.00,-50.00,23800.00,23400.00,400.00,0 +24000.00,23850.00,150.00,23861.05,23600.00,261.05,0 +24183.88,24050.00,133.88,23661.05,23600.00,61.05,0 +23983.88,24200.00,-216.12,23461.05,23650.00,-188.95,0 +23783.88,24350.00,-566.12,23261.05,23100.00,161.05,0 +23583.88,24000.00,-416.12,23061.05,23150.00,-88.95,0 +23383.88,24600.00,-1216.12,22861.05,23950.00,-1088.95,0 +23183.88,23650.00,-466.12,22661.05,22750.00,-88.95,0 +22983.88,22800.00,183.88,22461.05,22050.00,411.05,0 +22783.88,22600.00,183.88,22261.05,22000.00,261.05,0 +22583.88,22800.00,-216.12,22061.05,22100.00,-38.95,0 +22383.88,22750.00,-366.12,21861.05,22050.00,-188.95,0 +22183.88,23500.00,-1316.12,21661.05,22750.00,-1088.95,0 +21983.88,23100.00,-1116.12,21461.05,22200.00,-738.95,0 +21783.88,21400.00,383.88,21261.05,20650.00,611.05,0 +21583.88,21150.00,433.88,21061.05,20300.00,761.05,0 +21383.88,21300.00,83.88,20861.05,20450.00,411.05,0 +21183.88,21900.00,-716.12,20661.05,20900.00,-238.95,0 +20983.88,22550.00,-1566.12,20461.05,21700.00,-1238.95,0 +20783.88,21600.00,-816.12,20261.05,21100.00,-838.95,0 +20583.88,20550.00,33.88,20061.05,20000.00,61.05,0 +20383.88,18900.00,1483.88,19861.05,18100.00,1761.05,0 +20183.88,20250.00,-66.12,19661.05,18850.00,811.05,0 +19983.88,20950.00,-966.12,19461.05,20050.00,-588.95,0 +19783.88,20500.00,-716.12,19261.05,20250.00,-988.95,0 +19583.88,19700.00,-116.12,19061.05,19300.00,-238.95,0 +19383.88,19500.00,-116.12,18861.05,18550.00,311.05,0 +19183.88,19600.00,-416.12,18661.05,18100.00,561.05,0 +18983.88,19550.00,-566.12,18461.05,18350.00,111.05,0 +18783.88,19100.00,-316.12,18261.05,18450.00,-188.95,0 +18583.88,18700.00,-116.12,18061.05,18100.00,-38.95,0 +18383.88,18550.00,-166.12,17861.05,17500.00,361.05,0 +18183.88,18550.00,-366.12,17661.05,17600.00,61.05,0 +17983.88,18350.00,-366.12,17461.05,17450.00,11.05,0 +17783.88,18050.00,-266.12,17261.05,17250.00,11.05,0 +17583.88,17850.00,-266.12,17061.05,16900.00,161.05,0 +17383.88,17700.00,-316.12,16861.05,16600.00,261.05,0 +17183.88,17400.00,-216.12,16661.05,16400.00,261.05,0 +16983.88,17200.00,-216.12,16461.05,16400.00,61.05,0 +16783.88,16900.00,-116.12,16261.05,16250.00,11.05,0 +16583.88,16050.00,533.88,16061.05,15150.00,911.05,0 +16383.88,16650.00,-266.12,15861.05,15900.00,-38.95,0 +16183.88,19900.00,-3716.12,15661.05,19050.00,-3388.95,0 +15983.88,15150.00,833.88,15461.05,14650.00,811.05,0 +15783.88,12600.00,3183.88,15261.05,12350.00,2911.05,0 +15583.88,15050.00,533.88,15061.05,13850.00,1211.05,0 +15383.88,17100.00,-1716.12,14861.05,15100.00,-238.95,0 +15183.88,16800.00,-1616.12,14661.05,15950.00,-1288.95,0 +14983.88,15000.00,-16.12,14461.05,15150.00,-688.95,0 +14783.88,14200.00,583.88,14261.05,14050.00,211.05,0 +14583.88,14750.00,-166.12,14061.05,13400.00,661.05,0 +14383.88,15150.00,-766.12,13861.05,13350.00,511.05,0 +14183.88,14500.00,-316.12,13661.05,13500.00,161.05,0 +13983.88,13650.00,333.88,13461.05,13300.00,161.05,0 +13783.88,13500.00,283.88,13261.05,13200.00,61.05,0 +13583.88,13650.00,-66.12,13061.05,12850.00,211.05,0 +13383.88,13700.00,-316.12,12861.05,12550.00,311.05,0 +13183.88,12950.00,233.88,12661.05,11850.00,811.05,0 +12983.88,13150.00,-166.12,12461.05,12350.00,111.05,0 +12783.88,13050.00,-266.12,12261.05,12500.00,-238.95,0 +12583.88,12800.00,-216.12,12061.05,12150.00,-88.95,0 +12383.88,12450.00,-66.12,11861.05,11550.00,311.05,0 +12183.88,12300.00,-116.12,11661.05,11250.00,411.05,0 +11983.88,12150.00,-166.12,11461.05,11100.00,361.05,0 +11783.88,11450.00,333.88,11261.05,10550.00,711.05,0 +11583.88,11800.00,-216.12,11061.05,10950.00,111.05,0 +11383.88,11700.00,-316.12,10861.05,10800.00,61.05,0 +11183.88,11400.00,-216.12,10661.05,10500.00,161.05,0 +10983.88,11000.00,-16.12,10461.05,10150.00,311.05,0 +10783.88,10400.00,383.88,10261.05,9400.00,861.05,0 +10583.88,10800.00,-216.12,10061.05,9700.00,361.05,0 +10383.88,10900.00,-516.12,9861.05,9800.00,61.05,0 +10183.88,10400.00,-216.12,9661.05,9450.00,211.05,0 +9983.88,9800.00,183.88,9461.05,9000.00,461.05,0 +9783.88,9650.00,133.88,9261.05,8750.00,511.05,0 +9583.88,9400.00,183.88,9061.05,8150.00,911.05,0 +9383.88,9450.00,-66.12,8861.05,8150.00,711.05,0 +9183.88,9200.00,-16.12,8661.05,8200.00,461.05,0 +8983.88,8900.00,83.88,8461.05,8100.00,361.05,0 +8783.88,8750.00,33.88,8261.05,7900.00,361.05,0 +8583.88,8600.00,-16.12,8061.05,7600.00,461.05,0 +8383.88,8600.00,-216.12,7861.05,7650.00,211.05,0 +8183.88,8400.00,-216.12,7661.05,7450.00,211.05,0 +7983.88,7650.00,333.88,7461.05,7000.00,461.05,0 +7783.88,6600.00,1183.88,7261.05,6500.00,761.05,0 +7583.88,6900.00,683.88,7061.05,6400.00,661.05,0 +7383.88,7250.00,133.88,6861.05,6350.00,511.05,0 +7183.88,7600.00,-416.12,6661.05,6450.00,211.05,0 +6983.88,7050.00,-66.12,6461.05,5900.00,561.05,0 +6783.88,5900.00,883.88,6261.05,5100.00,1161.05,0 +6583.88,5450.00,1133.88,6061.05,4900.00,1161.05,0 +6383.88,5750.00,633.88,5861.05,5050.00,811.05,0 +6183.88,6050.00,133.88,5661.05,5100.00,561.05,0 +5983.88,5800.00,183.88,5461.05,4850.00,611.05,0 +5783.88,5050.00,733.88,5261.05,4800.00,461.05,0 +5583.88,4300.00,1283.88,5061.05,4200.00,861.05,0 +5383.88,4800.00,583.88,4861.05,3500.00,1361.05,0 +5183.88,5050.00,133.88,4661.05,3550.00,1111.05,0 +4983.88,4950.00,33.88,4461.05,3700.00,761.05,0 +4783.88,4050.00,733.88,4261.05,3550.00,711.05,0 +4583.88,3350.00,1233.88,4061.05,2550.00,1511.05,0 +4383.88,3000.00,1383.88,3861.05,1950.00,1911.05,0 +4183.88,3500.00,683.88,3661.05,2600.00,1061.05,0 +3983.88,3700.00,283.88,3461.05,3200.00,261.05,0 +3783.88,3000.00,783.88,3261.05,2800.00,461.05,0 +3583.88,2100.00,1483.88,3061.05,1500.00,1561.05,0 +3383.88,1850.00,1533.88,2861.05,1800.00,1061.05,0 +3183.88,2600.00,583.88,2661.05,1050.00,1611.05,0 +2983.88,2500.00,483.88,2461.05,1000.00,1461.05,0 +2783.88,1650.00,1133.88,2261.05,1600.00,661.05,0 +2583.88,950.00,1633.88,2061.05,850.00,1211.05,0 +2383.88,1550.00,833.88,1861.05,500.00,1361.05,0 +2183.88,750.00,1433.88,1661.05,750.00,911.05,0 +1983.88,450.00,1533.88,1461.05,350.00,1111.05,0 +1783.88,1550.00,233.88,1261.05,0.00,1261.05,0 +1583.88,1400.00,183.88,1061.05,0.00,1061.05,0 +1383.88,700.00,683.88,861.05,0.00,861.05,0 +1183.88,900.00,283.88,661.05,0.00,661.05,0 +983.88,350.00,633.88,461.05,0.00,461.05,0 +783.88,-250.00,1033.88,261.05,0.00,261.05,0 +583.88,0.00,583.88,61.05,0.00,61.05,0 +383.88,0.00,383.88,0.00,0.00,0.00,0 +183.88,0.00,183.88,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +-250.00,0.00,-250.00,-250.00,0.00,-250.00,0 +-500.00,0.00,-500.00,-500.00,0.00,-500.00,0 +-750.00,0.00,-750.00,-750.00,0.00,-750.00,0 +-1060.00,0.00,-1060.00,-1060.00,0.00,-1060.00,0 +-1310.00,0.00,-1310.00,-1310.00,0.00,-1310.00,0 +-1570.00,0.00,-1570.00,-1570.00,0.00,-1570.00,0 +-1830.00,0.00,-1830.00,-1830.00,0.00,-1830.00,0 +-2080.00,-240.00,-1840.00,-2080.00,-160.00,-1920.00,0 +-2340.00,-384.62,-1955.38,-2340.00,-576.92,-1763.08,0 +-2590.00,-440.00,-2150.00,-2590.00,-640.00,-1950.00,0 +-2850.00,-1384.62,-1465.38,-2850.00,-1461.54,-1388.46,0 +-3110.00,-2307.69,-802.31,-3110.00,-1807.69,-1302.31,0 +-3370.00,-2153.85,-1216.15,-3370.00,-1923.08,-1446.92,0 +-3630.00,-1846.15,-1783.85,-3630.00,-2038.46,-1591.54,0 +-3890.00,-2230.77,-1659.23,-3890.00,-2153.85,-1736.15,0 +-4150.00,-2961.54,-1188.46,-4150.00,-2384.62,-1765.38,0 +-4410.00,-3269.23,-1140.77,-4410.00,-2769.23,-1640.77,0 +-4680.00,-3407.41,-1272.59,-4680.00,-3148.15,-1531.85,0 +-4940.00,-3538.46,-1401.54,-4940.00,-3423.08,-1516.92,0 +-5210.00,-3925.93,-1284.07,-5210.00,-3703.70,-1506.30,0 +-5470.00,-4192.31,-1277.69,-5470.00,-3846.15,-1623.85,0 +-5740.00,-4518.52,-1221.48,-5740.00,-4222.22,-1517.78,0 +-6000.00,-4807.69,-1192.31,-6000.00,-4576.92,-1423.08,0 +-6270.00,-5000.00,-1270.00,-6270.00,-4814.81,-1455.19,0 +-6540.00,-5296.30,-1243.70,-6540.00,-5074.07,-1465.93,0 +-6800.00,-5538.46,-1261.54,-6800.00,-5384.62,-1415.38,0 +-7070.00,-5888.89,-1181.11,-7070.00,-5629.63,-1440.37,0 +-7330.00,-6192.31,-1137.69,-7330.00,-5884.62,-1445.38,0 +-7600.00,-6370.37,-1229.63,-7600.00,-6111.11,-1488.89,0 +-7860.00,-6538.46,-1321.54,-7860.00,-6384.62,-1475.38,0 +-8130.00,-6851.85,-1278.15,-8130.00,-6666.67,-1463.33,0 +-8400.00,-7148.15,-1251.85,-8400.00,-6925.93,-1474.07,0 +-8660.00,-7423.08,-1236.92,-8660.00,-7153.85,-1506.15,0 +-8930.00,-7666.67,-1263.33,-8930.00,-7407.41,-1522.59,0 +-9190.00,-7961.54,-1228.46,-9190.00,-7807.69,-1382.31,0 +-9460.00,-8259.26,-1200.74,-9460.00,-8000.00,-1460.00,0 +-9720.00,-8384.62,-1335.38,-9720.00,-8230.77,-1489.23,0 +-9990.00,-8518.52,-1471.48,-9990.00,-8518.52,-1471.48,0 +-10260.00,-8851.85,-1408.15,-10260.00,-8703.70,-1556.30,0 +-10530.00,-9296.30,-1233.70,-10530.00,-8888.89,-1641.11,0 +-10800.00,-9703.70,-1096.30,-10800.00,-9148.15,-1651.85,0 +-11070.00,-9925.93,-1144.07,-11070.00,-9518.52,-1551.48,0 +-11340.00,-10074.07,-1265.93,-11340.00,-9814.81,-1525.19,0 +-11610.00,-10259.26,-1350.74,-11610.00,-9962.96,-1647.04,0 +-11870.00,-10576.92,-1293.08,-11870.00,-10153.85,-1716.15,0 +-12140.00,-10962.96,-1177.04,-12140.00,-10481.48,-1658.52,0 +-12410.00,-11296.30,-1113.70,-12410.00,-10703.70,-1706.30,0 +-12680.00,-11481.48,-1198.52,-12680.00,-10962.96,-1717.04,0 +-12950.00,-11592.59,-1357.41,-12950.00,-11259.26,-1690.74,0 +-13220.00,-11814.81,-1405.19,-13220.00,-11555.56,-1664.44,0 +-13490.00,-12148.15,-1341.85,-13490.00,-11740.74,-1749.26,0 +-13760.00,-12518.52,-1241.48,-13760.00,-12000.00,-1760.00,0 +-14030.00,-12814.81,-1215.19,-14030.00,-12296.30,-1733.70,0 +-14290.00,-13000.00,-1290.00,-14290.00,-12615.38,-1674.62,0 +-14550.00,-13269.23,-1280.77,-14550.00,-12961.54,-1588.46,0 +-14820.00,-13518.52,-1301.48,-14820.00,-13222.22,-1597.78,0 +-15080.00,-13884.62,-1195.38,-15080.00,-13384.62,-1695.38,0 +-15350.00,-14111.11,-1238.89,-15350.00,-13777.78,-1572.22,0 +-15620.00,-14333.33,-1286.67,-15620.00,-13962.96,-1657.04,0 +-15890.00,-14592.59,-1297.41,-15890.00,-14222.22,-1667.78,0 +-16160.00,-14740.74,-1419.26,-16160.00,-14555.56,-1604.44,0 +-16430.00,-15037.04,-1392.96,-16430.00,-14777.78,-1652.22,0 +-16700.00,-15296.30,-1403.70,-16700.00,-15111.11,-1588.89,0 +-16970.00,-15592.59,-1377.41,-16970.00,-15370.37,-1599.63,0 +-17240.00,-15925.93,-1314.07,-17240.00,-15629.63,-1610.37,0 +-17510.00,-16148.15,-1361.85,-17510.00,-15925.93,-1584.07,0 +-17780.00,-16222.22,-1557.78,-17780.00,-16222.22,-1557.78,0 +-18050.00,-16740.74,-1309.26,-18050.00,-16407.41,-1642.59,0 +-18320.00,-17111.11,-1208.89,-18320.00,-16629.63,-1690.37,0 +-18590.00,-17407.41,-1182.59,-18590.00,-16888.89,-1701.11,0 +-18860.00,-17370.37,-1489.63,-18860.00,-17185.19,-1674.81,0 +-19130.00,-17518.52,-1611.48,-19130.00,-17407.41,-1722.59,0 +-19390.00,-17846.15,-1543.85,-19390.00,-17615.38,-1774.62,0 +-19660.00,-18148.15,-1511.85,-19660.00,-17703.70,-1956.30,0 +-19930.00,-18518.52,-1411.48,-19930.00,-18222.22,-1707.78,0 +-20190.00,-18730.77,-1459.23,-20190.00,-18307.69,-1882.31,0 +-20460.00,-19074.07,-1385.93,-20460.00,-18666.67,-1793.33,0 +-20730.00,-19296.30,-1433.70,-20730.00,-18814.81,-1915.19,0 +-21000.00,-19666.67,-1333.33,-21000.00,-19111.11,-1888.89,0 +-21320.00,-19937.50,-1382.50,-21320.00,-19250.00,-2070.00,0 +-21590.00,-20074.07,-1515.93,-21590.00,-19666.67,-1923.33,0 +-21860.00,-20259.26,-1600.74,-21860.00,-20037.04,-1822.96,0 +-22130.00,-20629.63,-1500.37,-22130.00,-20296.30,-1833.70,0 +-22400.00,-21074.07,-1325.93,-22400.00,-20592.59,-1807.41,0 +-22670.00,-21222.22,-1447.78,-22670.00,-20740.74,-1929.26,0 +-22940.00,-21370.37,-1569.63,-22940.00,-21111.11,-1828.89,0 +-23210.00,-21518.52,-1691.48,-23210.00,-21296.30,-1913.70,0 +-23480.00,-21814.81,-1665.19,-23022.90,-21703.70,-1319.20,0 +-23295.93,-22296.30,-999.64,-22752.90,-21814.81,-938.09,0 +-23025.93,-22407.41,-618.53,-22482.90,-21592.59,-890.31,0 +-22755.93,-22000.00,-755.93,-22212.90,-21370.37,-842.53,0 +-22485.93,-21740.74,-745.19,-21942.90,-21000.00,-942.90,0 +-22215.93,-21481.48,-734.45,-21672.90,-20740.74,-932.16,0 +-21955.93,-21307.69,-648.24,-21412.90,-20384.62,-1028.29,0 +-21685.93,-21148.15,-537.79,-21142.90,-20296.30,-846.61,0 +-21415.93,-20814.81,-601.12,-20872.90,-19888.89,-984.01,0 +-21145.93,-20481.48,-664.45,-20602.90,-19481.48,-1121.42,0 +-20875.93,-20259.26,-616.68,-20332.90,-19148.15,-1184.75,0 +-20605.93,-19666.67,-939.27,-20062.90,-19000.00,-1062.90,0 +-20335.93,-19370.37,-965.56,-19792.90,-18740.74,-1052.16,0 +-20065.93,-19518.52,-547.42,-19522.90,-18518.52,-1004.38,0 +-19795.93,-19333.33,-462.60,-19252.90,-18185.19,-1067.72,0 +-19535.93,-18884.62,-651.32,-18992.90,-18038.46,-954.44,0 +-19275.93,-18615.38,-660.55,-18732.90,-17807.69,-925.21,0 +-19005.93,-18296.30,-709.64,-18462.90,-17592.59,-870.31,0 +-18745.93,-18230.77,-515.17,-18202.90,-17307.69,-895.21,0 +-18475.93,-18000.00,-475.93,-17932.90,-17037.04,-895.87,0 +-18205.93,-17629.63,-576.31,-17662.90,-16740.74,-922.16,0 +-17935.93,-17333.33,-602.60,-17392.90,-16592.59,-800.31,0 +-17675.93,-17115.38,-560.55,-17132.90,-16384.62,-748.29,0 +-17405.93,-16925.93,-480.01,-16862.90,-16185.19,-677.72,0 +-17135.93,-16777.78,-358.16,-16592.90,-15888.89,-704.01,0 +-16865.93,-16481.48,-384.45,-16322.90,-15629.63,-693.27,0 +-16595.93,-16000.00,-595.93,-16052.90,-15407.41,-645.50,0 +-16325.93,-15740.74,-585.19,-15782.90,-15037.04,-745.87,0 +-16055.93,-15629.63,-426.31,-15512.90,-14777.78,-735.13,0 +-15785.93,-15481.48,-304.45,-15242.90,-14518.52,-724.38,0 +-15515.93,-15148.15,-367.79,-14972.90,-14259.26,-713.64,0 +-15255.93,-14769.23,-486.70,-14712.90,-14038.46,-674.44,0 +-14985.93,-14296.30,-689.64,-14442.90,-13740.74,-702.16,0 +-14715.93,-14259.26,-456.68,-14172.90,-13481.48,-691.42,0 +-14445.93,-14148.15,-297.79,-13902.90,-13148.15,-754.75,0 +-14175.93,-13814.81,-361.12,-13632.90,-12777.78,-855.13,0 +-13915.93,-13384.62,-531.32,-13372.90,-12538.46,-834.44,0 +-13645.93,-13111.11,-534.82,-13102.90,-12259.26,-843.64,0 +-13375.93,-12888.89,-487.05,-12832.90,-11925.93,-906.98,0 +-13105.93,-12629.63,-476.31,-12562.90,-11740.74,-822.16,0 +-12835.93,-12444.44,-391.49,-12292.90,-11444.44,-848.46,0 +-12575.93,-12346.15,-229.78,-12032.90,-11230.77,-802.13,0 +-12315.93,-12115.38,-200.55,-11772.90,-11000.00,-772.90,0 +-12045.93,-11740.74,-305.19,-11502.90,-10777.78,-725.13,0 +-11775.93,-11333.33,-442.60,-11232.90,-10444.44,-788.46,0 +-11505.93,-11074.07,-431.86,-10962.90,-10185.19,-777.72,0 +-11235.93,-10925.93,-310.01,-10692.90,-9962.96,-729.94,0 +-10975.93,-10769.23,-206.70,-10432.90,-9730.77,-702.13,0 +-10705.93,-10444.44,-261.49,-10162.90,-9592.59,-570.31,0 +-10435.93,-9962.96,-472.97,-9892.90,-9222.22,-670.68,0 +-10165.93,-9888.89,-277.05,-9622.90,-9037.04,-585.87,0 +-9895.93,-9851.85,-44.08,-9352.90,-8740.74,-612.16,0 +-9635.93,-9500.00,-135.93,-9092.90,-8423.08,-669.83,0 +-9365.93,-9074.07,-291.86,-8822.90,-8185.19,-637.72,0 +-9095.93,-8777.78,-318.16,-8552.90,-7925.93,-626.98,0 +-8825.93,-8555.56,-270.38,-8282.90,-7703.70,-579.20,0 +-8565.93,-8384.62,-181.32,-8022.90,-7423.08,-599.83,0 +-8295.93,-8111.11,-184.82,-7752.90,-7148.15,-604.75,0 +-8025.93,-7814.81,-211.12,-7482.90,-6925.93,-556.98,0 +-7755.93,-7518.52,-237.42,-7212.90,-6666.67,-546.24,0 +-7485.93,-7222.22,-263.71,-6942.90,-6481.48,-461.42,0 +-7225.93,-6961.54,-264.40,-6682.90,-6192.31,-490.60,0 +-6955.93,-6703.70,-252.23,-6412.90,-5925.93,-486.98,0 +-6685.93,-6481.48,-204.45,-6142.90,-5666.67,-476.24,0 +-6415.93,-6000.00,-415.93,-5872.90,-5444.44,-428.46,0 +-6145.93,-5222.22,-923.71,-5602.90,-5037.04,-565.87,0 +-5885.93,-5269.23,-616.70,-5342.90,-4307.69,-1035.21,0 +-5565.93,-5406.25,-159.68,-5022.90,-4312.50,-710.40,0 +-5305.93,-5076.92,-229.01,-4762.90,-4230.77,-532.13,0 +-5045.93,-4269.23,-776.70,-4502.90,-4000.00,-502.90,0 +-4785.93,-3692.31,-1093.63,-4242.90,-3192.31,-1050.60,0 +-4515.93,-4000.00,-515.93,-3972.90,-2814.81,-1158.09,0 +-4245.93,-4074.07,-171.86,-3702.90,-2851.85,-851.05,0 +-3985.93,-3346.15,-639.78,-3442.90,-2769.23,-673.67,0 +-3725.93,-2653.85,-1072.09,-3182.90,-1961.54,-1221.36,0 +-3465.93,-2269.23,-1196.70,-2922.90,-1769.23,-1153.67,0 +-3205.93,-2576.92,-629.01,-2662.90,-1653.85,-1009.06,0 +-2945.93,-2692.31,-253.63,-2402.90,-692.31,-1710.60,0 +-2685.93,-2153.85,-532.09,-2142.90,76.92,-2219.83,0 +-2425.93,-1269.23,-1156.70,-1882.90,-423.08,-1459.83,0 +-2165.93,-1192.31,-973.63,-1622.90,-1192.31,-430.60,0 +-1905.93,153.85,-2059.78,-1362.90,-923.08,-439.83,0 +-1645.93,307.69,-1953.63,-1102.90,307.69,-1410.60,0 +-1385.93,-769.23,-616.70,-842.90,384.62,-1227.52,0 +-1135.93,-640.00,-495.93,-592.90,-200.00,-392.90,0 +-875.93,-269.23,-606.70,-332.90,-38.46,-294.44,0 +-605.93,-222.22,-383.71,-62.90,0.00,-62.90,0 +-355.93,-480.00,124.07,0.00,0.00,0.00,0 +-95.93,-307.69,211.76,0.00,0.00,0.00,0 +0.00,80.00,-80.00,0.00,0.00,0.00,0 +0.00,40.00,-40.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +240.00,0.00,240.00,240.00,0.00,240.00,0 +490.00,0.00,490.00,490.00,0.00,490.00,0 +740.00,0.00,740.00,740.00,0.00,740.00,0 +990.00,0.00,990.00,990.00,0.00,990.00,0 +1240.00,0.00,1240.00,1240.00,0.00,1240.00,0 +1540.00,0.00,1540.00,1540.00,0.00,1540.00,0 +1790.00,0.00,1790.00,1790.00,0.00,1790.00,0 +2040.00,200.00,1840.00,2040.00,240.00,1800.00,0 +2290.00,400.00,1890.00,2290.00,400.00,1890.00,0 +2540.00,440.00,2100.00,2540.00,320.00,2220.00,0 +2790.00,1200.00,1590.00,2790.00,640.00,2150.00,0 +3040.00,2240.00,800.00,3040.00,1800.00,1240.00,0 +3300.00,2269.23,1030.77,3300.00,2153.85,1146.15,0 +3550.00,1720.00,1830.00,3550.00,2120.00,1430.00,0 +3800.00,1080.00,2720.00,3800.00,2080.00,1720.00,0 +4050.00,2640.00,1410.00,4050.00,2240.00,1810.00,0 +4300.00,4040.00,260.00,4300.00,2560.00,1740.00,0 +4560.00,3846.15,713.85,4560.00,2884.62,1675.38,0 +4810.00,2960.00,1850.00,4810.00,3320.00,1490.00,0 +5070.00,2769.23,2300.77,5070.00,3461.54,1608.46,0 +5330.00,3923.08,1406.92,5330.00,3576.92,1753.08,0 +5580.00,4960.00,620.00,5580.00,3960.00,1620.00,0 +5840.00,5192.31,647.69,5840.00,4192.31,1647.69,0 +6090.00,5000.00,1090.00,6090.00,4520.00,1570.00,0 +6350.00,4923.08,1426.92,6350.00,4769.23,1580.77,0 +6610.00,5346.15,1263.85,6610.00,5000.00,1610.00,0 +6860.00,5760.00,1100.00,6860.00,5240.00,1620.00,0 +7120.00,5961.54,1158.46,7120.00,5423.08,1696.92,0 +7370.00,6160.00,1210.00,7370.00,5760.00,1610.00,0 +7630.00,6461.54,1168.46,7630.00,6038.46,1591.54,0 +7890.00,6692.31,1197.69,7890.00,6346.15,1543.85,0 +8140.00,7040.00,1100.00,8140.00,6560.00,1580.00,0 +8400.00,7307.69,1092.31,8400.00,6769.23,1630.77,0 +8650.00,7480.00,1170.00,8650.00,7000.00,1650.00,0 +8900.00,7560.00,1340.00,8900.00,7320.00,1580.00,0 +9160.00,7846.15,1313.85,9160.00,7576.92,1583.08,0 +9410.00,8160.00,1250.00,9410.00,7760.00,1650.00,0 +9670.00,8461.54,1208.46,9670.00,8000.00,1670.00,0 +9930.00,8769.23,1160.77,9930.00,8307.69,1622.31,0 +10190.00,9038.46,1151.54,10190.00,8615.38,1574.62,0 +10450.00,9307.69,1142.31,10450.00,8961.54,1488.46,0 +10710.00,9423.08,1286.92,10710.00,9192.31,1517.69,0 +10970.00,9730.77,1239.23,10970.00,9576.92,1393.08,0 +11230.00,9961.54,1268.46,11230.00,9692.31,1537.69,0 +11480.00,10160.00,1320.00,11480.00,9760.00,1720.00,0 +11740.00,10423.08,1316.92,11740.00,10076.92,1663.08,0 +12000.00,10730.77,1269.23,12000.00,10423.08,1576.92,0 +12260.00,10923.08,1336.92,12260.00,10692.31,1567.69,0 +12520.00,11192.31,1327.69,12520.00,10846.15,1673.85,0 +12780.00,11461.54,1318.46,12780.00,11076.92,1703.08,0 +13040.00,11769.23,1270.77,13040.00,11423.08,1616.92,0 +13300.00,12000.00,1300.00,13300.00,11769.23,1530.77,0 +13560.00,12307.69,1252.31,13560.00,12076.92,1483.08,0 +13810.00,12560.00,1250.00,13810.00,12320.00,1490.00,0 +14070.00,12807.69,1262.31,14070.00,12538.46,1531.54,0 +14330.00,13000.00,1330.00,14330.00,12730.77,1599.23,0 +14590.00,13192.31,1397.69,14590.00,12884.62,1705.38,0 +14850.00,13538.46,1311.54,14850.00,13423.08,1426.92,0 +15100.00,13920.00,1180.00,15100.00,13520.00,1580.00,0 +15360.00,14230.77,1129.23,15360.00,13884.62,1475.38,0 +15620.00,14461.54,1158.46,15620.00,14192.31,1427.69,0 +15880.00,14615.38,1264.62,15880.00,14115.38,1764.62,0 +16140.00,14846.15,1293.85,16140.00,14461.54,1678.46,0 +16400.00,15153.85,1246.15,16400.00,14846.15,1553.85,0 +16660.00,15423.08,1236.92,16660.00,15346.15,1313.85,0 +16920.00,15769.23,1150.77,16920.00,15576.92,1343.08,0 +17180.00,15961.54,1218.46,17180.00,15692.31,1487.69,0 +17440.00,16153.85,1286.15,17440.00,15538.46,1901.54,0 +17700.00,16461.54,1238.46,17700.00,16038.46,1661.54,0 +17960.00,16769.23,1190.77,17960.00,16269.23,1690.77,0 +18220.00,16615.38,1604.62,18220.00,16730.77,1489.23,0 +18480.00,16807.69,1672.31,18480.00,16807.69,1672.31,0 +18730.00,17160.00,1570.00,18730.00,17000.00,1730.00,0 +18990.00,17538.46,1451.54,18990.00,17038.46,1951.54,0 +19250.00,17730.77,1519.23,19250.00,17461.54,1788.46,0 +19510.00,18038.46,1471.54,19510.00,17807.69,1702.31,0 +19770.00,18307.69,1462.31,19770.00,17961.54,1808.46,0 +20030.00,18461.54,1568.46,20030.00,18346.15,1683.85,0 +20290.00,18730.77,1559.23,20290.00,18692.31,1597.69,0 +20550.00,18846.15,1703.85,20550.00,18846.15,1703.85,0 +20810.00,19423.08,1386.92,20810.00,19153.85,1656.15,0 +21070.00,19692.31,1377.69,21070.00,19384.62,1685.38,0 +21330.00,19692.31,1637.69,21330.00,19653.85,1676.15,0 +21640.00,20096.77,1543.23,21640.00,19870.97,1769.03,0 +21890.00,20400.00,1490.00,21890.00,20320.00,1570.00,0 +22150.00,20576.92,1573.08,22150.00,20076.92,2073.08,0 +22410.00,20846.15,1563.85,22410.00,20769.23,1640.77,0 +22670.00,21230.77,1439.23,22670.00,21153.85,1516.15,0 +22930.00,21423.08,1506.92,22930.00,21346.15,1583.85,0 +23190.00,21500.00,1690.00,23190.00,21423.08,1766.92,0 +23440.00,21960.00,1480.00,23206.76,21680.00,1526.76,0 +23490.08,22160.00,1330.08,22956.76,21840.00,1116.76,0 +23230.08,22576.92,653.16,22696.76,21730.77,965.99,0 +22970.08,22538.46,431.62,22436.76,21807.69,629.07,0 +22710.08,21846.15,863.93,22176.76,21269.23,907.53,0 +22450.08,21384.62,1065.47,21916.76,21115.38,801.37,0 +22190.08,21192.31,997.77,21656.76,20461.54,1195.22,0 +21930.08,21115.38,814.70,21396.76,20307.69,1089.07,0 +21670.08,21000.00,670.08,21136.76,20115.38,1021.37,0 +21410.08,20576.92,833.16,20876.76,20115.38,761.37,0 +21150.08,20346.15,803.93,20616.76,19769.23,847.53,0 +20890.08,20076.92,813.16,20356.76,19384.62,972.14,0 +20630.08,19730.77,899.31,20096.76,19153.85,942.91,0 +20380.08,19520.00,860.08,19846.76,18960.00,886.76,0 +20120.08,19461.54,658.54,19586.76,18730.77,855.99,0 +19870.08,19320.00,550.08,19336.76,18560.00,776.76,0 +19620.08,19040.00,580.08,19086.76,18200.00,886.76,0 +19360.08,18615.38,744.70,18826.76,18076.92,749.83,0 +19100.08,18346.15,753.93,18566.76,17653.85,912.91,0 +18850.08,18120.00,730.08,18316.76,17400.00,916.76,0 +18590.08,18153.85,436.23,18056.76,17000.00,1056.76,0 +18330.08,17846.15,483.93,17796.76,16923.08,873.68,0 +18070.08,17461.54,608.54,17536.76,16769.23,767.53,0 +17810.08,17115.38,694.70,17276.76,16423.08,853.68,0 +17550.08,16961.54,588.54,17016.76,16038.46,978.30,0 +17290.08,16807.69,482.39,16756.76,15923.08,833.68,0 +17040.08,16640.00,400.08,16506.76,15760.00,746.76,0 +16780.08,16307.69,472.39,16246.76,15461.54,785.22,0 +16530.08,15960.00,570.08,15996.76,15280.00,716.76,0 +16290.08,15458.33,831.75,15756.76,14791.67,965.09,0 +16030.08,15384.62,645.47,15496.76,14730.77,765.99,0 +15770.08,15307.69,462.39,15236.76,14615.38,621.37,0 +15510.08,15115.38,394.70,14976.76,14269.23,707.53,0 +15260.08,14640.00,620.08,14726.76,13880.00,846.76,0 +15000.08,14346.15,653.93,14466.76,13576.92,889.83,0 +14750.08,14080.00,670.08,14216.76,13400.00,816.76,0 +14490.08,14000.00,490.08,13956.76,13115.38,841.37,0 +14230.08,13807.69,422.39,13696.76,13115.38,581.37,0 +13980.08,13360.00,620.08,13446.76,12840.00,606.76,0 +13720.08,13076.92,643.16,13186.76,12423.08,763.68,0 +13460.08,13038.46,421.62,12926.76,12076.92,849.83,0 +13200.08,12807.69,392.39,12666.76,11846.15,820.60,0 +12940.08,12538.46,401.62,12406.76,11384.62,1022.14,0 +12680.08,12230.77,449.31,12146.76,11423.08,723.68,0 +12430.08,11920.00,510.08,11896.76,11320.00,576.76,0 +12180.08,11800.00,380.08,11646.76,11040.00,606.76,0 +11920.08,11653.85,266.23,11386.76,10730.77,655.99,0 +11660.08,11384.62,275.47,11126.76,10500.00,626.76,0 +11400.08,11076.92,323.16,10866.76,10346.15,520.60,0 +11140.08,10846.15,293.93,10606.76,10038.46,568.30,0 +10880.08,10615.38,264.70,10346.76,9769.23,577.53,0 +10620.08,10384.62,235.47,10086.76,9615.38,471.37,0 +10360.08,10153.85,206.23,9826.76,9269.23,557.53,0 +10100.08,9846.15,253.93,9566.76,8961.54,605.22,0 +9840.08,9615.38,224.70,9306.76,8653.85,652.91,0 +9580.08,9423.08,157.00,9046.76,8423.08,623.68,0 +9320.08,9115.38,204.70,8786.76,8269.23,517.53,0 +9060.08,8807.69,252.39,8526.76,7884.62,642.14,0 +8800.08,8576.92,223.16,8266.76,7615.38,651.37,0 +8540.08,8384.62,155.47,8006.76,7461.54,545.22,0 +8280.08,8115.38,164.70,7746.76,7153.85,592.91,0 +8020.08,7884.62,135.47,7486.76,6923.08,563.68,0 +7760.08,7538.46,221.62,7226.76,6653.85,572.91,0 +7500.08,7307.69,192.39,6966.76,6346.15,620.60,0 +7240.08,7153.85,86.23,6706.76,6115.38,591.37,0 +6980.08,6615.38,364.70,6446.76,5846.15,600.60,0 +6730.08,5760.00,970.08,6196.76,5640.00,556.76,0 +6470.08,5846.15,623.93,5936.76,5384.62,552.14,0 +6220.08,6160.00,60.08,5686.76,5080.00,606.76,0 +5960.08,5769.23,190.85,5426.76,4769.23,657.53,0 +5700.08,4846.15,853.93,5166.76,4538.46,628.30,0 +5400.08,4366.67,1033.41,4866.76,4033.33,833.42,0 +5140.08,4807.69,332.39,4606.76,3307.69,1299.07,0 +4880.08,4769.23,110.85,4346.76,3192.31,1154.45,0 +4620.08,3961.54,658.54,4086.76,3307.69,779.07,0 +4360.08,3269.23,1090.85,3826.76,3000.00,826.76,0 +4110.08,3040.00,1070.08,3576.76,2200.00,1376.76,0 +3860.08,3480.00,380.08,3326.76,1680.00,1646.76,0 +3610.08,3440.00,170.08,3076.76,1920.00,1156.76,0 +3360.08,2640.00,720.08,2826.76,2000.00,826.76,0 +3100.08,2153.85,946.23,2566.76,1000.00,1566.76,0 +2850.08,1440.00,1410.08,2316.76,160.00,2156.76,0 +2600.08,1600.00,1000.08,2066.76,1080.00,986.76,0 +2350.08,1760.00,590.08,1816.76,1480.00,336.76,0 +2100.08,640.00,1460.08,1566.76,320.00,1246.76,0 +1850.08,-160.00,2010.08,1316.76,-40.00,1356.76,0 +1600.08,120.00,1480.08,1066.76,0.00,1066.76,0 +1350.08,200.00,1150.08,816.76,0.00,816.76,0 +1100.08,-360.00,1460.08,566.76,0.00,566.76,0 +850.08,-760.00,1610.08,316.76,0.00,316.76,0 +600.08,-160.00,760.08,66.76,0.00,66.76,0 +350.08,240.00,110.08,0.00,0.00,0.00,0 +110.08,-41.67,151.75,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,0 +0.00,0.00,0.00,0.00,0.00,0.00,252.58 +0.00,0.00,0.00,0.00,0.00,0.00,252.61 +0.00,0.00,0.00,0.00,0.00,0.00,252.63 +0.00,0.00,0.00,0.00,0.00,0.00,252.66 +0.00,0.00,0.00,0.00,0.00,0.00,252.68 +0.00,0.00,0.00,0.00,0.00,0.00,252.70 +0.00,0.00,0.00,0.00,0.00,0.00,252.69 +0.00,0.00,0.00,0.00,0.00,0.00,252.68 +-280.00,0.00,-280.00,-280.00,0.00,-280.00,252.63 +-610.00,0.00,-610.00,-610.00,0.00,-610.00,252.59 +-890.00,0.00,-890.00,-890.00,0.00,-890.00,252.56 +-1180.00,0.00,-1180.00,-1180.00,0.00,-1180.00,252.57 +-1460.00,0.00,-1460.00,-1460.00,0.00,-1460.00,252.58 +-1750.00,0.00,-1750.00,-1750.00,0.00,-1750.00,252.59 +-2030.00,-178.57,-1851.43,-2030.00,-250.00,-1780.00,252.59 +-2320.00,-275.86,-2044.14,-2320.00,-1448.28,-871.72,252.59 +-2610.00,-206.90,-2403.10,-2610.00,-931.03,-1678.97,252.59 +-2900.00,-758.62,-2141.38,-2900.00,-896.55,-2003.45,252.39 +-3190.00,-2448.28,-741.72,-3190.00,-1172.41,-2017.59,252.22 +-3480.00,-2862.07,-617.93,-3480.00,-1793.10,-1686.90,252.07 +-3770.00,-1655.17,-2114.83,-3770.00,-2137.93,-1632.07,251.94 +-4060.00,-1620.69,-2439.31,-4060.00,-2275.86,-1784.14,251.84 +-4350.00,-3068.97,-1281.03,-4350.00,-2413.79,-1936.21,251.69 +-4640.00,-4206.90,-433.10,-4640.00,-2827.59,-1812.41,251.56 +-4930.00,-4000.00,-930.00,-4930.00,-3241.38,-1688.62,251.46 +-5220.00,-3068.97,-2151.03,-5220.00,-3448.28,-1771.72,251.38 +-5510.00,-3551.72,-1958.28,-5510.00,-3724.14,-1785.86,251.32 +-5800.00,-4758.62,-1041.38,-5800.00,-4068.97,-1731.03,251.27 +-6080.00,-5357.14,-722.86,-6080.00,-4392.86,-1687.14,251.21 +-6370.00,-5275.86,-1094.14,-6370.00,-4620.69,-1749.31,251.16 +-6660.00,-5172.41,-1487.59,-6660.00,-4931.03,-1728.97,251.14 +-6940.00,-5500.00,-1440.00,-6940.00,-5250.00,-1690.00,251.11 +-7230.00,-5965.52,-1264.48,-7230.00,-5551.72,-1678.28,251.10 +-7510.00,-6392.86,-1117.14,-7510.00,-5857.14,-1652.86,251.11 +-7800.00,-6551.72,-1248.28,-7800.00,-6137.93,-1662.07,251.12 +-8090.00,-6827.59,-1262.41,-8090.00,-6551.72,-1538.28,251.13 +-8380.00,-7103.45,-1276.55,-8380.00,-6896.55,-1483.45,251.11 +-8670.00,-7448.28,-1221.72,-8670.00,-7103.45,-1566.55,251.09 +-8960.00,-7724.14,-1235.86,-8960.00,-7379.31,-1580.69,251.07 +-9250.00,-8000.00,-1250.00,-9250.00,-7724.14,-1525.86,251.05 +-9540.00,-8241.38,-1298.62,-9540.00,-7965.52,-1574.48,251.04 +-9830.00,-8517.24,-1312.76,-9830.00,-8275.86,-1554.14,251.02 +-10110.00,-8857.14,-1252.86,-10110.00,-8607.14,-1502.86,251.02 +-10400.00,-9206.90,-1193.10,-10400.00,-8931.03,-1468.97,251.02 +-10690.00,-9482.76,-1207.24,-10690.00,-9172.41,-1517.59,250.93 +-10980.00,-9724.14,-1255.86,-10980.00,-9413.79,-1566.21,250.85 +-11270.00,-10034.48,-1235.52,-11270.00,-9724.14,-1545.86,250.79 +-11560.00,-10241.38,-1318.62,-11560.00,-10103.45,-1456.55,250.85 +-11850.00,-10586.21,-1263.79,-11850.00,-10379.31,-1470.69,250.89 +-12140.00,-11000.00,-1140.00,-12140.00,-10689.66,-1450.34,250.93 +-12440.00,-11233.33,-1206.67,-12440.00,-11066.67,-1373.33,250.93 +-12730.00,-11413.79,-1316.21,-12730.00,-11310.34,-1419.66,250.92 +-13020.00,-11689.66,-1330.34,-13020.00,-11551.72,-1468.28,250.92 +-13310.00,-12034.48,-1275.52,-13310.00,-11827.59,-1482.41,250.93 +-13610.00,-12400.00,-1210.00,-13610.00,-12166.67,-1443.33,250.94 +-13910.00,-12700.00,-1210.00,-13910.00,-12433.33,-1476.67,251.00 +-14210.00,-12966.67,-1243.33,-14210.00,-12666.67,-1543.33,251.04 +-14500.00,-13206.90,-1293.10,-14500.00,-12827.59,-1672.41,251.08 +-14800.00,-13500.00,-1300.00,-14800.00,-13066.67,-1733.33,251.10 +-15100.00,-13833.33,-1266.67,-15100.00,-13466.67,-1633.33,251.11 +-15400.00,-14133.33,-1266.67,-15400.00,-13733.33,-1666.67,251.12 +-15700.00,-14333.33,-1366.67,-15700.00,-14066.67,-1633.33,251.16 +-16000.00,-14500.00,-1500.00,-16000.00,-14400.00,-1600.00,251.19 +-16290.00,-14931.03,-1358.97,-16290.00,-14586.21,-1703.79,251.17 +-16590.00,-15400.00,-1190.00,-16590.00,-14866.67,-1723.33,251.16 +-16890.00,-15700.00,-1190.00,-16890.00,-15133.33,-1756.67,251.14 +-17190.00,-15833.33,-1356.67,-17190.00,-15433.33,-1756.67,251.16 +-17490.00,-16066.67,-1423.33,-17490.00,-15666.67,-1823.33,251.18 +-17790.00,-16133.33,-1656.67,-17790.00,-15933.33,-1856.67,251.19 +-18090.00,-16766.67,-1323.33,-18090.00,-16133.33,-1956.67,251.16 +-18390.00,-17166.67,-1223.33,-18390.00,-16600.00,-1790.00,251.13 +-18690.00,-17566.67,-1123.33,-18690.00,-17000.00,-1690.00,251.10 +-18990.00,-17600.00,-1390.00,-18990.00,-17200.00,-1790.00,251.08 +-19290.00,-17600.00,-1690.00,-19290.00,-17433.33,-1856.67,251.07 +-19590.00,-18166.67,-1423.33,-19590.00,-17766.67,-1823.33,251.01 +-19890.00,-18566.67,-1323.33,-19890.00,-18066.67,-1823.33,250.97 +-20180.00,-18931.03,-1248.97,-20180.00,-18448.28,-1731.72,250.93 +-20480.00,-19100.00,-1380.00,-20480.00,-18800.00,-1680.00,250.96 +-20830.00,-19228.57,-1601.43,-20830.00,-19028.57,-1801.43,250.98 +-21130.00,-19533.33,-1596.67,-21130.00,-19400.00,-1730.00,250.98 +-21430.00,-20066.67,-1363.33,-21430.00,-19700.00,-1730.00,250.98 +-21730.00,-20266.67,-1463.33,-21730.00,-19933.33,-1796.67,250.98 +-22030.00,-20633.33,-1396.67,-22030.00,-20100.00,-1930.00,251.04 +-22330.00,-20900.00,-1430.00,-22330.00,-20433.33,-1896.67,251.09 +-22630.00,-21200.00,-1430.00,-22630.00,-20733.33,-1896.67,251.17 +-22930.00,-21266.67,-1663.33,-22930.00,-20933.33,-1996.67,251.24 +-23230.00,-21566.67,-1663.33,-23230.00,-21233.33,-1996.67,251.29 +-23488.72,-22033.33,-1455.39,-22932.89,-21600.00,-1332.89,251.20 +-23188.72,-22200.00,-988.72,-22632.89,-21733.33,-899.56,251.13 +-22888.72,-22333.33,-555.39,-22332.89,-21566.67,-766.22,251.08 +-22598.72,-22413.79,-184.93,-22042.89,-21103.45,-939.44,251.04 +-22298.72,-21666.67,-632.05,-21742.89,-20633.33,-1109.56,251.02 +-21998.72,-21333.33,-665.39,-21442.89,-20233.33,-1209.56,251.00 +-21698.72,-20900.00,-798.72,-21142.89,-20100.00,-1042.89,251.03 +-21398.72,-20666.67,-732.05,-20842.89,-19933.33,-909.56,251.06 +-21098.72,-20466.67,-632.05,-20542.89,-19666.67,-876.22,250.98 +-20798.72,-20200.00,-598.72,-20242.89,-19300.00,-942.89,250.92 +-20498.72,-19666.67,-832.05,-19942.89,-19100.00,-842.89,250.88 +-20198.72,-19666.67,-532.05,-19642.89,-18800.00,-842.89,250.94 +-19898.72,-19533.33,-365.39,-19342.89,-18533.33,-809.56,251.00 +-19598.72,-19133.33,-465.39,-19042.89,-18233.33,-809.56,251.04 +-19298.72,-18766.67,-532.05,-18742.89,-18000.00,-742.89,251.11 +-18998.72,-18400.00,-598.72,-18442.89,-17566.67,-876.22,251.17 +-18698.72,-18000.00,-698.72,-18142.89,-17200.00,-942.89,251.20 +-18398.72,-17966.67,-432.05,-17842.89,-16900.00,-942.89,251.22 +-18098.72,-17733.33,-365.39,-17542.89,-16666.67,-876.22,251.24 +-17798.72,-17266.67,-532.05,-17242.89,-16333.33,-909.56,251.25 +-17498.72,-16600.00,-898.72,-16942.89,-16000.00,-942.89,251.26 +-17208.72,-16620.69,-588.03,-16652.89,-15758.62,-894.27,251.27 +-16908.72,-16433.33,-475.39,-16352.89,-15500.00,-852.89,251.18 +-16608.72,-16200.00,-408.72,-16052.89,-15133.33,-919.56,251.10 +-16308.72,-15866.67,-442.05,-15752.89,-14800.00,-952.89,251.07 +-16008.72,-15633.33,-375.39,-15452.89,-14400.00,-1052.89,251.04 +-15708.72,-15366.67,-342.05,-15152.89,-14266.67,-886.22,251.02 +-15418.72,-15000.00,-418.72,-14862.89,-14068.97,-793.92,251.01 +-15118.72,-14666.67,-452.05,-14562.89,-13866.67,-696.22,251.01 +-14828.72,-14482.76,-345.96,-14272.89,-13551.72,-721.16,251.01 +-14528.72,-14166.67,-362.05,-13972.89,-13166.67,-806.22,251.00 +-14238.72,-13827.59,-411.13,-13682.89,-12827.59,-855.30,251.00 +-13948.72,-13551.72,-397.00,-13392.89,-12551.72,-841.16,251.01 +-13658.72,-13310.34,-348.37,-13102.89,-12413.79,-689.10,251.02 +-13358.72,-13100.00,-258.72,-12802.89,-12133.33,-669.56,251.03 +-13058.72,-12833.33,-225.39,-12502.89,-11866.67,-636.22,251.04 +-12768.72,-12482.76,-285.96,-12212.89,-11724.14,-488.75,251.05 +-12478.72,-12137.93,-340.79,-11922.89,-11379.31,-543.58,251.06 +-12188.72,-11827.59,-361.13,-11632.89,-11068.97,-563.92,251.08 +-11898.72,-11551.72,-347.00,-11342.89,-10793.10,-549.78,251.10 +-11608.72,-11275.86,-332.86,-11052.89,-10482.76,-570.13,251.12 +-11308.72,-10966.67,-342.05,-10752.89,-10200.00,-552.89,251.14 +-11018.72,-10724.14,-294.58,-10462.89,-9965.52,-497.37,251.16 +-10728.72,-10482.76,-245.96,-10172.89,-9689.66,-483.23,251.13 +-10438.72,-10137.93,-300.79,-9882.89,-9275.86,-607.03,251.11 +-10158.72,-9892.86,-265.86,-9602.89,-8964.29,-638.60,251.09 +-9868.72,-9655.17,-213.55,-9312.89,-8689.66,-623.23,251.08 +-9578.72,-9344.83,-233.89,-9022.89,-8482.76,-540.13,251.07 +-9288.72,-8931.03,-357.69,-8732.89,-8206.90,-525.99,251.06 +-9008.72,-8607.14,-401.58,-8452.89,-7857.14,-595.75,251.10 +-8718.72,-8482.76,-235.96,-8162.89,-7620.69,-542.20,251.14 +-8428.72,-8206.90,-221.82,-7872.89,-7275.86,-597.03,251.17 +-8138.72,-7862.07,-276.65,-7582.89,-7068.97,-513.92,251.19 +-7848.72,-7586.21,-262.51,-7292.89,-6724.14,-568.75,251.21 +-7568.72,-7285.71,-283.01,-7012.89,-6428.57,-584.32,251.24 +-7288.72,-7035.71,-253.01,-6732.89,-6035.71,-697.17,251.27 +-7008.72,-6750.00,-258.72,-6452.89,-5857.14,-595.75,251.29 +-6728.72,-6428.57,-300.15,-6172.89,-5535.71,-637.17,251.28 +-6448.72,-6214.29,-234.43,-5892.89,-5214.29,-678.60,251.27 +-6108.72,-5735.29,-373.43,-5552.89,-4941.18,-611.71,251.27 +-5818.72,-4655.17,-1163.55,-5262.89,-4586.21,-676.68,251.24 +-5528.72,-4137.93,-1390.79,-4972.89,-4310.34,-662.54,251.21 +-5248.72,-4750.00,-498.72,-4692.89,-3892.86,-800.03,251.20 +-4968.72,-4678.57,-290.15,-4412.89,-3250.00,-1162.89,251.18 +-4688.72,-3821.43,-867.29,-4132.89,-2928.57,-1204.32,251.17 +-4398.72,-3310.34,-1088.37,-3842.89,-3034.48,-808.41,251.16 +-4118.72,-3607.14,-511.58,-3562.89,-2857.14,-705.75,251.14 +-3828.72,-3655.17,-173.55,-3272.89,-1965.52,-1307.37,251.13 +-3548.72,-3000.00,-548.72,-2992.89,-1464.29,-1528.60,251.04 +-3258.72,-2275.86,-982.86,-2702.89,-1310.34,-1392.54,250.97 +-2978.72,-1571.43,-1407.29,-2422.89,-1571.43,-851.46,250.92 +-2698.72,-1571.43,-1127.29,-2142.89,-1500.00,-642.89,250.92 +-2408.72,-1758.62,-650.10,-1852.89,-137.93,-1714.96,250.92 +-2118.72,-931.03,-1187.69,-1562.89,413.79,-1976.68,250.93 +-1828.72,206.90,-2035.62,-1272.89,-206.90,-1065.99,250.89 +-1548.72,392.86,-1941.58,-992.89,-35.71,-957.17,250.86 +-1268.72,-285.71,-983.01,-712.89,571.43,-1284.32,250.83 +-978.72,-275.86,-702.86,-422.89,68.97,-491.85,250.78 +-688.72,275.86,-964.58,-132.89,-68.97,-63.92,250.74 +-398.72,896.55,-1295.27,0.00,0.00,0.00,250.77 +-118.72,-71.43,-47.29,0.00,0.00,0.00,250.80 +0.00,-214.29,214.29,0.00,0.00,0.00,250.82 +0.00,71.43,-71.43,0.00,0.00,0.00,250.87 +0.00,0.00,0.00,0.00,0.00,0.00,250.92 +0.00,0.00,0.00,0.00,0.00,0.00,250.95 +0.00,0.00,0.00,0.00,0.00,0.00,250.97 +0.00,0.00,0.00,0.00,0.00,0.00,250.98 +0.00,0.00,0.00,0.00,0.00,0.00,250.99 +0.00,0.00,0.00,0.00,0.00,0.00,250.98 +0.00,0.00,0.00,0.00,0.00,0.00,250.98 +0.00,0.00,0.00,0.00,0.00,0.00,250.97 +0.00,0.00,0.00,0.00,0.00,0.00,250.96 +0.00,0.00,0.00,0.00,0.00,0.00,250.96 +0.00,0.00,0.00,0.00,0.00,0.00,250.95 +0.00,0.00,0.00,0.00,0.00,0.00,250.94 +0.00,0.00,0.00,0.00,0.00,0.00,250.93 +0.00,0.00,0.00,0.00,0.00,0.00,250.93 +0.00,0.00,0.00,0.00,0.00,0.00,250.96 +0.00,0.00,0.00,0.00,0.00,0.00,250.99 +0.00,0.00,0.00,0.00,0.00,0.00,251.01 +0.00,0.00,0.00,0.00,0.00,0.00,251.00 +0.00,0.00,0.00,0.00,0.00,0.00,250.99 +0.00,0.00,0.00,0.00,0.00,0.00,250.99 +0.00,0.00,0.00,0.00,0.00,0.00,251.00 +0.00,0.00,0.00,0.00,0.00,0.00,251.01 +0.00,0.00,0.00,0.00,0.00,0.00,251.01 +0.00,0.00,0.00,0.00,0.00,0.00,251.03 +0.00,0.00,0.00,0.00,0.00,0.00,251.03 +0.00,0.00,0.00,0.00,0.00,0.00,251.03 +0.00,0.00,0.00,0.00,0.00,0.00,251.02 +0.00,0.00,0.00,0.00,0.00,0.00,251.02 +0.00,0.00,0.00,0.00,0.00,0.00,251.02 +0.00,0.00,0.00,0.00,0.00,0.00,251.03 +0.00,0.00,0.00,0.00,0.00,0.00,251.04 +0.00,0.00,0.00,0.00,0.00,0.00,251.08 +0.00,0.00,0.00,0.00,0.00,0.00,251.11 +0.00,0.00,0.00,0.00,0.00,0.00,251.13 +0.00,0.00,0.00,0.00,0.00,0.00,251.15 +0.00,0.00,0.00,0.00,0.00,0.00,251.17 +0.00,0.00,0.00,0.00,0.00,0.00,251.18 +0.00,0.00,0.00,0.00,0.00,0.00,251.17 +0.00,0.00,0.00,0.00,0.00,0.00,251.16 +0.00,0.00,0.00,0.00,0.00,0.00,251.15 +0.00,0.00,0.00,0.00,0.00,0.00,251.17 +0.00,0.00,0.00,0.00,0.00,0.00,251.18 +0.00,0.00,0.00,0.00,0.00,0.00,251.19 +0.00,0.00,0.00,0.00,0.00,0.00,251.17 +0.00,0.00,0.00,0.00,0.00,0.00,251.15 +0.00,0.00,0.00,0.00,0.00,0.00,251.14 +0.00,0.00,0.00,0.00,0.00,0.00,251.12 +0.00,0.00,0.00,0.00,0.00,0.00,251.12 +0.00,0.00,0.00,0.00,0.00,0.00,251.11 +0.00,0.00,0.00,0.00,0.00,0.00,251.11 +0.00,0.00,0.00,0.00,0.00,0.00,251.10 +0.00,0.00,0.00,0.00,0.00,0.00,251.13 +0.00,0.00,0.00,0.00,0.00,0.00,251.16 +0.00,0.00,0.00,0.00,0.00,0.00,251.18 +0.00,0.00,0.00,0.00,0.00,0.00,251.14 +0.00,0.00,0.00,0.00,0.00,0.00,251.11 +0.00,0.00,0.00,0.00,0.00,0.00,251.09 +0.00,0.00,0.00,0.00,0.00,0.00,251.07 +0.00,0.00,0.00,0.00,0.00,0.00,251.05 +0.00,0.00,0.00,0.00,0.00,0.00,251.04 +0.00,0.00,0.00,0.00,0.00,0.00,250.99 +0.00,0.00,0.00,0.00,0.00,0.00,250.95 +0.00,0.00,0.00,0.00,0.00,0.00,250.92 +0.00,0.00,0.00,0.00,0.00,0.00,250.96 +0.00,0.00,0.00,0.00,0.00,0.00,251.00 +0.00,0.00,0.00,0.00,0.00,0.00,251.02 +0.00,0.00,0.00,0.00,0.00,0.00,251.04 +0.00,0.00,0.00,0.00,0.00,0.00,251.06 +0.00,0.00,0.00,0.00,0.00,0.00,251.05 +0.00,0.00,0.00,0.00,0.00,0.00,251.04 +0.00,0.00,0.00,0.00,0.00,0.00,251.03 +0.00,0.00,0.00,0.00,0.00,0.00,251.08 +0.00,0.00,0.00,0.00,0.00,0.00,251.12 +0.00,0.00,0.00,0.00,0.00,0.00,251.16 +0.00,0.00,0.00,0.00,0.00,0.00,251.16 +0.00,0.00,0.00,0.00,0.00,0.00,251.16 +0.00,0.00,0.00,0.00,0.00,0.00,251.16 +0.00,0.00,0.00,0.00,0.00,0.00,251.20 +0.00,0.00,0.00,0.00,0.00,0.00,251.23 +0.00,0.00,0.00,0.00,0.00,0.00,251.25 +0.00,0.00,0.00,0.00,0.00,0.00,251.25 +0.00,0.00,0.00,0.00,0.00,0.00,251.24 +0.00,0.00,0.00,0.00,0.00,0.00,251.24 +0.00,0.00,0.00,0.00,0.00,0.00,251.25 +0.00,0.00,0.00,0.00,0.00,0.00,251.26 +0.00,0.00,0.00,0.00,0.00,0.00,251.27 +0.00,0.00,0.00,0.00,0.00,0.00,251.27 +0.00,0.00,0.00,0.00,0.00,0.00,251.28 +0.00,0.00,0.00,0.00,0.00,0.00,251.28 +0.00,0.00,0.00,0.00,0.00,0.00,251.24 +0.00,0.00,0.00,0.00,0.00,0.00,251.20 +0.00,0.00,0.00,0.00,0.00,0.00,251.24 +0.00,0.00,0.00,0.00,0.00,0.00,251.27 +0.00,0.00,0.00,0.00,0.00,0.00,251.29 +0.00,0.00,0.00,0.00,0.00,0.00,251.29 +0.00,0.00,0.00,0.00,0.00,0.00,251.28 +0.00,0.00,0.00,0.00,0.00,0.00,251.28 +0.00,0.00,0.00,0.00,0.00,0.00,251.29 +0.00,0.00,0.00,0.00,0.00,0.00,251.30 +0.00,0.00,0.00,0.00,0.00,0.00,251.31 +0.00,0.00,0.00,0.00,0.00,0.00,251.31 +0.00,0.00,0.00,0.00,0.00,0.00,251.31 +0.00,0.00,0.00,0.00,0.00,0.00,251.30 +0.00,0.00,0.00,0.00,0.00,0.00,251.33 +0.00,0.00,0.00,0.00,0.00,0.00,251.35 +0.00,0.00,0.00,0.00,0.00,0.00,251.37 +0.00,0.00,0.00,0.00,0.00,0.00,251.32 +0.00,0.00,0.00,0.00,0.00,0.00,251.29 +0.00,0.00,0.00,0.00,0.00,0.00,251.26 +0.00,0.00,0.00,0.00,0.00,0.00,251.25 +0.00,0.00,0.00,0.00,0.00,0.00,251.24 +0.00,0.00,0.00,0.00,0.00,0.00,251.23 +0.00,0.00,0.00,0.00,0.00,0.00,251.20 +0.00,0.00,0.00,0.00,0.00,0.00,251.17 +0.00,0.00,0.00,0.00,0.00,0.00,251.15 +0.00,0.00,0.00,0.00,0.00,0.00,251.15 +0.00,0.00,0.00,0.00,0.00,0.00,251.15 +0.00,0.00,0.00,0.00,0.00,0.00,251.15 +0.00,0.00,0.00,0.00,0.00,0.00,251.18 +0.00,0.00,0.00,0.00,0.00,0.00,251.21 +0.00,0.00,0.00,0.00,0.00,0.00,251.21 +0.00,0.00,0.00,0.00,0.00,0.00,251.21 +0.00,0.00,0.00,0.00,0.00,0.00,251.21 +0.00,0.00,0.00,0.00,0.00,0.00,251.19 +0.00,0.00,0.00,0.00,0.00,0.00,251.18 +0.00,0.00,0.00,0.00,0.00,0.00,251.17 +0.00,0.00,0.00,0.00,0.00,0.00,251.14 +0.00,0.00,0.00,0.00,0.00,0.00,251.12 +0.00,0.00,0.00,0.00,0.00,0.00,251.10 +0.00,0.00,0.00,0.00,0.00,0.00,251.07 +0.00,0.00,0.00,0.00,0.00,0.00,251.05 +0.00,0.00,0.00,0.00,0.00,0.00,251.03 +0.00,0.00,0.00,0.00,0.00,0.00,251.08 +0.00,0.00,0.00,0.00,0.00,0.00,251.11 +0.00,0.00,0.00,0.00,0.00,0.00,251.14 +0.00,0.00,0.00,0.00,0.00,0.00,251.13 +0.00,0.00,0.00,0.00,0.00,0.00,251.11 +0.00,0.00,0.00,0.00,0.00,0.00,251.13 +0.00,0.00,0.00,0.00,0.00,0.00,251.15 +0.00,0.00,0.00,0.00,0.00,0.00,251.17 +0.00,0.00,0.00,0.00,0.00,0.00,251.21 +0.00,0.00,0.00,0.00,0.00,0.00,251.25 +0.00,0.00,0.00,0.00,0.00,0.00,251.28 +0.00,0.00,0.00,0.00,0.00,0.00,251.26 +0.00,0.00,0.00,0.00,0.00,0.00,251.25 +0.00,0.00,0.00,0.00,0.00,0.00,251.24 +0.00,0.00,0.00,0.00,0.00,0.00,251.25 +0.00,0.00,0.00,0.00,0.00,0.00,251.26 +0.00,0.00,0.00,0.00,0.00,0.00,251.27 +0.00,0.00,0.00,0.00,0.00,0.00,251.27 +0.00,0.00,0.00,0.00,0.00,0.00,251.28 +0.00,0.00,0.00,0.00,0.00,0.00,251.29 +0.00,0.00,0.00,0.00,0.00,0.00,251.29 +0.00,0.00,0.00,0.00,0.00,0.00,251.29 +0.00,0.00,0.00,0.00,0.00,0.00,251.29 +0.00,0.00,0.00,0.00,0.00,0.00,251.28 +0.00,0.00,0.00,0.00,0.00,0.00,251.27 +0.00,0.00,0.00,0.00,0.00,0.00,251.26 +0.00,0.00,0.00,0.00,0.00,0.00,251.30 +0.00,0.00,0.00,0.00,0.00,0.00,251.33 +0.00,0.00,0.00,0.00,0.00,0.00,251.35 +0.00,0.00,0.00,0.00,0.00,0.00,251.32 +0.00,0.00,0.00,0.00,0.00,0.00,251.29 +0.00,0.00,0.00,0.00,0.00,0.00,251.24 +0.00,0.00,0.00,0.00,0.00,0.00,251.20 +0.00,0.00,0.00,0.00,0.00,0.00,251.17 +0.00,0.00,0.00,0.00,0.00,0.00,251.13 +0.00,0.00,0.00,0.00,0.00,0.00,251.09 +0.00,0.00,0.00,0.00,0.00,0.00,251.06 +0.00,0.00,0.00,0.00,0.00,0.00,251.11 +0.00,0.00,0.00,0.00,0.00,0.00,251.14 +0.00,0.00,0.00,0.00,0.00,0.00,251.17 +0.00,0.00,0.00,0.00,0.00,0.00,251.15 +0.00,0.00,0.00,0.00,0.00,0.00,251.14 +0.00,0.00,0.00,0.00,0.00,0.00,251.12 +0.00,0.00,0.00,0.00,0.00,0.00,251.13 +0.00,0.00,0.00,0.00,0.00,0.00,251.13 +0.00,0.00,0.00,0.00,0.00,0.00,251.14 +0.00,0.00,0.00,0.00,0.00,0.00,251.13 +0.00,0.00,0.00,0.00,0.00,0.00,251.11 +0.00,0.00,0.00,0.00,0.00,0.00,251.11 +0.00,0.00,0.00,0.00,0.00,0.00,251.10 +0.00,0.00,0.00,0.00,0.00,0.00,251.10 +0.00,0.00,0.00,0.00,0.00,0.00,251.10 +0.00,0.00,0.00,0.00,0.00,0.00,251.13 +0.00,0.00,0.00,0.00,0.00,0.00,251.15 +0.00,0.00,0.00,0.00,0.00,0.00,251.17 +0.00,0.00,0.00,0.00,0.00,0.00,251.29 +0.00,0.00,0.00,0.00,0.00,0.00,251.38 +0.00,0.00,0.00,0.00,0.00,0.00,251.46 +0.00,0.00,0.00,0.00,0.00,0.00,251.40 +0.00,0.00,0.00,0.00,0.00,0.00,251.35 +0.00,0.00,0.00,0.00,0.00,0.00,251.31 +0.00,0.00,0.00,0.00,0.00,0.00,251.33 +0.00,0.00,0.00,0.00,0.00,0.00,251.34 +0.00,0.00,0.00,0.00,0.00,0.00,251.32 +0.00,0.00,0.00,0.00,0.00,0.00,251.30 +0.00,0.00,0.00,0.00,0.00,0.00,251.29 +0.00,0.00,0.00,0.00,0.00,0.00,251.29 +0.00,0.00,0.00,0.00,0.00,0.00,251.29 +0.00,0.00,0.00,0.00,0.00,0.00,251.29 +0.00,0.00,0.00,0.00,0.00,0.00,251.29 +0.00,0.00,0.00,0.00,0.00,0.00,251.29 +0.00,0.00,0.00,0.00,0.00,0.00,251.29 +0.00,0.00,0.00,0.00,0.00,0.00,251.30 +0.00,0.00,0.00,0.00,0.00,0.00,251.32 +0.00,0.00,0.00,0.00,0.00,0.00,251.33 +0.00,0.00,0.00,0.00,0.00,0.00,251.31 +0.00,0.00,0.00,0.00,0.00,0.00,251.30 +0.00,0.00,0.00,0.00,0.00,0.00,251.29 +0.00,0.00,0.00,0.00,0.00,0.00,251.27 +0.00,0.00,0.00,0.00,0.00,0.00,251.25 +0.00,0.00,0.00,0.00,0.00,0.00,251.24 +0.00,0.00,0.00,0.00,0.00,0.00,251.24 +0.00,0.00,0.00,0.00,0.00,0.00,251.24 +0.00,0.00,0.00,0.00,0.00,0.00,251.24 +0.00,0.00,0.00,0.00,0.00,0.00,251.24 +0.00,0.00,0.00,0.00,0.00,0.00,251.24 +0.00,0.00,0.00,0.00,0.00,0.00,251.25 +0.00,0.00,0.00,0.00,0.00,0.00,251.26 +0.00,0.00,0.00,0.00,0.00,0.00,251.27 +0.00,0.00,0.00,0.00,0.00,0.00,251.27 +0.00,0.00,0.00,0.00,0.00,0.00,251.27 +0.00,0.00,0.00,0.00,0.00,0.00,251.27 +0.00,0.00,0.00,0.00,0.00,0.00,251.24 +0.00,0.00,0.00,0.00,0.00,0.00,251.22 +0.00,0.00,0.00,0.00,0.00,0.00,251.21 +0.00,0.00,0.00,0.00,0.00,0.00,251.20 +0.00,0.00,0.00,0.00,0.00,0.00,251.19 +0.00,0.00,0.00,0.00,0.00,0.00,251.18 +0.00,0.00,0.00,0.00,0.00,0.00,251.19 +0.00,0.00,0.00,0.00,0.00,0.00,251.20 +0.00,0.00,0.00,0.00,0.00,0.00,251.24 +0.00,0.00,0.00,0.00,0.00,0.00,251.26 +0.00,0.00,0.00,0.00,0.00,0.00,251.29 +0.00,0.00,0.00,0.00,0.00,0.00,251.28 +0.00,0.00,0.00,0.00,0.00,0.00,251.27 +0.00,0.00,0.00,0.00,0.00,0.00,251.27 +0.00,0.00,0.00,0.00,0.00,0.00,251.30 +0.00,0.00,0.00,0.00,0.00,0.00,251.32 +0.00,0.00,0.00,0.00,0.00,0.00,251.34 +0.00,0.00,0.00,0.00,0.00,0.00,251.32 +0.00,0.00,0.00,0.00,0.00,0.00,251.30 +0.00,0.00,0.00,0.00,0.00,0.00,251.28 +0.00,0.00,0.00,0.00,0.00,0.00,251.33 +0.00,0.00,0.00,0.00,0.00,0.00,251.37 +0.00,0.00,0.00,0.00,0.00,0.00,251.40 +0.00,0.00,0.00,0.00,0.00,0.00,251.39 +0.00,0.00,0.00,0.00,0.00,0.00,251.39 +0.00,0.00,0.00,0.00,0.00,0.00,251.38 +0.00,0.00,0.00,0.00,0.00,0.00,251.40 +0.00,0.00,0.00,0.00,0.00,0.00,251.41 +0.00,0.00,0.00,0.00,0.00,0.00,251.40 +0.00,0.00,0.00,0.00,0.00,0.00,251.39 +0.00,0.00,0.00,0.00,0.00,0.00,251.38 +0.00,0.00,0.00,0.00,0.00,0.00,251.37 +0.00,0.00,0.00,0.00,0.00,0.00,251.36 +0.00,0.00,0.00,0.00,0.00,0.00,251.36 +0.00,0.00,0.00,0.00,0.00,0.00,251.34 +0.00,0.00,0.00,0.00,0.00,0.00,251.33 +0.00,0.00,0.00,0.00,0.00,0.00,251.31 +0.00,0.00,0.00,0.00,0.00,0.00,251.30 +280.00,0.00,280.00,280.00,0.00,280.00,251.28 +570.00,0.00,570.00,570.00,0.00,570.00,251.27 +850.00,0.00,850.00,850.00,0.00,850.00,251.26 +1130.00,0.00,1130.00,1130.00,0.00,1130.00,251.26 +1460.00,0.00,1460.00,1460.00,0.00,1460.00,251.25 +1740.00,0.00,1740.00,1740.00,0.00,1740.00,251.27 +2020.00,178.57,1841.43,2020.00,142.86,1877.14,251.28 +2300.00,428.57,1871.43,2300.00,321.43,1978.57,251.32 +2580.00,392.86,2187.14,2580.00,178.57,2401.43,251.35 +2860.00,1464.29,1395.71,2860.00,678.57,2181.43,251.38 +3140.00,2571.43,568.57,3140.00,2035.71,1104.29,251.29 +3420.00,2607.14,812.86,3420.00,2214.29,1205.71,251.22 +3700.00,1714.29,1985.71,3700.00,1607.14,2092.86,251.16 +3980.00,1428.57,2551.43,3980.00,1714.29,2265.71,251.13 +4260.00,2714.29,1545.71,4260.00,2607.14,1652.86,251.11 +4540.00,4035.71,504.29,4540.00,3392.86,1147.14,251.09 +4820.00,3964.29,855.71,4820.00,3535.71,1284.29,251.18 +5100.00,3107.14,1992.86,5100.00,3571.43,1528.57,251.25 +5380.00,3428.57,1951.43,5380.00,3535.71,1844.29,251.31 +5660.00,4535.71,1124.29,5660.00,3928.57,1731.43,251.24 +5940.00,5178.57,761.43,5940.00,4357.14,1582.86,251.19 +6220.00,5178.57,1041.43,6220.00,4607.14,1612.86,251.15 +6500.00,5142.86,1357.14,6500.00,4892.86,1607.14,251.12 +6780.00,5500.00,1280.00,6780.00,5178.57,1601.43,251.10 +7060.00,6000.00,1060.00,7060.00,5464.29,1595.71,251.08 +7340.00,6250.00,1090.00,7340.00,5785.71,1554.29,251.10 +7620.00,6464.29,1155.71,7620.00,6000.00,1620.00,251.11 +7900.00,6714.29,1185.71,7900.00,6250.00,1650.00,251.07 +8180.00,7035.71,1144.29,8180.00,6642.86,1537.14,251.03 +8470.00,7310.34,1159.66,8470.00,6965.52,1504.48,251.00 +8750.00,7642.86,1107.14,8750.00,7250.00,1500.00,251.02 +9030.00,7857.14,1172.86,9030.00,7535.71,1494.29,251.03 +9310.00,8071.43,1238.57,9310.00,7750.00,1560.00,251.04 +9600.00,8379.31,1220.69,9600.00,8000.00,1600.00,251.04 +9890.00,8689.66,1200.34,9890.00,8275.86,1614.14,251.03 +10170.00,9035.71,1134.29,10170.00,8642.86,1527.14,251.03 +10450.00,9285.71,1164.29,10450.00,8928.57,1521.43,251.02 +10740.00,9586.21,1153.79,10740.00,9275.86,1464.14,251.02 +11020.00,9928.57,1091.43,11020.00,9535.71,1484.29,251.01 +11300.00,10214.29,1085.71,11300.00,9785.71,1514.29,251.07 +11580.00,10464.29,1115.71,11580.00,10035.71,1544.29,251.11 +11860.00,10678.57,1181.43,11860.00,10357.14,1502.86,251.17 +12140.00,11000.00,1140.00,12140.00,10607.14,1532.86,251.22 +12420.00,11178.57,1241.43,12420.00,10785.71,1634.29,251.27 +12710.00,11344.83,1365.17,12710.00,11068.97,1641.03,251.26 +12990.00,11678.57,1311.43,12990.00,11357.14,1632.86,251.26 +13280.00,12034.48,1245.52,13280.00,11620.69,1659.31,251.26 +13560.00,12321.43,1238.57,13560.00,12000.00,1560.00,251.21 +13850.00,12482.76,1367.24,13850.00,12275.86,1574.14,251.17 +14140.00,12689.66,1450.34,14140.00,12413.79,1726.21,251.14 +14420.00,13000.00,1420.00,14420.00,12714.29,1705.71,251.11 +14710.00,13275.86,1434.14,14710.00,13000.00,1710.00,251.09 +15000.00,13689.66,1310.34,15000.00,13275.86,1724.14,251.07 +15290.00,13931.03,1358.97,15290.00,13551.72,1738.28,251.05 +15580.00,14137.93,1442.07,15580.00,13689.66,1890.34,251.03 +15860.00,14357.14,1502.86,15860.00,14178.57,1681.43,250.98 +16150.00,14724.14,1425.86,16150.00,14620.69,1529.31,250.95 +16440.00,14931.03,1508.97,16440.00,14896.55,1543.45,250.92 +16730.00,15241.38,1488.62,16730.00,15034.48,1695.52,250.92 +17020.00,15586.21,1433.79,17020.00,15172.41,1847.59,250.91 +17310.00,16034.48,1275.52,17310.00,15551.72,1758.28,250.91 +17600.00,16241.38,1358.62,17600.00,15896.55,1703.45,250.89 +17890.00,16310.34,1579.66,17890.00,16379.31,1510.69,250.88 +18180.00,16482.76,1697.24,18180.00,16551.72,1628.28,250.87 +18470.00,17103.45,1366.55,18470.00,16827.59,1642.41,250.90 +18760.00,17379.31,1380.69,18760.00,17068.97,1691.03,250.92 +19050.00,17724.14,1325.86,19050.00,17206.90,1843.10,250.97 +19340.00,17896.55,1443.45,19340.00,17448.28,1891.72,251.01 +19630.00,18379.31,1250.69,19630.00,18068.97,1561.03,251.05 +19920.00,18827.59,1092.41,19920.00,18551.72,1368.28,251.05 +20210.00,18931.03,1278.97,20210.00,18793.10,1416.90,251.04 +20500.00,18965.52,1534.48,20500.00,18931.03,1568.97,251.04 +20780.00,19000.00,1780.00,20780.00,19000.00,1780.00,251.04 +21070.00,19241.38,1828.62,21070.00,19137.93,1932.07,251.04 +21360.00,19758.62,1601.38,21360.00,19586.21,1773.79,251.04 +21700.00,20088.24,1611.76,21700.00,19794.12,1905.88,251.03 +21990.00,20275.86,1714.14,21990.00,20068.97,1921.03,251.01 +22270.00,20714.29,1555.71,22270.00,20500.00,1770.00,251.02 +22560.00,20827.59,1732.41,22560.00,20931.03,1628.97,251.02 +22850.00,21137.93,1712.07,22850.00,20862.07,1987.93,251.02 +23140.00,21655.17,1484.83,23140.00,21137.93,2002.07,251.03 +23430.00,21896.55,1533.45,23182.02,21620.69,1561.33,251.04 +23412.15,22137.93,1274.22,22892.02,21931.03,960.98,251.05 +23122.15,22137.93,984.22,22602.02,21793.10,808.91,251.06 +22832.15,22068.97,763.19,22312.02,21586.21,725.81,251.07 +22542.15,21896.55,645.60,22022.02,21310.34,711.67,251.08 +22252.15,21482.76,769.40,21732.02,20586.21,1145.81,251.14 +21962.15,21344.83,617.33,21442.02,20482.76,959.26,251.19 +21672.15,21172.41,499.74,21152.02,20206.90,945.12,251.23 +21382.15,20620.69,761.46,20862.02,20068.97,793.05,251.25 +21092.15,20379.31,712.84,20572.02,19586.21,985.81,251.27 +20802.15,20241.38,560.78,20282.02,19413.79,868.22,251.25 +20512.15,20000.00,512.15,19992.02,19172.41,819.60,251.23 +20222.15,19620.69,601.46,19702.02,18965.52,736.50,251.22 +19932.15,18896.55,1035.60,19412.02,18241.38,1170.64,251.17 +19642.15,18517.24,1124.91,19122.02,18241.38,880.64,251.13 +19352.15,18586.21,765.95,18832.02,17827.59,1004.43,251.09 +19062.15,18344.83,717.33,18542.02,17689.66,852.36,251.08 +18772.15,18275.86,496.29,18252.02,17172.41,1079.60,251.07 +18482.15,17931.03,551.12,17962.02,17172.41,789.60,251.07 +18192.15,17689.66,502.50,17672.02,16896.55,775.46,251.07 +17902.15,17379.31,522.84,17382.02,16344.83,1037.19,251.07 +17612.15,16965.52,646.64,17092.02,16137.93,954.08,251.13 +17322.15,16724.14,598.02,16802.02,15931.03,870.98,251.18 +17032.15,16551.72,480.43,16512.02,15758.62,753.39,251.22 +16742.15,16275.86,466.29,16222.02,15344.83,877.19,251.23 +16452.15,16068.97,383.19,15932.02,15206.90,725.12,251.24 +16162.15,15724.14,438.02,15642.02,14931.03,710.98,251.25 +15872.15,15310.34,561.81,15352.02,14620.69,731.33,251.13 +15582.15,15206.90,375.26,15062.02,14310.34,751.67,251.04 +15292.15,15000.00,292.15,14772.02,14034.48,737.53,251.15 +15002.15,14758.62,243.53,14482.02,13448.28,1033.74,251.24 +14712.15,14344.83,367.33,14192.02,13482.76,709.26,251.32 +14422.15,14034.48,387.67,13902.02,13379.31,522.71,251.32 +14132.15,13793.10,339.05,13612.02,13068.97,543.05,251.33 +13842.15,13586.21,255.95,13322.02,12551.72,770.29,251.34 +13562.15,13250.00,312.15,13042.02,12392.86,649.16,251.31 +13272.15,12758.62,513.53,12752.02,11896.55,855.46,251.29 +12982.15,12344.83,637.33,12462.02,11758.62,703.39,251.27 +12692.15,12137.93,554.22,12172.02,11517.24,654.77,251.26 +12412.15,12142.86,269.30,11892.02,11250.00,642.02,251.26 +12122.15,11931.03,191.12,11602.02,10827.59,774.43,251.26 +11832.15,11379.31,452.84,11312.02,10620.69,691.33,251.29 +11542.15,11000.00,542.15,11022.02,10344.83,677.19,251.31 +11252.15,10793.10,459.05,10732.02,9931.03,800.98,251.25 +10972.15,10571.43,400.73,10452.02,9785.71,666.30,251.20 +10682.15,10344.83,337.33,10162.02,9517.24,644.77,251.16 +10402.15,10071.43,330.73,9882.02,9178.57,703.44,251.05 +10122.15,9857.14,265.01,9602.02,8928.57,673.44,250.95 +9842.15,9571.43,270.73,9322.02,8678.57,643.44,250.88 +9562.15,9250.00,312.15,9042.02,8321.43,720.59,251.09 +9282.15,8892.86,389.30,8762.02,8107.14,654.87,251.26 +9002.15,8642.86,359.30,8482.02,7928.57,553.44,251.39 +8712.15,8413.79,298.36,8192.02,7620.69,571.33,251.34 +8432.15,8142.86,289.30,7912.02,7214.29,697.73,251.31 +8152.15,7928.57,223.58,7632.02,6892.86,739.16,251.28 +7862.15,7689.66,172.50,7342.02,6620.69,721.33,251.20 +7582.15,7464.29,117.87,7062.02,6321.43,740.59,251.15 +7292.15,7206.90,85.26,6772.02,6103.45,668.57,251.28 +7002.15,6620.69,381.46,6482.02,5862.07,619.95,251.39 +6722.15,5607.14,1115.01,6202.02,5571.43,630.59,251.47 +6442.15,5750.00,692.15,5922.02,5285.71,636.30,251.43 +6162.15,6071.43,90.73,5642.02,4928.57,713.44,251.39 +5882.15,5857.14,25.01,5362.02,4607.14,754.87,251.36 +5602.15,4892.86,709.30,5082.02,4392.86,689.16,251.21 +5272.15,4303.03,969.12,4752.02,4121.21,630.80,251.08 +4992.15,4607.14,385.01,4472.02,3642.86,829.16,250.98 +4712.15,4678.57,33.58,4192.02,3071.43,1120.59,251.19 +4432.15,4000.00,432.15,3912.02,2928.57,983.44,251.35 +4152.15,3428.57,723.58,3632.02,2785.71,846.30,251.48 +3872.15,2821.43,1050.73,3352.02,2607.14,744.87,251.52 +3592.15,2464.29,1127.87,3072.02,1821.43,1250.59,251.56 +3312.15,2821.43,490.73,2792.02,785.71,2006.30,251.58 +3032.15,3000.00,32.15,2512.02,1500.00,1012.02,251.50 +2752.15,2321.43,430.73,2232.02,1714.29,517.73,251.43 +2472.15,1642.86,829.30,1952.02,928.57,1023.44,251.43 +2192.15,1107.14,1085.01,1672.02,-357.14,2029.16,251.43 +1912.15,642.86,1269.30,1392.02,-285.71,1677.73,251.43 +1632.15,-607.14,2239.30,1112.02,535.71,576.30,251.54 +1352.15,357.14,995.01,832.02,-107.14,939.16,251.62 +1072.15,785.71,286.44,552.02,-678.57,1230.59,251.69 +792.15,35.71,756.44,272.02,35.71,236.30,251.62 +512.15,-71.43,583.58,0.00,35.71,-35.71,251.57 +232.15,-71.43,303.58,0.00,0.00,0.00,251.52 +0.00,-285.71,285.71,0.00,0.00,0.00,251.48 +0.00,-888.89,888.89,0.00,0.00,0.00,251.44 +0.00,71.43,-71.43,0.00,0.00,0.00,251.41 +0.00,178.57,-178.57,0.00,0.00,0.00,251.59 +0.00,-71.43,71.43,0.00,0.00,0.00,251.73 +0.00,0.00,0.00,0.00,0.00,0.00,251.85 +0.00,0.00,0.00,0.00,0.00,0.00,251.88 +0.00,0.00,0.00,0.00,0.00,0.00,251.91 +0.00,0.00,0.00,0.00,0.00,0.00,251.93 +0.00,0.00,0.00,0.00,0.00,0.00,251.94 +0.00,0.00,0.00,0.00,0.00,0.00,251.96 +0.00,0.00,0.00,0.00,0.00,0.00,252.00 +0.00,0.00,0.00,0.00,0.00,0.00,252.03 +0.00,0.00,0.00,0.00,0.00,0.00,252.05 +0.00,0.00,0.00,0.00,0.00,0.00,252.06 +0.00,0.00,0.00,0.00,0.00,0.00,252.07 +0.00,0.00,0.00,0.00,0.00,0.00,252.07 +0.00,0.00,0.00,0.00,0.00,0.00,252.08 +0.00,0.00,0.00,0.00,0.00,0.00,252.08 +0.00,0.00,0.00,0.00,0.00,0.00,252.08 +0.00,0.00,0.00,0.00,0.00,0.00,252.07 +0.00,0.00,0.00,0.00,0.00,0.00,252.06 +0.00,0.00,0.00,0.00,0.00,0.00,252.05 +0.00,0.00,0.00,0.00,0.00,0.00,252.06 +0.00,0.00,0.00,0.00,0.00,0.00,252.07 +0.00,0.00,0.00,0.00,0.00,0.00,252.07 +0.00,0.00,0.00,0.00,0.00,0.00,252.09 +0.00,0.00,0.00,0.00,0.00,0.00,252.11 +0.00,0.00,0.00,0.00,0.00,0.00,252.12 +0.00,0.00,0.00,0.00,0.00,0.00,252.12 +0.00,0.00,0.00,0.00,0.00,0.00,252.12 +0.00,0.00,0.00,0.00,0.00,0.00,252.10 +0.00,0.00,0.00,0.00,0.00,0.00,252.09 +0.00,0.00,0.00,0.00,0.00,0.00,252.08 +0.00,0.00,0.00,0.00,0.00,0.00,252.08 +0.00,0.00,0.00,0.00,0.00,0.00,252.07 +0.00,0.00,0.00,0.00,0.00,0.00,252.07 +0.00,0.00,0.00,0.00,0.00,0.00,252.07 +0.00,0.00,0.00,0.00,0.00,0.00,252.07 +0.00,0.00,0.00,0.00,0.00,0.00,252.07 +0.00,0.00,0.00,0.00,0.00,0.00,252.07 +0.00,0.00,0.00,0.00,0.00,0.00,251.82 +0.00,0.00,0.00,0.00,0.00,0.00,251.82 +0.00,0.00,0.00,0.00,0.00,0.00,251.82 +0.00,0.00,0.00,0.00,0.00,0.00,251.82 +0.00,0.00,0.00,0.00,0.00,0.00,251.82 +0.00,0.00,0.00,0.00,0.00,0.00,251.86 +0.00,0.00,0.00,0.00,0.00,0.00,251.90 +0.00,0.00,0.00,0.00,0.00,0.00,251.92 +0.00,0.00,0.00,0.00,0.00,0.00,251.94 +0.00,0.00,0.00,0.00,0.00,0.00,251.96 +0.00,0.00,0.00,0.00,0.00,0.00,251.96 +0.00,0.00,0.00,0.00,0.00,0.00,251.96 +0.00,0.00,0.00,0.00,0.00,0.00,251.96 +0.00,0.00,0.00,0.00,0.00,0.00,251.96 +0.00,0.00,0.00,0.00,0.00,0.00,251.96 +0.00,0.00,0.00,0.00,0.00,0.00,251.96 +0.00,0.00,0.00,0.00,0.00,0.00,251.96 +0.00,0.00,0.00,0.00,0.00,0.00,251.96 +0.00,0.00,0.00,0.00,0.00,0.00,251.96 +0.00,0.00,0.00,0.00,0.00,0.00,251.95 +0.00,0.00,0.00,0.00,0.00,0.00,251.95 +0.00,0.00,0.00,0.00,0.00,0.00,251.94 +-280.00,0.00,-280.00,-280.00,0.00,-280.00,251.96 +-610.00,0.00,-610.00,-610.00,0.00,-610.00,251.97 +-890.00,0.00,-890.00,-890.00,0.00,-890.00,251.98 +-1160.00,0.00,-1160.00,-1160.00,0.00,-1160.00,251.92 +-1440.00,0.00,-1440.00,-1440.00,0.00,-1440.00,251.88 +-1720.00,0.00,-1720.00,-1720.00,0.00,-1720.00,251.84 +-2000.00,-178.57,-1821.43,-2000.00,-178.57,-1821.43,251.80 +-2290.00,-310.34,-1979.66,-2290.00,-344.83,-1945.17,251.76 +-2570.00,-321.43,-2248.57,-2570.00,-214.29,-2355.71,251.78 +-2850.00,-1214.29,-1635.71,-2850.00,-607.14,-2242.86,251.80 +-3130.00,-2500.00,-630.00,-3130.00,-1928.57,-1201.43,251.81 +-3420.00,-2586.21,-833.79,-3420.00,-2241.38,-1178.62,251.71 +-3710.00,-1482.76,-2227.24,-3710.00,-2137.93,-1572.07,251.64 +-3990.00,-1571.43,-2418.57,-3990.00,-2107.14,-1882.86,251.57 +-4280.00,-3103.45,-1176.55,-4280.00,-2241.38,-2038.62,251.36 +-4560.00,-4357.14,-202.86,-4560.00,-2821.43,-1738.57,251.20 +-4850.00,-4206.90,-643.10,-4850.00,-3310.34,-1539.66,251.06 +-5130.00,-3178.57,-1951.43,-5130.00,-3607.14,-1522.86,251.13 +-5410.00,-2857.14,-2552.86,-5410.00,-3678.57,-1731.43,251.18 +-5700.00,-4379.31,-1320.69,-5700.00,-3827.59,-1872.41,251.23 +-5990.00,-5793.10,-196.90,-5990.00,-4241.38,-1748.62,251.16 +-6280.00,-5551.72,-728.28,-6280.00,-4517.24,-1762.76,251.11 +-6570.00,-4655.17,-1914.83,-6570.00,-4931.03,-1638.97,251.06 +-6860.00,-4931.03,-1928.97,-6860.00,-5344.83,-1515.17,251.01 +-7150.00,-5862.07,-1287.93,-7150.00,-5655.17,-1494.83,250.98 +-7440.00,-6655.17,-784.83,-7440.00,-5827.59,-1612.41,251.01 +-7710.00,-6777.78,-932.22,-7710.00,-6074.07,-1635.93,251.04 +-7990.00,-6714.29,-1275.71,-7990.00,-6428.57,-1561.43,251.06 +-8270.00,-6964.29,-1305.71,-8270.00,-6821.43,-1448.57,251.02 +-8560.00,-7379.31,-1180.69,-8560.00,-7034.48,-1525.52,250.99 +-8840.00,-7821.43,-1018.57,-8840.00,-7357.14,-1482.86,250.97 +-9130.00,-8137.93,-992.07,-9130.00,-7689.66,-1440.34,250.95 +-9400.00,-8407.41,-992.59,-9400.00,-8000.00,-1400.00,250.93 +-9690.00,-8655.17,-1034.83,-9690.00,-8275.86,-1414.14,250.91 +-9980.00,-8827.59,-1152.41,-9980.00,-8551.72,-1428.28,250.94 +-10270.00,-8965.52,-1304.48,-10270.00,-8931.03,-1338.97,250.97 +-10560.00,-9172.41,-1387.59,-10560.00,-9206.90,-1353.10,250.95 +-10850.00,-9655.17,-1194.83,-10850.00,-9379.31,-1470.69,250.94 +-11130.00,-10107.14,-1022.86,-11130.00,-9642.86,-1487.14,250.93 +-11420.00,-10275.86,-1144.14,-11420.00,-9931.03,-1488.97,250.93 +-11710.00,-10517.24,-1192.76,-11710.00,-10275.86,-1434.14,250.94 +-12010.00,-10800.00,-1210.00,-12010.00,-10600.00,-1410.00,250.94 +-12300.00,-11103.45,-1196.55,-12300.00,-10827.59,-1472.41,250.96 +-12600.00,-11366.67,-1233.33,-12600.00,-11133.33,-1466.67,250.98 +-12890.00,-11655.17,-1234.83,-12890.00,-11241.38,-1648.62,251.00 +-13180.00,-12000.00,-1180.00,-13180.00,-11517.24,-1662.76,251.06 +-13470.00,-12241.38,-1228.62,-13470.00,-11862.07,-1607.93,251.10 +-13760.00,-12517.24,-1242.76,-13760.00,-12206.90,-1553.10,251.14 +-14050.00,-12827.59,-1222.41,-14050.00,-12551.72,-1498.28,251.18 +-14340.00,-13068.97,-1271.03,-14340.00,-12793.10,-1546.90,251.20 +-14630.00,-13275.86,-1354.14,-14630.00,-12931.03,-1698.97,251.23 +-14930.00,-13600.00,-1330.00,-14930.00,-13266.67,-1663.33,251.24 +-15220.00,-14000.00,-1220.00,-15220.00,-13586.21,-1633.79,251.26 +-15520.00,-14166.67,-1353.33,-15520.00,-13866.67,-1653.33,251.26 +-15810.00,-14482.76,-1327.24,-15810.00,-14103.45,-1706.55,251.27 +-16100.00,-14724.14,-1375.86,-16100.00,-14344.83,-1755.17,251.27 +-16390.00,-14931.03,-1458.97,-16390.00,-14517.24,-1872.76,251.21 +-16680.00,-15172.41,-1507.59,-16680.00,-14758.62,-1921.38,251.16 +-16970.00,-15689.66,-1280.34,-16970.00,-15103.45,-1866.55,251.08 +-17260.00,-16172.41,-1087.59,-17260.00,-15517.24,-1742.76,251.01 +-17550.00,-16344.83,-1205.17,-17550.00,-15931.03,-1618.97,250.96 +-17840.00,-16413.79,-1426.21,-17840.00,-16206.90,-1633.10,250.93 +-18140.00,-16600.00,-1540.00,-18140.00,-16400.00,-1740.00,250.91 +-18440.00,-17000.00,-1440.00,-18440.00,-16666.67,-1773.33,250.89 +-18740.00,-17400.00,-1340.00,-18740.00,-16866.67,-1873.33,250.82 +-19040.00,-17766.67,-1273.33,-19040.00,-17300.00,-1740.00,250.77 +-19340.00,-17900.00,-1440.00,-19340.00,-17766.67,-1573.33,250.78 +-19630.00,-18310.34,-1319.66,-19630.00,-18137.93,-1492.07,250.79 +-19930.00,-18600.00,-1330.00,-19930.00,-18300.00,-1630.00,250.80 +-20230.00,-18666.67,-1563.33,-20230.00,-18433.33,-1796.67,250.82 +-20530.00,-18933.33,-1596.67,-20530.00,-18833.33,-1696.67,250.85 +-20880.00,-19600.00,-1280.00,-20880.00,-19142.86,-1737.14,250.86 +-21170.00,-20034.48,-1135.52,-21170.00,-19310.34,-1859.66,250.86 +-21470.00,-20033.33,-1436.67,-21470.00,-19700.00,-1770.00,250.85 +-21760.00,-20241.38,-1518.62,-21760.00,-20068.97,-1691.03,250.89 +-22050.00,-20413.79,-1636.21,-22050.00,-20068.97,-1981.03,250.93 +-22350.00,-20766.67,-1583.33,-22350.00,-20300.00,-2050.00,250.95 +-22650.00,-21300.00,-1350.00,-22650.00,-20800.00,-1850.00,250.90 +-22950.00,-21466.67,-1483.33,-22950.00,-21166.67,-1783.33,250.86 +-23250.00,-21700.00,-1550.00,-23225.80,-21400.00,-1825.80,250.83 +-23496.36,-21833.33,-1663.03,-22925.80,-21400.00,-1525.80,250.85 +-23196.36,-22433.33,-763.03,-22625.80,-21700.00,-925.80,250.87 +-22896.36,-22433.33,-463.03,-22325.80,-21566.67,-759.13,250.87 +-22596.36,-21933.33,-663.03,-22025.80,-21233.33,-792.47,250.87 +-22296.36,-21733.33,-563.03,-21725.80,-20766.67,-959.13,250.87 +-21996.36,-21566.67,-429.69,-21425.80,-20433.33,-992.47,250.89 +-21696.36,-21000.00,-696.36,-21125.80,-20233.33,-892.47,250.91 +-21396.36,-20700.00,-696.36,-20825.80,-19966.67,-859.13,250.92 +-21106.36,-20620.69,-485.67,-20535.80,-19758.62,-777.18,250.96 +-20806.36,-20433.33,-373.03,-20235.80,-19466.67,-769.13,250.99 +-20506.36,-20033.33,-473.03,-19935.80,-19133.33,-802.47,251.03 +-20216.36,-19586.21,-630.15,-19645.80,-18689.66,-956.14,251.06 +-19916.36,-19266.67,-649.69,-19345.80,-18600.00,-745.80,251.09 +-19626.36,-19103.45,-522.91,-19055.80,-18310.34,-745.46,251.14 +-19326.36,-18700.00,-626.36,-18755.80,-17900.00,-855.80,251.19 +-19026.36,-18200.00,-826.36,-18455.80,-17300.00,-1155.80,251.22 +-18726.36,-17966.67,-759.69,-18155.80,-17100.00,-1055.80,251.19 +-18426.36,-17933.33,-493.03,-17855.80,-16933.33,-922.47,251.17 +-18126.36,-17533.33,-593.03,-17555.80,-16666.67,-889.13,251.17 +-17826.36,-17333.33,-493.03,-17255.80,-16366.67,-889.13,251.17 +-17536.36,-17172.41,-363.95,-16965.80,-16034.48,-931.32,251.17 +-17236.36,-16866.67,-369.69,-16665.80,-15666.67,-999.13,251.16 +-16946.36,-16448.28,-498.08,-16375.80,-15586.21,-789.59,251.15 +-16656.36,-16103.45,-552.91,-16085.80,-15310.34,-775.46,251.14 +-16356.36,-15866.67,-489.69,-15785.80,-15000.00,-785.80,251.06 +-16066.36,-15655.17,-411.19,-15495.80,-14689.66,-806.14,251.00 +-15766.36,-15266.67,-499.69,-15195.80,-14133.33,-1062.47,250.95 +-15476.36,-15000.00,-476.36,-14905.80,-12965.52,-1940.28,250.93 +-15176.36,-14566.67,-609.69,-14605.80,-12866.67,-1739.13,250.91 +-14886.36,-14206.90,-679.46,-14315.80,-12517.24,-1798.56,251.00 +-14596.36,-13931.03,-665.33,-14025.80,-12034.48,-1991.32,251.07 +-14296.36,-13733.33,-563.03,-13725.80,-11600.00,-2125.80,251.13 +-14006.36,-13517.24,-489.12,-13435.80,-11137.93,-2297.87,251.08 +-13716.36,-13137.93,-578.43,-13145.80,-11068.97,-2076.83,251.04 +-13426.36,-12482.76,-943.60,-12855.80,-10344.83,-2510.97,251.00 +-13136.36,-11793.10,-1343.26,-12565.80,-10137.93,-2427.87,250.97 +-12856.36,-10892.86,-1963.50,-12285.80,-8928.57,-3357.23,250.94 +-12566.36,-10275.86,-2290.50,-11995.80,-9034.48,-2961.32,250.92 +-12276.36,-10172.41,-2103.95,-11705.80,-8310.34,-3395.46,250.83 +-11986.36,-10000.00,-1986.36,-11415.80,-7275.86,-4139.94,250.75 +-11696.36,-9827.59,-1868.77,-11125.80,-7724.14,-3401.66,250.80 +-11406.36,-9241.38,-2164.98,-10835.80,-7344.83,-3490.97,250.83 +-11116.36,-9344.83,-1771.53,-10545.80,-5896.55,-4649.25,250.85 +-10826.36,-9344.83,-1481.53,-10255.80,-7172.41,-3083.39,250.80 +-10536.36,-9379.31,-1157.05,-9965.80,-8275.86,-1689.94,250.76 +-10246.36,-8793.10,-1453.26,-9675.80,-7034.48,-2641.32,250.73 +-9956.36,-8448.28,-1508.08,-9385.80,-5310.34,-4075.46,250.54 +-9676.36,-8071.43,-1604.93,-9105.80,-4714.29,-4391.51,250.39 +-9386.36,-7965.52,-1420.84,-8815.80,-4793.10,-4022.70,250.26 +-9096.36,-7586.21,-1510.15,-8525.80,-5482.76,-3043.04,250.23 +-8806.36,-7241.38,-1564.98,-8235.80,-5482.76,-2753.04,250.21 +-8516.36,-7448.28,-1068.08,-7945.80,-4172.41,-3773.39,250.04 +-8226.36,-7310.34,-916.02,-7655.80,-2896.55,-4759.25,249.90 +-7936.36,-6482.76,-1453.60,-7365.80,-3172.41,-4193.39,249.79 +-7646.36,-5931.03,-1715.33,-7075.80,-5413.79,-1662.01,249.92 +-7356.36,-5827.59,-1528.77,-6785.80,-4965.52,-1820.28,250.01 +-7066.36,-5758.62,-1307.74,-6495.80,-1965.52,-4530.28,250.09 +-6776.36,-5724.14,-1052.22,-6205.80,-965.52,-5240.28,250.12 +-6486.36,-5275.86,-1210.50,-5915.80,-2551.72,-3364.08,250.14 +-6146.36,-4823.53,-1322.83,-5575.80,-5147.06,-428.74,250.16 +-5856.36,-4965.52,-890.84,-5285.80,-4310.34,-975.46,250.07 +-5566.36,-5000.00,-566.36,-4995.80,-758.62,-4237.18,249.99 +-5276.36,-4448.28,-828.08,-4705.80,-344.83,-4360.97,250.31 +-4996.36,-4071.43,-924.93,-4425.80,-2071.43,-2354.37,250.56 +-4706.36,-3862.07,-844.29,-4135.80,-3724.14,-411.66,250.76 +-4416.36,-3793.10,-623.26,-3845.80,-3172.41,-673.39,250.57 +-4126.36,-3241.38,-884.98,-3555.80,-1517.24,-2038.56,250.41 +-3836.36,-2241.38,-1594.98,-3265.80,-758.62,-2507.18,250.29 +-3556.36,-1678.57,-1877.79,-2985.80,-535.71,-2450.09,250.28 +-3266.36,-2137.93,-1128.43,-2695.80,-827.59,-1868.21,250.27 +-2986.36,-2428.57,-557.79,-2415.80,-1464.29,-951.51,250.26 +-2696.36,-1862.07,-834.29,-2125.80,-517.24,-1608.56,250.24 +-2416.36,-714.29,-1702.07,-1845.80,-35.71,-1810.09,250.23 +-2136.36,-892.86,-1243.50,-1565.80,-214.29,-1351.51,250.08 +-1846.36,-1034.48,-811.88,-1275.80,-758.62,-517.18,249.95 +-1566.36,35.71,-1602.07,-995.80,-142.86,-852.94,249.86 +-1286.36,0.00,-1286.36,-715.80,71.43,-787.23,249.90 +-1006.36,-214.29,-792.07,-435.80,0.00,-435.80,249.93 +-726.36,35.71,-762.07,-155.80,0.00,-155.80,249.96 +-446.36,0.00,-446.36,0.00,0.00,0.00,249.96 +-176.36,0.00,-176.36,0.00,0.00,0.00,249.96 +0.00,0.00,0.00,0.00,0.00,0.00,249.96 +0.00,0.00,0.00,0.00,0.00,0.00,250.02 +0.00,0.00,0.00,0.00,0.00,0.00,250.07 +0.00,0.00,0.00,0.00,0.00,0.00,250.11 +0.00,0.00,0.00,0.00,0.00,0.00,250.10 +0.00,0.00,0.00,0.00,0.00,0.00,250.10 +0.00,0.00,0.00,0.00,0.00,0.00,250.09 +0.00,0.00,0.00,0.00,0.00,0.00,250.08 +0.00,0.00,0.00,0.00,0.00,0.00,250.07 +0.00,0.00,0.00,0.00,0.00,0.00,250.07 +0.00,0.00,0.00,0.00,0.00,0.00,250.04 +0.00,0.00,0.00,0.00,0.00,0.00,250.02 +0.00,0.00,0.00,0.00,0.00,0.00,250.00 +0.00,0.00,0.00,0.00,0.00,0.00,250.01 +0.00,0.00,0.00,0.00,0.00,0.00,250.01 +0.00,0.00,0.00,0.00,0.00,0.00,250.01 +0.00,0.00,0.00,0.00,0.00,0.00,249.98 +0.00,0.00,0.00,0.00,0.00,0.00,249.96 +0.00,0.00,0.00,0.00,0.00,0.00,249.94 +0.00,0.00,0.00,0.00,0.00,0.00,249.93 +0.00,0.00,0.00,0.00,0.00,0.00,249.92 +0.00,0.00,0.00,0.00,0.00,0.00,249.95 +0.00,0.00,0.00,0.00,0.00,0.00,249.97 +0.00,0.00,0.00,0.00,0.00,0.00,249.98 +0.00,0.00,0.00,0.00,0.00,0.00,249.95 +0.00,0.00,0.00,0.00,0.00,0.00,249.92 +0.00,0.00,0.00,0.00,0.00,0.00,249.90 +0.00,0.00,0.00,0.00,0.00,0.00,249.91 +0.00,0.00,0.00,0.00,0.00,0.00,249.91 +0.00,0.00,0.00,0.00,0.00,0.00,249.92 +0.00,0.00,0.00,0.00,0.00,0.00,249.95 +0.00,0.00,0.00,0.00,0.00,0.00,249.97 +0.00,0.00,0.00,0.00,0.00,0.00,249.99 +0.00,0.00,0.00,0.00,0.00,0.00,249.98 +0.00,0.00,0.00,0.00,0.00,0.00,249.98 +0.00,0.00,0.00,0.00,0.00,0.00,249.97 +0.00,0.00,0.00,0.00,0.00,0.00,249.92 +0.00,0.00,0.00,0.00,0.00,0.00,249.87 +0.00,0.00,0.00,0.00,0.00,0.00,249.84 +0.00,0.00,0.00,0.00,0.00,0.00,249.85 +0.00,0.00,0.00,0.00,0.00,0.00,249.87 +0.00,0.00,0.00,0.00,0.00,0.00,249.88 +0.00,0.00,0.00,0.00,0.00,0.00,249.85 +0.00,0.00,0.00,0.00,0.00,0.00,249.83 +0.00,0.00,0.00,0.00,0.00,0.00,249.88 +0.00,0.00,0.00,0.00,0.00,0.00,249.92 +0.00,0.00,0.00,0.00,0.00,0.00,249.95 +0.00,0.00,0.00,0.00,0.00,0.00,249.94 +0.00,0.00,0.00,0.00,0.00,0.00,249.94 +0.00,0.00,0.00,0.00,0.00,0.00,249.93 +0.00,0.00,0.00,0.00,0.00,0.00,249.94 +0.00,0.00,0.00,0.00,0.00,0.00,249.94 +0.00,0.00,0.00,0.00,0.00,0.00,249.94 +0.00,0.00,0.00,0.00,0.00,0.00,249.97 +0.00,0.00,0.00,0.00,0.00,0.00,249.99 +0.00,0.00,0.00,0.00,0.00,0.00,250.00 +0.00,0.00,0.00,0.00,0.00,0.00,250.00 +0.00,0.00,0.00,0.00,0.00,0.00,250.00 +0.00,0.00,0.00,0.00,0.00,0.00,250.00 +0.00,0.00,0.00,0.00,0.00,0.00,249.95 +0.00,0.00,0.00,0.00,0.00,0.00,249.91 +0.00,0.00,0.00,0.00,0.00,0.00,249.88 +0.00,0.00,0.00,0.00,0.00,0.00,249.83 +0.00,0.00,0.00,0.00,0.00,0.00,249.79 +0.00,0.00,0.00,0.00,0.00,0.00,249.75 +0.00,0.00,0.00,0.00,0.00,0.00,249.78 +0.00,0.00,0.00,0.00,0.00,0.00,249.80 +0.00,0.00,0.00,0.00,0.00,0.00,249.83 +0.00,0.00,0.00,0.00,0.00,0.00,249.86 +0.00,0.00,0.00,0.00,0.00,0.00,249.87 +0.00,0.00,0.00,0.00,0.00,0.00,249.86 +0.00,0.00,0.00,0.00,0.00,0.00,249.85 +0.00,0.00,0.00,0.00,0.00,0.00,249.84 +0.00,0.00,0.00,0.00,0.00,0.00,249.91 +0.00,0.00,0.00,0.00,0.00,0.00,249.96 +0.00,0.00,0.00,0.00,0.00,0.00,250.00 +0.00,0.00,0.00,0.00,0.00,0.00,249.98 +0.00,0.00,0.00,0.00,0.00,0.00,249.97 +0.00,0.00,0.00,0.00,0.00,0.00,249.95 +0.00,0.00,0.00,0.00,0.00,0.00,249.95 +0.00,0.00,0.00,0.00,0.00,0.00,249.95 +0.00,0.00,0.00,0.00,0.00,0.00,249.94 +0.00,0.00,0.00,0.00,0.00,0.00,249.97 +0.00,0.00,0.00,0.00,0.00,0.00,249.99 +0.00,0.00,0.00,0.00,0.00,0.00,250.01 +0.00,0.00,0.00,0.00,0.00,0.00,249.97 +0.00,0.00,0.00,0.00,0.00,0.00,249.94 +0.00,0.00,0.00,0.00,0.00,0.00,249.91 +0.00,0.00,0.00,0.00,0.00,0.00,249.96 +0.00,0.00,0.00,0.00,0.00,0.00,250.00 +0.00,0.00,0.00,0.00,0.00,0.00,250.03 +0.00,0.00,0.00,0.00,0.00,0.00,250.07 +0.00,0.00,0.00,0.00,0.00,0.00,250.10 +0.00,0.00,0.00,0.00,0.00,0.00,250.10 +0.00,0.00,0.00,0.00,0.00,0.00,250.10 +0.00,0.00,0.00,0.00,0.00,0.00,250.10 +0.00,0.00,0.00,0.00,0.00,0.00,250.13 +0.00,0.00,0.00,0.00,0.00,0.00,250.16 +0.00,0.00,0.00,0.00,0.00,0.00,250.18 +0.00,0.00,0.00,0.00,0.00,0.00,250.15 +0.00,0.00,0.00,0.00,0.00,0.00,250.12 +0.00,0.00,0.00,0.00,0.00,0.00,250.10 +0.00,0.00,0.00,0.00,0.00,0.00,250.08 +0.00,0.00,0.00,0.00,0.00,0.00,250.07 +0.00,0.00,0.00,0.00,0.00,0.00,250.05 +0.00,0.00,0.00,0.00,0.00,0.00,250.01 +0.00,0.00,0.00,0.00,0.00,0.00,249.98 +0.00,0.00,0.00,0.00,0.00,0.00,249.95 +0.00,0.00,0.00,0.00,0.00,0.00,249.99 +0.00,0.00,0.00,0.00,0.00,0.00,250.01 +0.00,0.00,0.00,0.00,0.00,0.00,250.03 +0.00,0.00,0.00,0.00,0.00,0.00,250.07 +0.00,0.00,0.00,0.00,0.00,0.00,250.10 +0.00,0.00,0.00,0.00,0.00,0.00,250.12 +0.00,0.00,0.00,0.00,0.00,0.00,250.12 +0.00,0.00,0.00,0.00,0.00,0.00,250.11 +0.00,0.00,0.00,0.00,0.00,0.00,250.10 +0.00,0.00,0.00,0.00,0.00,0.00,250.08 +0.00,0.00,0.00,0.00,0.00,0.00,250.07 +0.00,0.00,0.00,0.00,0.00,0.00,250.05 +0.00,0.00,0.00,0.00,0.00,0.00,250.03 +0.00,0.00,0.00,0.00,0.00,0.00,250.02 +0.00,0.00,0.00,0.00,0.00,0.00,249.97 +0.00,0.00,0.00,0.00,0.00,0.00,249.94 +0.00,0.00,0.00,0.00,0.00,0.00,249.91 +0.00,0.00,0.00,0.00,0.00,0.00,249.93 +0.00,0.00,0.00,0.00,0.00,0.00,249.95 +0.00,0.00,0.00,0.00,0.00,0.00,249.96 +0.00,0.00,0.00,0.00,0.00,0.00,249.99 +0.00,0.00,0.00,0.00,0.00,0.00,250.02 +0.00,0.00,0.00,0.00,0.00,0.00,250.04 +0.00,0.00,0.00,0.00,0.00,0.00,250.03 +0.00,0.00,0.00,0.00,0.00,0.00,250.03 +0.00,0.00,0.00,0.00,0.00,0.00,250.03 +0.00,0.00,0.00,0.00,0.00,0.00,249.97 +0.00,0.00,0.00,0.00,0.00,0.00,249.92 +0.00,0.00,0.00,0.00,0.00,0.00,249.88 +0.00,0.00,0.00,0.00,0.00,0.00,249.86 +0.00,0.00,0.00,0.00,0.00,0.00,249.85 +0.00,0.00,0.00,0.00,0.00,0.00,249.84 +0.00,0.00,0.00,0.00,0.00,0.00,249.84 +0.00,0.00,0.00,0.00,0.00,0.00,249.85 +0.00,0.00,0.00,0.00,0.00,0.00,249.86 +0.00,0.00,0.00,0.00,0.00,0.00,249.89 +0.00,0.00,0.00,0.00,0.00,0.00,249.92 +0.00,0.00,0.00,0.00,0.00,0.00,249.92 +0.00,0.00,0.00,0.00,0.00,0.00,249.93 +0.00,0.00,0.00,0.00,0.00,0.00,249.93 +0.00,0.00,0.00,0.00,0.00,0.00,249.93 +0.00,0.00,0.00,0.00,0.00,0.00,249.93 +0.00,0.00,0.00,0.00,0.00,0.00,249.93 +0.00,0.00,0.00,0.00,0.00,0.00,249.91 +0.00,0.00,0.00,0.00,0.00,0.00,249.90 +0.00,0.00,0.00,0.00,0.00,0.00,249.88 +0.00,0.00,0.00,0.00,0.00,0.00,249.92 +0.00,0.00,0.00,0.00,0.00,0.00,249.95 +0.00,0.00,0.00,0.00,0.00,0.00,249.98 +0.00,0.00,0.00,0.00,0.00,0.00,250.00 +0.00,0.00,0.00,0.00,0.00,0.00,250.01 +0.00,0.00,0.00,0.00,0.00,0.00,250.02 +0.00,0.00,0.00,0.00,0.00,0.00,250.01 +0.00,0.00,0.00,0.00,0.00,0.00,250.01 +0.00,0.00,0.00,0.00,0.00,0.00,250.00 +0.00,0.00,0.00,0.00,0.00,0.00,250.04 +0.00,0.00,0.00,0.00,0.00,0.00,250.06 +0.00,0.00,0.00,0.00,0.00,0.00,250.09 +0.00,0.00,0.00,0.00,0.00,0.00,250.10 +0.00,0.00,0.00,0.00,0.00,0.00,250.11 +0.00,0.00,0.00,0.00,0.00,0.00,250.11 +0.00,0.00,0.00,0.00,0.00,0.00,250.12 +0.00,0.00,0.00,0.00,0.00,0.00,250.12 +0.00,0.00,0.00,0.00,0.00,0.00,250.10 +0.00,0.00,0.00,0.00,0.00,0.00,250.08 +0.00,0.00,0.00,0.00,0.00,0.00,250.07 +0.00,0.00,0.00,0.00,0.00,0.00,250.08 +0.00,0.00,0.00,0.00,0.00,0.00,250.08 +0.00,0.00,0.00,0.00,0.00,0.00,250.08 +0.00,0.00,0.00,0.00,0.00,0.00,250.11 +0.00,0.00,0.00,0.00,0.00,0.00,250.14 +0.00,0.00,0.00,0.00,0.00,0.00,250.16 +0.00,0.00,0.00,0.00,0.00,0.00,250.10 +0.00,0.00,0.00,0.00,0.00,0.00,250.06 +0.00,0.00,0.00,0.00,0.00,0.00,250.02 +0.00,0.00,0.00,0.00,0.00,0.00,250.05 +0.00,0.00,0.00,0.00,0.00,0.00,250.07 +0.00,0.00,0.00,0.00,0.00,0.00,250.08 +0.00,0.00,0.00,0.00,0.00,0.00,250.10 +0.00,0.00,0.00,0.00,0.00,0.00,250.11 +0.00,0.00,0.00,0.00,0.00,0.00,250.12 +0.00,0.00,0.00,0.00,0.00,0.00,250.10 +0.00,0.00,0.00,0.00,0.00,0.00,250.09 +0.00,0.00,0.00,0.00,0.00,0.00,250.09 +0.00,0.00,0.00,0.00,0.00,0.00,250.04 +0.00,0.00,0.00,0.00,0.00,0.00,250.01 +0.00,0.00,0.00,0.00,0.00,0.00,249.98 +0.00,0.00,0.00,0.00,0.00,0.00,249.95 +0.00,0.00,0.00,0.00,0.00,0.00,249.94 +0.00,0.00,0.00,0.00,0.00,0.00,249.97 +0.00,0.00,0.00,0.00,0.00,0.00,250.00 +0.00,0.00,0.00,0.00,0.00,0.00,250.02 +0.00,0.00,0.00,0.00,0.00,0.00,250.02 +0.00,0.00,0.00,0.00,0.00,0.00,250.02 +0.00,0.00,0.00,0.00,0.00,0.00,250.01 +0.00,0.00,0.00,0.00,0.00,0.00,250.03 +0.00,0.00,0.00,0.00,0.00,0.00,250.05 +0.00,0.00,0.00,0.00,0.00,0.00,250.06 +0.00,0.00,0.00,0.00,0.00,0.00,250.08 +0.00,0.00,0.00,0.00,0.00,0.00,250.09 +0.00,0.00,0.00,0.00,0.00,0.00,250.10 +0.00,0.00,0.00,0.00,0.00,0.00,250.11 +0.00,0.00,0.00,0.00,0.00,0.00,250.12 +0.00,0.00,0.00,0.00,0.00,0.00,250.13 +0.00,0.00,0.00,0.00,0.00,0.00,250.15 +0.00,0.00,0.00,0.00,0.00,0.00,250.18 +0.00,0.00,0.00,0.00,0.00,0.00,250.20 +0.00,0.00,0.00,0.00,0.00,0.00,250.22 +0.00,0.00,0.00,0.00,0.00,0.00,250.23 +0.00,0.00,0.00,0.00,0.00,0.00,250.24 +0.00,0.00,0.00,0.00,0.00,0.00,250.23 +0.00,0.00,0.00,0.00,0.00,0.00,250.22 +0.00,0.00,0.00,0.00,0.00,0.00,250.20 +0.00,0.00,0.00,0.00,0.00,0.00,250.18 +0.00,0.00,0.00,0.00,0.00,0.00,250.16 +0.00,0.00,0.00,0.00,0.00,0.00,250.10 +0.00,0.00,0.00,0.00,0.00,0.00,250.04 +0.00,0.00,0.00,0.00,0.00,0.00,250.00 +0.00,0.00,0.00,0.00,0.00,0.00,249.97 +0.00,0.00,0.00,0.00,0.00,0.00,249.95 +0.00,0.00,0.00,0.00,0.00,0.00,249.93 +0.00,0.00,0.00,0.00,0.00,0.00,249.97 +0.00,0.00,0.00,0.00,0.00,0.00,250.00 +0.00,0.00,0.00,0.00,0.00,0.00,250.02 +0.00,0.00,0.00,0.00,0.00,0.00,250.00 +0.00,0.00,0.00,0.00,0.00,0.00,249.98 +0.00,0.00,0.00,0.00,0.00,0.00,249.97 +0.00,0.00,0.00,0.00,0.00,0.00,249.99 +0.00,0.00,0.00,0.00,0.00,0.00,250.01 +0.00,0.00,0.00,0.00,0.00,0.00,250.02 +0.00,0.00,0.00,0.00,0.00,0.00,250.04 +0.00,0.00,0.00,0.00,0.00,0.00,250.05 +0.00,0.00,0.00,0.00,0.00,0.00,250.06 +0.00,0.00,0.00,0.00,0.00,0.00,250.06 +0.00,0.00,0.00,0.00,0.00,0.00,250.06 +0.00,0.00,0.00,0.00,0.00,0.00,250.03 +0.00,0.00,0.00,0.00,0.00,0.00,250.01 +0.00,0.00,0.00,0.00,0.00,0.00,250.00 +0.00,0.00,0.00,0.00,0.00,0.00,249.98 +0.00,0.00,0.00,0.00,0.00,0.00,249.97 +0.00,0.00,0.00,0.00,0.00,0.00,249.97 +0.00,0.00,0.00,0.00,0.00,0.00,249.98 +0.00,0.00,0.00,0.00,0.00,0.00,249.99 +0.00,0.00,0.00,0.00,0.00,0.00,250.00 +0.00,0.00,0.00,0.00,0.00,0.00,250.00 +0.00,0.00,0.00,0.00,0.00,0.00,250.00 +0.00,0.00,0.00,0.00,0.00,0.00,250.00 +0.00,0.00,0.00,0.00,0.00,0.00,249.95 +0.00,0.00,0.00,0.00,0.00,0.00,249.91 +0.00,0.00,0.00,0.00,0.00,0.00,249.88 +0.00,0.00,0.00,0.00,0.00,0.00,249.90 +0.00,0.00,0.00,0.00,0.00,0.00,249.92 +0.00,0.00,0.00,0.00,0.00,0.00,249.93 +0.00,0.00,0.00,0.00,0.00,0.00,249.93 +0.00,0.00,0.00,0.00,0.00,0.00,249.94 +0.00,0.00,0.00,0.00,0.00,0.00,249.94 +280.00,0.00,280.00,280.00,0.00,280.00,249.97 +560.00,0.00,560.00,560.00,0.00,560.00,249.98 +840.00,0.00,840.00,840.00,0.00,840.00,250.00 +1110.00,0.00,1110.00,1110.00,0.00,1110.00,250.01 +1440.00,0.00,1440.00,1440.00,0.00,1440.00,250.02 +1720.00,0.00,1720.00,1720.00,0.00,1720.00,250.01 +2000.00,250.00,1750.00,2000.00,142.86,1857.14,249.99 +2270.00,1370.37,899.63,2270.00,370.37,1899.63,249.98 +2550.00,1071.43,1478.57,2550.00,357.14,2192.86,249.94 +2830.00,1178.57,1651.43,2830.00,857.14,1972.86,249.91 +3110.00,1035.71,2074.29,3110.00,1357.14,1752.86,249.89 +3390.00,1964.29,1425.71,3390.00,892.86,2497.14,249.81 +3670.00,2642.86,1027.14,3670.00,1250.00,2420.00,249.75 +3950.00,2607.14,1342.86,3950.00,1035.71,2914.29,249.71 +4220.00,1777.78,2442.22,4220.00,1555.56,2664.44,249.62 +4500.00,1607.14,2892.86,4500.00,1571.43,2928.57,249.54 +4780.00,2607.14,2172.86,4780.00,1607.14,3172.86,249.49 +5060.00,3535.71,1524.29,5060.00,1857.14,3202.86,249.51 +5340.00,3678.57,1661.43,5340.00,2142.86,3197.14,249.52 +5620.00,3642.86,1977.14,5620.00,2714.29,2905.71,249.61 +5900.00,4071.43,1828.57,5900.00,3428.57,2471.43,249.68 +6180.00,4607.14,1572.86,6180.00,3821.43,2358.57,249.74 +6460.00,4821.43,1638.57,6460.00,3892.86,2567.14,249.97 +6740.00,4500.00,2240.00,6740.00,3785.71,2954.29,250.15 +7020.00,4714.29,2305.71,7020.00,3500.00,3520.00,250.29 +7300.00,5535.71,1764.29,7300.00,4178.57,3121.43,250.27 +7590.00,6172.41,1417.59,7590.00,5379.31,2210.69,250.26 +7870.00,5750.00,2120.00,7870.00,5821.43,2048.57,250.25 +8160.00,5862.07,2297.93,8160.00,4413.79,3746.21,250.36 +8440.00,6571.43,1868.57,8440.00,3714.29,4725.71,250.44 +8720.00,7035.71,1684.29,8720.00,5928.57,2791.43,250.50 +9010.00,6862.07,2147.93,9010.00,8310.34,699.66,250.41 +9290.00,7357.14,1932.86,9290.00,7428.57,1861.43,250.33 +9570.00,7607.14,1962.86,9570.00,5428.57,4141.43,250.27 +9850.00,7464.29,2385.71,9850.00,5607.14,4242.86,250.53 +10130.00,7964.29,2165.71,10130.00,7714.29,2415.71,250.73 +10410.00,8142.86,2267.14,10410.00,8285.71,2124.29,250.97 +10700.00,8206.90,2493.10,10700.00,7689.66,3010.34,251.16 +10980.00,9035.71,1944.29,10980.00,7035.71,3944.29,251.32 +11260.00,9178.57,2081.43,11260.00,7285.71,3974.29,251.31 +11550.00,9413.79,2136.21,11550.00,9034.48,2515.52,251.30 +11830.00,9607.14,2222.86,11830.00,9821.43,2008.57,251.29 +12110.00,10071.43,2038.57,12110.00,9107.14,3002.86,251.43 +12390.00,10571.43,1818.57,12390.00,8428.57,3961.43,251.54 +12680.00,10758.62,1921.38,12680.00,9000.00,3680.00,251.63 +12960.00,10785.71,2174.29,12960.00,10928.57,2031.43,251.46 +13250.00,11068.97,2181.03,13250.00,11103.45,2146.55,251.32 +13530.00,11142.86,2387.14,13530.00,10107.14,3422.86,251.21 +13820.00,11448.28,2371.72,13820.00,8931.03,4888.97,251.24 +14100.00,11500.00,2600.00,14100.00,10535.71,3564.29,251.27 +14390.00,11758.62,2631.38,14390.00,12517.24,1872.76,251.30 +14670.00,11892.86,2777.14,14670.00,12392.86,2277.14,251.33 +14960.00,12275.86,2684.14,14960.00,10448.28,4511.72,251.35 +15250.00,12448.28,2801.72,15250.00,10965.52,4284.48,251.18 +15540.00,12793.10,2746.90,15540.00,12931.03,2608.97,251.04 +15830.00,13379.31,2450.69,15830.00,13379.31,2450.69,250.93 +16120.00,13655.17,2464.83,16120.00,12310.34,3809.66,251.03 +16410.00,13862.07,2547.93,16410.00,11827.59,4582.41,251.10 +16690.00,14000.00,2690.00,16690.00,13392.86,3297.14,251.16 +16970.00,14214.29,2755.71,16970.00,14964.29,2005.71,251.01 +17260.00,14724.14,2535.86,17260.00,14068.97,3191.03,250.89 +17540.00,15071.43,2468.57,17540.00,13250.00,4290.00,250.80 +17820.00,15250.00,2570.00,17820.00,13964.29,3855.71,250.83 +18100.00,15178.57,2921.43,18100.00,15321.43,2778.57,250.85 +18380.00,15571.43,2808.57,18380.00,15535.71,2844.29,250.87 +18660.00,15892.86,2767.14,18660.00,14964.29,3695.71,250.90 +18950.00,16000.00,2950.00,18950.00,14931.03,4018.97,250.93 +19240.00,16137.93,3102.07,19240.00,16000.00,3240.00,250.81 +19530.00,16413.79,3116.21,19530.00,16413.79,3116.21,250.71 +19820.00,16862.07,2957.93,19820.00,16000.00,3820.00,250.64 +20110.00,17172.41,2937.59,20110.00,15827.59,4282.41,250.65 +20400.00,17482.76,2917.24,20400.00,16586.21,3813.79,250.66 +20690.00,17965.52,2724.48,20690.00,17793.10,2896.90,250.67 +20970.00,18000.00,2970.00,20970.00,17607.14,3362.86,250.67 +21260.00,18379.31,2880.69,21260.00,17137.93,4122.07,250.66 +21600.00,18852.94,2747.06,21600.00,17352.94,4247.06,250.53 +21890.00,18965.52,2924.48,21890.00,18103.45,3786.55,250.43 +22170.00,18892.86,3277.14,22170.00,18642.86,3527.14,250.34 +22460.00,19000.00,3460.00,22460.00,18793.10,3666.90,250.26 +22750.00,19275.86,3474.14,22750.00,18689.66,4060.34,250.19 +23040.00,20034.48,3005.52,22463.41,18758.62,3704.79,250.14 +23330.00,20482.76,2847.24,22173.41,18827.59,3345.82,249.92 +23127.41,20517.24,2610.16,21883.41,18620.69,3262.72,249.75 +22837.41,20000.00,2837.41,21593.41,18310.34,3283.06,249.61 +22547.41,20137.93,2409.48,21303.41,18172.41,3130.99,249.59 +22257.41,20413.79,1843.61,21013.41,17551.72,3461.68,249.57 +21977.41,19964.29,2013.12,20733.41,17142.86,3590.55,249.56 +21687.41,19206.90,2480.51,20443.41,17068.97,3374.44,249.55 +21397.41,18655.17,2742.23,20153.41,17413.79,2739.61,249.54 +21117.41,18464.29,2653.12,19873.41,17178.57,2694.84,249.51 +20837.41,18607.14,2230.26,19593.41,16571.43,3021.98,249.50 +20547.41,18413.79,2133.61,19303.41,15586.21,3717.20,249.48 +20257.41,18103.45,2153.96,19013.41,15000.00,4013.41,249.39 +19977.41,17642.86,2334.55,18733.41,15464.29,3269.12,249.31 +19697.41,17357.14,2340.26,18453.41,15964.29,2489.12,249.25 +19407.41,16965.52,2441.89,18163.41,15068.97,3094.44,249.27 +19127.41,16964.29,2163.12,17883.41,14107.14,3776.26,249.29 +18837.41,16827.59,2009.82,17593.41,14241.38,3352.03,249.31 +18547.41,16689.66,1857.75,17303.41,14896.55,2406.85,249.11 +18267.41,16500.00,1767.41,17023.41,14535.71,2487.69,248.95 +17977.41,16137.93,1839.48,16733.41,13482.76,3250.65,248.83 +17687.41,15724.14,1963.27,16443.41,13034.48,3408.92,248.83 +17407.41,15285.71,2121.69,16163.41,13571.43,2591.98,248.83 +17117.41,15241.38,1876.03,15873.41,13931.03,1942.37,248.78 +16837.41,14964.29,1873.12,15593.41,13000.00,2593.41,248.74 +16547.41,14827.59,1719.82,15303.41,12103.45,3199.96,248.70 +16257.41,14482.76,1774.65,15013.41,11896.55,3116.85,248.74 +15977.41,14142.86,1834.55,14733.41,12678.57,2054.84,248.76 +15687.41,14034.48,1652.92,14443.41,12517.24,1926.17,248.78 +15397.41,13862.07,1535.34,14153.41,11655.17,2498.23,248.78 +15117.41,13571.43,1545.98,13873.41,10714.29,3159.12,248.79 +14837.41,13178.57,1658.83,13593.41,10750.00,2843.41,248.79 +14557.41,12785.71,1771.69,13313.41,11500.00,1813.41,248.77 +14277.41,12714.29,1563.12,13033.41,11535.71,1497.69,248.75 +13997.41,12642.86,1354.55,12753.41,10785.71,1967.69,248.73 +13717.41,12678.57,1038.83,12473.41,9964.29,2509.12,248.81 +13437.41,12571.43,865.98,12193.41,9607.14,2586.26,248.88 +13157.41,12392.86,764.55,11913.41,10000.00,1913.41,248.91 +12867.41,11965.52,901.89,11623.41,10172.41,1450.99,248.94 +12577.41,11413.79,1163.61,11333.41,9827.59,1505.82,248.96 +12297.41,11142.86,1154.55,11053.41,9285.71,1767.69,248.90 +12017.41,11178.57,838.83,10773.41,8928.57,1844.84,248.86 +11737.41,11178.57,558.83,10493.41,9000.00,1493.41,248.82 +11447.41,10655.17,792.23,10203.41,8965.52,1237.89,248.72 +11167.41,10285.71,881.69,9923.41,8785.71,1137.69,248.64 +10877.41,10034.48,842.92,9633.41,8034.48,1598.92,248.58 +10597.41,9785.71,811.69,9353.41,7607.14,1746.26,248.64 +10317.41,9535.71,781.69,9073.41,7500.00,1573.41,248.68 +10037.41,9285.71,751.69,8793.41,7214.29,1579.12,248.71 +9747.41,8965.52,781.89,8503.41,7103.45,1399.96,248.73 +9457.41,8655.17,802.23,8213.41,6965.52,1247.89,248.74 +9177.41,8428.57,748.83,7933.41,6500.00,1433.41,248.70 +8887.41,8172.41,714.99,7643.41,6344.83,1298.58,248.68 +8607.41,8000.00,607.41,7363.41,6000.00,1363.41,248.66 +8327.41,7571.43,755.98,7083.41,5428.57,1654.84,248.69 +8047.41,7107.14,940.26,6803.41,5035.71,1767.69,248.71 +7767.41,6928.57,838.83,6523.41,4928.57,1594.84,248.73 +7477.41,6620.69,856.72,6233.41,4896.55,1336.85,248.66 +7197.41,6285.71,911.69,5953.41,4678.57,1274.84,248.61 +6917.41,6107.14,810.26,5673.41,4142.86,1530.55,248.57 +6637.41,5750.00,887.41,5393.41,3928.57,1464.84,248.48 +6367.41,5407.41,960.00,5123.41,4037.04,1086.37,248.42 +6087.41,5285.71,801.69,4843.41,3750.00,1093.41,248.36 +5807.41,5178.57,628.83,4563.41,3142.86,1420.55,248.45 +5527.41,4821.43,705.98,4283.41,2642.86,1640.55,248.52 +5247.41,4357.14,890.26,4003.41,2464.29,1539.12,248.58 +4907.41,4058.82,848.58,3663.41,2352.94,1310.47,248.46 +4627.41,3892.86,734.55,3383.41,2321.43,1061.98,248.36 +4347.41,3607.14,740.26,3103.41,1964.29,1139.12,248.41 +4067.41,2607.14,1460.26,2823.41,892.86,1930.55,248.45 +3797.41,2037.04,1760.37,2553.41,629.63,1923.78,248.48 +3517.41,2250.00,1267.41,2273.41,535.71,1737.69,248.36 +3237.41,2500.00,737.41,1993.41,357.14,1636.26,248.26 +2957.41,2357.14,600.26,1713.41,642.86,1070.55,248.18 +2677.41,1392.86,1284.55,1433.41,857.14,576.26,248.20 +2397.41,785.71,1611.69,1153.41,-178.57,1331.98,248.22 +2127.41,-148.15,2275.55,883.41,-185.19,1068.59,248.24 +1847.41,250.00,1597.41,603.41,35.71,567.69,248.37 +1567.41,607.14,960.26,323.41,0.00,323.41,248.47 +1287.41,821.43,465.98,43.41,0.00,43.41,248.55 +1017.41,703.70,313.70,0.00,0.00,0.00,248.61 +747.41,-185.19,932.59,0.00,0.00,0.00,248.66 +467.41,-71.43,538.83,0.00,0.00,0.00,248.70 +197.41,37.04,160.37,0.00,0.00,0.00,248.75 +0.00,0.00,0.00,0.00,0.00,0.00,248.79 +0.00,0.00,0.00,0.00,0.00,0.00,248.83 +0.00,0.00,0.00,0.00,0.00,0.00,248.83 +0.00,0.00,0.00,0.00,0.00,0.00,248.84 +0.00,0.00,0.00,0.00,0.00,0.00,248.84 +0.00,0.00,0.00,0.00,0.00,0.00,248.88 +0.00,0.00,0.00,0.00,0.00,0.00,248.91 +0.00,0.00,0.00,0.00,0.00,0.00,248.82 +0.00,0.00,0.00,0.00,0.00,0.00,248.75 +0.00,0.00,0.00,0.00,0.00,0.00,248.69 +0.00,0.00,0.00,0.00,0.00,0.00,248.66 +0.00,0.00,0.00,0.00,0.00,0.00,248.64 +0.00,0.00,0.00,0.00,0.00,0.00,248.63 +0.00,0.00,0.00,0.00,0.00,0.00,248.66 +0.00,0.00,0.00,0.00,0.00,0.00,248.68 +0.00,0.00,0.00,0.00,0.00,0.00,248.69 +0.00,0.00,0.00,0.00,0.00,0.00,248.75 +0.00,0.00,0.00,0.00,0.00,0.00,248.80 +0.00,0.00,0.00,0.00,0.00,0.00,248.83 +0.00,0.00,0.00,0.00,0.00,0.00,248.83 +0.00,0.00,0.00,0.00,0.00,0.00,248.83 +0.00,0.00,0.00,0.00,0.00,0.00,248.83 +0.00,0.00,0.00,0.00,0.00,0.00,248.85 +0.00,0.00,0.00,0.00,0.00,0.00,248.87 +0.00,0.00,0.00,0.00,0.00,0.00,248.88 +0.00,0.00,0.00,0.00,0.00,0.00,248.92 +0.00,0.00,0.00,0.00,0.00,0.00,248.96 +0.00,0.00,0.00,0.00,0.00,0.00,248.99 +0.00,0.00,0.00,0.00,0.00,0.00,249.03 +0.00,0.00,0.00,0.00,0.00,0.00,249.06 +0.00,0.00,0.00,0.00,0.00,0.00,249.09 +0.00,0.00,0.00,0.00,0.00,0.00,249.11 +0.00,0.00,0.00,0.00,0.00,0.00,249.13 +0.00,0.00,0.00,0.00,0.00,0.00,249.15 +0.00,0.00,0.00,0.00,0.00,0.00,249.14 +0.00,0.00,0.00,0.00,0.00,0.00,249.14 +0.00,0.00,0.00,0.00,0.00,0.00,249.14 +0.00,0.00,0.00,0.00,0.00,0.00,249.15 +0.00,0.00,0.00,0.00,0.00,0.00,249.15 +0.00,0.00,0.00,0.00,0.00,0.00,249.14 +0.00,0.00,0.00,0.00,0.00,0.00,249.13 +0.00,0.00,0.00,0.00,0.00,0.00,249.12 +0.00,0.00,0.00,0.00,0.00,0.00,249.11 +0.00,0.00,0.00,0.00,0.00,0.00,249.10 +0.00,0.00,0.00,0.00,0.00,0.00,249.10 +0.00,0.00,0.00,0.00,0.00,0.00,249.10 +0.00,0.00,0.00,0.00,0.00,0.00,249.11 +0.00,0.00,0.00,0.00,0.00,0.00,249.11 +0.00,0.00,0.00,0.00,0.00,0.00,248.38 +0.00,0.00,0.00,0.00,0.00,0.00,248.38 +0.00,0.00,0.00,0.00,0.00,0.00,248.38 +0.00,0.00,0.00,0.00,0.00,0.00,248.38 +0.00,0.00,0.00,0.00,0.00,0.00,248.38 +0.00,0.00,0.00,0.00,0.00,0.00,248.38 +0.00,0.00,0.00,0.00,0.00,0.00,248.37 +0.00,0.00,0.00,0.00,0.00,0.00,248.37 +0.00,0.00,0.00,0.00,0.00,0.00,248.37 +0.00,0.00,0.00,0.00,0.00,0.00,248.32 +0.00,0.00,0.00,0.00,0.00,0.00,248.32 +0.00,0.00,0.00,0.00,0.00,0.00,248.32 +0.00,0.00,0.00,0.00,0.00,0.00,248.22 +0.00,0.00,0.00,0.00,0.00,0.00,248.22 +0.00,0.00,0.00,0.00,0.00,0.00,248.22 +0.00,0.00,0.00,0.00,0.00,0.00,248.15 +0.00,35.71,-35.71,0.00,0.00,0.00,248.15 +0.00,0.00,0.00,0.00,0.00,0.00,248.15 +0.00,0.00,0.00,0.00,0.00,0.00,248.14 +0.00,0.00,0.00,0.00,0.00,0.00,248.14 +0.00,0.00,0.00,0.00,0.00,0.00,248.10 +0.00,0.00,0.00,0.00,0.00,0.00,248.10 +0.00,0.00,0.00,0.00,0.00,0.00,248.10 +0.00,0.00,0.00,0.00,0.00,0.00,248.05 +0.00,0.00,0.00,0.00,0.00,0.00,248.05 +0.00,0.00,0.00,0.00,0.00,0.00,248.05 +0.00,0.00,0.00,0.00,0.00,0.00,248.04 +0.00,0.00,0.00,0.00,0.00,0.00,248.04 +0.00,0.00,0.00,0.00,0.00,0.00,248.04 +0.00,0.00,0.00,0.00,0.00,0.00,248.07 +0.00,0.00,0.00,0.00,0.00,0.00,248.07 +0.00,0.00,0.00,0.00,0.00,0.00,248.07 +0.00,0.00,0.00,0.00,0.00,0.00,248.04 +0.00,0.00,0.00,0.00,0.00,0.00,248.04 +0.00,0.00,0.00,0.00,0.00,0.00,248.04 +0.00,0.00,0.00,0.00,0.00,0.00,248.07 +0.00,0.00,0.00,0.00,0.00,0.00,248.07 +0.00,0.00,0.00,0.00,0.00,0.00,248.07 +0.00,0.00,0.00,0.00,0.00,0.00,248.14 +0.00,0.00,0.00,0.00,0.00,0.00,248.14 +0.00,0.00,0.00,0.00,0.00,0.00,248.14 +0.00,0.00,0.00,0.00,0.00,0.00,248.18 +0.00,0.00,0.00,0.00,-35.71,35.71,248.18 +0.00,0.00,0.00,0.00,0.00,0.00,248.18 +0.00,0.00,0.00,0.00,0.00,0.00,248.25 +0.00,0.00,0.00,0.00,0.00,0.00,248.25 +0.00,0.00,0.00,0.00,0.00,0.00,248.25 +0.00,0.00,0.00,0.00,0.00,0.00,248.26 +0.00,0.00,0.00,0.00,0.00,0.00,248.26 +0.00,0.00,0.00,0.00,0.00,0.00,248.26 +0.00,0.00,0.00,0.00,0.00,0.00,248.21 +0.00,0.00,0.00,0.00,0.00,0.00,248.21 +0.00,0.00,0.00,0.00,0.00,0.00,248.21 +0.00,0.00,0.00,0.00,0.00,0.00,248.19 +0.00,0.00,0.00,0.00,0.00,0.00,248.19 +0.00,0.00,0.00,0.00,0.00,0.00,248.19 +0.00,0.00,0.00,0.00,0.00,0.00,248.19 +0.00,0.00,0.00,0.00,0.00,0.00,248.19 +0.00,0.00,0.00,0.00,0.00,0.00,248.19 +0.00,0.00,0.00,0.00,0.00,0.00,248.16 +0.00,0.00,0.00,0.00,0.00,0.00,248.16 +0.00,0.00,0.00,0.00,0.00,0.00,248.16 +0.00,0.00,0.00,0.00,0.00,0.00,248.18 +0.00,0.00,0.00,0.00,0.00,0.00,248.18 +0.00,0.00,0.00,0.00,0.00,0.00,248.18 +0.00,0.00,0.00,0.00,0.00,0.00,248.20 +0.00,0.00,0.00,0.00,0.00,0.00,248.20 +0.00,0.00,0.00,0.00,0.00,0.00,248.20 +0.00,0.00,0.00,0.00,0.00,0.00,248.23 +0.00,0.00,0.00,0.00,0.00,0.00,248.23 +0.00,0.00,0.00,0.00,0.00,0.00,248.23 +0.00,0.00,0.00,0.00,0.00,0.00,248.27 +0.00,0.00,0.00,0.00,0.00,0.00,248.27 +0.00,0.00,0.00,0.00,0.00,0.00,248.27 +0.00,0.00,0.00,0.00,0.00,0.00,248.30 +0.00,0.00,0.00,0.00,0.00,0.00,248.30 +0.00,0.00,0.00,0.00,0.00,0.00,248.30 +0.00,0.00,0.00,0.00,0.00,0.00,248.32 +0.00,0.00,0.00,0.00,71.43,-71.43,248.32 +0.00,0.00,0.00,0.00,0.00,0.00,248.32 +0.00,0.00,0.00,0.00,0.00,0.00,248.36 +0.00,0.00,0.00,0.00,0.00,0.00,248.36 +0.00,0.00,0.00,0.00,38.46,-38.46,248.36 +0.00,0.00,0.00,0.00,38.46,-38.46,248.30 +0.00,0.00,0.00,0.00,0.00,0.00,248.30 +0.00,0.00,0.00,0.00,0.00,0.00,248.30 +0.00,0.00,0.00,0.00,0.00,0.00,248.32 +0.00,0.00,0.00,0.00,0.00,0.00,248.32 +0.00,0.00,0.00,0.00,0.00,0.00,248.32 +0.00,0.00,0.00,0.00,0.00,0.00,248.24 +290.00,34.48,255.52,290.00,-34.48,324.48,248.24 +550.00,0.00,550.00,550.00,0.00,550.00,248.24 +810.00,0.00,810.00,810.00,0.00,810.00,248.23 +1090.00,0.00,1090.00,1090.00,0.00,1090.00,248.23 +1400.00,0.00,1400.00,1400.00,0.00,1400.00,248.23 +1660.00,38.46,1621.54,1660.00,-38.46,1698.46,248.22 +1950.00,172.41,1777.59,1950.00,0.00,1950.00,248.22 +2210.00,423.08,1786.92,2210.00,76.92,2133.08,248.22 +2480.00,888.89,1591.11,2480.00,37.04,2442.96,248.01 +2760.00,2250.00,510.00,2760.00,71.43,2688.57,248.01 +3030.00,2370.37,659.63,3030.00,111.11,2918.89,248.01 +3300.00,1666.67,1633.33,3300.00,74.07,3225.93,247.78 +3590.00,689.66,2900.34,3590.00,68.97,3521.03,247.78 +3850.00,2115.38,1734.62,3850.00,423.08,3426.92,247.78 +4120.00,3703.70,416.30,4120.00,888.89,3231.11,247.38 +4410.00,3655.17,754.83,4410.00,1620.69,2789.31,247.38 +4680.00,2518.52,2161.48,4680.00,1555.56,3124.44,247.38 +4940.00,2076.92,2863.08,4940.00,1269.23,3670.77,247.24 +5220.00,2928.57,2291.43,5220.00,2000.00,3220.00,247.24 +5490.00,4518.52,971.48,5490.00,2703.70,2786.30,247.24 +5760.00,5444.44,315.56,5760.00,2814.81,2945.19,247.12 +6050.00,5206.90,843.10,6050.00,2827.59,3222.41,247.12 +6320.00,4444.44,1875.56,6320.00,3333.33,2986.67,247.12 +6590.00,4666.67,1923.33,6590.00,4111.11,2478.89,247.04 +6880.00,5206.90,1673.10,6880.00,4655.17,2224.83,247.04 +7150.00,5814.81,1335.19,7150.00,4740.74,2409.26,247.07 +7440.00,6172.41,1267.59,7440.00,5241.38,2198.62,247.07 +7710.00,6259.26,1450.74,7710.00,5555.56,2154.44,247.07 +7980.00,6444.44,1535.56,7980.00,5259.26,2720.74,247.14 +8270.00,6586.21,1683.79,8270.00,5379.31,2890.69,247.14 +8540.00,6555.56,1984.44,8540.00,6259.26,2280.74,247.14 +8810.00,6814.81,1995.19,8810.00,6777.78,2032.22,247.27 +9100.00,7413.79,1686.21,9100.00,6586.21,2513.79,247.27 +9370.00,7481.48,1888.52,9370.00,6259.26,3110.74,247.27 +9640.00,7592.59,2047.41,9640.00,6370.37,3269.63,247.40 +9930.00,7965.52,1964.48,9930.00,7103.45,2826.55,247.40 +10200.00,8037.04,2162.96,10200.00,8111.11,2088.89,247.40 +10470.00,8296.30,2173.70,10470.00,8259.26,2210.74,247.63 +10760.00,8758.62,2001.38,10760.00,7793.10,2966.90,247.63 +11030.00,8962.96,2067.04,11030.00,7777.78,3252.22,247.63 +11300.00,9333.33,1966.67,11300.00,8111.11,3188.89,247.74 +11590.00,9379.31,2210.69,11590.00,9206.90,2383.10,247.74 +11860.00,9592.59,2267.41,11860.00,9851.85,2008.15,247.74 +12130.00,9925.93,2204.07,12130.00,9703.70,2426.30,247.87 +12420.00,10103.45,2316.55,12420.00,8827.59,3592.41,247.87 +12690.00,10666.67,2023.33,12690.00,8925.93,3764.07,247.87 +12960.00,10777.78,2182.22,12960.00,10185.19,2774.81,247.77 +13250.00,10965.52,2284.48,13250.00,10931.03,2318.97,247.77 +13520.00,11185.19,2334.81,13520.00,10851.85,2668.15,247.81 +13810.00,11620.69,2189.31,13810.00,10379.31,3430.69,247.81 +14080.00,11962.96,2117.04,14080.00,10555.56,3524.44,247.81 +14350.00,12333.33,2016.67,14350.00,10888.89,3461.11,247.89 +14640.00,12551.72,2088.28,14640.00,11931.03,2708.97,247.89 +14920.00,12714.29,2205.71,14920.00,12142.86,2777.14,247.89 +15190.00,13037.04,2152.96,15190.00,12148.15,3041.85,247.89 +15490.00,13166.67,2323.33,15490.00,12033.33,3456.67,247.89 +15760.00,13444.44,2315.56,15760.00,12148.15,3611.85,247.89 +16040.00,13785.71,2254.29,16040.00,12535.71,3504.29,247.89 +16330.00,13896.55,2433.45,16330.00,13241.38,3088.62,247.89 +16610.00,14142.86,2467.14,16610.00,13928.57,2681.43,247.89 +16870.00,14538.46,2331.54,16870.00,13846.15,3023.85,247.88 +17160.00,14758.62,2401.38,17160.00,13655.17,3504.83,247.88 +17430.00,15037.04,2392.96,17430.00,14148.15,3281.85,247.88 +17700.00,15185.19,2514.81,17700.00,14703.70,2996.30,247.83 +17990.00,15310.34,2679.66,17990.00,15206.90,2783.10,247.83 +18260.00,15851.85,2408.15,18260.00,15074.07,3185.93,247.83 +18530.00,16222.22,2307.78,18530.00,15222.22,3307.78,247.81 +18820.00,16448.28,2371.72,18820.00,15310.34,3509.66,247.81 +19100.00,16678.57,2421.43,19100.00,15392.86,3707.14,247.81 +19370.00,16851.85,2518.15,19370.00,16259.26,3110.74,247.79 +19670.00,16966.67,2703.33,19670.00,17133.33,2536.67,247.79 +19940.00,17259.26,2680.74,19940.00,17037.04,2902.96,247.92 +20240.00,17666.67,2573.33,20240.00,16633.33,3606.67,247.92 +20510.00,18074.07,2435.93,20510.00,16703.70,3806.30,247.92 +20790.00,18321.43,2468.57,20790.00,17500.00,3290.00,247.93 +21080.00,18379.31,2700.69,21080.00,18586.21,2493.79,247.93 +21350.00,18740.74,2609.26,21350.00,18703.70,2646.30,247.93 +21670.00,18906.25,2763.75,21670.00,18125.00,3545.00,248.01 +21970.00,19400.00,2570.00,21970.00,17766.67,4203.33,248.01 +22250.00,19785.71,2464.29,22250.00,18535.71,3714.29,248.01 +22520.00,19962.96,2557.04,22520.00,19555.56,2964.44,247.92 +22810.00,20241.38,2568.62,22810.00,20000.00,2810.00,247.92 +23090.00,20392.86,2697.14,23090.00,20035.71,3054.29,247.92 +23360.00,20555.56,2804.44,23288.47,19666.67,3621.81,247.89 +23512.27,20620.69,2891.58,22998.47,19448.28,3550.20,247.89 +23232.27,20821.43,2410.84,22718.47,19892.86,2825.62,247.90 +22942.27,20655.17,2287.10,22428.47,20103.45,2325.02,247.90 +22672.27,20444.44,2227.83,22158.47,19555.56,2602.92,247.90 +22402.27,20037.04,2365.24,21888.47,18814.81,3073.66,247.91 +22102.27,19966.67,2135.61,21588.47,18266.67,3321.81,247.91 +21822.27,19714.29,2107.99,21308.47,18107.14,3201.33,247.91 +21542.27,19607.14,1935.13,21028.47,18571.43,2457.04,247.86 +21252.27,19241.38,2010.89,20738.47,18482.76,2255.71,247.86 +20972.27,18857.14,2115.13,20458.47,17607.14,2851.33,247.86 +20702.27,18555.56,2146.72,20188.47,16518.52,3669.95,247.93 +20412.27,18413.79,1998.48,19898.47,16758.62,3139.85,247.93 +20142.27,18259.26,1883.01,19628.47,17740.74,1887.73,247.93 +19872.27,18037.04,1835.24,19358.47,17740.74,1617.73,248.00 +19572.27,17866.67,1705.61,19058.47,16666.67,2391.81,248.00 +19302.27,17555.56,1746.72,18788.47,15555.56,3232.92,248.00 +19022.27,17392.86,1629.42,18508.47,15071.43,3437.04,248.08 +18732.27,17137.93,1594.34,18218.47,15931.03,2287.44,248.08 +18452.27,16714.29,1737.99,17938.47,16428.57,1509.90,248.17 +18162.27,16310.34,1851.93,17648.47,15379.31,2269.16,248.17 +17882.27,16071.43,1810.84,17368.47,14142.86,3225.62,248.17 +17612.27,15777.78,1834.50,17098.47,13777.78,3320.69,248.11 +17322.27,15620.69,1701.58,16808.47,14689.66,2118.82,248.11 +17052.27,15407.41,1644.87,16538.47,15111.11,1427.36,248.11 +16782.27,15074.07,1708.20,16268.47,14222.22,2046.25,248.18 +16492.27,14931.03,1561.24,15978.47,13137.93,2840.54,248.18 +16222.27,14703.70,1518.57,15708.47,12555.56,3152.92,248.18 +15952.27,14407.41,1544.87,15438.47,13111.11,2327.36,248.13 +15662.27,14103.45,1558.82,15148.47,13620.69,1527.78,248.13 +15392.27,14037.04,1355.24,14878.47,13222.22,1656.25,248.13 +15122.27,14037.04,1085.24,14608.47,12222.22,2386.25,248.21 +14832.27,13724.14,1108.14,14318.47,11827.59,2490.89,248.21 +14562.27,13296.30,1265.98,14048.47,12037.04,2011.44,248.21 +14282.27,13035.71,1246.56,13768.47,12214.29,1554.19,248.11 +13992.27,12896.55,1095.72,13478.47,11827.59,1650.89,248.11 +13712.27,12678.57,1033.70,13198.47,10964.29,2234.19,248.11 +13442.27,12333.33,1108.94,12928.47,10740.74,2187.73,248.15 +13152.27,12103.45,1048.82,12638.47,11241.38,1397.09,248.15 +12882.27,12037.04,845.24,12368.47,11407.41,961.07,248.15 +12612.27,11814.81,797.46,12098.47,10962.96,1135.51,248.20 +12322.27,11551.72,770.55,11808.47,9862.07,1946.40,248.20 +12052.27,11259.26,793.01,11538.47,9259.26,2279.21,248.31 +11762.27,10965.52,796.76,11248.47,9448.28,1800.20,248.31 +11492.27,10629.63,862.64,10978.47,9962.96,1015.51,248.31 +11222.27,10370.37,851.90,10708.47,9888.89,819.58,248.29 +10932.27,10310.34,621.93,10418.47,9172.41,1246.06,248.29 +10662.27,10185.19,477.09,10148.47,8703.70,1444.77,248.29 +10402.27,9807.69,594.58,9888.47,8692.31,1196.16,248.28 +10112.27,9620.69,491.58,9598.47,8862.07,736.40,248.28 +9842.27,9259.26,583.01,9328.47,8407.41,921.07,248.28 +9582.27,9038.46,543.81,9068.47,7730.77,1337.70,248.35 +9292.27,8655.17,637.10,8778.47,7551.72,1226.75,248.35 +9032.27,8384.62,647.66,8518.47,7538.46,980.01,248.35 +8762.27,8185.19,577.09,8248.47,7518.52,729.95,248.24 +8472.27,7896.55,575.72,7958.47,7172.41,786.06,248.24 +8202.27,7629.63,572.64,7688.47,6444.44,1244.03,248.24 +7932.27,7296.30,635.98,7418.47,5814.81,1603.66,248.28 +7642.27,6862.07,780.20,7128.47,5758.62,1369.85,248.28 +7372.27,6666.67,705.61,6858.47,5962.96,895.51,248.28 +7102.27,6407.41,694.87,6588.47,5962.96,625.51,248.22 +6812.27,6172.41,639.86,6298.47,5586.21,712.27,248.22 +6542.27,5925.93,616.35,6028.47,5185.19,843.29,248.22 +6272.27,5740.74,531.53,5758.47,4740.74,1017.73,248.21 +5982.27,5379.31,602.96,5468.47,4344.83,1123.65,248.21 +5712.27,5037.04,675.24,5198.47,4185.19,1013.29,248.21 +5392.27,4750.00,642.27,4878.47,4062.50,815.97,248.23 +5112.27,4464.29,647.99,4598.47,3821.43,777.04,248.23 +4852.27,4153.85,698.43,4338.47,3346.15,992.32,248.32 +4572.27,3571.43,1000.84,4058.47,2535.71,1522.76,248.32 +4302.27,3000.00,1302.27,3788.47,2481.48,1306.99,248.32 +4032.27,3148.15,884.12,3518.47,2629.63,888.84,248.31 +3742.27,3068.97,673.31,3228.47,2379.31,849.16,248.31 +3472.27,2296.30,1175.98,2958.47,1740.74,1217.73,248.31 +3212.27,1769.23,1443.04,2698.47,923.08,1775.40,248.23 +2922.27,1655.17,1267.10,2408.47,1379.31,1029.16,248.23 +2662.27,1807.69,854.58,2148.47,1230.77,917.70,248.23 +2392.27,1740.74,651.53,1878.47,888.89,989.58,248.29 +2112.27,321.43,1790.84,1598.47,-178.57,1777.04,248.29 +1842.27,-111.11,1953.38,1328.47,37.04,1291.44,248.29 +1572.27,592.59,979.68,1058.47,74.07,984.40,248.23 +1292.27,1321.43,-29.16,778.47,-142.86,921.33,248.23 +1022.27,111.11,911.16,508.47,0.00,508.47,248.23 +762.27,-692.31,1454.58,248.47,0.00,248.47,248.31 +472.27,206.90,265.38,0.00,0.00,0.00,248.31 +202.27,74.07,128.20,0.00,0.00,0.00,248.31 +0.00,-38.46,38.46,0.00,0.00,0.00,248.37 +0.00,0.00,0.00,0.00,0.00,0.00,248.37 +0.00,0.00,0.00,0.00,0.00,0.00,248.37 +0.00,0.00,0.00,0.00,0.00,0.00,248.45 +0.00,0.00,0.00,0.00,0.00,0.00,248.45 +0.00,0.00,0.00,0.00,0.00,0.00,248.45 +0.00,0.00,0.00,0.00,0.00,0.00,248.48 +0.00,0.00,0.00,0.00,0.00,0.00,248.48 +0.00,0.00,0.00,0.00,0.00,0.00,248.48 +0.00,0.00,0.00,0.00,0.00,0.00,248.53 +0.00,0.00,0.00,0.00,0.00,0.00,248.53 +0.00,0.00,0.00,0.00,0.00,0.00,248.53 +0.00,0.00,0.00,0.00,0.00,0.00,248.56 +0.00,0.00,0.00,0.00,-35.71,35.71,248.56 +0.00,0.00,0.00,0.00,-38.46,38.46,248.56 +0.00,0.00,0.00,0.00,0.00,0.00,248.59 +0.00,0.00,0.00,0.00,-142.86,142.86,248.59 +0.00,0.00,0.00,0.00,-230.77,230.77,248.59 +0.00,0.00,0.00,0.00,-307.69,307.69,248.60 +0.00,0.00,0.00,0.00,-1000.00,1000.00,248.60 +0.00,0.00,0.00,0.00,-2500.00,2500.00,248.60 +0.00,0.00,0.00,0.00,-2666.67,2666.67,248.60 +0.00,0.00,0.00,0.00,-1310.34,1310.34,248.60 +0.00,38.46,-38.46,0.00,-576.92,576.92,248.60 +0.00,444.44,-444.44,0.00,-2703.70,2703.70,248.79 +0.00,1137.93,-1137.93,0.00,-3862.07,3862.07,248.79 +0.00,2074.07,-2074.07,0.00,-1925.93,1925.93,248.79 +0.00,2074.07,-2074.07,0.00,-592.59,592.59,248.36 +0.00,1413.79,-1413.79,0.00,-2482.76,2482.76,248.36 +0.00,1296.30,-1296.30,0.00,-4222.22,4222.22,248.36 +0.00,2407.41,-2407.41,0.00,-2851.85,2851.85,248.07 +0.00,2586.21,-2586.21,0.00,-1034.48,1034.48,248.07 +0.00,1777.78,-1777.78,0.00,-2777.78,2777.78,248.00 +0.00,1241.38,-1241.38,0.00,-4965.52,4965.52,248.00 +0.00,2148.15,-2148.15,0.00,-2814.81,2814.81,248.00 +0.00,1666.67,-1666.67,0.00,-37.04,37.04,248.10 +0.00,250.00,-250.00,0.00,-321.43,321.43,248.10 +0.00,1000.00,-1000.00,0.00,-1518.52,1518.52,248.10 +0.00,703.70,-703.70,0.00,-2259.26,2259.26,248.17 +0.00,-620.69,620.69,0.00,-1172.41,1172.41,248.17 +0.00,-148.15,148.15,0.00,1148.15,-1148.15,248.17 +0.00,269.23,-269.23,0.00,192.31,-192.31,248.24 +0.00,-68.97,68.97,0.00,-551.72,551.72,248.24 +0.00,0.00,0.00,0.00,74.07,-74.07,248.24 +0.00,0.00,0.00,0.00,37.04,-37.04,248.14 +0.00,0.00,0.00,0.00,0.00,0.00,248.14 +0.00,0.00,0.00,0.00,0.00,0.00,248.14 +0.00,0.00,0.00,0.00,0.00,0.00,248.12 +0.00,0.00,0.00,0.00,0.00,0.00,248.12 +0.00,0.00,0.00,0.00,0.00,0.00,248.12 +0.00,0.00,0.00,0.00,0.00,0.00,248.14 +0.00,0.00,0.00,0.00,0.00,0.00,248.14 +0.00,0.00,0.00,0.00,0.00,0.00,248.14 +0.00,0.00,0.00,0.00,0.00,0.00,248.19 +0.00,0.00,0.00,0.00,0.00,0.00,248.19 +0.00,0.00,0.00,0.00,0.00,0.00,248.19 +0.00,0.00,0.00,0.00,0.00,0.00,248.18 +0.00,0.00,0.00,0.00,0.00,0.00,248.18 +0.00,0.00,0.00,0.00,0.00,0.00,248.18 +0.00,0.00,0.00,0.00,0.00,0.00,248.23 +0.00,0.00,0.00,0.00,0.00,0.00,248.23 +0.00,0.00,0.00,0.00,0.00,0.00,248.23 +0.00,0.00,0.00,0.00,0.00,0.00,248.20 +0.00,0.00,0.00,0.00,35.71,-35.71,248.20 +0.00,0.00,0.00,0.00,74.07,-74.07,248.20 +0.00,0.00,0.00,0.00,0.00,0.00,248.16 +0.00,0.00,0.00,0.00,0.00,0.00,248.16 +0.00,0.00,0.00,0.00,0.00,0.00,248.16 +0.00,0.00,0.00,0.00,0.00,0.00,248.21 +0.00,0.00,0.00,0.00,0.00,0.00,248.21 +0.00,0.00,0.00,0.00,0.00,0.00,248.21 +0.00,0.00,0.00,0.00,38.46,-38.46,248.25 +0.00,0.00,0.00,0.00,71.43,-71.43,248.25 +0.00,0.00,0.00,0.00,38.46,-38.46,248.25 +0.00,0.00,0.00,0.00,148.15,-148.15,248.29 +0.00,0.00,0.00,0.00,103.45,-103.45,248.29 +0.00,0.00,0.00,0.00,0.00,0.00,248.31 +0.00,0.00,0.00,0.00,35.71,-35.71,248.31 +0.00,0.00,0.00,0.00,185.19,-185.19,248.31 +0.00,0.00,0.00,0.00,961.54,-961.54,248.26 +0.00,-34.48,34.48,0.00,3034.48,-3034.48,248.26 +0.00,-37.04,37.04,0.00,3407.41,-3407.41,248.26 +0.00,-37.04,37.04,0.00,1148.15,-1148.15,248.15 +0.00,-103.45,103.45,0.00,1068.97,-1068.97,248.15 +0.00,0.00,0.00,0.00,2962.96,-2962.96,248.15 +0.00,0.00,0.00,0.00,3444.44,-3444.44,248.18 +0.00,0.00,0.00,0.00,1137.93,-1137.93,248.18 +0.00,0.00,0.00,0.00,461.54,-461.54,248.18 +0.00,-37.04,37.04,0.00,2629.63,-2629.63,247.94 +0.00,0.00,0.00,0.00,2793.10,-2793.10,247.94 +0.00,0.00,0.00,0.00,730.77,-730.77,247.94 +0.00,0.00,0.00,0.00,-111.11,111.11,247.73 +0.00,0.00,0.00,0.00,0.00,0.00,247.73 +0.00,38.46,-38.46,0.00,0.00,0.00,247.73 +0.00,38.46,-38.46,0.00,0.00,0.00,247.76 +0.00,0.00,0.00,0.00,0.00,0.00,247.76 +0.00,0.00,0.00,0.00,0.00,0.00,247.76 +0.00,0.00,0.00,0.00,0.00,0.00,247.78 +0.00,0.00,0.00,0.00,0.00,0.00,247.78 +0.00,0.00,0.00,0.00,-76.92,76.92,247.78 +0.00,0.00,0.00,0.00,0.00,0.00,247.71 +0.00,35.71,-35.71,0.00,0.00,0.00,247.71 +0.00,38.46,-38.46,0.00,0.00,0.00,247.71 +0.00,0.00,0.00,0.00,0.00,0.00,247.66 +0.00,0.00,0.00,0.00,0.00,0.00,247.66 +0.00,0.00,0.00,0.00,0.00,0.00,247.66 +0.00,0.00,0.00,0.00,0.00,0.00,247.64 +0.00,0.00,0.00,0.00,0.00,0.00,247.64 +0.00,0.00,0.00,0.00,0.00,0.00,247.64 +0.00,0.00,0.00,0.00,0.00,0.00,247.62 +0.00,0.00,0.00,0.00,0.00,0.00,247.62 +0.00,0.00,0.00,0.00,0.00,0.00,247.62 +0.00,0.00,0.00,0.00,0.00,0.00,247.63 +0.00,0.00,0.00,0.00,0.00,0.00,247.63 +0.00,0.00,0.00,0.00,0.00,0.00,247.63 +0.00,0.00,0.00,0.00,0.00,0.00,247.65 +0.00,-35.71,35.71,0.00,0.00,0.00,247.65 +0.00,0.00,0.00,0.00,0.00,0.00,247.65 +0.00,0.00,0.00,0.00,0.00,0.00,247.66 +0.00,0.00,0.00,0.00,0.00,0.00,247.66 +0.00,0.00,0.00,0.00,0.00,0.00,247.66 +0.00,0.00,0.00,0.00,76.92,-76.92,247.61 +0.00,0.00,0.00,0.00,71.43,-71.43,247.61 +0.00,0.00,0.00,0.00,38.46,-38.46,247.61 +0.00,0.00,0.00,0.00,74.07,-74.07,247.65 +0.00,-35.71,35.71,0.00,357.14,-357.14,247.65 +0.00,0.00,0.00,0.00,653.85,-653.85,247.65 +0.00,-38.46,38.46,0.00,1730.77,-1730.77,247.68 +0.00,0.00,0.00,0.00,2242.42,-2242.42,247.68 +0.00,0.00,0.00,0.00,1961.54,-1961.54,247.68 +0.00,0.00,0.00,0.00,222.22,-222.22,247.85 +0.00,0.00,0.00,0.00,-142.86,142.86,247.85 +0.00,0.00,0.00,0.00,-153.85,153.85,247.85 +0.00,0.00,0.00,0.00,-38.46,38.46,247.85 +0.00,0.00,0.00,0.00,0.00,0.00,247.85 +0.00,0.00,0.00,0.00,0.00,0.00,247.85 +0.00,38.46,-38.46,0.00,0.00,0.00,247.78 +0.00,71.43,-71.43,0.00,0.00,0.00,247.78 +0.00,38.46,-38.46,0.00,-76.92,76.92,247.78 +0.00,0.00,0.00,0.00,0.00,0.00,247.73 +0.00,0.00,0.00,0.00,0.00,0.00,247.73 +0.00,0.00,0.00,0.00,0.00,0.00,247.73 +0.00,0.00,0.00,0.00,0.00,0.00,247.60 +0.00,0.00,0.00,0.00,0.00,0.00,247.60 +0.00,0.00,0.00,0.00,0.00,0.00,247.60 +0.00,0.00,0.00,0.00,0.00,0.00,247.59 +0.00,0.00,0.00,0.00,0.00,0.00,247.59 +0.00,0.00,0.00,0.00,0.00,0.00,247.59 +0.00,0.00,0.00,0.00,0.00,0.00,247.56 +0.00,0.00,0.00,0.00,0.00,0.00,247.56 +0.00,0.00,0.00,0.00,0.00,0.00,247.53 +0.00,0.00,0.00,0.00,0.00,0.00,247.53 +0.00,0.00,0.00,0.00,0.00,0.00,247.53 +0.00,0.00,0.00,0.00,0.00,0.00,247.45 +0.00,0.00,0.00,0.00,0.00,0.00,247.45 +0.00,0.00,0.00,0.00,0.00,0.00,247.45 +0.00,0.00,0.00,0.00,0.00,0.00,247.38 +0.00,0.00,0.00,0.00,0.00,0.00,247.38 +0.00,0.00,0.00,0.00,0.00,0.00,247.38 +0.00,0.00,0.00,0.00,0.00,0.00,247.41 +0.00,0.00,0.00,0.00,0.00,0.00,247.41 +0.00,0.00,0.00,0.00,0.00,0.00,247.41 +0.00,0.00,0.00,0.00,0.00,0.00,247.44 +0.00,0.00,0.00,0.00,0.00,0.00,247.44 +0.00,0.00,0.00,0.00,0.00,0.00,247.44 +0.00,0.00,0.00,0.00,0.00,0.00,247.46 +0.00,0.00,0.00,0.00,0.00,0.00,247.46 +0.00,0.00,0.00,0.00,0.00,0.00,247.46 +0.00,0.00,0.00,0.00,0.00,0.00,247.49 +0.00,0.00,0.00,0.00,0.00,0.00,247.49 +0.00,0.00,0.00,0.00,0.00,0.00,247.49 +0.00,0.00,0.00,0.00,0.00,0.00,247.46 +0.00,0.00,0.00,0.00,0.00,0.00,247.46 +0.00,0.00,0.00,0.00,0.00,0.00,247.46 +0.00,0.00,0.00,0.00,0.00,0.00,247.50 +0.00,0.00,0.00,0.00,0.00,0.00,247.50 +0.00,0.00,0.00,0.00,0.00,0.00,247.50 +0.00,0.00,0.00,0.00,0.00,0.00,247.51 +0.00,0.00,0.00,0.00,0.00,0.00,247.51 +0.00,0.00,0.00,0.00,0.00,0.00,247.51 +0.00,0.00,0.00,0.00,0.00,0.00,247.52 +0.00,0.00,0.00,0.00,0.00,0.00,247.52 +0.00,0.00,0.00,0.00,0.00,0.00,247.52 +0.00,0.00,0.00,0.00,0.00,0.00,247.49 +0.00,0.00,0.00,0.00,0.00,0.00,247.49 +0.00,0.00,0.00,0.00,0.00,0.00,247.49 +0.00,0.00,0.00,0.00,0.00,0.00,247.47 +0.00,0.00,0.00,0.00,0.00,0.00,247.47 +0.00,0.00,0.00,0.00,0.00,0.00,247.47 +0.00,0.00,0.00,0.00,0.00,0.00,247.45 +0.00,0.00,0.00,0.00,0.00,0.00,247.45 +0.00,0.00,0.00,0.00,0.00,0.00,247.45 +0.00,0.00,0.00,0.00,0.00,0.00,247.45 +0.00,0.00,0.00,0.00,0.00,0.00,247.45 +0.00,0.00,0.00,0.00,0.00,0.00,247.45 +0.00,0.00,0.00,0.00,0.00,0.00,247.46 +0.00,0.00,0.00,0.00,0.00,0.00,247.46 +0.00,0.00,0.00,0.00,0.00,0.00,247.46 +0.00,0.00,0.00,0.00,0.00,0.00,247.44 +0.00,0.00,0.00,0.00,0.00,0.00,247.44 +0.00,0.00,0.00,0.00,0.00,0.00,247.44 +0.00,0.00,0.00,0.00,0.00,0.00,247.44 +0.00,0.00,0.00,0.00,0.00,0.00,247.44 +0.00,0.00,0.00,0.00,0.00,0.00,247.44 +0.00,0.00,0.00,0.00,0.00,0.00,247.43 +0.00,0.00,0.00,0.00,0.00,0.00,247.43 +0.00,0.00,0.00,0.00,0.00,0.00,247.43 +0.00,0.00,0.00,0.00,0.00,0.00,247.42 +0.00,0.00,0.00,0.00,0.00,0.00,247.42 +0.00,0.00,0.00,0.00,0.00,0.00,247.42 +0.00,0.00,0.00,0.00,0.00,0.00,247.43 +0.00,0.00,0.00,0.00,0.00,0.00,247.43 +0.00,0.00,0.00,0.00,0.00,0.00,247.43 +0.00,0.00,0.00,0.00,0.00,0.00,247.42 +0.00,0.00,0.00,0.00,0.00,0.00,247.42 +0.00,0.00,0.00,0.00,0.00,0.00,247.42 +0.00,0.00,0.00,0.00,0.00,0.00,247.41 +0.00,0.00,0.00,0.00,0.00,0.00,247.41 +0.00,0.00,0.00,0.00,0.00,0.00,247.41 +0.00,0.00,0.00,0.00,0.00,0.00,247.45 +0.00,0.00,0.00,0.00,0.00,0.00,247.45 +0.00,0.00,0.00,0.00,0.00,0.00,247.45 +0.00,0.00,0.00,0.00,0.00,0.00,247.44 +0.00,0.00,0.00,0.00,0.00,0.00,247.44 +0.00,0.00,0.00,0.00,0.00,0.00,247.44 +0.00,0.00,0.00,0.00,0.00,0.00,247.49 +0.00,0.00,0.00,0.00,0.00,0.00,247.49 +0.00,0.00,0.00,0.00,0.00,0.00,247.49 +0.00,0.00,0.00,0.00,0.00,0.00,247.52 +0.00,0.00,0.00,0.00,0.00,0.00,247.52 +0.00,0.00,0.00,0.00,0.00,0.00,247.52 +0.00,0.00,0.00,0.00,0.00,0.00,247.54 +0.00,0.00,0.00,0.00,0.00,0.00,247.54 +0.00,0.00,0.00,0.00,0.00,0.00,247.54 +0.00,0.00,0.00,0.00,0.00,0.00,247.49 +0.00,0.00,0.00,0.00,0.00,0.00,247.49 +0.00,0.00,0.00,0.00,0.00,0.00,247.49 +0.00,0.00,0.00,0.00,0.00,0.00,247.44 +0.00,0.00,0.00,0.00,0.00,0.00,247.44 +0.00,0.00,0.00,0.00,0.00,0.00,247.44 +0.00,0.00,0.00,0.00,0.00,0.00,247.45 +0.00,0.00,0.00,0.00,0.00,0.00,247.45 +0.00,0.00,0.00,0.00,0.00,0.00,247.45 +0.00,0.00,0.00,0.00,0.00,0.00,247.48 +0.00,0.00,0.00,0.00,0.00,0.00,247.48 +0.00,0.00,0.00,0.00,0.00,0.00,247.48 +0.00,0.00,0.00,0.00,0.00,0.00,247.47 +0.00,0.00,0.00,0.00,0.00,0.00,247.47 +0.00,0.00,0.00,0.00,0.00,0.00,247.47 +0.00,0.00,0.00,0.00,0.00,0.00,247.50 +0.00,0.00,0.00,0.00,0.00,0.00,247.50 +0.00,0.00,0.00,0.00,0.00,0.00,247.50 +0.00,0.00,0.00,0.00,0.00,0.00,247.55 +0.00,0.00,0.00,0.00,0.00,0.00,247.55 +0.00,0.00,0.00,0.00,0.00,0.00,247.55 +0.00,0.00,0.00,0.00,0.00,0.00,247.52 +0.00,0.00,0.00,0.00,0.00,0.00,247.52 +0.00,0.00,0.00,0.00,0.00,0.00,247.52 +0.00,0.00,0.00,0.00,0.00,0.00,247.46 +0.00,0.00,0.00,0.00,0.00,0.00,247.46 +0.00,0.00,0.00,0.00,0.00,0.00,247.46 +0.00,0.00,0.00,0.00,0.00,0.00,247.39 +0.00,0.00,0.00,0.00,0.00,0.00,247.39 +0.00,0.00,0.00,0.00,0.00,0.00,247.39 +0.00,0.00,0.00,0.00,0.00,0.00,247.35 +0.00,0.00,0.00,0.00,0.00,0.00,247.35 +0.00,0.00,0.00,0.00,0.00,0.00,247.35 +0.00,0.00,0.00,0.00,0.00,0.00,247.28 +0.00,0.00,0.00,0.00,0.00,0.00,247.28 +0.00,0.00,0.00,0.00,0.00,0.00,247.28 +0.00,0.00,0.00,0.00,0.00,0.00,247.24 +-290.00,0.00,-290.00,-290.00,0.00,-290.00,247.24 +-550.00,0.00,-550.00,-550.00,0.00,-550.00,247.24 +-820.00,0.00,-820.00,-820.00,0.00,-820.00,247.26 +-1100.00,0.00,-1100.00,-1100.00,0.00,-1100.00,247.26 +-1370.00,0.00,-1370.00,-1370.00,0.00,-1370.00,247.27 +-1660.00,0.00,-1660.00,-1660.00,0.00,-1660.00,247.27 +-1930.00,-111.11,-1818.89,-1930.00,-148.15,-1781.85,247.27 +-2250.00,-218.75,-2031.25,-2250.00,-187.50,-2062.50,247.43 +-2540.00,-172.41,-2367.59,-2540.00,-34.48,-2505.52,247.43 +-2810.00,-740.74,-2069.26,-2810.00,-185.19,-2624.81,247.43 +-3080.00,-2296.30,-783.70,-3080.00,-444.44,-2635.56,247.49 +-3370.00,-2724.14,-645.86,-3370.00,-1068.97,-2301.03,247.49 +-3640.00,-1962.96,-1677.04,-3640.00,-1814.81,-1825.19,247.49 +-3910.00,-1444.44,-2465.56,-3910.00,-1740.74,-2169.26,247.25 +-4200.00,-2413.79,-1786.21,-4200.00,-931.03,-3268.97,247.25 +-4480.00,-3785.71,-694.29,-4480.00,-1678.57,-2801.43,247.25 +-4750.00,-3370.37,-1379.63,-4750.00,-2518.52,-2231.48,247.26 +-5050.00,-1800.00,-3250.00,-5050.00,-2800.00,-2250.00,247.26 +-5320.00,-2777.78,-2542.22,-5320.00,-3037.04,-2282.96,247.26 +-5600.00,-4428.57,-1171.43,-5600.00,-3500.00,-2100.00,247.04 +-5900.00,-5233.33,-666.67,-5900.00,-4233.33,-1666.67,247.04 +-6180.00,-5035.71,-1144.29,-6180.00,-4285.71,-1894.29,247.10 +-6480.00,-4700.00,-1780.00,-6480.00,-3600.00,-2880.00,247.10 +-6750.00,-4555.56,-2194.44,-6750.00,-3444.44,-3305.56,247.10 +-7020.00,-5037.04,-1982.96,-7020.00,-4222.22,-2797.78,247.13 +-7320.00,-5900.00,-1420.00,-7320.00,-5800.00,-1520.00,247.13 +-7600.00,-6214.29,-1385.71,-7600.00,-6142.86,-1457.14,247.13 +-7870.00,-5703.70,-2166.30,-7870.00,-5185.19,-2684.81,247.07 +-8170.00,-5733.33,-2436.67,-8170.00,-4266.67,-3903.33,247.07 +-8440.00,-6518.52,-1921.48,-8440.00,-5703.70,-2736.30,247.07 +-8720.00,-6892.86,-1827.14,-8720.00,-7357.14,-1362.86,247.17 +-9020.00,-6833.33,-2186.67,-9020.00,-7433.33,-1586.67,247.17 +-9300.00,-7178.57,-2121.43,-9300.00,-7035.71,-2264.29,247.17 +-9580.00,-7750.00,-1830.00,-9580.00,-6535.71,-3044.29,247.20 +-9880.00,-7900.00,-1980.00,-9880.00,-6600.00,-3280.00,247.20 +-10160.00,-8321.43,-1838.57,-10160.00,-8107.14,-2052.86,247.21 +-10440.00,-8678.57,-1761.43,-10440.00,-8892.86,-1547.14,247.21 +-10720.00,-9000.00,-1720.00,-10720.00,-8928.57,-1791.43,247.21 +-11000.00,-9285.71,-1714.29,-11000.00,-8678.57,-2321.43,247.25 +-11300.00,-9466.67,-1833.33,-11300.00,-8566.67,-2733.33,247.25 +-11580.00,-9750.00,-1830.00,-11580.00,-9321.43,-2258.57,247.25 +-11860.00,-9964.29,-1895.71,-11860.00,-10000.00,-1860.00,247.31 +-12160.00,-10300.00,-1860.00,-12160.00,-10266.67,-1893.33,247.31 +-12440.00,-10642.86,-1797.14,-12440.00,-10000.00,-2440.00,247.31 +-12720.00,-11035.71,-1684.29,-12720.00,-10071.43,-2648.57,247.30 +-13020.00,-11233.33,-1786.67,-13020.00,-10266.67,-2753.33,247.30 +-13300.00,-11464.29,-1835.71,-13300.00,-11000.00,-2300.00,247.30 +-13580.00,-11642.86,-1937.14,-13580.00,-11285.71,-2294.29,247.25 +-13880.00,-12100.00,-1780.00,-13880.00,-11600.00,-2280.00,247.25 +-14160.00,-12428.57,-1731.43,-14160.00,-11642.86,-2517.14,247.18 +-14460.00,-12400.00,-2060.00,-14460.00,-12066.67,-2393.33,247.18 +-14740.00,-12714.29,-2025.71,-14740.00,-12392.86,-2347.14,247.18 +-15020.00,-13000.00,-2020.00,-15020.00,-12821.43,-2198.57,247.12 +-15320.00,-13500.00,-1820.00,-15320.00,-13133.33,-2186.67,247.12 +-15600.00,-13821.43,-1778.57,-15600.00,-13107.14,-2492.86,247.12 +-15880.00,-13928.57,-1951.43,-15880.00,-13357.14,-2522.86,247.07 +-16180.00,-14266.67,-1913.33,-16180.00,-13733.33,-2446.67,247.07 +-16460.00,-14750.00,-1710.00,-16460.00,-14214.29,-2245.71,247.07 +-16740.00,-15142.86,-1597.14,-16740.00,-14714.29,-2025.71,247.07 +-17040.00,-15533.33,-1506.67,-17040.00,-14933.33,-2106.67,247.07 +-17320.00,-15678.57,-1641.43,-17320.00,-15071.43,-2248.57,247.07 +-17600.00,-15678.57,-1921.43,-17600.00,-15214.29,-2385.71,246.98 +-17900.00,-16033.33,-1866.67,-17900.00,-15800.00,-2100.00,246.98 +-18180.00,-16464.29,-1715.71,-18180.00,-16214.29,-1965.71,246.97 +-18480.00,-16700.00,-1780.00,-18480.00,-16400.00,-2080.00,246.97 +-18760.00,-16750.00,-2010.00,-18760.00,-16250.00,-2510.00,246.97 +-19040.00,-16928.57,-2111.43,-19040.00,-16428.57,-2611.43,246.97 +-19340.00,-17133.33,-2206.67,-19340.00,-16833.33,-2506.67,246.97 +-19620.00,-17500.00,-2120.00,-19620.00,-17214.29,-2405.71,246.97 +-19900.00,-17964.29,-1935.71,-19900.00,-17428.57,-2471.43,247.00 +-20200.00,-18166.67,-2033.33,-20200.00,-17500.00,-2700.00,247.00 +-20480.00,-18214.29,-2265.71,-20480.00,-17714.29,-2765.71,247.00 +-20760.00,-18642.86,-2117.14,-20760.00,-17928.57,-2831.43,247.08 +-21060.00,-19133.33,-1926.67,-21060.00,-17933.33,-3126.67,247.08 +-21340.00,-19321.43,-2018.57,-21340.00,-18142.86,-3197.14,247.11 +-21640.00,-19533.33,-2106.67,-21640.00,-18866.67,-2773.33,247.11 +-21930.00,-19827.59,-2102.41,-21930.00,-19655.17,-2274.83,247.11 +-22260.00,-20242.42,-2017.58,-22037.18,-19757.58,-2279.60,247.07 +-22560.00,-20366.67,-2193.33,-21737.18,-19466.67,-2270.51,247.07 +-22840.00,-20535.71,-2304.29,-21457.18,-19321.43,-2135.75,247.07 +-22961.67,-20821.43,-2140.24,-21177.18,-19250.00,-1927.18,246.93 +-22661.67,-21433.33,-1228.33,-20877.18,-19066.67,-1810.51,246.93 +-22371.67,-21551.72,-819.94,-20587.18,-18827.59,-1759.59,246.93 +-22091.67,-20750.00,-1341.67,-20307.18,-18357.14,-1950.04,246.87 +-21781.67,-20290.32,-1491.34,-19997.18,-17967.74,-2029.44,246.87 +-21501.67,-20214.29,-1287.38,-19717.18,-17892.86,-1824.32,246.88 +-21201.67,-20033.33,-1168.33,-19417.18,-17566.67,-1850.51,246.88 +-20921.67,-19678.57,-1243.10,-19137.18,-17178.57,-1958.61,246.88 +-20641.67,-19357.14,-1284.52,-18857.18,-16928.57,-1928.61,246.93 +-20341.67,-19233.33,-1108.33,-18557.18,-16766.67,-1790.51,246.93 +-20061.67,-18928.57,-1133.10,-18277.18,-16464.29,-1812.89,246.93 +-19781.67,-18500.00,-1281.67,-17997.18,-16035.71,-1961.46,246.95 +-19471.67,-18225.81,-1245.86,-17687.18,-15516.13,-2171.05,246.95 +-19191.67,-18107.14,-1084.52,-17407.18,-15250.00,-2157.18,246.95 +-18911.67,-17928.57,-983.10,-17127.18,-15285.71,-1841.46,246.94 +-18611.67,-17600.00,-1011.67,-16827.18,-15366.67,-1460.51,246.94 +-18321.67,-17379.31,-942.36,-16537.18,-14758.62,-1778.56,246.96 +-18021.67,-16800.00,-1221.67,-16237.18,-14233.33,-2003.84,246.96 +-17741.67,-16607.14,-1134.52,-15957.18,-14250.00,-1707.18,246.96 +-17461.67,-16428.57,-1033.10,-15677.18,-14214.29,-1462.89,247.06 +-17161.67,-16133.33,-1028.33,-15377.18,-14033.33,-1343.84,247.06 +-16881.67,-15857.14,-1024.52,-15097.18,-13857.14,-1240.04,247.06 +-16591.67,-15689.66,-902.01,-14807.18,-13275.86,-1531.32,247.06 +-16291.67,-15433.33,-858.33,-14507.18,-13000.00,-1507.18,247.06 +-16011.67,-15250.00,-761.67,-14227.18,-12928.57,-1298.61,247.06 +-15731.67,-15178.57,-553.10,-13947.18,-12821.43,-1125.75,247.06 +-15421.67,-14903.23,-518.44,-13637.18,-12677.42,-959.76,247.06 +-15141.67,-14571.43,-570.24,-13357.18,-12321.43,-1035.75,247.08 +-14831.67,-14032.26,-799.41,-13047.18,-12064.52,-982.66,247.08 +-14551.67,-13678.57,-873.10,-12767.18,-11892.86,-874.32,247.08 +-14261.67,-13517.24,-744.43,-12477.18,-11620.69,-856.49,247.10 +-13961.67,-13300.00,-661.67,-12177.18,-11366.67,-810.51,247.10 +-13671.67,-13068.97,-602.70,-11887.18,-10965.52,-921.66,247.10 +-13391.67,-12714.29,-677.38,-11607.18,-10642.86,-964.32,247.18 +-13091.67,-12466.67,-625.00,-11307.18,-10366.67,-940.51,247.18 +-12811.67,-12250.00,-561.67,-11027.18,-10178.57,-848.61,247.18 +-12531.67,-11678.57,-853.10,-10747.18,-9928.57,-818.61,247.17 +-12231.67,-11400.00,-831.67,-10447.18,-9533.33,-913.84,247.17 +-11951.67,-11250.00,-701.67,-10167.18,-9178.57,-988.61,247.25 +-11661.67,-10965.52,-696.15,-9877.18,-8862.07,-1015.11,247.25 +-11381.67,-10857.14,-524.52,-9597.18,-8285.71,-1311.46,247.25 +-11101.67,-10642.86,-458.81,-9317.18,-8107.14,-1210.04,247.26 +-10801.67,-10333.33,-468.33,-9017.18,-7900.00,-1117.18,247.26 +-10531.67,-10000.00,-531.67,-8747.18,-7740.74,-1006.44,247.26 +-10251.67,-9750.00,-501.67,-8467.18,-7535.71,-931.46,247.23 +-9951.67,-9400.00,-551.67,-8167.18,-7133.33,-1033.84,247.23 +-9671.67,-9178.57,-493.10,-7887.18,-6857.14,-1030.04,247.23 +-9391.67,-8892.86,-498.81,-7607.18,-6571.43,-1035.75,247.33 +-9091.67,-8600.00,-491.67,-7307.18,-6266.67,-1040.51,247.33 +-8811.67,-8321.43,-490.24,-7027.18,-6071.43,-955.75,247.33 +-8531.67,-8035.71,-495.95,-6747.18,-5892.86,-854.32,247.35 +-8231.67,-7833.33,-398.33,-6447.18,-5666.67,-780.51,247.35 +-7951.67,-7535.71,-415.95,-6167.18,-5285.71,-881.46,247.31 +-7651.67,-7233.33,-418.33,-5867.18,-4933.33,-933.84,247.31 +-7371.67,-6928.57,-443.10,-5587.18,-4678.57,-908.61,247.31 +-7091.67,-6571.43,-520.24,-5307.18,-4357.14,-950.04,247.27 +-6801.67,-6275.86,-525.80,-5017.18,-3965.52,-1051.66,247.27 +-6521.67,-6107.14,-414.52,-4737.18,-3714.29,-1022.89,247.27 +-6251.67,-5740.74,-510.93,-4467.18,-3444.44,-1022.73,247.24 +-5951.67,-5500.00,-451.67,-4167.18,-3233.33,-933.84,247.24 +-5681.67,-5259.26,-422.41,-3897.18,-2962.96,-934.22,247.24 +-5401.67,-4964.29,-437.38,-3617.18,-2535.71,-1081.46,247.17 +-5111.67,-4103.45,-1008.22,-3327.18,-1724.14,-1603.04,247.17 +-4841.67,-3592.59,-1249.07,-3057.18,-1555.56,-1501.62,247.17 +-4571.67,-3740.74,-830.93,-2787.18,-1703.70,-1083.47,247.17 +-4281.67,-3862.07,-419.60,-2497.18,-1379.31,-1117.87,247.17 +-4011.67,-3777.78,-233.89,-2227.18,-666.67,-1560.51,247.17 +-3681.67,-3000.00,-681.67,-1897.18,181.82,-2079.00,247.08 +-3391.67,-2068.97,-1322.70,-1607.18,-137.93,-1469.25,247.08 +-3121.67,-1740.74,-1380.93,-1337.18,74.07,-1411.25,246.96 +-2831.67,-1931.03,-900.63,-1047.18,413.79,-1460.97,246.96 +-2551.67,-2071.43,-480.24,-767.18,-35.71,-731.46,246.96 +-2281.67,-1074.07,-1207.59,-497.18,0.00,-497.18,246.92 +-1991.67,-965.52,-1026.15,-207.18,0.00,-207.18,246.92 +-1721.67,-444.44,-1277.22,0.00,0.00,0.00,246.92 +-1461.67,538.46,-2000.13,0.00,0.00,0.00,247.06 +-1171.67,-344.83,-826.84,0.00,0.00,0.00,247.06 +-901.67,-296.30,-605.37,0.00,0.00,0.00,247.06 +-631.67,629.63,-1261.30,0.00,0.00,0.00,247.21 +-341.67,0.00,-341.67,0.00,0.00,0.00,247.21 +-81.67,-76.92,-4.74,0.00,0.00,0.00,247.21 +0.00,0.00,0.00,0.00,0.00,0.00,247.35 +0.00,0.00,0.00,0.00,0.00,0.00,247.35 +0.00,0.00,0.00,0.00,0.00,0.00,247.35 +0.00,0.00,0.00,0.00,0.00,0.00,247.40 +0.00,0.00,0.00,0.00,0.00,0.00,247.40 +0.00,0.00,0.00,0.00,0.00,0.00,247.40 +0.00,0.00,0.00,0.00,0.00,0.00,247.51 +0.00,0.00,0.00,0.00,0.00,0.00,247.51 +0.00,0.00,0.00,0.00,0.00,0.00,247.51 +0.00,0.00,0.00,0.00,0.00,0.00,247.50 +0.00,0.00,0.00,0.00,0.00,0.00,247.50 +0.00,0.00,0.00,0.00,0.00,0.00,247.50 +0.00,0.00,0.00,0.00,0.00,0.00,247.54 +0.00,0.00,0.00,0.00,0.00,0.00,247.54 +0.00,0.00,0.00,0.00,0.00,0.00,247.54 +0.00,0.00,0.00,0.00,0.00,0.00,247.59 +0.00,0.00,0.00,0.00,0.00,0.00,247.59 +0.00,0.00,0.00,0.00,0.00,0.00,247.59 +0.00,0.00,0.00,0.00,0.00,0.00,247.58 +0.00,0.00,0.00,0.00,0.00,0.00,247.58 +0.00,0.00,0.00,0.00,0.00,0.00,247.58 +0.00,0.00,0.00,0.00,0.00,0.00,247.58 +0.00,0.00,0.00,0.00,0.00,0.00,247.58 +0.00,0.00,0.00,0.00,0.00,0.00,247.58 \ No newline at end of file diff --git a/src/main.cpp b/src/main.cpp index f6aad9f..eb17f22 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -21,6 +21,7 @@ //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() { @@ -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 @@ -69,7 +72,9 @@ void loop() { // Run control loop // TODO change time parameter to be actual delta time, not just delay between loops - controlLoop(loopDelayMilliseconds, framesUntilPrint); + 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 426a0e9..d28782e 100644 --- a/src/robot/control.cpp +++ b/src/robot/control.cpp @@ -339,9 +339,9 @@ void controlLoop(int loopDelayMs, int8_t framesUntilPrint) { serialLog(rightSetpoint.velocity - currentVelocityB, 3); serialLog(",", 3); // test magnet data - // float heading = magnet->readDegrees(); - // serialLogln(heading, 3); - serialLogln(0, 3); + float heading = magnet->readDegrees(); + serialLogln(heading, 3); + // serialLogln(0, 3); #endif From 8fcaf6951fbe403eddc777b14fd874927a4b3fea Mon Sep 17 00:00:00 2001 From: democat Date: Wed, 8 Oct 2025 18:29:32 -0500 Subject: [PATCH 31/47] Add interrupt to magnetometer anyway --- src/robot/magnet.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/src/robot/magnet.cpp b/src/robot/magnet.cpp index 0b463b1..7cceee1 100644 --- a/src/robot/magnet.cpp +++ b/src/robot/magnet.cpp @@ -20,8 +20,8 @@ Magnet::Magnet() bmm350.setOperationMode(eBmm350NormalMode); bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY, BMM350_DATA_RATE_12_5HZ); bmm350.setMeasurementXYZ(); - // bmm350.setDataReadyPin(BMM350_ENABLE_INTERRUPT, BMM350_ACTIVE_LOW); - // pinMode(/*Pin */ 13, INPUT_PULLUP); + bmm350.setDataReadyPin(BMM350_ENABLE_INTERRUPT, BMM350_ACTIVE_LOW); + pinMode(/*Pin */ 13, INPUT_PULLUP); // attachInterrupt(/*interput io*/ 13, [this](){ this->updateReadings(); }, ONLOW); } @@ -74,9 +74,9 @@ float Magnet::readDegreesRaw() { float Magnet::readDegrees() { // Only works if data ready interrupt is enabled - // if (!bmm350.getDataReadyState()) { - // return previousReading; // Return the last reading if data is not ready - // } + if (!bmm350.getDataReadyState()) { + return previousReading; // Return the last reading if data is not ready + } float currentReading = readDegreesRaw(); // Handle wrap-around if (currentReading - previousReading > 180) { From 6e2cc4b41ab2bd0f43e60f49797ff5dd289dd25a Mon Sep 17 00:00:00 2001 From: democat Date: Wed, 8 Oct 2025 18:36:22 -0500 Subject: [PATCH 32/47] Wait for magnet ready before finishing bot setup --- include/robot/magnet.h | 1 + src/robot/control.cpp | 10 ++++++++++ 2 files changed, 11 insertions(+) diff --git a/include/robot/magnet.h b/include/robot/magnet.h index 54cc155..edaf561 100644 --- a/include/robot/magnet.h +++ b/include/robot/magnet.h @@ -19,6 +19,7 @@ class Magnet { float getCompassDegree(struct MagnetReading mag); float readDegreesRaw(); float readDegrees(); + bool isDataReady() { return bmm350.getDataReadyState(); } private: float hard_iron_offset[3] = { -23.71, -5.45, -8.27 }; float soft_iron_matrix[3][3] = { diff --git a/src/robot/control.cpp b/src/robot/control.cpp index d28782e..d40e2e5 100644 --- a/src/robot/control.cpp +++ b/src/robot/control.cpp @@ -186,6 +186,16 @@ void setupBot() { setupIR(); setupEncodersNew(); magnet = new Magnet(); + int maxTries = 5; + while (maxTries-- > 0 && !magnet->isDataReady()) { + delay(100); + } + if (!magnet->isDataReady()) { + serialLogln("Magnetometer not responding!", 0); + } else { + serialLogln("Magnetometer ready!", 2); + // headingTarget = magnet->readDegrees(); + } serialLogln("Bot Set Up!", 2); encoderAVelocityController.Reset(); From 276ed573d64c2a88290f65f5dd11bb2d84339bb3 Mon Sep 17 00:00:00 2001 From: democat Date: Mon, 13 Oct 2025 18:31:34 -0500 Subject: [PATCH 33/47] Add heading controller --- include/robot/control.h | 3 +++ include/utils/config.h | 2 ++ src/robot/control.cpp | 39 ++++++++++++++++++++++++++++----------- src/utils/config.cpp | 4 ++++ 4 files changed, 37 insertions(+), 11 deletions(-) diff --git a/include/robot/control.h b/include/robot/control.h index 4c7b97b..61ac820 100644 --- a/include/robot/control.h +++ b/include/robot/control.h @@ -19,14 +19,17 @@ struct ControlSetting static ControlSetting leftMotorControl; static ControlSetting rightMotorControl; +static double headingTarget = 0.0; static MotionProfile profileA = {THEORETICAL_MAX_VELOCITY_TPS, THEORETICAL_MAX_ACCELERATION_TPSPS, 0, 0, 0, 0, 75.0}; // maxVelocity, maxAcceleration, currentPosition, currentVelocity, targetPosition, targetVelocity static MotionProfile profileB = {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 setHeadingTarget(double target); ControlSetting getLeftMotorControl(); ControlSetting getRightMotorControl(); +double getHeadingTarget(); void setupBot(); void drive(float tiles, std::string id); diff --git a/include/utils/config.h b/include/utils/config.h index 803c9b3..7ed8d5e 100644 --- a/include/utils/config.h +++ b/include/utils/config.h @@ -40,6 +40,8 @@ extern float ACCELERATION_LIMIT_TPSPS; extern float MIN_MOTOR_POWER; 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/src/robot/control.cpp b/src/robot/control.cpp index d40e2e5..fc80836 100644 --- a/src/robot/control.cpp +++ b/src/robot/control.cpp @@ -35,8 +35,9 @@ TrapezoidProfile::Constraints profileConstraints(VELOCITY_LIMIT_TPS, ACCELERATIO TrapezoidProfile leftProfile(profileConstraints); TrapezoidProfile rightProfile(profileConstraints); TrapezoidProfile::State leftSetpoint, rightSetpoint; -PIDController encoderAVelocityController(0.00006, 0.000000, 0.00000, -1, +1); // Blue -PIDController encoderBVelocityController(0.00006, 0.000000, 0.00000, -1, +1); //Red +PIDController encoderAVelocityController(0.00006, 0.000000, 0.00000, -1, +1); // blue on graph // input ticks per second, output duty cycle +PIDController encoderBVelocityController(0.00006, 0.000000, 0.00000, -1, +1); // red on graph // input ticks per second, output duty cycle +PIDController headingController(0.008, 0.00000, 0.0000, -0.3, +0.3); // 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; @@ -125,12 +126,14 @@ void testEncoderPID() testEncoderPID_value = true; setLeftMotorControl({POSITION, (float)TICKS_PER_ROTATION * 5}); setRightMotorControl({POSITION, (float)TICKS_PER_ROTATION * 5}); + setHeadingTarget(magnet->readDegrees()); } else { testEncoderPID_value = false; setLeftMotorControl({POSITION, 0.0f}); setRightMotorControl({POSITION, 0.0f}); + setHeadingTarget(magnet->readDegrees()); } updateCritRange(); @@ -194,7 +197,7 @@ void setupBot() { serialLogln("Magnetometer not responding!", 0); } else { serialLogln("Magnetometer ready!", 2); - // headingTarget = magnet->readDegrees(); + headingTarget = magnet->readDegrees(); } serialLogln("Bot Set Up!", 2); @@ -205,7 +208,7 @@ void setupBot() { testEncoderPID(); timerInterval(12000, &testEncoderPID); } - + if (DO_TURN_TEST) { angle = 30; testTurn(); @@ -284,11 +287,17 @@ void controlLoop(int loopDelayMs, int8_t framesUntilPrint) { prevPositionA = currentPositionEncoderA; prevPositionB = currentPositionEncoderB; - double leftFeedForward = leftSetpoint.velocity / THEORETICAL_MAX_VELOCITY_TPS; - double rightFeedForward = rightSetpoint.velocity / THEORETICAL_MAX_VELOCITY_TPS; + double currentHeading = magnet->readDegrees(); + double velocityOffsetFromHeading = MAGNET_CCW_IS_POSITIVE * headingController.Compute(headingTarget, currentHeading, loopDelaySeconds); + // if error is positive, then assume we need to turn CCW, so slow left and speed up right + double desiredVelocityLeft = leftSetpoint.velocity - velocityOffsetFromHeading; + double desiredVelocityRight = rightSetpoint.velocity + velocityOffsetFromHeading; - double leftMotorPower = encoderAVelocityController.Compute(leftSetpoint.velocity, currentVelocityA, loopDelaySeconds) + leftFeedForward; - double rightMotorPower = encoderBVelocityController.Compute(rightSetpoint.velocity, currentVelocityB, loopDelaySeconds) + rightFeedForward; + double leftFeedForward = desiredVelocityLeft / THEORETICAL_MAX_VELOCITY_TPS; + double rightFeedForward = desiredVelocityRight / THEORETICAL_MAX_VELOCITY_TPS; + + double leftMotorPower = encoderAVelocityController.Compute(desiredVelocityLeft, currentVelocityA, loopDelaySeconds) + leftFeedForward; + double rightMotorPower = encoderBVelocityController.Compute(desiredVelocityRight, currentVelocityB, loopDelaySeconds) + rightFeedForward; if (leftMotorPower > 1) leftMotorPower = 1; if (leftMotorPower < -1) leftMotorPower = -1; @@ -349,8 +358,7 @@ void controlLoop(int loopDelayMs, int8_t framesUntilPrint) { serialLog(rightSetpoint.velocity - currentVelocityB, 3); serialLog(",", 3); // test magnet data - float heading = magnet->readDegrees(); - serialLogln(heading, 3); + serialLogln(currentHeading, 3); // serialLogln(0, 3); #endif @@ -540,6 +548,10 @@ void setRightMotorControl(ControlSetting control) { profileB.targetVelocity = control.value; } +void setHeadingTarget(double target) { + headingTarget = target; +} + ControlSetting getLeftMotorControl() { return leftMotorControl; } @@ -548,6 +560,10 @@ ControlSetting getRightMotorControl() { return rightMotorControl; } +double getHeadingTarget() { + return headingTarget; +} + void drive(float tiles, std::string id) { if (!getStoppedStatus()) { const float TILE_SIZE_INCHES = 24; @@ -593,7 +609,7 @@ 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); @@ -610,6 +626,7 @@ void turn(float angleRadians, std::string id) { } else { setRightMotorControl({POSITION, (float)(readRightEncoder() + offsetTicks)}); } + setHeadingTarget(getHeadingTarget() + (angleRadians * 180.0 / M_PI)); if (id != "NULL") { diff --git a/src/utils/config.cpp b/src/utils/config.cpp index 2f9aebc..86a1bb0 100644 --- a/src/utils/config.cpp +++ b/src/utils/config.cpp @@ -44,6 +44,8 @@ float ACCELERATION_LIMIT_TPSPS = 10000; float MIN_MOTOR_POWER = 0.12; // Minimum motor power to elicit motor response, empirically determined 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; @@ -75,6 +77,8 @@ void setConfig(JsonObject config) { 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["MAGNET_CCW_IS_POSITIVE"].is()) MAGNET_CCW_IS_POSITIVE = config["MAGNET_CCW_IS_POSITIVE"]; + serialLogln("Config Set!", 2); } From a36c591d3fbea1f0bbeda1e2951d0e5c876cc996 Mon Sep 17 00:00:00 2001 From: democat Date: Tue, 14 Oct 2025 00:30:12 -0500 Subject: [PATCH 34/47] Properly wait for magnet to initialize --- include/robot/magnet.h | 6 +++-- src/robot/control.cpp | 9 +++----- src/robot/magnet.cpp | 50 +++++++++++++++++++++++++++++++++--------- src/utils/config.cpp | 2 +- 4 files changed, 48 insertions(+), 19 deletions(-) diff --git a/include/robot/magnet.h b/include/robot/magnet.h index edaf561..fd82c71 100644 --- a/include/robot/magnet.h +++ b/include/robot/magnet.h @@ -19,7 +19,8 @@ class Magnet { float getCompassDegree(struct MagnetReading mag); float readDegreesRaw(); float readDegrees(); - bool isDataReady() { return bmm350.getDataReadyState(); } + bool isDataReady(); + bool isActive(); private: float hard_iron_offset[3] = { -23.71, -5.45, -8.27 }; float soft_iron_matrix[3][3] = { @@ -29,7 +30,8 @@ class Magnet { }; DFRobot_BMM350_I2C bmm350; - float previousReading = 0.0; + float previousReading = -1.0; + bool activeFlag = false; }; #endif // MAGNET_H \ No newline at end of file diff --git a/src/robot/control.cpp b/src/robot/control.cpp index fc80836..704598b 100644 --- a/src/robot/control.cpp +++ b/src/robot/control.cpp @@ -189,11 +189,7 @@ void setupBot() { setupIR(); setupEncodersNew(); magnet = new Magnet(); - int maxTries = 5; - while (maxTries-- > 0 && !magnet->isDataReady()) { - delay(100); - } - if (!magnet->isDataReady()) { + if (!magnet->isActive()) { serialLogln("Magnetometer not responding!", 0); } else { serialLogln("Magnetometer ready!", 2); @@ -203,6 +199,7 @@ void setupBot() { encoderAVelocityController.Reset(); encoderBVelocityController.Reset(); + headingController.Reset(); if (DO_PID_TEST) { testEncoderPID(); @@ -626,7 +623,7 @@ void turn(float angleRadians, std::string id) { } else { setRightMotorControl({POSITION, (float)(readRightEncoder() + offsetTicks)}); } - setHeadingTarget(getHeadingTarget() + (angleRadians * 180.0 / M_PI)); + setHeadingTarget(getHeadingTarget() + MAGNET_CCW_IS_POSITIVE * (angleRadians * 180.0 / M_PI)); if (id != "NULL") { diff --git a/src/robot/magnet.cpp b/src/robot/magnet.cpp index 7cceee1..84afed3 100644 --- a/src/robot/magnet.cpp +++ b/src/robot/magnet.cpp @@ -1,28 +1,53 @@ #include "DFRobot_BMM350.h" #include "robot/magnet.h" +#include "utils/logging.h" #define SDA_PIN 8 #define SCL_PIN 9 -// volatile uint8_t interruptFlag = 0; -// void Magnet::updateReadings(void) -// { -// // interruptFlag = 1; // Interrupt flag -// // detachInterrupt(13); // Detach interrupt -// currentRaw = readDegreesRaw(); -// } - Magnet::Magnet() : bmm350(&Wire, 0x14) { Wire.begin(SDA_PIN, SCL_PIN); - bmm350.begin(); + 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_12_5HZ); bmm350.setMeasurementXYZ(); bmm350.setDataReadyPin(BMM350_ENABLE_INTERRUPT, BMM350_ACTIVE_LOW); pinMode(/*Pin */ 13, INPUT_PULLUP); - // attachInterrupt(/*interput io*/ 13, [this](){ this->updateReadings(); }, ONLOW); + 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) { @@ -78,6 +103,11 @@ float Magnet::readDegrees() { return previousReading; // Return the last reading if data is not ready } float currentReading = readDegreesRaw(); + // Handle first reading + if (previousReading < 0) { + previousReading = currentReading; + return currentReading; + } // Handle wrap-around if (currentReading - previousReading > 180) { previousReading += 360; diff --git a/src/utils/config.cpp b/src/utils/config.cpp index 86a1bb0..1e4ae7a 100644 --- a/src/utils/config.cpp +++ b/src/utils/config.cpp @@ -44,7 +44,7 @@ float ACCELERATION_LIMIT_TPSPS = 10000; float MIN_MOTOR_POWER = 0.12; // Minimum motor power to elicit motor response, empirically determined 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 +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; From 46586a9fe34748a49601b1d8a62320dadf801f83 Mon Sep 17 00:00:00 2001 From: democat Date: Tue, 14 Oct 2025 00:31:53 -0500 Subject: [PATCH 35/47] configurable error tolerance, fix multiplier on heading controller output --- include/robot/pidController.h | 4 +++- include/robot/profiledPIDController.h | 3 ++- src/robot/control.cpp | 17 +++++++++++------ src/robot/pidController.cpp | 2 +- 4 files changed, 17 insertions(+), 9 deletions(-) diff --git a/include/robot/pidController.h b/include/robot/pidController.h index 299a0da..ea12694 100644 --- a/include/robot/pidController.h +++ b/include/robot/pidController.h @@ -5,7 +5,8 @@ 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 @@ -15,6 +16,7 @@ class PIDController double prev_error, prev_velocity_error; // Previous error double integral; // Integral accumulator + double errorTolerance; // Allowed error before returning 0 }; // Manually making the clamp function // template diff --git a/include/robot/profiledPIDController.h b/include/robot/profiledPIDController.h index aa4f8a3..b2a978d 100644 --- a/include/robot/profiledPIDController.h +++ b/include/robot/profiledPIDController.h @@ -8,8 +8,9 @@ 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), profile(constraints), lastTime(0.0) {} + : 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) { diff --git a/src/robot/control.cpp b/src/robot/control.cpp index 704598b..ab62835 100644 --- a/src/robot/control.cpp +++ b/src/robot/control.cpp @@ -35,9 +35,9 @@ TrapezoidProfile::Constraints profileConstraints(VELOCITY_LIMIT_TPS, ACCELERATIO TrapezoidProfile leftProfile(profileConstraints); TrapezoidProfile rightProfile(profileConstraints); TrapezoidProfile::State leftSetpoint, rightSetpoint; -PIDController encoderAVelocityController(0.00006, 0.000000, 0.00000, -1, +1); // blue on graph // input ticks per second, output duty cycle -PIDController encoderBVelocityController(0.00006, 0.000000, 0.00000, -1, +1); // red on graph // input ticks per second, output duty cycle -PIDController headingController(0.008, 0.00000, 0.0000, -0.3, +0.3); // input degrees, output duty cycle +PIDController encoderAVelocityController(0.00006, 0.000000, 0.00000, -1, +1, 100); // blue on graph // input ticks per second, output duty cycle +PIDController encoderBVelocityController(0.00006, 0.000000, 0.00000, -1, +1, 100); // red on graph // input ticks per second, output duty cycle +PIDController headingController(0.007, 0.00000, 0.0000, -0.3, +0.3, 0.5); // 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; @@ -285,7 +285,8 @@ void controlLoop(int loopDelayMs, int8_t framesUntilPrint) { prevPositionB = currentPositionEncoderB; double currentHeading = magnet->readDegrees(); - double velocityOffsetFromHeading = MAGNET_CCW_IS_POSITIVE * headingController.Compute(headingTarget, currentHeading, loopDelaySeconds); + double controllerOutput = headingController.Compute(headingTarget, currentHeading, loopDelaySeconds); + double velocityOffsetFromHeading = controllerOutput * THEORETICAL_MAX_VELOCITY_TPS * MAGNET_CCW_IS_POSITIVE; // if error is positive, then assume we need to turn CCW, so slow left and speed up right double desiredVelocityLeft = leftSetpoint.velocity - velocityOffsetFromHeading; double desiredVelocityRight = rightSetpoint.velocity + velocityOffsetFromHeading; @@ -355,8 +356,12 @@ void controlLoop(int loopDelayMs, int8_t framesUntilPrint) { serialLog(rightSetpoint.velocity - currentVelocityB, 3); serialLog(",", 3); // test magnet data - serialLogln(currentHeading, 3); - // serialLogln(0, 3); + serialLog(velocityOffsetFromHeading, 3); + serialLog(",", 3); + serialLog(headingTarget, 3); + serialLog(",", 3); + serialLog(currentHeading, 3); + serialLogln("", 3); #endif diff --git a/src/robot/pidController.cpp b/src/robot/pidController.cpp index 2c74fba..a562cbe 100644 --- a/src/robot/pidController.cpp +++ b/src/robot/pidController.cpp @@ -11,7 +11,7 @@ double PIDController::Compute(double setpoint, double actual_value, double dt) { // Calculate error double error = setpoint - actual_value; - if (abs(error) < 100) { + if (abs(error) < errorTolerance) { return 0; } From a527314bb3ba1bcc7c0e915c6d45245f4236149c Mon Sep 17 00:00:00 2001 From: democat Date: Tue, 14 Oct 2025 02:04:48 -0500 Subject: [PATCH 36/47] continuous pid control for heading --- include/robot/pidController.h | 24 +- pid_test.csv | 7234 +++++++-------------------------- pid_vis.py | 14 +- src/robot/control.cpp | 5 +- src/robot/magnet.cpp | 6 +- src/robot/pidController.cpp | 2 +- 6 files changed, 1537 insertions(+), 5748 deletions(-) diff --git a/include/robot/pidController.h b/include/robot/pidController.h index ea12694..85f7a6c 100644 --- a/include/robot/pidController.h +++ b/include/robot/pidController.h @@ -9,7 +9,7 @@ class PIDController : 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 @@ -17,6 +17,8 @@ class PIDController 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 @@ -24,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/pid_test.csv b/pid_test.csv index d888e93..7d6fc3f 100644 --- a/pid_test.csv +++ b/pid_test.csv @@ -1,5736 +1,1498 @@ -LeftSetpoint,LeftVelocity,LeftError,RightSetpoint,RightVelocity,RightError,Heading -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 --200.00,0.00,-200.00,-200.00,0.00,-200.00,0 --400.00,0.00,-400.00,-400.00,0.00,-400.00,0 --600.00,0.00,-600.00,-600.00,0.00,-600.00,0 --800.00,0.00,-800.00,-800.00,0.00,-800.00,0 --1000.00,0.00,-1000.00,-1000.00,0.00,-1000.00,0 --1200.00,0.00,-1200.00,-1200.00,0.00,-1200.00,0 --1400.00,0.00,-1400.00,-1400.00,0.00,-1400.00,0 --1600.00,0.00,-1600.00,-1600.00,0.00,-1600.00,0 --1800.00,-100.00,-1700.00,-1800.00,-250.00,-1550.00,0 --2000.00,-350.00,-1650.00,-2000.00,-300.00,-1700.00,0 --2200.00,-150.00,-2050.00,-2200.00,0.00,-2200.00,0 --2400.00,-350.00,-2050.00,-2400.00,-100.00,-2300.00,0 --2600.00,-1550.00,-1050.00,-2600.00,-200.00,-2400.00,0 --2800.00,-2150.00,-650.00,-2800.00,-450.00,-2350.00,0 --3000.00,-600.00,-2400.00,-3000.00,-700.00,-2300.00,0 --3200.00,-1450.00,-1750.00,-3200.00,-1400.00,-1800.00,0 --3400.00,-3050.00,-350.00,-3400.00,-1250.00,-2150.00,0 --3600.00,-2650.00,-950.00,-3600.00,-1350.00,-2250.00,0 --3800.00,-1200.00,-2600.00,-3800.00,-1350.00,-2450.00,0 --4000.00,-450.00,-3550.00,-4000.00,-1350.00,-2650.00,0 --4200.00,-3150.00,-1050.00,-4200.00,-2050.00,-2150.00,0 --4400.00,-4250.00,-150.00,-4400.00,-2100.00,-2300.00,0 --4600.00,-2000.00,-2600.00,-4600.00,-2100.00,-2500.00,0 --4800.00,-950.00,-3850.00,-4800.00,-2500.00,-2300.00,0 --5000.00,-4250.00,-750.00,-5000.00,-3300.00,-1700.00,0 --5200.00,-5050.00,-150.00,-5200.00,-3500.00,-1700.00,0 --5400.00,-2550.00,-2850.00,-5400.00,-3100.00,-2300.00,0 --5600.00,-3000.00,-2600.00,-5600.00,-3250.00,-2350.00,0 --5800.00,-5900.00,100.00,-5800.00,-4300.00,-1500.00,0 --6000.00,-5250.00,-750.00,-6000.00,-4300.00,-1700.00,0 --6200.00,-3600.00,-2600.00,-6200.00,-4150.00,-2050.00,0 --6400.00,-4650.00,-1750.00,-6400.00,-4350.00,-2050.00,0 --6600.00,-6150.00,-450.00,-6600.00,-4700.00,-1900.00,0 --6800.00,-5500.00,-1300.00,-6800.00,-4650.00,-2150.00,0 --7000.00,-4900.00,-2100.00,-7000.00,-4650.00,-2350.00,0 --7200.00,-7050.00,-150.00,-7200.00,-6200.00,-1000.00,0 --7400.00,-6050.00,-1350.00,-7400.00,-4950.00,-2450.00,0 --7600.00,-5950.00,-1650.00,-7600.00,-5300.00,-2300.00,0 --7800.00,-6600.00,-1200.00,-7800.00,-5800.00,-2000.00,0 --8000.00,-6800.00,-1200.00,-8000.00,-6000.00,-2000.00,0 --8200.00,-6550.00,-1650.00,-8200.00,-6150.00,-2050.00,0 --8400.00,-6400.00,-2000.00,-8400.00,-6300.00,-2100.00,0 --8600.00,-6850.00,-1750.00,-8600.00,-6650.00,-1950.00,0 --8800.00,-7450.00,-1350.00,-8800.00,-6800.00,-2000.00,0 --9000.00,-7600.00,-1400.00,-9000.00,-6900.00,-2100.00,0 --9200.00,-7550.00,-1650.00,-9200.00,-7000.00,-2200.00,0 --9400.00,-7600.00,-1800.00,-9400.00,-7400.00,-2000.00,0 --9600.00,-7800.00,-1800.00,-9600.00,-7700.00,-1900.00,0 --9800.00,-8450.00,-1350.00,-9800.00,-7950.00,-1850.00,0 --10000.00,-8900.00,-1100.00,-10000.00,-8150.00,-1850.00,0 --10200.00,-8850.00,-1350.00,-10200.00,-7850.00,-2350.00,0 --10400.00,-8950.00,-1450.00,-10400.00,-8150.00,-2250.00,0 --10600.00,-9200.00,-1400.00,-10600.00,-8800.00,-1800.00,0 --10800.00,-9400.00,-1400.00,-10800.00,-9200.00,-1600.00,0 --11000.00,-9850.00,-1150.00,-11000.00,-9700.00,-1300.00,0 --11200.00,-9850.00,-1350.00,-11200.00,-9350.00,-1850.00,0 --11400.00,-10000.00,-1400.00,-11400.00,-9550.00,-1850.00,0 --11600.00,-10150.00,-1450.00,-11600.00,-9500.00,-2100.00,0 --11800.00,-10350.00,-1450.00,-11800.00,-10000.00,-1800.00,0 --12000.00,-10900.00,-1100.00,-12000.00,-10700.00,-1300.00,0 --12200.00,-10750.00,-1450.00,-12200.00,-10550.00,-1650.00,0 --12400.00,-10650.00,-1750.00,-12400.00,-10500.00,-1900.00,0 --12600.00,-11600.00,-1000.00,-12600.00,-11350.00,-1250.00,0 --12800.00,-11800.00,-1000.00,-12800.00,-10850.00,-1950.00,0 --13000.00,-11400.00,-1600.00,-13000.00,-10800.00,-2200.00,0 --13200.00,-12300.00,-900.00,-13200.00,-11700.00,-1500.00,0 --13400.00,-12700.00,-700.00,-13400.00,-12100.00,-1300.00,0 --13600.00,-12700.00,-900.00,-13600.00,-12150.00,-1450.00,0 --13800.00,-12050.00,-1750.00,-13800.00,-11850.00,-1950.00,0 --14000.00,-12750.00,-1250.00,-14000.00,-12350.00,-1650.00,0 --14200.00,-13100.00,-1100.00,-14200.00,-12500.00,-1700.00,0 --14400.00,-13700.00,-700.00,-14400.00,-12900.00,-1500.00,0 --14600.00,-13450.00,-1150.00,-14600.00,-12800.00,-1800.00,0 --14800.00,-14100.00,-700.00,-14800.00,-13650.00,-1150.00,0 --15000.00,-14300.00,-700.00,-15000.00,-13250.00,-1750.00,0 --15200.00,-14000.00,-1200.00,-15200.00,-13500.00,-1700.00,0 --15400.00,-15000.00,-400.00,-15400.00,-14800.00,-600.00,0 --15600.00,-14750.00,-850.00,-15600.00,-14700.00,-900.00,0 --15800.00,-13900.00,-1900.00,-15800.00,-13550.00,-2250.00,0 --16000.00,-14550.00,-1450.00,-16000.00,-14050.00,-1950.00,0 --16200.00,-16400.00,200.00,-16200.00,-15200.00,-1000.00,0 --16400.00,-16200.00,-200.00,-16400.00,-15400.00,-1000.00,0 --16600.00,-15250.00,-1350.00,-16600.00,-14500.00,-2100.00,0 --16800.00,-16250.00,-550.00,-16800.00,-15650.00,-1150.00,0 --17000.00,-16500.00,-500.00,-17000.00,-15900.00,-1100.00,0 --17200.00,-15850.00,-1350.00,-17200.00,-15250.00,-1950.00,0 --17400.00,-15650.00,-1750.00,-17400.00,-15650.00,-1750.00,0 --17600.00,-16700.00,-900.00,-17600.00,-16400.00,-1200.00,0 --17800.00,-17700.00,-100.00,-17800.00,-16950.00,-850.00,0 --18000.00,-17500.00,-500.00,-18000.00,-16900.00,-1100.00,0 --18200.00,-17550.00,-650.00,-18200.00,-17550.00,-650.00,0 --18400.00,-18050.00,-350.00,-18400.00,-16650.00,-1750.00,0 --18600.00,-17550.00,-1050.00,-18600.00,-16600.00,-2000.00,0 --18800.00,-18300.00,-500.00,-18800.00,-17700.00,-1100.00,0 --19000.00,-18000.00,-1000.00,-19000.00,-17050.00,-1950.00,0 --19200.00,-18550.00,-650.00,-19200.00,-18350.00,-850.00,0 --19400.00,-19000.00,-400.00,-19400.00,-18200.00,-1200.00,0 --19600.00,-18250.00,-1350.00,-19600.00,-17200.00,-2400.00,0 --19800.00,-19350.00,-450.00,-19800.00,-18600.00,-1200.00,0 --20000.00,-20100.00,100.00,-20000.00,-19000.00,-1000.00,0 --20200.00,-18700.00,-1500.00,-20200.00,-18200.00,-2000.00,0 --20400.00,-19850.00,-550.00,-20400.00,-19850.00,-550.00,0 --20600.00,-20250.00,-350.00,-20600.00,-19050.00,-1550.00,0 --20800.00,-19950.00,-850.00,-20800.00,-19200.00,-1600.00,0 --21000.00,-20700.00,-300.00,-21000.00,-20100.00,-900.00,0 --21200.00,-20500.00,-700.00,-21200.00,-19800.00,-1400.00,0 --21400.00,-20150.00,-1250.00,-21400.00,-19850.00,-1550.00,0 --21600.00,-21000.00,-600.00,-21600.00,-20100.00,-1500.00,0 --21800.00,-21500.00,-300.00,-21800.00,-19900.00,-1900.00,0 --22000.00,-21050.00,-950.00,-22000.00,-20400.00,-1600.00,0 --22200.00,-21350.00,-850.00,-22200.00,-21250.00,-950.00,0 --22400.00,-26300.00,3900.00,-22400.00,-26000.00,3600.00,0 --22600.00,-21400.00,-1200.00,-22600.00,-19700.00,-2900.00,0 --22800.00,-20000.00,-2800.00,-22800.00,-20000.00,-2800.00,0 --23000.00,-23250.00,250.00,-23000.00,-23000.00,0.00,0 --23200.00,-23600.00,400.00,-23200.00,-21650.00,-1550.00,0 --23400.00,-21200.00,-2200.00,-23184.98,-21850.00,-1334.98,0 --23371.48,-22400.00,-971.48,-22984.98,-21550.00,-1434.98,0 --23171.48,-23950.00,778.52,-22784.98,-22850.00,65.02,0 --22971.48,-23600.00,628.52,-22584.98,-21600.00,-984.98,0 --22771.48,-22200.00,-571.48,-22384.98,-21800.00,-584.98,0 --22571.48,-22400.00,-171.48,-22184.98,-22950.00,765.02,0 --22371.48,-22350.00,-21.48,-21984.98,-20150.00,-1834.98,0 --22171.48,-23300.00,1128.52,-21784.98,-21400.00,-384.98,0 --21971.48,-23050.00,1078.52,-21584.98,-22000.00,415.02,0 --21771.48,-22150.00,378.52,-21384.98,-20050.00,-1334.98,0 --21571.48,-21800.00,228.52,-21184.98,-21000.00,-184.98,0 --21371.48,-21400.00,28.52,-20984.98,-20150.00,-834.98,0 --21171.48,-21300.00,128.52,-20784.98,-20300.00,-484.98,0 --20971.48,-21100.00,128.52,-20584.98,-20200.00,-384.98,0 --20771.48,-20100.00,-671.48,-20384.98,-19100.00,-1284.98,0 --20571.48,-20750.00,178.52,-20184.98,-19700.00,-484.98,0 --20371.48,-20400.00,28.52,-19984.98,-19100.00,-884.98,0 --20171.48,-19050.00,-1121.48,-19784.98,-18250.00,-1534.98,0 --19971.48,-20250.00,278.52,-19584.98,-19850.00,265.02,0 --19771.48,-20200.00,428.52,-19384.98,-18300.00,-1084.98,0 --19571.48,-19050.00,-521.48,-19184.98,-17600.00,-1584.98,0 --19371.48,-19950.00,578.52,-18984.98,-18900.00,-84.98,0 --19171.48,-20250.00,1078.52,-18784.98,-18500.00,-284.98,0 --18971.48,-18200.00,-771.48,-18584.98,-17750.00,-834.98,0 --18771.48,-18900.00,128.52,-18384.98,-19050.00,665.02,0 --18571.48,-19250.00,678.52,-18184.98,-16650.00,-1534.98,0 --18371.48,-19400.00,1028.52,-17984.98,-17200.00,-784.98,0 --18171.48,-18400.00,228.52,-17784.98,-18900.00,1115.02,0 --17971.48,-17000.00,-971.48,-17584.98,-16050.00,-1534.98,0 --17771.48,-16800.00,-971.48,-17384.98,-15900.00,-1484.98,0 --17571.48,-18500.00,928.52,-17184.98,-18400.00,1215.02,0 --17371.48,-17550.00,178.52,-16984.98,-16100.00,-884.98,0 --17171.48,-16300.00,-871.48,-16784.98,-15300.00,-1484.98,0 --16971.48,-17050.00,78.52,-16584.98,-17400.00,815.02,0 --16771.48,-17650.00,878.52,-16384.98,-16900.00,515.02,0 --16571.48,-16500.00,-71.48,-16184.98,-15400.00,-784.98,0 --16371.48,-16150.00,-221.48,-15984.98,-16050.00,65.02,0 --16171.48,-16150.00,-21.48,-15784.98,-16350.00,565.02,0 --15971.48,-15850.00,-121.48,-15584.98,-14450.00,-1134.98,0 --15771.48,-15800.00,28.52,-15384.98,-14000.00,-1384.98,0 --15571.48,-16300.00,728.52,-15184.98,-15550.00,365.02,0 --15371.48,-15600.00,228.52,-14984.98,-14300.00,-684.98,0 --15171.48,-15450.00,278.52,-14784.98,-14300.00,-484.98,0 --14971.48,-14650.00,-321.48,-14584.98,-14050.00,-534.98,0 --14771.48,-15000.00,228.52,-14384.98,-13900.00,-484.98,0 --14571.48,-14400.00,-171.48,-14184.98,-13300.00,-884.98,0 --14371.48,-14400.00,28.52,-13984.98,-13250.00,-734.98,0 --14171.48,-13550.00,-621.48,-13784.98,-13000.00,-784.98,0 --13971.48,-13750.00,-221.48,-13584.98,-13150.00,-434.98,0 --13771.48,-14300.00,528.52,-13384.98,-13250.00,-134.98,0 --13571.48,-13600.00,28.52,-13184.98,-12650.00,-534.98,0 --13371.48,-12700.00,-671.48,-12984.98,-12100.00,-884.98,0 --13171.48,-13650.00,478.52,-12784.98,-12650.00,-134.98,0 --12971.48,-12750.00,-221.48,-12584.98,-11850.00,-734.98,0 --12771.48,-12450.00,-321.48,-12384.98,-11950.00,-434.98,0 --12571.48,-12750.00,178.52,-12184.98,-11500.00,-684.98,0 --12371.48,-12100.00,-271.48,-11984.98,-10850.00,-1134.98,0 --12171.48,-11950.00,-221.48,-11784.98,-11150.00,-634.98,0 --11971.48,-12400.00,428.52,-11584.98,-11300.00,-284.98,0 --11771.48,-11350.00,-421.48,-11384.98,-10450.00,-934.98,0 --11571.48,-11350.00,-221.48,-11184.98,-10500.00,-684.98,0 --11371.48,-10650.00,-721.48,-10984.98,-9800.00,-1184.98,0 --11171.48,-10450.00,-721.48,-10784.98,-9700.00,-1084.98,0 --10971.48,-10400.00,-571.48,-10584.98,-9350.00,-1234.98,0 --10771.48,-10500.00,-271.48,-10384.98,-9200.00,-1184.98,0 --10571.48,-10450.00,-121.48,-10184.98,-8900.00,-1284.98,0 --10371.48,-9800.00,-571.48,-9984.98,-8800.00,-1184.98,0 --10171.48,-9650.00,-521.48,-9784.98,-9100.00,-684.98,0 --9971.48,-9800.00,-171.48,-9584.98,-9100.00,-484.98,0 --9771.48,-9950.00,178.52,-9384.98,-9300.00,-84.98,0 --9571.48,-9600.00,28.52,-9184.98,-8500.00,-684.98,0 --9371.48,-11000.00,1628.52,-8984.98,-10250.00,1265.02,0 --9171.48,-8350.00,-821.48,-8784.98,-7750.00,-1034.98,0 --8971.48,-7350.00,-1621.48,-8584.98,-6850.00,-1734.98,0 --8771.48,-8350.00,-421.48,-8384.98,-8050.00,-334.98,0 --8571.48,-8250.00,-321.48,-8184.98,-7850.00,-334.98,0 --8371.48,-7750.00,-621.48,-7984.98,-6850.00,-1134.98,0 --8171.48,-7550.00,-621.48,-7784.98,-6800.00,-984.98,0 --7971.48,-7750.00,-221.48,-7584.98,-6950.00,-634.98,0 --7771.48,-7550.00,-221.48,-7384.98,-6800.00,-584.98,0 --7571.48,-7200.00,-371.48,-7184.98,-6450.00,-734.98,0 --7371.48,-6850.00,-521.48,-6984.98,-6100.00,-884.98,0 --7171.48,-6700.00,-471.48,-6784.98,-5800.00,-984.98,0 --6971.48,-6350.00,-621.48,-6584.98,-5700.00,-884.98,0 --6771.48,-5800.00,-971.48,-6384.98,-5350.00,-1034.98,0 --6571.48,-6000.00,-571.48,-6184.98,-5450.00,-734.98,0 --6371.48,-6000.00,-371.48,-5984.98,-5350.00,-634.98,0 --6171.48,-5600.00,-571.48,-5784.98,-4700.00,-1084.98,0 --5971.48,-4900.00,-1071.48,-5584.98,-4300.00,-1284.98,0 --5771.48,-5050.00,-721.48,-5384.98,-4250.00,-1134.98,0 --5571.48,-4850.00,-721.48,-5184.98,-4250.00,-934.98,0 --5371.48,-4500.00,-871.48,-4984.98,-3900.00,-1084.98,0 --5171.48,-4400.00,-771.48,-4784.98,-3650.00,-1134.98,0 --4971.48,-4050.00,-921.48,-4584.98,-3400.00,-1184.98,0 --4771.48,-3800.00,-971.48,-4384.98,-3250.00,-1134.98,0 --4571.48,-3750.00,-821.48,-4184.98,-3200.00,-984.98,0 --4371.48,-3550.00,-821.48,-3984.98,-3200.00,-784.98,0 --4171.48,-3100.00,-1071.48,-3784.98,-2900.00,-884.98,0 --3971.48,-2600.00,-1371.48,-3584.98,-2100.00,-1484.98,0 --3771.48,-3150.00,-621.48,-3384.98,-1450.00,-1934.98,0 --3571.48,-2800.00,-771.48,-3184.98,-3100.00,-84.98,0 --3371.48,-1200.00,-2171.48,-2984.98,-2400.00,-584.98,0 --3171.48,-1950.00,-1221.48,-2784.98,0.00,-2784.98,0 --2971.48,-2750.00,-221.48,-2584.98,-1700.00,-884.98,0 --2771.48,-1850.00,-921.48,-2384.98,-1900.00,-484.98,0 --2571.48,-1100.00,-1471.48,-2184.98,800.00,-2984.98,0 --2371.48,-950.00,-1421.48,-1984.98,-1200.00,-784.98,0 --2171.48,-350.00,-1821.48,-1784.98,-1900.00,115.02,0 --1971.48,0.00,-1971.48,-1584.98,50.00,-1634.98,0 --1771.48,-250.00,-1521.48,-1384.98,-200.00,-1184.98,0 --1571.48,-200.00,-1371.48,-1184.98,-150.00,-1034.98,0 --1371.48,100.00,-1471.48,-984.98,300.00,-1284.98,0 --1171.48,500.00,-1671.48,-784.98,0.00,-784.98,0 --971.48,1100.00,-2071.48,-584.98,0.00,-584.98,0 --771.48,-350.00,-421.48,-384.98,0.00,-384.98,0 --571.48,-400.00,-171.48,-184.98,0.00,-184.98,0 --371.48,850.00,-1221.48,0.00,0.00,0.00,0 --171.48,-200.00,28.52,0.00,0.00,0.00,0 -0.00,-200.00,200.00,0.00,0.00,0.00,0 -0.00,100.00,-100.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -200.00,0.00,200.00,200.00,0.00,200.00,0 -400.00,0.00,400.00,400.00,0.00,400.00,0 -600.00,0.00,600.00,600.00,0.00,600.00,0 -800.00,0.00,800.00,800.00,0.00,800.00,0 -1000.00,0.00,1000.00,1000.00,0.00,1000.00,0 -1200.00,0.00,1200.00,1200.00,0.00,1200.00,0 -1400.00,0.00,1400.00,1400.00,0.00,1400.00,0 -1600.00,0.00,1600.00,1600.00,0.00,1600.00,0 -1800.00,200.00,1600.00,1800.00,200.00,1600.00,0 -2000.00,400.00,1600.00,2000.00,500.00,1500.00,0 -2200.00,50.00,2150.00,2200.00,0.00,2200.00,0 -2400.00,250.00,2150.00,2400.00,100.00,2300.00,0 -2600.00,900.00,1700.00,2600.00,200.00,2400.00,0 -2800.00,2300.00,500.00,2800.00,300.00,2500.00,0 -3000.00,1200.00,1800.00,3000.00,600.00,2400.00,0 -3200.00,1000.00,2200.00,3200.00,1250.00,1950.00,0 -3400.00,1800.00,1600.00,3400.00,1350.00,2050.00,0 -3600.00,1850.00,1750.00,3600.00,1550.00,2050.00,0 -3800.00,1600.00,2200.00,3800.00,1350.00,2450.00,0 -4000.00,2300.00,1700.00,4000.00,1700.00,2300.00,0 -4200.00,2300.00,1900.00,4200.00,1700.00,2500.00,0 -4400.00,2100.00,2300.00,4400.00,1950.00,2450.00,0 -4600.00,2800.00,1800.00,4600.00,2200.00,2400.00,0 -4800.00,3000.00,1800.00,4800.00,2550.00,2250.00,0 -5000.00,2500.00,2500.00,5000.00,2750.00,2250.00,0 -5200.00,3100.00,2100.00,5200.00,2850.00,2350.00,0 -5400.00,3650.00,1750.00,5400.00,3100.00,2300.00,0 -5600.00,3700.00,1900.00,5600.00,3400.00,2200.00,0 -5800.00,3950.00,1850.00,5800.00,3600.00,2200.00,0 -6000.00,4100.00,1900.00,6000.00,3900.00,2100.00,0 -6200.00,4550.00,1650.00,6200.00,4250.00,1950.00,0 -6400.00,4700.00,1700.00,6400.00,4450.00,1950.00,0 -6600.00,4950.00,1650.00,6600.00,4650.00,1950.00,0 -6800.00,5100.00,1700.00,6800.00,4650.00,2150.00,0 -7000.00,5300.00,1700.00,7000.00,5150.00,1850.00,0 -7200.00,5800.00,1400.00,7200.00,5250.00,1950.00,0 -7400.00,5950.00,1450.00,7400.00,5600.00,1800.00,0 -7600.00,6150.00,1450.00,7600.00,5750.00,1850.00,0 -7800.00,6150.00,1650.00,7800.00,5450.00,2350.00,0 -8000.00,7500.00,500.00,8000.00,7100.00,900.00,0 -8200.00,6350.00,1850.00,8200.00,5900.00,2300.00,0 -8400.00,6400.00,2000.00,8400.00,6300.00,2100.00,0 -8600.00,7050.00,1550.00,8600.00,6400.00,2200.00,0 -8800.00,7100.00,1700.00,8800.00,6600.00,2200.00,0 -9000.00,7250.00,1750.00,9000.00,6900.00,2100.00,0 -9200.00,7450.00,1750.00,9200.00,6950.00,2250.00,0 -9400.00,7600.00,1800.00,9400.00,7350.00,2050.00,0 -9600.00,7750.00,1850.00,9600.00,7500.00,2100.00,0 -9800.00,8100.00,1700.00,9800.00,7950.00,1850.00,0 -10000.00,8600.00,1400.00,10000.00,8050.00,1950.00,0 -10200.00,8900.00,1300.00,10200.00,8350.00,1850.00,0 -10400.00,9150.00,1250.00,10400.00,8250.00,2150.00,0 -10600.00,9250.00,1350.00,10600.00,8400.00,2200.00,0 -10800.00,9250.00,1550.00,10800.00,8550.00,2250.00,0 -11000.00,9250.00,1750.00,11000.00,8600.00,2400.00,0 -11200.00,9450.00,1750.00,11200.00,9000.00,2200.00,0 -11400.00,9650.00,1750.00,11400.00,9250.00,2150.00,0 -11600.00,9800.00,1800.00,11600.00,9800.00,1800.00,0 -11800.00,9800.00,2000.00,11800.00,9950.00,1850.00,0 -12000.00,10150.00,1850.00,12000.00,10100.00,1900.00,0 -12200.00,10450.00,1750.00,12200.00,10350.00,1850.00,0 -12400.00,10950.00,1450.00,12400.00,10550.00,1850.00,0 -12600.00,11400.00,1200.00,12600.00,10750.00,1850.00,0 -12800.00,11600.00,1200.00,12800.00,11000.00,1800.00,0 -13000.00,11600.00,1400.00,13000.00,11050.00,1950.00,0 -13200.00,11650.00,1550.00,13200.00,11250.00,1950.00,0 -13400.00,12550.00,850.00,13400.00,12200.00,1200.00,0 -13600.00,11850.00,1750.00,13600.00,11550.00,2050.00,0 -13800.00,11800.00,2000.00,13800.00,11750.00,2050.00,0 -14000.00,12250.00,1750.00,14000.00,11900.00,2100.00,0 -14200.00,12550.00,1650.00,14200.00,12300.00,1900.00,0 -14400.00,12850.00,1550.00,14400.00,12700.00,1700.00,0 -14600.00,13550.00,1050.00,14600.00,13000.00,1600.00,0 -14800.00,13550.00,1250.00,14800.00,13100.00,1700.00,0 -15000.00,13800.00,1200.00,15000.00,13500.00,1500.00,0 -15200.00,13950.00,1250.00,15200.00,13450.00,1750.00,0 -15400.00,14550.00,850.00,15400.00,14050.00,1350.00,0 -15600.00,14200.00,1400.00,15600.00,13900.00,1700.00,0 -15800.00,14750.00,1050.00,15800.00,14350.00,1450.00,0 -16000.00,14400.00,1600.00,16000.00,13950.00,2050.00,0 -16200.00,15550.00,650.00,16200.00,14850.00,1350.00,0 -16400.00,15600.00,800.00,16400.00,14850.00,1550.00,0 -16600.00,14950.00,1650.00,16600.00,14700.00,1900.00,0 -16800.00,15800.00,1000.00,16800.00,15350.00,1450.00,0 -17000.00,15550.00,1450.00,17000.00,15100.00,1900.00,0 -17200.00,15350.00,1850.00,17200.00,15650.00,1550.00,0 -17400.00,16550.00,850.00,17400.00,16350.00,1050.00,0 -17600.00,16800.00,800.00,17600.00,16200.00,1400.00,0 -17800.00,16800.00,1000.00,17800.00,15950.00,1850.00,0 -18000.00,17200.00,800.00,18000.00,16450.00,1550.00,0 -18200.00,17550.00,650.00,18200.00,17150.00,1050.00,0 -18400.00,17100.00,1300.00,18400.00,16800.00,1600.00,0 -18600.00,17250.00,1350.00,18600.00,16700.00,1900.00,0 -18800.00,17800.00,1000.00,18800.00,17250.00,1550.00,0 -19000.00,17200.00,1800.00,19000.00,17150.00,1850.00,0 -19200.00,18450.00,750.00,19200.00,17600.00,1600.00,0 -19400.00,18650.00,750.00,19400.00,18400.00,1000.00,0 -19600.00,18550.00,1050.00,19600.00,18400.00,1200.00,0 -19800.00,18800.00,1000.00,19800.00,18700.00,1100.00,0 -20000.00,18900.00,1100.00,20000.00,18350.00,1650.00,0 -20200.00,19350.00,850.00,20200.00,19350.00,850.00,0 -20400.00,19450.00,950.00,20400.00,18500.00,1900.00,0 -20600.00,20100.00,500.00,20600.00,19750.00,850.00,0 -20800.00,20550.00,250.00,20800.00,19350.00,1450.00,0 -21000.00,18750.00,2250.00,21000.00,18900.00,2100.00,0 -21200.00,19650.00,1550.00,21200.00,20000.00,1200.00,0 -21400.00,21100.00,300.00,21400.00,20300.00,1100.00,0 -21600.00,20400.00,1200.00,21600.00,20200.00,1400.00,0 -21800.00,20750.00,1050.00,21800.00,19950.00,1850.00,0 -22000.00,21450.00,550.00,22000.00,20850.00,1150.00,0 -22200.00,20850.00,1350.00,22200.00,20600.00,1600.00,0 -22400.00,21250.00,1150.00,22400.00,21950.00,450.00,0 -22600.00,22200.00,400.00,22600.00,21450.00,1150.00,0 -22800.00,22200.00,600.00,22800.00,21600.00,1200.00,0 -23000.00,21600.00,1400.00,23000.00,21400.00,1600.00,0 -23200.00,21950.00,1250.00,23200.00,21800.00,1400.00,0 -23400.00,22300.00,1100.00,23279.76,22300.00,979.76,0 -23600.00,22150.00,1450.00,23079.76,22350.00,729.76,0 -23760.91,27800.00,-4039.09,22879.76,27300.00,-4420.24,0 -23560.91,22100.00,1460.91,22679.76,20200.00,2479.76,0 -23360.91,20200.00,3160.91,22479.76,18450.00,4029.76,0 -23160.91,23500.00,-339.09,22279.76,23450.00,-1170.24,0 -22960.91,26200.00,-3239.09,22079.76,21900.00,179.76,0 -22760.91,22050.00,710.91,21879.76,19950.00,1929.76,0 -22560.91,20400.00,2160.91,21679.76,21900.00,-220.24,0 -22360.91,22450.00,-89.09,21479.76,23000.00,-1520.24,0 -22160.91,24950.00,-2789.09,21279.76,20900.00,379.76,0 -21960.91,21500.00,460.91,21079.76,18900.00,2179.76,0 -21760.91,19950.00,1810.91,20879.76,21600.00,-720.24,0 -21560.91,21600.00,-39.09,20679.76,20650.00,29.76,0 -21360.91,23100.00,-1739.09,20479.76,19150.00,1329.76,0 -21160.91,22350.00,-1189.09,20279.76,20600.00,-320.24,0 -20960.91,21300.00,-339.09,20079.76,21850.00,-1770.24,0 -20760.91,19850.00,910.91,19879.76,18250.00,1629.76,0 -20560.91,20100.00,460.91,19679.76,18150.00,1529.76,0 -20360.91,20550.00,-189.09,19479.76,20200.00,-720.24,0 -20160.91,20200.00,-39.09,19279.76,18250.00,1029.76,0 -19960.91,19550.00,410.91,19079.76,17600.00,1479.76,0 -19760.91,19450.00,310.91,18879.76,18800.00,79.76,0 -19560.91,19800.00,-239.09,18679.76,18300.00,379.76,0 -19360.91,19550.00,-189.09,18479.76,17100.00,1379.76,0 -19160.91,18600.00,560.91,18279.76,18100.00,179.76,0 -18960.91,18500.00,460.91,18079.76,18600.00,-520.24,0 -18760.91,18800.00,-39.09,17879.76,17000.00,879.76,0 -18560.91,18400.00,160.91,17679.76,17150.00,529.76,0 -18360.91,17800.00,560.91,17479.76,16950.00,529.76,0 -18160.91,16850.00,1310.91,17279.76,15850.00,1429.76,0 -17960.91,17100.00,860.91,17079.76,16550.00,529.76,0 -17760.91,18150.00,-389.09,16879.76,16800.00,79.76,0 -17560.91,17650.00,-89.09,16679.76,16450.00,229.76,0 -17360.91,16900.00,460.91,16479.76,16050.00,429.76,0 -17160.91,16950.00,210.91,16279.76,16000.00,279.76,0 -16960.91,16950.00,10.91,16079.76,15600.00,479.76,0 -16760.91,16550.00,210.91,15879.76,15600.00,279.76,0 -16560.91,16350.00,210.91,15679.76,15200.00,479.76,0 -16360.91,16300.00,60.91,15479.76,14900.00,579.76,0 -16160.91,15400.00,760.91,15279.76,14300.00,979.76,0 -15960.91,15200.00,760.91,15079.76,14400.00,679.76,0 -15760.91,15550.00,210.91,14879.76,14650.00,229.76,0 -15560.91,15050.00,510.91,14679.76,14650.00,29.76,0 -15360.91,15000.00,360.91,14479.76,14500.00,-20.24,0 -15160.91,15200.00,-39.09,14279.76,13850.00,429.76,0 -14960.91,14900.00,60.91,14079.76,13350.00,729.76,0 -14760.91,14700.00,60.91,13879.76,13400.00,479.76,0 -14560.91,14700.00,-139.09,13679.76,12800.00,879.76,0 -14360.91,14100.00,260.91,13479.76,13050.00,429.76,0 -14160.91,13150.00,1010.91,13279.76,13200.00,79.76,0 -13960.91,12800.00,1160.91,13079.76,12350.00,729.76,0 -13760.91,12700.00,1060.91,12879.76,12000.00,879.76,0 -13560.91,13200.00,360.91,12679.76,12200.00,479.76,0 -13360.91,13450.00,-89.09,12479.76,11900.00,579.76,0 -13160.91,12750.00,410.91,12279.76,11650.00,629.76,0 -12960.91,12650.00,310.91,12079.76,11450.00,629.76,0 -12760.91,12550.00,210.91,11879.76,11150.00,729.76,0 -12560.91,12200.00,360.91,11679.76,11450.00,229.76,0 -12360.91,11750.00,610.91,11479.76,10800.00,679.76,0 -12160.91,11450.00,710.91,11279.76,10600.00,679.76,0 -11960.91,11600.00,360.91,11079.76,10650.00,429.76,0 -11760.91,11600.00,160.91,10879.76,9650.00,1229.76,0 -11560.91,11100.00,460.91,10679.76,9850.00,829.76,0 -11360.91,10650.00,710.91,10479.76,9550.00,929.76,0 -11160.91,10250.00,910.91,10279.76,9150.00,1129.76,0 -10960.91,9550.00,1410.91,10079.76,8900.00,1179.76,0 -10760.91,9600.00,1160.91,9879.76,8800.00,1079.76,0 -10560.91,9450.00,1110.91,9679.76,8650.00,1029.76,0 -10360.91,9400.00,960.91,9479.76,8900.00,579.76,0 -10160.91,10000.00,160.91,9279.76,9100.00,179.76,0 -9960.91,9150.00,810.91,9079.76,8250.00,829.76,0 -9760.91,8600.00,1160.91,8879.76,7950.00,929.76,0 -9560.91,8600.00,960.91,8679.76,7750.00,929.76,0 -9360.91,8200.00,1160.91,8479.76,7400.00,1079.76,0 -9160.91,8200.00,960.91,8279.76,7150.00,1129.76,0 -8960.91,7900.00,1060.91,8079.76,6900.00,1179.76,0 -8760.91,8150.00,610.91,7879.76,7100.00,779.76,0 -8560.91,7950.00,610.91,7679.76,6850.00,829.76,0 -8360.91,7450.00,910.91,7479.76,6850.00,629.76,0 -8160.91,8700.00,-539.09,7279.76,7750.00,-470.24,0 -7960.91,6800.00,1160.91,7079.76,6250.00,829.76,0 -7760.91,5950.00,1810.91,6879.76,5350.00,1529.76,0 -7560.91,6550.00,1010.91,6679.76,6050.00,629.76,0 -7360.91,6100.00,1260.91,6479.76,5700.00,779.76,0 -7160.91,5850.00,1310.91,6279.76,5000.00,1279.76,0 -6960.91,6000.00,960.91,6079.76,5550.00,529.76,0 -6760.91,5600.00,1160.91,5879.76,5200.00,679.76,0 -6560.91,5300.00,1260.91,5679.76,4350.00,1329.76,0 -6360.91,5150.00,1210.91,5479.76,4600.00,879.76,0 -6160.91,5050.00,1110.91,5279.76,4550.00,729.76,0 -5960.91,4550.00,1410.91,5079.76,3950.00,1129.76,0 -5760.91,4500.00,1260.91,4879.76,3900.00,979.76,0 -5560.91,4250.00,1310.91,4679.76,3600.00,1079.76,0 -5360.91,4000.00,1360.91,4479.76,3300.00,1179.76,0 -5160.91,3650.00,1510.91,4279.76,3200.00,1079.76,0 -4960.91,3450.00,1510.91,4079.76,2900.00,1179.76,0 -4760.91,3300.00,1460.91,3879.76,2800.00,1079.76,0 -4560.91,3000.00,1560.91,3679.76,2400.00,1279.76,0 -4360.91,2850.00,1510.91,3479.76,2250.00,1229.76,0 -4160.91,2750.00,1410.91,3279.76,2350.00,929.76,0 -3960.91,2350.00,1610.91,3079.76,1300.00,1779.76,0 -3760.91,2350.00,1410.91,2879.76,1750.00,1129.76,0 -3560.91,2450.00,1110.91,2679.76,1900.00,779.76,0 -3360.91,1900.00,1460.91,2479.76,1050.00,1429.76,0 -3160.91,1650.00,1510.91,2279.76,500.00,1779.76,0 -2960.91,1600.00,1360.91,2079.76,150.00,1929.76,0 -2760.91,1550.00,1210.91,1879.76,400.00,1479.76,0 -2560.91,300.00,2260.91,1679.76,350.00,1329.76,0 -2360.91,200.00,2160.91,1479.76,-100.00,1579.76,0 -2160.91,2200.00,-39.09,1279.76,-200.00,1479.76,0 -1960.91,550.00,1410.91,1079.76,-600.00,1679.76,0 -1760.91,-1000.00,2760.91,879.76,-500.00,1379.76,0 -1560.91,250.00,1310.91,679.76,0.00,679.76,0 -1360.91,1100.00,260.91,479.76,0.00,479.76,0 -1160.91,-950.00,2110.91,279.76,0.00,279.76,0 -960.91,-450.00,1410.91,79.76,0.00,79.76,0 -760.91,650.00,110.91,0.00,0.00,0.00,0 -560.91,-800.00,1360.91,0.00,0.00,0.00,0 -360.91,50.00,310.91,0.00,0.00,0.00,0 -160.91,300.00,-139.09,0.00,0.00,0.00,0 -0.00,-150.00,150.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,290.55 -0.00,0.00,0.00,0.00,0.00,0.00,290.55 -0.00,0.00,0.00,0.00,0.00,0.00,290.55 -0.00,0.00,0.00,0.00,0.00,0.00,290.57 -0.00,0.00,0.00,0.00,0.00,0.00,290.56 -0.00,0.00,0.00,0.00,0.00,0.00,290.52 -0.00,0.00,0.00,0.00,0.00,0.00,290.51 -0.00,0.00,0.00,0.00,0.00,0.00,290.51 -0.00,0.00,0.00,0.00,0.00,0.00,290.55 -0.00,0.00,0.00,0.00,0.00,0.00,290.56 -0.00,0.00,0.00,0.00,0.00,0.00,290.57 -0.00,0.00,0.00,0.00,0.00,0.00,290.59 -0.00,0.00,0.00,0.00,0.00,0.00,290.60 -0.00,0.00,0.00,0.00,0.00,0.00,290.59 -0.00,0.00,0.00,0.00,0.00,0.00,290.55 -0.00,0.00,0.00,0.00,0.00,0.00,290.54 -0.00,0.00,0.00,0.00,0.00,0.00,290.54 -0.00,0.00,0.00,0.00,0.00,0.00,290.56 -0.00,0.00,0.00,0.00,0.00,0.00,290.56 --200.00,0.00,-200.00,-200.00,0.00,-200.00,290.53 --400.00,0.00,-400.00,-400.00,0.00,-400.00,290.58 --600.00,0.00,-600.00,-600.00,0.00,-600.00,290.56 --800.00,0.00,-800.00,-800.00,0.00,-800.00,290.56 --1000.00,0.00,-1000.00,-1000.00,0.00,-1000.00,290.53 --1200.00,0.00,-1200.00,-1200.00,0.00,-1200.00,290.47 --1400.00,0.00,-1400.00,-1400.00,0.00,-1400.00,290.47 --1600.00,0.00,-1600.00,-1600.00,0.00,-1600.00,290.48 --1800.00,-250.00,-1550.00,-1800.00,-150.00,-1650.00,290.49 --2000.00,-350.00,-1650.00,-2000.00,-250.00,-1750.00,290.47 --2200.00,0.00,-2200.00,-2200.00,0.00,-2200.00,290.52 --2400.00,-300.00,-2100.00,-2400.00,-200.00,-2200.00,290.52 --2600.00,-1050.00,-1550.00,-2600.00,-550.00,-2050.00,290.45 --2800.00,-2950.00,150.00,-2800.00,-1600.00,-1200.00,290.56 --3000.00,-3100.00,100.00,-3000.00,-2050.00,-950.00,290.48 --3200.00,-2000.00,-1200.00,-3200.00,-500.00,-2700.00,290.42 --3400.00,-1250.00,-2150.00,-3400.00,-1200.00,-2200.00,290.49 --3600.00,-2050.00,-1550.00,-3600.00,-3400.00,-200.00,290.49 --3800.00,-4150.00,350.00,-3800.00,-3900.00,100.00,290.42 --4000.00,-3900.00,-100.00,-4000.00,-2300.00,-1700.00,290.43 --4200.00,-2850.00,-1350.00,-4200.00,-1550.00,-2650.00,290.48 --4400.00,-1850.00,-2550.00,-4400.00,-2350.00,-2050.00,290.61 --4600.00,-4000.00,-600.00,-4600.00,-4550.00,-50.00,290.55 --4800.00,-5550.00,750.00,-4800.00,-4700.00,-100.00,290.58 --5000.00,-4100.00,-900.00,-5000.00,-3400.00,-1600.00,290.55 --5200.00,-3150.00,-2050.00,-5200.00,-2450.00,-2750.00,290.49 --5400.00,-4400.00,-1000.00,-5400.00,-3850.00,-1550.00,290.53 --5600.00,-6150.00,550.00,-5600.00,-6100.00,500.00,290.58 --5800.00,-5750.00,-50.00,-5800.00,-6150.00,350.00,290.59 --6000.00,-4300.00,-1700.00,-6000.00,-4750.00,-1250.00,290.59 --6200.00,-3900.00,-2300.00,-6200.00,-3750.00,-2450.00,290.71 --6400.00,-6300.00,-100.00,-6400.00,-4700.00,-1700.00,290.81 --6600.00,-7700.00,1100.00,-6600.00,-6750.00,150.00,290.77 --6800.00,-5850.00,-950.00,-6800.00,-7150.00,350.00,290.79 --7000.00,-4900.00,-2100.00,-7000.00,-5800.00,-1200.00,290.74 --7200.00,-6350.00,-850.00,-7200.00,-4800.00,-2400.00,290.68 --7400.00,-8450.00,1050.00,-7400.00,-5900.00,-1500.00,290.69 --7600.00,-8150.00,550.00,-7600.00,-8050.00,450.00,290.71 --7800.00,-6300.00,-1500.00,-7800.00,-8350.00,550.00,290.65 --8000.00,-5450.00,-2550.00,-8000.00,-6700.00,-1300.00,290.62 --8200.00,-8150.00,-50.00,-8200.00,-6150.00,-2050.00,290.63 --8400.00,-10550.00,2150.00,-8400.00,-7000.00,-1400.00,290.62 --8600.00,-9300.00,700.00,-8600.00,-8750.00,150.00,290.61 --8800.00,-7050.00,-1750.00,-8800.00,-9200.00,400.00,290.54 --9000.00,-6650.00,-2350.00,-9000.00,-8450.00,-550.00,290.49 --9200.00,-9600.00,400.00,-9200.00,-7150.00,-2050.00,290.49 --9400.00,-11300.00,1900.00,-9400.00,-7800.00,-1600.00,290.52 --9600.00,-9950.00,350.00,-9600.00,-10100.00,500.00,290.53 --9800.00,-8050.00,-1750.00,-9800.00,-10500.00,700.00,290.52 --10000.00,-8550.00,-1450.00,-10000.00,-9450.00,-550.00,290.43 --10200.00,-10400.00,200.00,-10200.00,-7950.00,-2250.00,290.44 --10400.00,-11150.00,750.00,-10400.00,-8950.00,-1450.00,290.46 --10600.00,-10800.00,200.00,-10600.00,-11050.00,450.00,290.40 --10800.00,-10100.00,-700.00,-10800.00,-11700.00,900.00,290.36 --11000.00,-10350.00,-650.00,-11000.00,-10900.00,-100.00,290.29 --11200.00,-10950.00,-250.00,-11200.00,-9000.00,-2200.00,290.25 --11400.00,-11600.00,200.00,-11400.00,-9950.00,-1450.00,290.24 --11600.00,-11650.00,50.00,-11600.00,-12100.00,500.00,290.17 --11800.00,-11150.00,-650.00,-11800.00,-12550.00,750.00,290.14 --12000.00,-11750.00,-250.00,-12000.00,-12300.00,300.00,290.05 --12200.00,-11950.00,-250.00,-12200.00,-11300.00,-900.00,289.96 --12400.00,-12200.00,-200.00,-12400.00,-11050.00,-1350.00,289.93 --12600.00,-12400.00,-200.00,-12600.00,-11950.00,-650.00,289.98 --12800.00,-12900.00,100.00,-12800.00,-13350.00,550.00,289.99 --13000.00,-12650.00,-350.00,-13000.00,-13050.00,50.00,289.99 --13200.00,-12700.00,-500.00,-13200.00,-12600.00,-600.00,289.95 --13400.00,-13700.00,300.00,-13400.00,-12850.00,-550.00,290.02 --13600.00,-14100.00,500.00,-13600.00,-13350.00,-250.00,290.06 --13800.00,-13950.00,150.00,-13800.00,-13700.00,-100.00,290.09 --14000.00,-13400.00,-600.00,-14000.00,-13300.00,-700.00,290.09 --14200.00,-14300.00,100.00,-14200.00,-14000.00,-200.00,290.11 --14400.00,-14600.00,200.00,-14400.00,-14050.00,-350.00,290.14 --14600.00,-14400.00,-200.00,-14600.00,-14100.00,-500.00,290.14 --14800.00,-15000.00,200.00,-14800.00,-14750.00,-50.00,290.15 --15000.00,-14850.00,-150.00,-15000.00,-14600.00,-400.00,290.17 --15200.00,-15600.00,400.00,-15200.00,-14900.00,-300.00,290.19 --15400.00,-15350.00,-50.00,-15400.00,-14700.00,-700.00,290.24 --15600.00,-17950.00,2350.00,-15600.00,-17450.00,1850.00,290.28 --15800.00,-14700.00,-1100.00,-15800.00,-15050.00,-750.00,290.27 --16000.00,-12700.00,-3300.00,-16000.00,-14550.00,-1450.00,290.33 --16200.00,-16650.00,450.00,-16200.00,-15400.00,-800.00,290.39 --16400.00,-20900.00,4500.00,-16400.00,-16850.00,450.00,290.48 --16600.00,-17600.00,1000.00,-16600.00,-16700.00,100.00,290.51 --16800.00,-14000.00,-2800.00,-16800.00,-16950.00,150.00,290.55 --17000.00,-15800.00,-1200.00,-17000.00,-16900.00,-100.00,290.57 --17200.00,-21000.00,3800.00,-17200.00,-16850.00,-350.00,290.62 --17400.00,-19950.00,2550.00,-17400.00,-16650.00,-750.00,290.62 --17600.00,-15100.00,-2500.00,-17600.00,-17950.00,350.00,290.54 --17800.00,-14950.00,-2850.00,-17800.00,-18550.00,750.00,290.45 --18000.00,-20800.00,2800.00,-18000.00,-18350.00,350.00,290.33 --18200.00,-21250.00,3050.00,-18200.00,-17250.00,-950.00,290.26 --18400.00,-15000.00,-3400.00,-18400.00,-17500.00,-900.00,290.26 --18600.00,-14000.00,-4600.00,-18600.00,-19400.00,800.00,290.18 --18800.00,-23150.00,4350.00,-18800.00,-20250.00,1450.00,290.13 --19000.00,-26850.00,7850.00,-19000.00,-19550.00,550.00,290.06 --19200.00,-16400.00,-2800.00,-19200.00,-18150.00,-1050.00,290.00 --19400.00,-10250.00,-9150.00,-19400.00,-18800.00,-600.00,289.96 --19600.00,-21400.00,1800.00,-19600.00,-19650.00,50.00,290.08 --19800.00,-32250.00,12450.00,-19800.00,-22050.00,2250.00,289.97 --20000.00,-20450.00,450.00,-20000.00,-19700.00,-300.00,290.21 --20200.00,-10800.00,-9400.00,-20200.00,-19250.00,-950.00,290.08 --20400.00,-14900.00,-5500.00,-20400.00,-20400.00,0.00,289.84 --20600.00,-29600.00,9000.00,-20600.00,-23350.00,2750.00,289.97 --20800.00,-29950.00,9150.00,-20800.00,-19900.00,-900.00,290.20 --21000.00,-14000.00,-7000.00,-21000.00,-18300.00,-2700.00,290.13 --21200.00,-11800.00,-9400.00,-21200.00,-20050.00,-1150.00,290.32 --21400.00,-23950.00,2550.00,-21400.00,-24400.00,3000.00,290.31 --21600.00,-33050.00,11450.00,-21600.00,-23950.00,2350.00,290.52 --21800.00,-24950.00,3150.00,-21800.00,-20200.00,-1600.00,290.56 --22000.00,-12000.00,-10000.00,-22000.00,-19300.00,-2700.00,290.36 --22200.00,-16750.00,-5450.00,-22200.00,-22400.00,200.00,290.44 --22400.00,-30150.00,7750.00,-22400.00,-26700.00,4300.00,290.48 --22600.00,-32100.00,9500.00,-22600.00,-21700.00,-900.00,290.50 --22800.00,-21300.00,-1500.00,-22800.00,-17300.00,-5500.00,290.51 --23000.00,-14750.00,-8250.00,-23000.00,-21500.00,-1500.00,290.56 --23200.00,-22350.00,-850.00,-23200.00,-29550.00,6350.00,290.69 --23400.00,-29700.00,6300.00,-23400.00,-29050.00,5650.00,290.60 --23600.00,-28050.00,4450.00,-23600.00,-19650.00,-3950.00,290.50 --23800.00,-20700.00,-3100.00,-23554.83,-17150.00,-6404.83,290.43 --23916.18,-19800.00,-4116.18,-23354.83,-25150.00,1795.17,290.52 --23716.18,-27050.00,3333.82,-23154.83,-32750.00,9595.17,290.43 --23516.18,-28350.00,4833.82,-22954.83,-27050.00,4095.17,290.35 --23316.18,-23100.00,-216.18,-22754.83,-14550.00,-8204.83,290.28 --23116.18,-19000.00,-4116.18,-22554.83,-13300.00,-9254.83,290.41 --22916.18,-24000.00,1083.82,-22354.83,-28400.00,6045.17,290.30 --22716.18,-26100.00,3383.82,-22154.83,-33500.00,11345.17,290.15 --22516.18,-22750.00,233.82,-21954.83,-22500.00,545.17,290.19 --22316.18,-20050.00,-2266.18,-21754.83,-9200.00,-12554.83,289.99 --22116.18,-22500.00,383.82,-21554.83,-13500.00,-8054.83,290.29 --21916.18,-25700.00,3783.82,-21354.83,-29400.00,8045.17,290.45 --21716.18,-22700.00,983.82,-21154.83,-32000.00,10845.17,290.32 --21516.18,-20200.00,-1316.18,-20954.83,-18650.00,-2304.83,290.21 --21316.18,-20450.00,-866.18,-20754.83,-7050.00,-13704.83,290.18 --21116.18,-22400.00,1283.82,-20554.83,-14700.00,-5854.83,290.39 --20916.18,-23600.00,2683.82,-20354.83,-29250.00,8895.17,290.50 --20716.18,-20650.00,-66.18,-20154.83,-29300.00,9145.17,290.39 --20516.18,-20200.00,-316.18,-19954.83,-16050.00,-3904.83,290.32 --20316.18,-21600.00,1283.82,-19754.83,-7700.00,-12054.83,290.49 --20116.18,-20650.00,533.82,-19554.83,-16600.00,-2954.83,290.54 --19916.18,-21250.00,1333.82,-19354.83,-31000.00,11645.17,290.60 --19716.18,-20300.00,583.82,-19154.83,-27250.00,8095.17,290.47 --19516.18,-22400.00,2883.82,-18954.83,-10300.00,-8654.83,290.46 --19316.18,-18900.00,-416.18,-18754.83,-4350.00,-14404.83,290.71 --19116.18,-18550.00,-566.18,-18554.83,-19600.00,1045.17,290.75 --18916.18,-18300.00,-616.18,-18354.83,-29800.00,11445.17,290.69 --18716.18,-19450.00,733.82,-18154.83,-24200.00,6045.17,290.53 --18516.18,-19250.00,733.82,-17954.83,-8450.00,-9504.83,290.51 --18316.18,-19650.00,1333.82,-17754.83,-9050.00,-8704.83,290.59 --18116.18,-19150.00,1033.82,-17554.83,-22800.00,5245.17,290.57 --17916.18,-17650.00,-266.18,-17354.83,-29200.00,11845.17,290.46 --17716.18,-17500.00,-216.18,-17154.83,-19400.00,2245.17,290.31 --17516.18,-18150.00,633.82,-16954.83,-3600.00,-13354.83,290.36 --17316.18,-17950.00,633.82,-16754.83,-5950.00,-10804.83,290.35 --17116.18,-17850.00,733.82,-16554.83,-21650.00,5095.17,290.32 --16916.18,-16450.00,-466.18,-16354.83,-28850.00,12495.17,290.17 --16716.18,-16700.00,-16.18,-16154.83,-19150.00,2995.17,290.05 --16516.18,-17100.00,583.82,-15954.83,-2400.00,-13554.83,290.09 --16316.18,-16750.00,433.82,-15754.83,-3650.00,-12104.83,290.17 --16116.18,-16150.00,33.82,-15554.83,-19250.00,3695.17,290.24 --15916.18,-15900.00,-16.18,-15354.83,-27800.00,12445.17,290.26 --15716.18,-15800.00,83.82,-15154.83,-17400.00,2245.17,290.12 --15516.18,-16000.00,483.82,-14954.83,-1750.00,-13204.83,290.00 --15316.18,-15800.00,483.82,-14754.83,-3300.00,-11454.83,290.11 --15116.18,-16000.00,883.82,-14554.83,-19250.00,4695.17,290.19 --14916.18,-14950.00,33.82,-14354.83,-27700.00,13345.17,290.12 --14716.18,-14400.00,-316.18,-14154.83,-17000.00,2845.17,290.15 --14516.18,-14450.00,-66.18,-13954.83,500.00,-14454.83,290.22 --14316.18,-14450.00,133.82,-13754.83,-1700.00,-12054.83,290.35 --14116.18,-14400.00,283.82,-13554.83,-17350.00,3795.17,290.41 --13916.18,-13600.00,-316.18,-13354.83,-25550.00,12195.17,290.28 --13716.18,-14050.00,333.82,-13154.83,-16500.00,3345.17,290.18 --13516.18,-13700.00,183.82,-12954.83,-800.00,-12154.83,290.16 --13316.18,-13550.00,233.82,-12754.83,-3650.00,-9104.83,290.27 --13116.18,-13400.00,283.82,-12554.83,-18300.00,5745.17,290.41 --12916.18,-12550.00,-366.18,-12354.83,-23200.00,10845.17,290.38 --12716.18,-12700.00,-16.18,-12154.83,-11750.00,-404.83,290.33 --12516.18,-13200.00,683.82,-11954.83,-200.00,-11754.83,290.45 --12316.18,-13050.00,733.82,-11754.83,-6000.00,-5754.83,290.57 --12116.18,-12700.00,583.82,-11554.83,-19750.00,8195.17,290.62 --11916.18,-11450.00,-466.18,-11354.83,-20350.00,8995.17,290.54 --11716.18,-11450.00,-266.18,-11154.83,-5850.00,-5304.83,290.53 --11516.18,-12700.00,1183.82,-10954.83,1850.00,-12804.83,290.44 --11316.18,-11500.00,183.82,-10754.83,-10000.00,-754.83,290.59 --11116.18,-9700.00,-1416.18,-10554.83,-22800.00,12245.17,290.62 --10916.18,-9750.00,-1166.18,-10354.83,-16900.00,6545.17,290.49 --10716.18,-11350.00,633.82,-10154.83,-300.00,-9854.83,290.43 --10516.18,-11400.00,883.82,-9954.83,700.00,-10654.83,290.54 --10316.18,-10750.00,433.82,-9754.83,-14000.00,4245.17,290.71 --10116.18,-8300.00,-1816.18,-9554.83,-21750.00,12195.17,290.62 --9916.18,-8600.00,-1316.18,-9354.83,-13750.00,4395.17,290.54 --9716.18,-10050.00,333.82,-9154.83,1500.00,-10654.83,290.57 --9516.18,-10450.00,933.82,-8954.83,-1400.00,-7554.83,290.64 --9316.18,-9900.00,583.82,-8754.83,-15150.00,6395.17,290.63 --9116.18,-7750.00,-1366.18,-8554.83,-19250.00,10695.17,290.46 --8916.18,-6950.00,-1966.18,-8354.83,-6300.00,-2054.83,290.37 --8716.18,-8700.00,-16.18,-8154.83,4400.00,-12554.83,290.31 --8516.18,-9850.00,1333.82,-7954.83,-3550.00,-4404.83,290.45 --8316.18,-9450.00,1133.82,-7754.83,-17150.00,9395.17,290.44 --8116.18,-7250.00,-866.18,-7554.83,-15400.00,7845.17,290.34 --7916.18,-6400.00,-1516.18,-7354.83,-300.00,-7054.83,290.33 --7716.18,-7300.00,-416.18,-7154.83,3700.00,-10854.83,290.40 --7516.18,-8050.00,533.82,-6954.83,-8150.00,1195.17,290.53 --7316.18,-7500.00,183.82,-6754.83,-17500.00,10745.17,290.46 --7116.18,-6150.00,-966.18,-6554.83,-10700.00,4145.17,290.24 --6916.18,-5350.00,-1566.18,-6354.83,3150.00,-9504.83,290.18 --6716.18,-6150.00,-566.18,-6154.83,700.00,-6854.83,290.37 --6516.18,-8100.00,1583.82,-5954.83,-15300.00,9345.17,290.38 --6316.18,-6600.00,283.82,-5754.83,-15900.00,10145.17,290.27 --6116.18,-5300.00,-816.18,-5554.83,-50.00,-5504.83,289.98 --5916.18,-4650.00,-1266.18,-5354.83,7000.00,-12354.83,289.97 --5716.18,-5100.00,-616.18,-5154.83,-4950.00,-204.83,289.98 --5516.18,-5300.00,-216.18,-4954.83,-16000.00,11045.17,290.03 --5316.18,-4950.00,-366.18,-4754.83,-9450.00,4695.17,289.89 --5116.18,-4000.00,-1116.18,-4554.83,5300.00,-9854.83,289.82 --4916.18,-3250.00,-1666.18,-4354.83,3300.00,-7654.83,289.92 --4716.18,-3900.00,-816.18,-4154.83,-10000.00,5845.17,289.99 --4516.18,-4600.00,83.82,-3954.83,-14450.00,10495.17,289.97 --4316.18,-4700.00,383.82,-3754.83,-2250.00,-1504.83,289.78 --4116.18,-3650.00,-466.18,-3554.83,7450.00,-11004.83,289.76 --3916.18,-2650.00,-1266.18,-3354.83,500.00,-3854.83,289.97 --3716.18,-2100.00,-1616.18,-3154.83,-12450.00,9295.17,290.00 --3516.18,-3100.00,-416.18,-2954.83,-10450.00,7495.17,289.96 --3316.18,-3300.00,-16.18,-2754.83,4500.00,-7254.83,289.95 --3116.18,-2500.00,-616.18,-2554.83,7400.00,-9954.83,290.09 --2916.18,-750.00,-2166.18,-2354.83,-6600.00,4245.17,290.07 --2716.18,-850.00,-1866.18,-2154.83,-14900.00,12745.17,290.01 --2516.18,-3650.00,1133.82,-1954.83,-2950.00,995.17,289.95 --2316.18,-3750.00,1433.82,-1754.83,9950.00,-11704.83,289.94 --2116.18,-2100.00,-16.18,-1554.83,4900.00,-6454.83,290.11 --1916.18,-1700.00,-216.18,-1354.83,-10300.00,8945.17,290.24 --1716.18,50.00,-1766.18,-1154.83,-11400.00,10245.17,290.10 --1516.18,150.00,-1666.18,-954.83,4100.00,-5054.83,290.14 --1316.18,-650.00,-666.18,-754.83,11200.00,-11954.83,290.28 --1116.18,200.00,-1316.18,-554.83,-1000.00,445.17,290.46 --916.18,950.00,-1866.18,-354.83,-12600.00,12245.17,290.43 --716.18,-550.00,-166.18,-154.83,-6250.00,6095.17,290.40 --516.18,-100.00,-416.18,0.00,8950.00,-8950.00,290.40 --316.18,500.00,-816.18,0.00,9300.00,-9300.00,290.49 --116.18,-150.00,33.82,0.00,-5900.00,5900.00,290.53 -0.00,0.00,0.00,0.00,-11500.00,11500.00,290.51 -0.00,0.00,0.00,0.00,1750.00,-1750.00,290.56 -0.00,0.00,0.00,0.00,12150.00,-12150.00,290.49 -0.00,0.00,0.00,0.00,6700.00,-6700.00,290.66 -0.00,0.00,0.00,0.00,-6100.00,6100.00,290.79 -0.00,0.00,0.00,0.00,-8200.00,8200.00,290.70 -0.00,0.00,0.00,0.00,3700.00,-3700.00,290.56 -0.00,0.00,0.00,0.00,9650.00,-9650.00,290.56 -0.00,0.00,0.00,0.00,650.00,-650.00,290.53 -0.00,0.00,0.00,0.00,-9150.00,9150.00,290.59 -0.00,0.00,0.00,0.00,-4650.00,4650.00,290.48 -0.00,0.00,0.00,0.00,7200.00,-7200.00,290.36 -0.00,0.00,0.00,0.00,6600.00,-6600.00,290.44 -0.00,0.00,0.00,0.00,-4900.00,4900.00,290.52 -0.00,0.00,0.00,0.00,-7850.00,7850.00,290.32 -0.00,0.00,0.00,0.00,1200.00,-1200.00,290.22 -0.00,0.00,0.00,0.00,8850.00,-8850.00,290.23 -0.00,0.00,0.00,0.00,4500.00,-4500.00,290.24 -0.00,0.00,0.00,0.00,-7100.00,7100.00,290.37 -0.00,0.00,0.00,0.00,-6200.00,6200.00,290.20 -0.00,0.00,0.00,0.00,4800.00,-4800.00,290.27 -0.00,0.00,0.00,0.00,7600.00,-7600.00,290.38 -0.00,0.00,0.00,0.00,-2450.00,2450.00,290.39 -0.00,0.00,0.00,0.00,-8550.00,8550.00,290.37 -0.00,0.00,0.00,0.00,-1250.00,1250.00,290.18 -0.00,0.00,0.00,0.00,7650.00,-7650.00,290.21 -0.00,0.00,0.00,0.00,4000.00,-4000.00,290.32 -0.00,0.00,0.00,0.00,-6100.00,6100.00,290.42 -0.00,0.00,0.00,0.00,-5100.00,5100.00,290.37 -0.00,0.00,0.00,0.00,3900.00,-3900.00,290.27 -0.00,0.00,0.00,0.00,5700.00,-5700.00,290.32 -0.00,0.00,0.00,0.00,-1100.00,1100.00,290.35 -0.00,0.00,0.00,0.00,-6300.00,6300.00,290.33 -0.00,0.00,0.00,0.00,-2800.00,2800.00,290.22 -0.00,0.00,0.00,0.00,4500.00,-4500.00,290.28 -0.00,0.00,0.00,0.00,3300.00,-3300.00,290.36 -0.00,0.00,0.00,0.00,-2100.00,2100.00,290.40 -0.00,0.00,0.00,0.00,-2950.00,2950.00,290.37 -0.00,0.00,0.00,0.00,-150.00,150.00,290.35 -0.00,0.00,0.00,0.00,1200.00,-1200.00,290.37 -0.00,0.00,0.00,0.00,1200.00,-1200.00,290.36 -0.00,0.00,0.00,0.00,0.00,0.00,290.38 -0.00,0.00,0.00,0.00,-50.00,50.00,290.32 -0.00,0.00,0.00,0.00,0.00,0.00,290.33 -0.00,0.00,0.00,0.00,0.00,0.00,290.31 -0.00,0.00,0.00,0.00,0.00,0.00,290.29 -0.00,0.00,0.00,0.00,0.00,0.00,290.30 -0.00,0.00,0.00,0.00,0.00,0.00,290.28 -0.00,0.00,0.00,0.00,0.00,0.00,290.28 -0.00,0.00,0.00,0.00,0.00,0.00,290.34 -0.00,0.00,0.00,0.00,0.00,0.00,290.39 -0.00,0.00,0.00,0.00,0.00,0.00,290.45 -0.00,0.00,0.00,0.00,0.00,0.00,290.42 -0.00,0.00,0.00,0.00,0.00,0.00,290.40 -0.00,0.00,0.00,0.00,0.00,0.00,290.40 -0.00,0.00,0.00,0.00,0.00,0.00,290.38 -0.00,0.00,0.00,0.00,0.00,0.00,290.34 -0.00,0.00,0.00,0.00,0.00,0.00,290.29 -0.00,0.00,0.00,0.00,0.00,0.00,290.27 -0.00,0.00,0.00,0.00,0.00,0.00,290.20 -0.00,0.00,0.00,0.00,0.00,0.00,290.12 -0.00,0.00,0.00,0.00,0.00,0.00,290.11 -0.00,0.00,0.00,0.00,0.00,0.00,290.08 -0.00,0.00,0.00,0.00,0.00,0.00,290.08 -0.00,0.00,0.00,0.00,0.00,0.00,290.10 -0.00,0.00,0.00,0.00,0.00,0.00,290.08 -0.00,0.00,0.00,0.00,0.00,0.00,290.11 -0.00,0.00,0.00,0.00,0.00,0.00,290.14 -0.00,0.00,0.00,0.00,0.00,0.00,290.12 -0.00,0.00,0.00,0.00,0.00,0.00,290.13 -0.00,0.00,0.00,0.00,0.00,0.00,290.15 -0.00,0.00,0.00,0.00,0.00,0.00,290.15 -0.00,0.00,0.00,0.00,0.00,0.00,290.18 -0.00,0.00,0.00,0.00,0.00,0.00,290.23 -0.00,0.00,0.00,0.00,0.00,0.00,290.25 -0.00,0.00,0.00,0.00,0.00,0.00,290.26 -0.00,0.00,0.00,0.00,0.00,0.00,290.28 -0.00,0.00,0.00,0.00,0.00,0.00,290.28 -0.00,0.00,0.00,0.00,0.00,0.00,290.28 -0.00,0.00,0.00,0.00,0.00,0.00,290.23 -0.00,0.00,0.00,0.00,0.00,0.00,290.21 -0.00,0.00,0.00,0.00,0.00,0.00,290.21 -0.00,0.00,0.00,0.00,0.00,0.00,290.26 -0.00,0.00,0.00,0.00,0.00,0.00,290.25 -0.00,0.00,0.00,0.00,0.00,0.00,290.23 -0.00,0.00,0.00,0.00,0.00,0.00,290.22 -0.00,0.00,0.00,0.00,0.00,0.00,290.18 -0.00,0.00,0.00,0.00,0.00,0.00,290.18 -0.00,0.00,0.00,0.00,0.00,0.00,290.23 -0.00,0.00,0.00,0.00,0.00,0.00,290.23 -0.00,0.00,0.00,0.00,0.00,0.00,290.21 -0.00,0.00,0.00,0.00,0.00,0.00,290.22 -0.00,0.00,0.00,0.00,0.00,0.00,290.25 -0.00,0.00,0.00,0.00,0.00,0.00,290.29 -0.00,0.00,0.00,0.00,0.00,0.00,290.30 -0.00,0.00,0.00,0.00,0.00,0.00,290.30 -0.00,0.00,0.00,0.00,0.00,0.00,290.32 -0.00,0.00,0.00,0.00,0.00,0.00,290.32 -0.00,0.00,0.00,0.00,0.00,0.00,290.30 -0.00,0.00,0.00,0.00,0.00,0.00,290.26 -0.00,0.00,0.00,0.00,0.00,0.00,290.25 -0.00,0.00,0.00,0.00,0.00,0.00,290.24 -0.00,0.00,0.00,0.00,0.00,0.00,290.23 -0.00,0.00,0.00,0.00,0.00,0.00,290.25 -0.00,0.00,0.00,0.00,0.00,0.00,290.20 -0.00,0.00,0.00,0.00,0.00,0.00,290.22 -0.00,0.00,0.00,0.00,0.00,0.00,290.20 -0.00,0.00,0.00,0.00,0.00,0.00,290.15 -0.00,0.00,0.00,0.00,0.00,0.00,290.19 -0.00,0.00,0.00,0.00,0.00,0.00,290.15 -0.00,0.00,0.00,0.00,0.00,0.00,290.17 -0.00,0.00,0.00,0.00,0.00,0.00,290.17 -0.00,0.00,0.00,0.00,0.00,0.00,290.19 -0.00,0.00,0.00,0.00,0.00,0.00,290.19 -0.00,0.00,0.00,0.00,0.00,0.00,290.20 -0.00,0.00,0.00,0.00,0.00,0.00,290.23 -0.00,0.00,0.00,0.00,0.00,0.00,290.21 -0.00,0.00,0.00,0.00,0.00,0.00,290.21 -0.00,0.00,0.00,0.00,0.00,0.00,290.20 -0.00,0.00,0.00,0.00,0.00,0.00,290.21 -0.00,0.00,0.00,0.00,0.00,0.00,290.20 -0.00,0.00,0.00,0.00,0.00,0.00,290.24 -0.00,0.00,0.00,0.00,0.00,0.00,290.23 -0.00,0.00,0.00,0.00,0.00,0.00,290.24 -0.00,0.00,0.00,0.00,0.00,0.00,290.27 -0.00,0.00,0.00,0.00,0.00,0.00,290.25 -0.00,0.00,0.00,0.00,0.00,0.00,290.27 -0.00,0.00,0.00,0.00,0.00,0.00,290.31 -0.00,0.00,0.00,0.00,0.00,0.00,290.32 -0.00,0.00,0.00,0.00,0.00,0.00,290.33 -0.00,0.00,0.00,0.00,0.00,0.00,290.31 -0.00,0.00,0.00,0.00,0.00,0.00,290.31 -0.00,0.00,0.00,0.00,0.00,0.00,290.29 -0.00,0.00,0.00,0.00,0.00,0.00,290.31 -0.00,0.00,0.00,0.00,0.00,0.00,290.38 -0.00,0.00,0.00,0.00,0.00,0.00,290.37 -0.00,0.00,0.00,0.00,0.00,0.00,290.38 -0.00,0.00,0.00,0.00,0.00,0.00,290.36 -0.00,0.00,0.00,0.00,0.00,0.00,290.30 -0.00,0.00,0.00,0.00,0.00,0.00,290.27 -0.00,0.00,0.00,0.00,0.00,0.00,290.25 -0.00,0.00,0.00,0.00,0.00,0.00,290.23 -0.00,0.00,0.00,0.00,0.00,0.00,290.27 -0.00,0.00,0.00,0.00,0.00,0.00,290.26 -0.00,0.00,0.00,0.00,0.00,0.00,290.23 -0.00,0.00,0.00,0.00,0.00,0.00,290.24 -0.00,0.00,0.00,0.00,0.00,0.00,290.23 -0.00,0.00,0.00,0.00,0.00,0.00,290.23 -0.00,0.00,0.00,0.00,0.00,0.00,290.24 -0.00,0.00,0.00,0.00,0.00,0.00,290.29 -0.00,0.00,0.00,0.00,0.00,0.00,290.32 -0.00,0.00,0.00,0.00,0.00,0.00,290.28 -0.00,0.00,0.00,0.00,0.00,0.00,290.30 -0.00,0.00,0.00,0.00,0.00,0.00,290.32 -0.00,0.00,0.00,0.00,0.00,0.00,290.27 -0.00,0.00,0.00,0.00,0.00,0.00,290.23 -0.00,0.00,0.00,0.00,0.00,0.00,290.25 -0.00,0.00,0.00,0.00,0.00,0.00,290.23 -0.00,0.00,0.00,0.00,0.00,0.00,290.21 -0.00,0.00,0.00,0.00,0.00,0.00,290.15 -0.00,0.00,0.00,0.00,0.00,0.00,290.13 -0.00,0.00,0.00,0.00,0.00,0.00,290.15 -0.00,0.00,0.00,0.00,0.00,0.00,290.16 -0.00,0.00,0.00,0.00,0.00,0.00,290.14 -200.00,0.00,200.00,200.00,0.00,200.00,290.08 -400.00,0.00,400.00,400.00,0.00,400.00,290.10 -600.00,0.00,600.00,600.00,0.00,600.00,290.09 -800.00,0.00,800.00,800.00,0.00,800.00,290.05 -1000.00,0.00,1000.00,1000.00,0.00,1000.00,290.09 -1200.00,0.00,1200.00,1200.00,0.00,1200.00,290.06 -1400.00,0.00,1400.00,1400.00,0.00,1400.00,290.03 -1600.00,0.00,1600.00,1600.00,0.00,1600.00,290.04 -1800.00,150.00,1650.00,1800.00,150.00,1650.00,290.00 -2000.00,250.00,1750.00,2000.00,150.00,1850.00,289.99 -2200.00,100.00,2100.00,2200.00,50.00,2150.00,289.96 -2400.00,200.00,2200.00,2400.00,150.00,2250.00,289.90 -2600.00,850.00,1750.00,2600.00,550.00,2050.00,289.92 -2800.00,2650.00,150.00,2800.00,1300.00,1500.00,289.99 -3000.00,2800.00,200.00,3000.00,2300.00,700.00,289.97 -3200.00,900.00,2300.00,3200.00,2050.00,1150.00,289.93 -3400.00,50.00,3350.00,3400.00,450.00,2950.00,289.98 -3600.00,3600.00,0.00,3600.00,150.00,3450.00,289.89 -3800.00,6100.00,-2300.00,3800.00,2850.00,950.00,289.90 -4000.00,4100.00,-100.00,4000.00,5100.00,-1100.00,289.89 -4200.00,2500.00,1700.00,4200.00,3850.00,350.00,289.94 -4400.00,1600.00,2800.00,4400.00,2350.00,2050.00,289.95 -4600.00,4350.00,250.00,4600.00,1600.00,3000.00,289.89 -4800.00,6150.00,-1350.00,4800.00,3850.00,950.00,289.89 -5000.00,4400.00,600.00,5000.00,6000.00,-1000.00,289.86 -5200.00,2800.00,2400.00,5200.00,5350.00,-150.00,289.84 -5400.00,2700.00,2700.00,5400.00,3800.00,1600.00,289.94 -5600.00,6250.00,-650.00,5600.00,3000.00,2600.00,289.90 -5800.00,7600.00,-1800.00,5800.00,4300.00,1500.00,289.90 -6000.00,5700.00,300.00,6000.00,6100.00,-100.00,289.97 -6200.00,4550.00,1650.00,6200.00,6050.00,150.00,289.97 -6400.00,4200.00,2200.00,6400.00,4650.00,1750.00,290.05 -6600.00,6150.00,450.00,6600.00,3800.00,2800.00,290.10 -6800.00,7350.00,-550.00,6800.00,5400.00,1400.00,290.08 -7000.00,6900.00,100.00,7000.00,8000.00,-1000.00,290.06 -7200.00,5600.00,1600.00,7200.00,7900.00,-700.00,290.14 -7400.00,5000.00,2400.00,7400.00,6050.00,1350.00,290.17 -7600.00,7300.00,300.00,7600.00,5150.00,2450.00,290.24 -7800.00,8750.00,-950.00,7800.00,6150.00,1650.00,290.26 -8000.00,8000.00,0.00,8000.00,8150.00,-150.00,290.27 -8200.00,7050.00,1150.00,8200.00,8600.00,-400.00,290.28 -8400.00,7400.00,1000.00,8400.00,6850.00,1550.00,290.31 -8600.00,8250.00,350.00,8600.00,5650.00,2950.00,290.26 -8800.00,8600.00,200.00,8800.00,7300.00,1500.00,290.25 -9000.00,8600.00,400.00,9000.00,10100.00,-1100.00,290.28 -9200.00,8650.00,550.00,9200.00,9800.00,-600.00,290.33 -9400.00,8850.00,550.00,9400.00,7800.00,1600.00,290.42 -9600.00,9300.00,300.00,9600.00,7000.00,2600.00,290.46 -9800.00,9950.00,-150.00,9800.00,8950.00,850.00,290.46 -10000.00,10050.00,-50.00,10000.00,11250.00,-1250.00,290.50 -10200.00,9850.00,350.00,10200.00,11000.00,-800.00,290.55 -10400.00,9900.00,500.00,10400.00,8400.00,2000.00,290.63 -10600.00,9950.00,650.00,10600.00,7700.00,2900.00,290.60 -10800.00,10550.00,250.00,10800.00,9950.00,850.00,290.55 -11000.00,11300.00,-300.00,11000.00,13150.00,-2150.00,290.51 -11200.00,10900.00,300.00,11200.00,12050.00,-850.00,290.50 -11400.00,11250.00,150.00,11400.00,10000.00,1400.00,290.52 -11600.00,11100.00,500.00,11600.00,9500.00,2100.00,290.50 -11800.00,11400.00,400.00,11800.00,10700.00,1100.00,290.49 -12000.00,12300.00,-300.00,12000.00,13050.00,-1050.00,290.51 -12200.00,12550.00,-350.00,12200.00,13100.00,-900.00,290.46 -12400.00,11950.00,450.00,12400.00,11600.00,800.00,290.49 -12600.00,12300.00,300.00,12600.00,11550.00,1050.00,290.49 -12800.00,12600.00,200.00,12800.00,11650.00,1150.00,290.52 -13000.00,12900.00,100.00,13000.00,12450.00,550.00,290.55 -13200.00,13150.00,50.00,13200.00,13100.00,100.00,290.59 -13400.00,13350.00,50.00,13400.00,13300.00,100.00,290.57 -13600.00,13400.00,200.00,13600.00,13150.00,450.00,290.52 -13800.00,14000.00,-200.00,13800.00,13600.00,200.00,290.50 -14000.00,13750.00,250.00,14000.00,13300.00,700.00,290.47 -14200.00,13800.00,400.00,14200.00,13500.00,700.00,290.44 -14400.00,14150.00,250.00,14400.00,13850.00,550.00,290.40 -14600.00,14550.00,50.00,14600.00,14150.00,450.00,290.38 -14800.00,14850.00,-50.00,14800.00,14400.00,400.00,290.33 -15000.00,14850.00,150.00,15000.00,14500.00,500.00,290.29 -15200.00,15500.00,-300.00,15200.00,15200.00,0.00,290.26 -15400.00,15150.00,250.00,15400.00,14850.00,550.00,290.23 -15600.00,15150.00,450.00,15600.00,14650.00,950.00,290.19 -15800.00,16200.00,-400.00,15800.00,15850.00,-50.00,290.10 -16000.00,16600.00,-600.00,16000.00,16500.00,-500.00,290.06 -16200.00,16200.00,0.00,16200.00,16450.00,-250.00,290.06 -16400.00,18900.00,-2500.00,16400.00,18550.00,-2150.00,290.05 -16600.00,15350.00,1250.00,16600.00,15300.00,1300.00,289.96 -16800.00,12400.00,4400.00,16800.00,14050.00,2750.00,289.91 -17000.00,16750.00,250.00,17000.00,16100.00,900.00,289.98 -17200.00,21950.00,-4750.00,17200.00,19600.00,-2400.00,289.98 -17400.00,19750.00,-2350.00,17400.00,19700.00,-2300.00,290.04 -17600.00,14800.00,2800.00,17600.00,17300.00,300.00,289.99 -17800.00,15850.00,1950.00,17800.00,16200.00,1600.00,290.04 -18000.00,20450.00,-2450.00,18000.00,16200.00,1800.00,290.00 -18200.00,21550.00,-3350.00,18200.00,18200.00,0.00,290.10 -18400.00,18300.00,100.00,18400.00,20150.00,-1750.00,290.16 -18600.00,14200.00,4400.00,18600.00,19800.00,-1200.00,290.23 -18800.00,17350.00,1450.00,18800.00,17900.00,900.00,290.41 -19000.00,24250.00,-5250.00,19000.00,17300.00,1700.00,290.35 -19200.00,22150.00,-2950.00,19200.00,19400.00,-200.00,290.38 -19400.00,16150.00,3250.00,19400.00,21050.00,-1650.00,290.33 -19600.00,17150.00,2450.00,19600.00,20600.00,-1000.00,290.36 -19800.00,24350.00,-4550.00,19800.00,19400.00,400.00,290.39 -20000.00,24650.00,-4650.00,20000.00,19000.00,1000.00,290.37 -20200.00,16750.00,3450.00,20200.00,19850.00,350.00,290.32 -20400.00,14950.00,5450.00,20400.00,21150.00,-750.00,290.37 -20600.00,24600.00,-4000.00,20600.00,21700.00,-1100.00,290.37 -20800.00,28500.00,-7700.00,20800.00,21000.00,-200.00,290.30 -21000.00,18150.00,2850.00,21000.00,20500.00,500.00,290.27 -21200.00,11850.00,9350.00,21200.00,20400.00,800.00,290.18 -21400.00,23900.00,-2500.00,21400.00,21700.00,-300.00,290.39 -21600.00,33200.00,-11600.00,21600.00,23300.00,-1700.00,290.34 -21800.00,21600.00,200.00,21800.00,21550.00,250.00,290.28 -22000.00,13150.00,8850.00,22000.00,20800.00,1200.00,290.10 -22200.00,17750.00,4450.00,22200.00,21400.00,800.00,290.47 -22400.00,28950.00,-6550.00,22400.00,24200.00,-1800.00,290.61 -22600.00,30100.00,-7500.00,22600.00,22850.00,-250.00,290.19 -22800.00,20950.00,1850.00,22800.00,21900.00,900.00,290.06 -23000.00,17400.00,5600.00,23000.00,21800.00,1200.00,290.14 -23200.00,25550.00,-2350.00,23200.00,23900.00,-700.00,290.13 -23400.00,33300.00,-9900.00,23400.00,25900.00,-2500.00,290.03 -23600.00,23450.00,150.00,23600.00,24100.00,-500.00,290.11 -23800.00,13350.00,10450.00,23800.00,22800.00,1000.00,289.96 -24000.00,22600.00,1400.00,24000.00,22700.00,1300.00,290.33 -24200.00,33700.00,-9500.00,23954.34,26200.00,-2245.66,290.44 -24370.48,27000.00,-2629.52,23754.34,24500.00,-745.66,290.16 -24170.48,18850.00,5320.48,23554.34,23550.00,4.34,290.21 -23970.48,20300.00,3670.48,23354.34,23200.00,154.34,290.52 -23770.48,28200.00,-4429.52,23154.34,23850.00,-695.66,290.60 -23570.48,29000.00,-5429.52,22954.34,24050.00,-1095.66,290.53 -23370.48,20700.00,2670.48,22754.34,23650.00,-895.66,290.51 -23170.48,20150.00,3020.48,22554.34,23050.00,-495.66,290.57 -22970.48,26050.00,-3079.52,22354.34,23000.00,-645.66,290.58 -22770.48,26450.00,-3679.52,22154.34,22650.00,-495.66,290.53 -22570.48,23150.00,-579.52,21954.34,22650.00,-695.66,290.42 -22370.48,20850.00,1520.48,21754.34,22550.00,-795.66,290.48 -22170.48,22800.00,-629.52,21554.34,21800.00,-245.66,290.55 -21970.48,25150.00,-3179.52,21354.34,21750.00,-395.66,290.35 -21770.48,23950.00,-2179.52,21154.34,21850.00,-695.66,290.40 -21570.48,21000.00,570.48,20954.34,21750.00,-795.66,290.22 -21370.48,20600.00,770.48,20754.34,21350.00,-595.66,290.14 -21170.48,22500.00,-1329.52,20554.34,20750.00,-195.66,290.08 -20970.48,23600.00,-2629.52,20354.34,20750.00,-395.66,289.98 -20770.48,21700.00,-929.52,20154.34,20700.00,-545.66,290.00 -20570.48,20000.00,570.48,19954.34,20750.00,-795.66,289.95 -20370.48,20600.00,-229.52,19754.34,20650.00,-895.66,289.94 -20170.48,22100.00,-1929.52,19554.34,20100.00,-545.66,289.94 -19970.48,21900.00,-1929.52,19354.34,19550.00,-195.66,289.96 -19770.48,20200.00,-429.52,19154.34,19250.00,-95.66,289.98 -19570.48,19400.00,170.48,18954.34,19450.00,-495.66,290.06 -19370.48,20200.00,-829.52,18754.34,19450.00,-695.66,290.13 -19170.48,20900.00,-1729.52,18554.34,19100.00,-545.66,290.21 -18970.48,23200.00,-4229.52,18354.34,21750.00,-3395.66,290.30 -18770.48,17550.00,1220.48,18154.34,17150.00,1004.34,290.39 -18570.48,14500.00,4070.48,17954.34,14600.00,3354.34,290.43 -18370.48,19650.00,-1279.52,17754.34,16900.00,854.34,290.47 -18170.48,24950.00,-6779.52,17554.34,21200.00,-3645.66,290.52 -17970.48,21250.00,-3279.52,17354.34,21150.00,-3795.66,290.56 -17770.48,14450.00,3320.48,17154.34,15200.00,1954.34,290.63 -17570.48,13600.00,3970.48,16954.34,12650.00,4304.34,290.71 -17370.48,21700.00,-4329.52,16754.34,17150.00,-395.66,290.68 -17170.48,24050.00,-6879.52,16554.34,21450.00,-4895.66,290.64 -16970.48,15300.00,1670.48,16354.34,20200.00,-3845.66,290.66 -16770.48,8950.00,7820.48,16154.34,15100.00,1054.34,290.61 -16570.48,17400.00,-829.52,15954.34,12400.00,3554.34,290.79 -16370.48,28400.00,-12029.52,15754.34,15000.00,754.34,290.59 -16170.48,18650.00,-2479.52,15554.34,18200.00,-2645.66,290.46 -15970.48,3750.00,12220.48,15354.34,18000.00,-2645.66,290.46 -15770.48,9750.00,6020.48,15154.34,13650.00,1504.34,290.71 -15570.48,27100.00,-11529.52,14954.34,13600.00,1354.34,290.95 -15370.48,24100.00,-8729.52,14754.34,12600.00,2154.34,290.46 -15170.48,6200.00,8970.48,14554.34,14550.00,4.34,290.18 -14970.48,4150.00,10820.48,14354.34,15800.00,-1445.66,290.55 -14770.48,18050.00,-3279.52,14154.34,15950.00,-1795.66,290.58 -14570.48,26200.00,-11629.52,13954.34,13400.00,554.34,290.52 -14370.48,15050.00,-679.52,13754.34,11150.00,2604.34,290.33 -14170.48,4350.00,9820.48,13554.34,12150.00,1404.34,290.46 -13970.48,9000.00,4970.48,13354.34,15050.00,-1695.66,290.45 -13770.48,18250.00,-4479.52,13154.34,15100.00,-1945.66,290.46 -13570.48,22850.00,-9279.52,12954.34,10750.00,2204.34,290.27 -13370.48,13800.00,-429.52,12754.34,10150.00,2604.34,290.32 -13170.48,3900.00,9270.48,12554.34,12650.00,-95.66,290.22 -12970.48,9550.00,3420.48,12354.34,14700.00,-2345.66,290.20 -12770.48,17500.00,-4729.52,12154.34,14000.00,-1845.66,290.39 -12570.48,19800.00,-7229.52,11954.34,10250.00,1704.34,290.30 -12370.48,12750.00,-379.52,11754.34,9200.00,2554.34,290.30 -12170.48,6550.00,5620.48,11554.34,11100.00,454.34,290.43 -11970.48,9500.00,2470.48,11354.34,13450.00,-2095.66,290.37 -11770.48,16950.00,-5179.52,11154.34,13100.00,-1945.66,290.46 -11570.48,14600.00,-3029.52,10954.34,9950.00,1004.34,290.64 -11370.48,8500.00,2870.48,10754.34,8800.00,1954.34,290.54 -11170.48,9900.00,1270.48,10554.34,9600.00,954.34,290.53 -10970.48,14150.00,-3179.52,10354.34,11550.00,-1195.66,290.45 -10770.48,13350.00,-2579.52,10154.34,11000.00,-845.66,290.40 -10570.48,9850.00,720.48,9954.34,9050.00,904.34,290.47 -10370.48,8350.00,2020.48,9754.34,7900.00,1854.34,290.53 -10170.48,9900.00,270.48,9554.34,8600.00,954.34,290.56 -9970.48,12500.00,-2529.52,9354.34,10350.00,-995.66,290.51 -9770.48,11400.00,-1629.52,9154.34,9950.00,-795.66,290.61 -9570.48,9100.00,470.48,8954.34,8100.00,854.34,290.64 -9370.48,7650.00,1720.48,8754.34,6950.00,1804.34,290.65 -9170.48,8900.00,270.48,8554.34,7750.00,804.34,290.68 -8970.48,11100.00,-2129.52,8354.34,9150.00,-795.66,290.66 -8770.48,10200.00,-1429.52,8154.34,9050.00,-895.66,290.71 -8570.48,8100.00,470.48,7954.34,7200.00,754.34,290.71 -8370.48,7000.00,1370.48,7754.34,5950.00,1804.34,290.71 -8170.48,8100.00,70.48,7554.34,6550.00,1004.34,290.70 -7970.48,8800.00,-829.52,7354.34,7700.00,-345.66,290.69 -7770.48,8350.00,-579.52,7154.34,7950.00,-795.66,290.65 -7570.48,6750.00,820.48,6954.34,6150.00,804.34,290.65 -7370.48,6100.00,1270.48,6754.34,5300.00,1454.34,290.72 -7170.48,7150.00,20.48,6554.34,5550.00,1004.34,290.62 -6970.48,7250.00,-279.52,6354.34,6250.00,104.34,290.63 -6770.48,6050.00,720.48,6154.34,6150.00,4.34,290.61 -6570.48,5450.00,1120.48,5954.34,4850.00,1104.34,290.64 -6370.48,6050.00,320.48,5754.34,4150.00,1604.34,290.59 -6170.48,6400.00,-229.52,5554.34,4550.00,1004.34,290.58 -5970.48,6150.00,-179.52,5354.34,5250.00,104.34,290.56 -5770.48,5050.00,720.48,5154.34,5250.00,-95.66,290.55 -5570.48,5200.00,370.48,4954.34,4500.00,454.34,290.51 -5370.48,4300.00,1070.48,4754.34,2500.00,2254.34,290.45 -5170.48,3850.00,1320.48,4554.34,2150.00,2404.34,290.40 -4970.48,4400.00,570.48,4354.34,4550.00,-195.66,290.44 -4770.48,4650.00,120.48,4154.34,5550.00,-1395.66,290.40 -4570.48,3850.00,720.48,3954.34,4450.00,-495.66,290.37 -4370.48,2850.00,1520.48,3754.34,3300.00,454.34,290.45 -4170.48,2600.00,1570.48,3554.34,2500.00,1054.34,290.43 -3970.48,3300.00,670.48,3354.34,700.00,2654.34,290.44 -3770.48,3950.00,-179.52,3154.34,200.00,2954.34,290.39 -3570.48,3100.00,470.48,2954.34,3400.00,-445.66,290.42 -3370.48,2450.00,920.48,2754.34,5000.00,-2245.66,290.47 -3170.48,850.00,2320.48,2554.34,3950.00,-1395.66,290.42 -2970.48,1050.00,1920.48,2354.34,2750.00,-395.66,290.40 -2770.48,3350.00,-579.52,2154.34,1500.00,654.34,290.43 -2570.48,4000.00,-1429.52,1954.34,0.00,1954.34,290.39 -2370.48,3050.00,-679.52,1754.34,100.00,1654.34,290.34 -2170.48,1850.00,320.48,1554.34,1700.00,-145.66,290.35 -1970.48,1250.00,720.48,1354.34,1600.00,-245.66,290.29 -1770.48,800.00,970.48,1154.34,0.00,1154.34,290.30 -1570.48,-550.00,2120.48,954.34,-250.00,1204.34,290.38 -1370.48,550.00,820.48,754.34,-750.00,1504.34,290.38 -1170.48,500.00,670.48,554.34,-550.00,1104.34,290.28 -970.48,-1100.00,2070.48,354.34,50.00,304.34,290.25 -770.48,350.00,420.48,154.34,50.00,104.34,290.24 -570.48,700.00,-129.52,0.00,0.00,0.00,290.17 -370.48,-1050.00,1420.48,0.00,0.00,0.00,290.12 -170.48,50.00,120.48,0.00,0.00,0.00,290.15 -0.00,250.00,-250.00,0.00,0.00,0.00,290.17 -0.00,-100.00,100.00,0.00,0.00,0.00,290.12 -0.00,0.00,0.00,0.00,0.00,0.00,290.13 -0.00,0.00,0.00,0.00,0.00,0.00,290.12 -0.00,0.00,0.00,0.00,0.00,0.00,290.12 -0.00,0.00,0.00,0.00,0.00,0.00,290.13 -0.00,0.00,0.00,0.00,0.00,0.00,290.12 -0.00,0.00,0.00,0.00,0.00,0.00,290.11 -0.00,0.00,0.00,0.00,0.00,0.00,290.11 -0.00,0.00,0.00,0.00,0.00,0.00,290.08 -0.00,0.00,0.00,0.00,0.00,0.00,290.07 -0.00,0.00,0.00,0.00,0.00,0.00,290.07 -0.00,0.00,0.00,0.00,0.00,0.00,290.12 -0.00,0.00,0.00,0.00,0.00,0.00,290.14 -0.00,0.00,0.00,0.00,0.00,0.00,290.09 -0.00,0.00,0.00,0.00,0.00,0.00,290.07 -0.00,0.00,0.00,0.00,0.00,0.00,290.08 -0.00,0.00,0.00,0.00,0.00,0.00,290.13 -0.00,0.00,0.00,0.00,0.00,0.00,290.16 -0.00,0.00,0.00,0.00,0.00,0.00,290.17 -0.00,0.00,0.00,0.00,0.00,0.00,290.17 -0.00,0.00,0.00,0.00,0.00,0.00,290.16 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 --200.00,0.00,-200.00,-200.00,0.00,-200.00,0 --400.00,0.00,-400.00,-400.00,0.00,-400.00,0 --600.00,0.00,-600.00,-600.00,0.00,-600.00,0 --800.00,0.00,-800.00,-800.00,0.00,-800.00,0 --1000.00,0.00,-1000.00,-1000.00,0.00,-1000.00,0 --1200.00,0.00,-1200.00,-1200.00,0.00,-1200.00,0 --1400.00,0.00,-1400.00,-1400.00,0.00,-1400.00,0 --1600.00,0.00,-1600.00,-1600.00,0.00,-1600.00,0 --1800.00,-250.00,-1550.00,-1800.00,-150.00,-1650.00,0 --2000.00,-350.00,-1650.00,-2000.00,-250.00,-1750.00,0 --2200.00,-50.00,-2150.00,-2200.00,-100.00,-2100.00,0 --2400.00,-250.00,-2150.00,-2400.00,-150.00,-2250.00,0 --2600.00,-950.00,-1650.00,-2600.00,-450.00,-2150.00,0 --2800.00,-2650.00,-150.00,-2800.00,-1400.00,-1400.00,0 --3000.00,-2650.00,-350.00,-3000.00,-2400.00,-600.00,0 --3200.00,-1550.00,-1650.00,-3200.00,-2050.00,-1150.00,0 --3400.00,-2050.00,-1350.00,-3400.00,-500.00,-2900.00,0 --3600.00,-2900.00,-700.00,-3600.00,-100.00,-3500.00,0 --3800.00,-2900.00,-900.00,-3800.00,-2700.00,-1100.00,0 --4000.00,-1750.00,-2250.00,-4000.00,-4700.00,700.00,0 --4200.00,-1850.00,-2350.00,-4200.00,-3950.00,-250.00,0 --4400.00,-4350.00,-50.00,-4400.00,-2950.00,-1450.00,0 --4600.00,-5300.00,700.00,-4600.00,-2300.00,-2300.00,0 --4800.00,-3900.00,-900.00,-4800.00,-2800.00,-2000.00,0 --5000.00,-3150.00,-1850.00,-5000.00,-4250.00,-750.00,0 --5200.00,-4150.00,-1050.00,-5200.00,-4700.00,-500.00,0 --5400.00,-4900.00,-500.00,-5400.00,-4200.00,-1200.00,0 --5600.00,-4700.00,-900.00,-5600.00,-3400.00,-2200.00,0 --5800.00,-4050.00,-1750.00,-5800.00,-3800.00,-2000.00,0 --6000.00,-4900.00,-1100.00,-6000.00,-5050.00,-950.00,0 --6200.00,-6250.00,50.00,-6200.00,-5950.00,-250.00,0 --6400.00,-5800.00,-600.00,-6400.00,-5300.00,-1100.00,0 --6600.00,-5050.00,-1550.00,-6600.00,-4700.00,-1900.00,0 --6800.00,-5750.00,-1050.00,-6800.00,-5200.00,-1600.00,0 --7000.00,-6900.00,-100.00,-7000.00,-6000.00,-1000.00,0 --7200.00,-6700.00,-500.00,-7200.00,-6600.00,-600.00,0 --7400.00,-5700.00,-1700.00,-7400.00,-6600.00,-800.00,0 --7600.00,-6100.00,-1500.00,-7600.00,-6200.00,-1400.00,0 --7800.00,-7600.00,-200.00,-7800.00,-6800.00,-1000.00,0 --8000.00,-8250.00,250.00,-8000.00,-7200.00,-800.00,0 --8200.00,-7450.00,-750.00,-8200.00,-7400.00,-800.00,0 --8400.00,-6400.00,-2000.00,-8400.00,-7600.00,-800.00,0 --8600.00,-7450.00,-1150.00,-8600.00,-7700.00,-900.00,0 --8800.00,-9200.00,400.00,-8800.00,-7900.00,-900.00,0 --9000.00,-8950.00,-50.00,-9000.00,-8200.00,-800.00,0 --9200.00,-7450.00,-1750.00,-9200.00,-8350.00,-850.00,0 --9400.00,-7900.00,-1500.00,-9400.00,-8650.00,-750.00,0 --9600.00,-9500.00,-100.00,-9600.00,-8850.00,-750.00,0 --9800.00,-9850.00,50.00,-9800.00,-8950.00,-850.00,0 --10000.00,-9650.00,-350.00,-10000.00,-9200.00,-800.00,0 --10200.00,-9600.00,-600.00,-10200.00,-9400.00,-800.00,0 --10400.00,-9750.00,-650.00,-10400.00,-9650.00,-750.00,0 --10600.00,-10050.00,-550.00,-10600.00,-9950.00,-650.00,0 --10800.00,-10350.00,-450.00,-10800.00,-10100.00,-700.00,0 --11000.00,-10600.00,-400.00,-11000.00,-10300.00,-700.00,0 --11200.00,-10850.00,-350.00,-11200.00,-10600.00,-600.00,0 --11400.00,-10950.00,-450.00,-11400.00,-10800.00,-600.00,0 --11600.00,-11100.00,-500.00,-11600.00,-10950.00,-650.00,0 --11800.00,-11300.00,-500.00,-11800.00,-11200.00,-600.00,0 --12000.00,-11650.00,-350.00,-12000.00,-11400.00,-600.00,0 --12200.00,-11900.00,-300.00,-12200.00,-11650.00,-550.00,0 --12400.00,-12000.00,-400.00,-12400.00,-11900.00,-500.00,0 --12600.00,-12100.00,-500.00,-12600.00,-12100.00,-500.00,0 --12800.00,-12350.00,-450.00,-12800.00,-12300.00,-500.00,0 --13000.00,-12800.00,-200.00,-13000.00,-12500.00,-500.00,0 --13200.00,-13050.00,-150.00,-13200.00,-12550.00,-650.00,0 --13400.00,-13550.00,150.00,-13400.00,-13250.00,-150.00,0 --13600.00,-13100.00,-500.00,-13600.00,-12900.00,-700.00,0 --13800.00,-13850.00,50.00,-13800.00,-13400.00,-400.00,0 --14000.00,-13700.00,-300.00,-14000.00,-13200.00,-800.00,0 --14200.00,-13900.00,-300.00,-14200.00,-13300.00,-900.00,0 --14400.00,-14150.00,-250.00,-14400.00,-13800.00,-600.00,0 --14600.00,-14300.00,-300.00,-14600.00,-14200.00,-400.00,0 --14800.00,-14450.00,-350.00,-14800.00,-14300.00,-500.00,0 --15000.00,-14850.00,-150.00,-15000.00,-14450.00,-550.00,0 --15200.00,-15850.00,650.00,-15200.00,-15050.00,-150.00,0 --15400.00,-15350.00,-50.00,-15400.00,-14650.00,-750.00,0 --15600.00,-18400.00,2800.00,-15600.00,-17950.00,2350.00,0 --15800.00,-14200.00,-1600.00,-15800.00,-14000.00,-1800.00,0 --16000.00,-12250.00,-3750.00,-16000.00,-12100.00,-3900.00,0 --16200.00,-16000.00,-200.00,-16200.00,-15000.00,-1200.00,0 --16400.00,-20350.00,3950.00,-16400.00,-18900.00,2500.00,0 --16600.00,-17300.00,700.00,-16600.00,-17450.00,850.00,0 --16800.00,-14000.00,-2800.00,-16800.00,-14500.00,-2300.00,0 --17000.00,-15100.00,-1900.00,-17000.00,-14050.00,-2950.00,0 --17200.00,-20100.00,2900.00,-17200.00,-17250.00,50.00,0 --17400.00,-19900.00,2500.00,-17400.00,-19450.00,2050.00,0 --17600.00,-14900.00,-2700.00,-17600.00,-18800.00,1200.00,0 --17800.00,-14500.00,-3300.00,-17800.00,-16500.00,-1300.00,0 --18000.00,-19450.00,1450.00,-18000.00,-16050.00,-1950.00,0 --18200.00,-22300.00,4100.00,-18200.00,-17950.00,-250.00,0 --18400.00,-18050.00,-350.00,-18400.00,-18600.00,200.00,0 --18600.00,-15050.00,-3550.00,-18600.00,-19400.00,800.00,0 --18800.00,-17400.00,-1400.00,-18800.00,-18200.00,-600.00,0 --19000.00,-22850.00,3850.00,-19000.00,-18650.00,-350.00,0 --19200.00,-21000.00,1800.00,-19200.00,-19150.00,-50.00,0 --19400.00,-15650.00,-3750.00,-19400.00,-18800.00,-600.00,0 --19600.00,-16950.00,-2650.00,-19600.00,-19000.00,-600.00,0 --19800.00,-23700.00,3900.00,-19800.00,-20150.00,350.00,0 --20000.00,-23400.00,3400.00,-20000.00,-20400.00,400.00,0 --20200.00,-16050.00,-4150.00,-20200.00,-19550.00,-650.00,0 --20400.00,-14800.00,-5600.00,-20400.00,-19400.00,-1000.00,0 --20600.00,-24300.00,3700.00,-20600.00,-20900.00,300.00,0 --20800.00,-27050.00,6250.00,-20800.00,-21400.00,600.00,0 --21000.00,-18500.00,-2500.00,-21000.00,-21000.00,0.00,0 --21200.00,-15500.00,-5700.00,-21200.00,-19950.00,-1250.00,0 --21400.00,-22800.00,1400.00,-21400.00,-20150.00,-1250.00,0 --21600.00,-29700.00,8100.00,-21600.00,-22150.00,550.00,0 --21800.00,-22800.00,1000.00,-21800.00,-21950.00,150.00,0 --22000.00,-14350.00,-7650.00,-22000.00,-21550.00,-450.00,0 --22200.00,-19050.00,-3150.00,-22200.00,-22050.00,-150.00,0 --22400.00,-30950.00,8550.00,-22400.00,-22800.00,400.00,0 --22600.00,-27650.00,5050.00,-22600.00,-22100.00,-500.00,0 --22800.00,-15300.00,-7500.00,-22800.00,-22100.00,-700.00,0 --23000.00,-16300.00,-6700.00,-23000.00,-21800.00,-1200.00,0 --23200.00,-30250.00,7050.00,-23200.00,-23650.00,450.00,0 --23400.00,-27950.00,4550.00,-23400.00,-23550.00,150.00,0 --23600.00,-20100.00,-3500.00,-23600.00,-22400.00,-1200.00,0 --23800.00,-21100.00,-2700.00,-23800.00,-23700.00,-100.00,0 --24000.00,-26100.00,2100.00,-23928.70,-24500.00,571.30,0 --24200.00,-25100.00,900.00,-23728.70,-24400.00,671.30,0 --24092.89,-24150.00,57.11,-23528.70,-23900.00,371.30,0 --23892.89,-23600.00,-292.89,-23328.70,-22900.00,-428.70,0 --23692.89,-25550.00,1857.11,-23128.70,-23700.00,571.30,0 --23492.89,-24750.00,1257.11,-22928.70,-23300.00,371.30,0 --23292.89,-24100.00,807.11,-22728.70,-23850.00,1121.30,0 --23092.89,-23250.00,157.11,-22528.70,-23350.00,821.30,0 --22892.89,-22350.00,-542.89,-22328.70,-21950.00,-378.70,0 --22692.89,-23450.00,757.11,-22128.70,-22500.00,371.30,0 --22492.89,-24350.00,1857.11,-21928.70,-22700.00,771.30,0 --22292.89,-22900.00,607.11,-21728.70,-21650.00,-78.70,0 --22092.89,-22650.00,557.11,-21528.70,-22050.00,521.30,0 --21892.89,-22600.00,707.11,-21328.70,-21950.00,621.30,0 --21692.89,-22400.00,707.11,-21128.70,-21550.00,421.30,0 --21492.89,-21450.00,-42.89,-20928.70,-20250.00,-678.70,0 --21292.89,-21350.00,57.11,-20728.70,-20100.00,-628.70,0 --21092.89,-22550.00,1457.11,-20528.70,-21400.00,871.30,0 --20892.89,-22500.00,1607.11,-20328.70,-21300.00,971.30,0 --20692.89,-20600.00,-92.89,-20128.70,-19800.00,-328.70,0 --20492.89,-20050.00,-442.89,-19928.70,-19100.00,-828.70,0 --20292.89,-21350.00,1057.11,-19728.70,-20200.00,471.30,0 --20092.89,-21200.00,1107.11,-19528.70,-19900.00,371.30,0 --19892.89,-21200.00,1307.11,-19328.70,-20200.00,871.30,0 --19692.89,-19700.00,7.11,-19128.70,-18900.00,-228.70,0 --19492.89,-19250.00,-242.89,-18928.70,-18500.00,-428.70,0 --19292.89,-19400.00,107.11,-18728.70,-18600.00,-128.70,0 --19092.89,-19850.00,757.11,-18528.70,-18800.00,271.30,0 --18892.89,-19650.00,757.11,-18328.70,-18600.00,271.30,0 --18692.89,-19300.00,607.11,-18128.70,-18250.00,121.30,0 --18492.89,-18900.00,407.11,-17928.70,-17950.00,21.30,0 --18292.89,-22000.00,3707.11,-17728.70,-21000.00,3271.30,0 --18092.89,-17050.00,-1042.89,-17528.70,-16500.00,-1028.70,0 --17892.89,-14200.00,-3692.89,-17328.70,-14150.00,-3178.70,0 --17692.89,-17500.00,-192.89,-17128.70,-15850.00,-1278.70,0 --17492.89,-21900.00,4407.11,-16928.70,-19550.00,2621.30,0 --17292.89,-18900.00,1607.11,-16728.70,-18200.00,1471.30,0 --17092.89,-14600.00,-2492.89,-16528.70,-14650.00,-1878.70,0 --16892.89,-15400.00,-1492.89,-16328.70,-14700.00,-1628.70,0 --16692.89,-19850.00,3157.11,-16128.70,-17000.00,871.30,0 --16492.89,-18450.00,1957.11,-15928.70,-16850.00,921.30,0 --16292.89,-14100.00,-2192.89,-15728.70,-16150.00,421.30,0 --16092.89,-14300.00,-1792.89,-15528.70,-15550.00,21.30,0 --15892.89,-17600.00,1707.11,-15328.70,-14850.00,-478.70,0 --15692.89,-18300.00,2607.11,-15128.70,-14700.00,-428.70,0 --15492.89,-15550.00,57.11,-14928.70,-14950.00,21.30,0 --15292.89,-12650.00,-2642.89,-14728.70,-15000.00,271.30,0 --15092.89,-14400.00,-692.89,-14528.70,-14600.00,71.30,0 --14892.89,-17300.00,2407.11,-14328.70,-14150.00,-178.70,0 --14692.89,-16150.00,1457.11,-14128.70,-13850.00,-278.70,0 --14492.89,-12550.00,-1942.89,-13928.70,-13750.00,-178.70,0 --14292.89,-12900.00,-1392.89,-13728.70,-13550.00,-178.70,0 --14092.89,-16050.00,1957.11,-13528.70,-13850.00,321.30,0 --13892.89,-15300.00,1407.11,-13328.70,-13100.00,-228.70,0 --13692.89,-12000.00,-1692.89,-13128.70,-12600.00,-528.70,0 --13492.89,-12050.00,-1442.89,-12928.70,-12500.00,-428.70,0 --13292.89,-14350.00,1057.11,-12728.70,-12500.00,-228.70,0 --13092.89,-15000.00,1907.11,-12528.70,-12500.00,-28.70,0 --12892.89,-13000.00,107.11,-12328.70,-12200.00,-128.70,0 --12692.89,-10600.00,-2092.89,-12128.70,-11950.00,-178.70,0 --12492.89,-11700.00,-792.89,-11928.70,-11650.00,-278.70,0 --12292.89,-14150.00,1857.11,-11728.70,-11600.00,-128.70,0 --12092.89,-13500.00,1407.11,-11528.70,-11300.00,-228.70,0 --11892.89,-9650.00,-2242.89,-11328.70,-10700.00,-628.70,0 --11692.89,-9400.00,-2292.89,-11128.70,-11050.00,-78.70,0 --11492.89,-12850.00,1357.11,-10928.70,-11000.00,71.30,0 --11292.89,-12800.00,1507.11,-10728.70,-10350.00,-378.70,0 --11092.89,-9950.00,-1142.89,-10528.70,-10400.00,-128.70,0 --10892.89,-8700.00,-2192.89,-10328.70,-10300.00,-28.70,0 --10692.89,-10750.00,57.11,-10128.70,-10000.00,-128.70,0 --10492.89,-12500.00,2007.11,-9928.70,-9650.00,-278.70,0 --10292.89,-10950.00,657.11,-9728.70,-9350.00,-378.70,0 --10092.89,-8650.00,-1442.89,-9528.70,-8850.00,-678.70,0 --9892.89,-9250.00,-642.89,-9328.70,-9150.00,-178.70,0 --9692.89,-10600.00,907.11,-9128.70,-9200.00,71.30,0 --9492.89,-9850.00,357.11,-8928.70,-8850.00,-78.70,0 --9292.89,-8250.00,-1042.89,-8728.70,-8350.00,-378.70,0 --9092.89,-8550.00,-542.89,-8528.70,-8200.00,-328.70,0 --8892.89,-9500.00,607.11,-8328.70,-8300.00,-28.70,0 --8692.89,-8700.00,7.11,-8128.70,-7800.00,-328.70,0 --8492.89,-7550.00,-942.89,-7928.70,-7600.00,-328.70,0 --8292.89,-7600.00,-692.89,-7728.70,-7450.00,-278.70,0 --8092.89,-8200.00,107.11,-7528.70,-7250.00,-278.70,0 --7892.89,-8200.00,307.11,-7328.70,-7150.00,-178.70,0 --7692.89,-7600.00,-92.89,-7128.70,-6850.00,-278.70,0 --7492.89,-6650.00,-842.89,-6928.70,-6750.00,-178.70,0 --7292.89,-6750.00,-542.89,-6728.70,-6500.00,-228.70,0 --7092.89,-7000.00,-92.89,-6528.70,-6250.00,-278.70,0 --6892.89,-6800.00,-92.89,-6328.70,-6100.00,-228.70,0 --6692.89,-5700.00,-992.89,-6128.70,-5750.00,-378.70,0 --6492.89,-5300.00,-1192.89,-5928.70,-4950.00,-978.70,0 --6292.89,-6200.00,-92.89,-5728.70,-5000.00,-728.70,0 --6092.89,-6200.00,107.11,-5528.70,-5250.00,-278.70,0 --5892.89,-5000.00,-892.89,-5328.70,-5000.00,-328.70,0 --5692.89,-4400.00,-1292.89,-5128.70,-4000.00,-1128.70,0 --5492.89,-5500.00,7.11,-4928.70,-3650.00,-1278.70,0 --5292.89,-5550.00,257.11,-4728.70,-4100.00,-628.70,0 --5092.89,-4750.00,-342.89,-4528.70,-4100.00,-428.70,0 --4892.89,-4000.00,-892.89,-4328.70,-3400.00,-928.70,0 --4692.89,-3500.00,-1192.89,-4128.70,-2650.00,-1478.70,0 --4492.89,-4300.00,-192.89,-3928.70,-3150.00,-778.70,0 --4292.89,-4450.00,157.11,-3728.70,-3100.00,-628.70,0 --4092.89,-3400.00,-692.89,-3528.70,-2450.00,-1078.70,0 --3892.89,-2950.00,-942.89,-3328.70,-2000.00,-1328.70,0 --3692.89,-2200.00,-1492.89,-3128.70,-2550.00,-578.70,0 --3492.89,-2050.00,-1442.89,-2928.70,-2400.00,-528.70,0 --3292.89,-3400.00,107.11,-2728.70,-2100.00,-628.70,0 --3092.89,-3100.00,7.11,-2528.70,-300.00,-2228.70,0 --2892.89,-2450.00,-442.89,-2328.70,200.00,-2528.70,0 --2692.89,-1250.00,-1442.89,-2128.70,-1550.00,-578.70,0 --2492.89,-1900.00,-592.89,-1928.70,-2650.00,721.30,0 --2292.89,-1800.00,-492.89,-1728.70,-1950.00,221.30,0 --2092.89,-1600.00,-492.89,-1528.70,-850.00,-678.70,0 --1892.89,300.00,-2192.89,-1328.70,450.00,-1778.70,0 --1692.89,100.00,-1792.89,-1128.70,400.00,-1528.70,0 --1492.89,-1100.00,-392.89,-928.70,-200.00,-728.70,0 --1292.89,-1200.00,-92.89,-728.70,250.00,-978.70,0 --1092.89,-1300.00,207.11,-528.70,50.00,-578.70,0 --892.89,400.00,-1292.89,-328.70,0.00,-328.70,0 --692.89,450.00,-1142.89,-128.70,0.00,-128.70,0 --492.89,-200.00,-292.89,0.00,0.00,0.00,0 --292.89,0.00,-292.89,0.00,0.00,0.00,0 --92.89,0.00,-92.89,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -200.00,0.00,200.00,200.00,0.00,200.00,0 -400.00,0.00,400.00,400.00,0.00,400.00,0 -600.00,0.00,600.00,600.00,0.00,600.00,0 -800.00,0.00,800.00,800.00,0.00,800.00,0 -1000.00,0.00,1000.00,1000.00,0.00,1000.00,0 -1200.00,0.00,1200.00,1200.00,0.00,1200.00,0 -1400.00,0.00,1400.00,1400.00,0.00,1400.00,0 -1600.00,0.00,1600.00,1600.00,0.00,1600.00,0 -1800.00,250.00,1550.00,1800.00,150.00,1650.00,0 -2000.00,250.00,1750.00,2000.00,300.00,1700.00,0 -2200.00,0.00,2200.00,2200.00,0.00,2200.00,0 -2400.00,200.00,2200.00,2400.00,200.00,2200.00,0 -2600.00,750.00,1850.00,2600.00,550.00,2050.00,0 -2800.00,2350.00,450.00,2800.00,1450.00,1350.00,0 -3000.00,2650.00,350.00,3000.00,2300.00,700.00,0 -3200.00,1500.00,1700.00,3200.00,2100.00,1100.00,0 -3400.00,500.00,2900.00,3400.00,550.00,2850.00,0 -3600.00,3000.00,600.00,3600.00,100.00,3500.00,0 -3800.00,4000.00,-200.00,3800.00,2850.00,950.00,0 -4000.00,2850.00,1150.00,4000.00,4700.00,-700.00,0 -4200.00,2350.00,1850.00,4200.00,3750.00,450.00,0 -4400.00,2950.00,1450.00,4400.00,2700.00,1700.00,0 -4600.00,3700.00,900.00,4600.00,2100.00,2500.00,0 -4800.00,4000.00,800.00,4800.00,3000.00,1800.00,0 -5000.00,4200.00,800.00,5000.00,4650.00,350.00,0 -5200.00,4300.00,900.00,5200.00,4550.00,650.00,0 -5400.00,4450.00,950.00,5400.00,3800.00,1600.00,0 -5600.00,4600.00,1000.00,5600.00,3950.00,1650.00,0 -5800.00,5000.00,800.00,5800.00,4400.00,1400.00,0 -6000.00,5050.00,950.00,6000.00,4900.00,1100.00,0 -6200.00,5400.00,800.00,6200.00,5200.00,1000.00,0 -6400.00,5600.00,800.00,6400.00,5400.00,1000.00,0 -6600.00,5750.00,850.00,6600.00,5300.00,1300.00,0 -6800.00,5900.00,900.00,6800.00,5600.00,1200.00,0 -7000.00,6150.00,850.00,7000.00,5850.00,1150.00,0 -7200.00,6400.00,800.00,7200.00,6100.00,1100.00,0 -7400.00,6650.00,750.00,7400.00,6400.00,1000.00,0 -7600.00,6900.00,700.00,7600.00,6450.00,1150.00,0 -7800.00,7050.00,750.00,7800.00,6700.00,1100.00,0 -8000.00,7250.00,750.00,8000.00,7050.00,950.00,0 -8200.00,7450.00,750.00,8200.00,7250.00,950.00,0 -8400.00,7700.00,700.00,8400.00,7350.00,1050.00,0 -8600.00,8000.00,600.00,8600.00,7550.00,1050.00,0 -8800.00,8200.00,600.00,8800.00,7800.00,1000.00,0 -9000.00,8500.00,500.00,9000.00,8000.00,1000.00,0 -9200.00,8650.00,550.00,9200.00,8150.00,1050.00,0 -9400.00,8700.00,700.00,9400.00,8350.00,1050.00,0 -9600.00,9050.00,550.00,9600.00,8500.00,1100.00,0 -9800.00,9600.00,200.00,9800.00,9200.00,600.00,0 -10000.00,9500.00,500.00,10000.00,9000.00,1000.00,0 -10200.00,9500.00,700.00,10200.00,9100.00,1100.00,0 -10400.00,10200.00,200.00,10400.00,9800.00,600.00,0 -10600.00,10150.00,450.00,10600.00,9700.00,900.00,0 -10800.00,10200.00,600.00,10800.00,9800.00,1000.00,0 -11000.00,10500.00,500.00,11000.00,10150.00,850.00,0 -11200.00,10800.00,400.00,11200.00,10350.00,850.00,0 -11400.00,11050.00,350.00,11400.00,10600.00,800.00,0 -11600.00,11700.00,-100.00,11600.00,11400.00,200.00,0 -11800.00,11350.00,450.00,11800.00,10900.00,900.00,0 -12000.00,11700.00,300.00,12000.00,11350.00,650.00,0 -12200.00,11500.00,700.00,12200.00,11150.00,1050.00,0 -12400.00,11750.00,650.00,12400.00,11450.00,950.00,0 -12600.00,12300.00,300.00,12600.00,11850.00,750.00,0 -12800.00,12700.00,100.00,12800.00,12150.00,650.00,0 -13000.00,12700.00,300.00,13000.00,12400.00,600.00,0 -13200.00,12750.00,450.00,13200.00,12500.00,700.00,0 -13400.00,12950.00,450.00,13400.00,12650.00,750.00,0 -13600.00,13350.00,250.00,13600.00,12750.00,850.00,0 -13800.00,13650.00,150.00,13800.00,12950.00,850.00,0 -14000.00,13650.00,350.00,14000.00,13250.00,750.00,0 -14200.00,14300.00,-100.00,14200.00,14150.00,50.00,0 -14400.00,14500.00,-100.00,14400.00,14100.00,300.00,0 -14600.00,13850.00,750.00,14600.00,13500.00,1100.00,0 -14800.00,14550.00,250.00,14800.00,14200.00,600.00,0 -15000.00,15150.00,-150.00,15000.00,14800.00,200.00,0 -15200.00,14700.00,500.00,15200.00,14100.00,1100.00,0 -15400.00,15300.00,100.00,15400.00,15100.00,300.00,0 -15600.00,15100.00,500.00,15600.00,15000.00,600.00,0 -15800.00,15200.00,600.00,15800.00,14950.00,850.00,0 -16000.00,16100.00,-100.00,16000.00,15800.00,200.00,0 -16200.00,16400.00,-200.00,16200.00,16150.00,50.00,0 -16400.00,16250.00,150.00,16400.00,16000.00,400.00,0 -16600.00,16150.00,450.00,16600.00,15950.00,650.00,0 -16800.00,19400.00,-2600.00,16800.00,19300.00,-2500.00,0 -17000.00,15500.00,1500.00,17000.00,15150.00,1850.00,0 -17200.00,13200.00,4000.00,17200.00,13700.00,3500.00,0 -17400.00,16450.00,950.00,17400.00,15750.00,1650.00,0 -17600.00,20750.00,-3150.00,17600.00,19450.00,-1850.00,0 -17800.00,18550.00,-750.00,17800.00,19800.00,-2000.00,0 -18000.00,14550.00,3450.00,18000.00,17900.00,100.00,0 -18200.00,16750.00,1450.00,18200.00,17100.00,1100.00,0 -18400.00,20500.00,-2100.00,18400.00,16300.00,2100.00,0 -18600.00,21500.00,-2900.00,18600.00,18350.00,250.00,0 -18800.00,18200.00,600.00,18800.00,18850.00,-50.00,0 -19000.00,17300.00,1700.00,19000.00,19500.00,-500.00,0 -19200.00,19000.00,200.00,19200.00,19200.00,0.00,0 -19400.00,19800.00,-400.00,19400.00,18250.00,1150.00,0 -19600.00,20200.00,-600.00,19600.00,19200.00,400.00,0 -19800.00,19000.00,800.00,19800.00,19250.00,550.00,0 -20000.00,19950.00,50.00,20000.00,20300.00,-300.00,0 -20200.00,20800.00,-600.00,20200.00,20150.00,50.00,0 -20400.00,20750.00,-350.00,20400.00,20150.00,250.00,0 -20600.00,20400.00,200.00,20600.00,20200.00,400.00,0 -20800.00,20500.00,300.00,20800.00,20300.00,500.00,0 -21000.00,21150.00,-150.00,21000.00,20800.00,200.00,0 -21200.00,21300.00,-100.00,21200.00,21300.00,-100.00,0 -21400.00,21400.00,0.00,21400.00,21100.00,300.00,0 -21600.00,20750.00,850.00,21600.00,20500.00,1100.00,0 -21800.00,21050.00,750.00,21800.00,20800.00,1000.00,0 -22000.00,22700.00,-700.00,22000.00,22500.00,-500.00,0 -22200.00,23050.00,-850.00,22200.00,22900.00,-700.00,0 -22400.00,22400.00,0.00,22400.00,22400.00,0.00,0 -22600.00,22200.00,400.00,22600.00,22000.00,600.00,0 -22800.00,22800.00,0.00,22800.00,22300.00,500.00,0 -23000.00,23050.00,-50.00,23000.00,22750.00,250.00,0 -23200.00,22950.00,250.00,23200.00,23050.00,150.00,0 -23400.00,23650.00,-250.00,23400.00,23400.00,0.00,0 -23600.00,24100.00,-500.00,23600.00,23600.00,0.00,0 -23800.00,24000.00,-200.00,23800.00,23800.00,0.00,0 -24000.00,23950.00,50.00,24000.00,23800.00,200.00,0 -24200.00,24050.00,150.00,23842.48,24050.00,-207.52,0 -24117.63,24400.00,-282.37,23642.48,24050.00,-407.52,0 -23917.63,25650.00,-1732.37,23442.48,24700.00,-1257.52,0 -23717.63,24250.00,-532.37,23242.48,23250.00,-7.52,0 -23517.63,23650.00,-132.37,23042.48,22700.00,342.48,0 -23317.63,23650.00,-332.37,22842.48,22950.00,-107.52,0 -23117.63,24100.00,-982.37,22642.48,23200.00,-557.52,0 -22917.63,23800.00,-882.37,22442.48,22900.00,-457.52,0 -22717.63,23150.00,-432.37,22242.48,22450.00,-207.52,0 -22517.63,22850.00,-332.37,22042.48,22350.00,-307.52,0 -22317.63,22950.00,-632.37,21842.48,22150.00,-307.52,0 -22117.63,22950.00,-832.37,21642.48,22250.00,-607.52,0 -21917.63,22350.00,-432.37,21442.48,21800.00,-357.52,0 -21717.63,22100.00,-382.37,21242.48,21550.00,-307.52,0 -21517.63,22000.00,-482.37,21042.48,21200.00,-157.52,0 -21317.63,21800.00,-482.37,20842.48,21050.00,-207.52,0 -21117.63,21450.00,-332.37,20642.48,20600.00,42.48,0 -20917.63,21400.00,-482.37,20442.48,20650.00,-207.52,0 -20717.63,21300.00,-582.37,20242.48,20700.00,-457.52,0 -20517.63,20800.00,-282.37,20042.48,20450.00,-407.52,0 -20317.63,20550.00,-232.37,19842.48,20100.00,-257.52,0 -20117.63,20600.00,-482.37,19642.48,19500.00,142.48,0 -19917.63,19750.00,167.63,19442.48,19000.00,442.48,0 -19717.63,20400.00,-682.37,19242.48,19800.00,-557.52,0 -19517.63,20600.00,-1082.37,19042.48,19850.00,-807.52,0 -19317.63,19800.00,-482.37,18842.48,19400.00,-557.52,0 -19117.63,19300.00,-182.37,18642.48,18750.00,-107.52,0 -18917.63,19300.00,-382.37,18442.48,18350.00,92.48,0 -18717.63,19250.00,-532.37,18242.48,18250.00,-7.52,0 -18517.63,19100.00,-582.37,18042.48,18150.00,-107.52,0 -18317.63,18900.00,-582.37,17842.48,18050.00,-207.52,0 -18117.63,18750.00,-632.37,17642.48,18000.00,-357.52,0 -17917.63,18450.00,-532.37,17442.48,17650.00,-207.52,0 -17717.63,18150.00,-432.37,17242.48,17400.00,-157.52,0 -17517.63,17850.00,-332.37,17042.48,17150.00,-107.52,0 -17317.63,17650.00,-332.37,16842.48,16850.00,-7.52,0 -17117.63,16950.00,167.63,16642.48,16100.00,542.48,0 -16917.63,17700.00,-782.37,16442.48,16500.00,-57.52,0 -16717.63,21000.00,-4282.37,16242.48,19800.00,-3557.52,0 -16517.63,16050.00,467.63,16042.48,15550.00,492.48,0 -16317.63,12650.00,3667.63,15842.48,12550.00,3292.48,0 -16117.63,15150.00,967.63,15642.48,14000.00,1642.48,0 -15917.63,18900.00,-2982.37,15442.48,16550.00,-1107.52,0 -15717.63,17650.00,-1932.37,15242.48,17700.00,-2457.52,0 -15517.63,13100.00,2417.63,15042.48,15000.00,42.48,0 -15317.63,13450.00,1867.63,14842.48,12700.00,2142.48,0 -15117.63,16650.00,-1532.37,14642.48,12900.00,1742.48,0 -14917.63,17350.00,-2432.37,14442.48,14650.00,-207.52,0 -14717.63,15100.00,-382.37,14242.48,15950.00,-1707.52,0 -14517.63,12100.00,2417.63,14042.48,15100.00,-1057.52,0 -14317.63,12900.00,1417.63,13842.48,13300.00,542.48,0 -14117.63,15650.00,-1532.37,13642.48,12600.00,1042.48,0 -13917.63,15450.00,-1532.37,13442.48,12850.00,592.48,0 -13717.63,14050.00,-332.37,13242.48,13750.00,-507.52,0 -13517.63,12650.00,867.63,13042.48,13100.00,-57.52,0 -13317.63,12950.00,367.63,12842.48,12700.00,142.48,0 -13117.63,14050.00,-932.37,12642.48,12750.00,-107.52,0 -12917.63,13350.00,-432.37,12442.48,12150.00,292.48,0 -12717.63,13100.00,-382.37,12242.48,12400.00,-157.52,0 -12517.63,12250.00,267.63,12042.48,11650.00,392.48,0 -12317.63,12500.00,-182.37,11842.48,11850.00,-7.52,0 -12117.63,12500.00,-382.37,11642.48,11700.00,-57.52,0 -11917.63,12200.00,-282.37,11442.48,11450.00,-7.52,0 -11717.63,11900.00,-182.37,11242.48,11050.00,192.48,0 -11517.63,11550.00,-32.37,11042.48,10800.00,242.48,0 -11317.63,11100.00,217.63,10842.48,10300.00,542.48,0 -11117.63,11550.00,-432.37,10642.48,10700.00,-57.52,0 -10917.63,11350.00,-432.37,10442.48,10550.00,-107.52,0 -10717.63,10550.00,167.63,10242.48,9800.00,442.48,0 -10517.63,10300.00,217.63,10042.48,9550.00,492.48,0 -10317.63,10450.00,-132.37,9842.48,9400.00,442.48,0 -10117.63,10850.00,-732.37,9642.48,9800.00,-157.52,0 -9917.63,10100.00,-182.37,9442.48,9600.00,-157.52,0 -9717.63,8500.00,1217.63,9242.48,9050.00,192.48,0 -9517.63,9000.00,517.63,9042.48,8650.00,392.48,0 -9317.63,9750.00,-432.37,8842.48,8100.00,742.48,0 -9117.63,9600.00,-482.37,8642.48,8250.00,392.48,0 -8917.63,8600.00,317.63,8442.48,8200.00,242.48,0 -8717.63,7500.00,1217.63,8242.48,8050.00,192.48,0 -8517.63,8200.00,317.63,8042.48,7800.00,242.48,0 -8317.63,9100.00,-782.37,7842.48,7450.00,392.48,0 -8117.63,8500.00,-382.37,7642.48,7300.00,342.48,0 -7917.63,6900.00,1017.63,7442.48,7150.00,292.48,0 -7717.63,6350.00,1367.63,7242.48,6900.00,342.48,0 -7517.63,7400.00,117.63,7042.48,6650.00,392.48,0 -7317.63,8150.00,-832.37,6842.48,6450.00,392.48,0 -7117.63,7500.00,-382.37,6642.48,6100.00,542.48,0 -6917.63,6050.00,867.63,6442.48,6000.00,442.48,0 -6717.63,5600.00,1117.63,6242.48,5800.00,442.48,0 -6517.63,6450.00,67.63,6042.48,5550.00,492.48,0 -6317.63,6800.00,-482.37,5842.48,5350.00,492.48,0 -6117.63,5850.00,267.63,5642.48,5200.00,442.48,0 -5917.63,4900.00,1017.63,5442.48,4600.00,842.48,0 -5717.63,4550.00,1167.63,5242.48,3950.00,1292.48,0 -5517.63,5350.00,167.63,5042.48,4100.00,942.48,0 -5317.63,5650.00,-332.37,4842.48,4400.00,442.48,0 -5117.63,4350.00,767.63,4642.48,4050.00,592.48,0 -4917.63,3950.00,967.63,4442.48,3250.00,1192.48,0 -4717.63,4600.00,117.63,4242.48,2550.00,1692.48,0 -4517.63,4750.00,-232.37,4042.48,2900.00,1142.48,0 -4317.63,3800.00,517.63,3842.48,3450.00,392.48,0 -4117.63,2950.00,1167.63,3642.48,3100.00,542.48,0 -3917.63,2750.00,1167.63,3442.48,2250.00,1192.48,0 -3717.63,3600.00,117.63,3242.48,1950.00,1292.48,0 -3517.63,3550.00,-32.37,3042.48,1900.00,1142.48,0 -3317.63,2750.00,567.63,2842.48,1800.00,1042.48,0 -3117.63,2150.00,967.63,2642.48,550.00,2092.48,0 -2917.63,1350.00,1567.63,2442.48,1300.00,1142.48,0 -2717.63,950.00,1767.63,2242.48,1300.00,942.48,0 -2517.63,2550.00,-32.37,2042.48,100.00,1942.48,0 -2317.63,2650.00,-332.37,1842.48,50.00,1792.48,0 -2117.63,1750.00,367.63,1642.48,1350.00,292.48,0 -1917.63,1650.00,267.63,1442.48,1600.00,-157.52,0 -1717.63,0.00,1717.63,1242.48,-200.00,1442.48,0 -1517.63,-250.00,1767.63,1042.48,-800.00,1842.48,0 -1317.63,300.00,1017.63,842.48,350.00,492.48,0 -1117.63,400.00,717.63,642.48,350.00,292.48,0 -917.63,-200.00,1117.63,442.48,-650.00,1092.48,0 -717.63,-550.00,1267.63,242.48,-100.00,342.48,0 -517.63,-1050.00,1567.63,42.48,50.00,-7.52,0 -317.63,150.00,167.63,0.00,0.00,0.00,0 -117.63,200.00,-82.37,0.00,0.00,0.00,0 -0.00,-50.00,50.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 --200.00,0.00,-200.00,-200.00,0.00,-200.00,0 --400.00,0.00,-400.00,-400.00,0.00,-400.00,0 --600.00,0.00,-600.00,-600.00,0.00,-600.00,0 --800.00,0.00,-800.00,-800.00,0.00,-800.00,0 --1000.00,0.00,-1000.00,-1000.00,0.00,-1000.00,0 --1200.00,0.00,-1200.00,-1200.00,0.00,-1200.00,0 --1400.00,0.00,-1400.00,-1400.00,0.00,-1400.00,0 --1600.00,0.00,-1600.00,-1600.00,0.00,-1600.00,0 --1800.00,-150.00,-1650.00,-1800.00,-200.00,-1600.00,0 --2000.00,-350.00,-1650.00,-2000.00,-400.00,-1600.00,0 --2200.00,0.00,-2200.00,-2200.00,-50.00,-2150.00,0 --2400.00,-200.00,-2200.00,-2400.00,-100.00,-2300.00,0 --2600.00,-650.00,-1950.00,-2600.00,-600.00,-2000.00,0 --2800.00,-2050.00,-750.00,-2800.00,-1500.00,-1300.00,0 --3000.00,-2450.00,-550.00,-3000.00,-1950.00,-1050.00,0 --3200.00,-1650.00,-1550.00,-3200.00,-1350.00,-1850.00,0 --3400.00,-200.00,-3200.00,-3400.00,-1350.00,-2050.00,0 --3600.00,-1550.00,-2050.00,-3600.00,-1350.00,-2250.00,0 --3800.00,-4600.00,800.00,-3800.00,-2400.00,-1400.00,0 --4000.00,-4600.00,600.00,-4000.00,-2900.00,-1100.00,0 --4200.00,-3200.00,-1000.00,-4200.00,-2900.00,-1300.00,0 --4400.00,-2600.00,-1800.00,-4400.00,-2700.00,-1700.00,0 --4600.00,-3150.00,-1450.00,-4600.00,-2950.00,-1650.00,0 --4800.00,-4200.00,-600.00,-4800.00,-3100.00,-1700.00,0 --5000.00,-4050.00,-950.00,-5000.00,-3450.00,-1550.00,0 --5200.00,-3550.00,-1650.00,-5200.00,-3800.00,-1400.00,0 --5400.00,-4250.00,-1150.00,-5400.00,-4000.00,-1400.00,0 --5600.00,-4850.00,-750.00,-5600.00,-4100.00,-1500.00,0 --5800.00,-4900.00,-900.00,-5800.00,-4150.00,-1650.00,0 --6000.00,-5250.00,-750.00,-6000.00,-4650.00,-1350.00,0 --6200.00,-5450.00,-750.00,-6200.00,-4950.00,-1250.00,0 --6400.00,-5550.00,-850.00,-6400.00,-5150.00,-1250.00,0 --6600.00,-5700.00,-900.00,-6600.00,-5300.00,-1300.00,0 --6800.00,-5900.00,-900.00,-6800.00,-5600.00,-1200.00,0 --7000.00,-6100.00,-900.00,-7000.00,-5750.00,-1250.00,0 --7200.00,-6350.00,-850.00,-7200.00,-6050.00,-1150.00,0 --7400.00,-6750.00,-650.00,-7400.00,-6350.00,-1050.00,0 --7600.00,-6950.00,-650.00,-7600.00,-6550.00,-1050.00,0 --7800.00,-7050.00,-750.00,-7800.00,-6700.00,-1100.00,0 --8000.00,-7250.00,-750.00,-8000.00,-6900.00,-1100.00,0 --8200.00,-7500.00,-700.00,-8200.00,-7100.00,-1100.00,0 --8400.00,-7750.00,-650.00,-8400.00,-7450.00,-950.00,0 --8600.00,-7950.00,-650.00,-8600.00,-7600.00,-1000.00,0 --8800.00,-8150.00,-650.00,-8800.00,-7850.00,-950.00,0 --9000.00,-8400.00,-600.00,-9000.00,-8100.00,-900.00,0 --9200.00,-8550.00,-650.00,-9200.00,-8250.00,-950.00,0 --9400.00,-8800.00,-600.00,-9400.00,-8400.00,-1000.00,0 --9600.00,-8900.00,-700.00,-9600.00,-8550.00,-1050.00,0 --9800.00,-9100.00,-700.00,-9800.00,-8800.00,-1000.00,0 --10000.00,-9450.00,-550.00,-10000.00,-9050.00,-950.00,0 --10200.00,-9650.00,-550.00,-10200.00,-9350.00,-850.00,0 --10400.00,-9850.00,-550.00,-10400.00,-9600.00,-800.00,0 --10600.00,-10050.00,-550.00,-10600.00,-9800.00,-800.00,0 --10800.00,-10150.00,-650.00,-10800.00,-10050.00,-750.00,0 --11000.00,-10200.00,-800.00,-11000.00,-10150.00,-850.00,0 --11200.00,-10450.00,-750.00,-11200.00,-10450.00,-750.00,0 --11400.00,-10850.00,-550.00,-11400.00,-10650.00,-750.00,0 --11600.00,-11050.00,-550.00,-11600.00,-10900.00,-700.00,0 --11800.00,-11300.00,-500.00,-11800.00,-11000.00,-800.00,0 --12000.00,-11400.00,-600.00,-12000.00,-11250.00,-750.00,0 --12200.00,-12000.00,-200.00,-12200.00,-11950.00,-250.00,0 --12400.00,-11650.00,-750.00,-12400.00,-11650.00,-750.00,0 --12600.00,-12250.00,-350.00,-12600.00,-12200.00,-400.00,0 --12800.00,-12100.00,-700.00,-12800.00,-11950.00,-850.00,0 --13000.00,-12250.00,-750.00,-13000.00,-12050.00,-950.00,0 --13200.00,-13150.00,-50.00,-13200.00,-12950.00,-250.00,0 --13400.00,-13450.00,50.00,-13400.00,-13200.00,-200.00,0 --13600.00,-12800.00,-800.00,-13600.00,-12600.00,-1000.00,0 --13800.00,-13300.00,-500.00,-13800.00,-13200.00,-600.00,0 --14000.00,-13750.00,-250.00,-14000.00,-13400.00,-600.00,0 --14200.00,-14000.00,-200.00,-14200.00,-13650.00,-550.00,0 --14400.00,-14050.00,-350.00,-14400.00,-13750.00,-650.00,0 --14600.00,-14100.00,-500.00,-14600.00,-13800.00,-800.00,0 --14800.00,-14450.00,-350.00,-14800.00,-14150.00,-650.00,0 --15000.00,-14750.00,-250.00,-15000.00,-14400.00,-600.00,0 --15200.00,-14400.00,-800.00,-15200.00,-14050.00,-1150.00,0 --15400.00,-14650.00,-750.00,-15400.00,-14400.00,-1000.00,0 --15600.00,-15850.00,250.00,-15600.00,-15600.00,0.00,0 --15800.00,-15750.00,-50.00,-15800.00,-15250.00,-550.00,0 --16000.00,-19050.00,3050.00,-16000.00,-18550.00,2550.00,0 --16200.00,-14500.00,-1700.00,-16200.00,-14000.00,-2200.00,0 --16400.00,-12950.00,-3450.00,-16400.00,-12950.00,-3450.00,0 --16600.00,-16450.00,-150.00,-16600.00,-15700.00,-900.00,0 --16800.00,-19650.00,2850.00,-16800.00,-18150.00,1350.00,0 --17000.00,-17250.00,250.00,-17000.00,-17750.00,750.00,0 --17200.00,-13350.00,-3850.00,-17200.00,-15950.00,-1250.00,0 --17400.00,-16000.00,-1400.00,-17400.00,-16200.00,-1200.00,0 --17600.00,-20550.00,2950.00,-17600.00,-16950.00,-650.00,0 --17800.00,-19250.00,1450.00,-17800.00,-17500.00,-300.00,0 --18000.00,-14300.00,-3700.00,-18000.00,-16950.00,-1050.00,0 --18200.00,-15500.00,-2700.00,-18200.00,-17150.00,-1050.00,0 --18400.00,-21200.00,2800.00,-18400.00,-18450.00,50.00,0 --18600.00,-22150.00,3550.00,-18600.00,-18700.00,100.00,0 --18800.00,-17400.00,-1400.00,-18800.00,-17900.00,-900.00,0 --19000.00,-15050.00,-3950.00,-19000.00,-18550.00,-450.00,0 --19200.00,-18000.00,-1200.00,-19200.00,-18350.00,-850.00,0 --19400.00,-23250.00,3850.00,-19400.00,-19400.00,0.00,0 --19600.00,-20350.00,750.00,-19600.00,-19000.00,-600.00,0 --19800.00,-16450.00,-3350.00,-19800.00,-19800.00,0.00,0 --20000.00,-18250.00,-1750.00,-20000.00,-19900.00,-100.00,0 --20200.00,-22750.00,2550.00,-20200.00,-19900.00,-300.00,0 --20400.00,-23000.00,2600.00,-20400.00,-19950.00,-450.00,0 --20600.00,-20150.00,-450.00,-20600.00,-20200.00,-400.00,0 --20800.00,-18950.00,-1850.00,-20800.00,-20450.00,-350.00,0 --21000.00,-20450.00,-550.00,-21000.00,-20750.00,-250.00,0 --21200.00,-21950.00,750.00,-21200.00,-20850.00,-350.00,0 --21400.00,-21900.00,500.00,-21400.00,-21000.00,-400.00,0 --21600.00,-21400.00,-200.00,-21600.00,-21150.00,-450.00,0 --21800.00,-21400.00,-400.00,-21800.00,-21350.00,-450.00,0 --22000.00,-22150.00,150.00,-22000.00,-21650.00,-350.00,0 --22200.00,-22550.00,350.00,-22200.00,-21700.00,-500.00,0 --22400.00,-22650.00,250.00,-22400.00,-21950.00,-450.00,0 --22600.00,-22650.00,50.00,-22600.00,-22200.00,-400.00,0 --22800.00,-22500.00,-300.00,-22800.00,-22450.00,-350.00,0 --23000.00,-22850.00,-150.00,-23000.00,-22650.00,-350.00,0 --23200.00,-23150.00,-50.00,-23200.00,-22700.00,-500.00,0 --23400.00,-23650.00,250.00,-23400.00,-23000.00,-400.00,0 --23600.00,-24000.00,400.00,-23600.00,-23250.00,-350.00,0 --23800.00,-23950.00,150.00,-23722.21,-23550.00,-172.21,0 --24000.00,-23150.00,-850.00,-23522.21,-22900.00,-622.21,0 --23982.98,-24550.00,567.02,-23322.21,-23750.00,427.79,0 --23782.98,-25400.00,1617.02,-23122.21,-23900.00,777.79,0 --23582.98,-24700.00,1117.02,-22922.21,-23650.00,727.79,0 --23382.98,-23600.00,217.02,-22722.21,-22900.00,177.79,0 --23182.98,-23300.00,117.02,-22522.21,-22500.00,-22.21,0 --22982.98,-23350.00,367.02,-22322.21,-22500.00,177.79,0 --22782.98,-22450.00,-332.98,-22122.21,-21600.00,-522.21,0 --22582.98,-23350.00,767.02,-21922.21,-22500.00,577.79,0 --22382.98,-23450.00,1067.02,-21722.21,-22600.00,877.79,0 --22182.98,-22900.00,717.02,-21522.21,-22050.00,527.79,0 --21982.98,-21400.00,-582.98,-21322.21,-20550.00,-772.21,0 --21782.98,-22300.00,517.02,-21122.21,-21100.00,-22.21,0 --21582.98,-22500.00,917.02,-20922.21,-21500.00,577.79,0 --21382.98,-22050.00,667.02,-20722.21,-21300.00,577.79,0 --21182.98,-20800.00,-382.98,-20522.21,-19900.00,-622.21,0 --20982.98,-21700.00,717.02,-20322.21,-20350.00,27.79,0 --20782.98,-21300.00,517.02,-20122.21,-19850.00,-272.21,0 --20582.98,-21650.00,1067.02,-19922.21,-20300.00,377.79,0 --20382.98,-21200.00,817.02,-19722.21,-20200.00,477.79,0 --20182.98,-19750.00,-432.98,-19522.21,-19000.00,-522.21,0 --19982.98,-20350.00,367.02,-19322.21,-19300.00,-22.21,0 --19782.98,-20500.00,717.02,-19122.21,-19400.00,277.79,0 --19582.98,-20250.00,667.02,-18922.21,-19100.00,177.79,0 --19382.98,-19200.00,-182.98,-18722.21,-17900.00,-822.21,0 --19182.98,-19700.00,517.02,-18522.21,-18550.00,27.79,0 --18982.98,-19800.00,817.02,-18322.21,-18700.00,377.79,0 --18782.98,-19450.00,667.02,-18122.21,-18450.00,327.79,0 --18582.98,-18950.00,367.02,-17922.21,-17900.00,-22.21,0 --18382.98,-18650.00,267.02,-17722.21,-17500.00,-222.21,0 --18182.98,-18600.00,417.02,-17522.21,-17400.00,-122.21,0 --17982.98,-17900.00,-82.98,-17322.21,-16700.00,-622.21,0 --17782.98,-17650.00,-132.98,-17122.21,-16700.00,-422.21,0 --17582.98,-17750.00,167.02,-16922.21,-17000.00,77.79,0 --17382.98,-17450.00,67.02,-16722.21,-16900.00,177.79,0 --17182.98,-21600.00,4417.02,-16522.21,-20400.00,3877.79,0 --16982.98,-16350.00,-632.98,-16322.21,-15200.00,-1122.21,0 --16782.98,-13500.00,-3282.98,-16122.21,-13050.00,-3072.21,0 --16582.98,-16450.00,-132.98,-15922.21,-15250.00,-672.21,0 --16382.98,-19000.00,2617.02,-15722.21,-17500.00,1777.79,0 --16182.98,-16650.00,467.02,-15522.21,-16600.00,1077.79,0 --15982.98,-13500.00,-2482.98,-15322.21,-15200.00,-122.21,0 --15782.98,-15050.00,-732.98,-15122.21,-15100.00,-22.21,0 --15582.98,-17700.00,2117.02,-14922.21,-15250.00,327.79,0 --15382.98,-16550.00,1167.02,-14722.21,-14100.00,-622.21,0 --15182.98,-15450.00,267.02,-14522.21,-14450.00,-72.21,0 --14982.98,-14800.00,-182.98,-14322.21,-14600.00,277.79,0 --14782.98,-14400.00,-382.98,-14122.21,-13800.00,-322.21,0 --14582.98,-15150.00,567.02,-13922.21,-13950.00,27.79,0 --14382.98,-14550.00,167.02,-13722.21,-13350.00,-372.21,0 --14182.98,-14650.00,467.02,-13522.21,-13800.00,277.79,0 --13982.98,-14000.00,17.02,-13322.21,-13050.00,-272.21,0 --13782.98,-14350.00,567.02,-13122.21,-13150.00,27.79,0 --13582.98,-13850.00,267.02,-12922.21,-12450.00,-472.21,0 --13382.98,-13800.00,417.02,-12722.21,-12650.00,-72.21,0 --13182.98,-12850.00,-332.98,-12522.21,-12000.00,-522.21,0 --12982.98,-13200.00,217.02,-12322.21,-12200.00,-122.21,0 --12782.98,-13300.00,517.02,-12122.21,-12100.00,-22.21,0 --12582.98,-12550.00,-32.98,-11922.21,-11300.00,-622.21,0 --12382.98,-12650.00,267.02,-11722.21,-11500.00,-222.21,0 --12182.98,-12550.00,367.02,-11522.21,-11400.00,-122.21,0 --11982.98,-11850.00,-132.98,-11322.21,-10650.00,-672.21,0 --11782.98,-12000.00,217.02,-11122.21,-10800.00,-322.21,0 --11582.98,-11600.00,17.02,-10922.21,-10450.00,-472.21,0 --11382.98,-11350.00,-32.98,-10722.21,-10300.00,-422.21,0 --11182.98,-11600.00,417.02,-10522.21,-10550.00,27.79,0 --10982.98,-11000.00,17.02,-10322.21,-9950.00,-372.21,0 --10782.98,-10600.00,-182.98,-10122.21,-9700.00,-422.21,0 --10582.98,-10550.00,-32.98,-9922.21,-9500.00,-422.21,0 --10382.98,-10900.00,517.02,-9722.21,-9750.00,27.79,0 --10182.98,-10250.00,67.02,-9522.21,-9200.00,-322.21,0 --9982.98,-9800.00,-182.98,-9322.21,-8800.00,-522.21,0 --9782.98,-10100.00,317.02,-9122.21,-9000.00,-122.21,0 --9582.98,-9600.00,17.02,-8922.21,-8550.00,-372.21,0 --9382.98,-9350.00,-32.98,-8722.21,-8250.00,-472.21,0 --9182.98,-9100.00,-82.98,-8522.21,-8050.00,-472.21,0 --8982.98,-8900.00,-82.98,-8322.21,-8050.00,-272.21,0 --8782.98,-8700.00,-82.98,-8122.21,-7850.00,-272.21,0 --8582.98,-8300.00,-282.98,-7922.21,-7600.00,-322.21,0 --8382.98,-8450.00,67.02,-7722.21,-7650.00,-72.21,0 --8182.98,-8000.00,-182.98,-7522.21,-6950.00,-572.21,0 --7982.98,-7750.00,-232.98,-7322.21,-6700.00,-622.21,0 --7782.98,-7650.00,-132.98,-7122.21,-6700.00,-422.21,0 --7582.98,-7750.00,167.02,-6922.21,-6750.00,-172.21,0 --7382.98,-7000.00,-382.98,-6722.21,-6350.00,-372.21,0 --7182.98,-6150.00,-1032.98,-6522.21,-6100.00,-422.21,0 --6982.98,-6350.00,-632.98,-6322.21,-5850.00,-472.21,0 --6782.98,-6650.00,-132.98,-6122.21,-5650.00,-472.21,0 --6582.98,-6400.00,-182.98,-5922.21,-5550.00,-372.21,0 --6382.98,-5450.00,-932.98,-5722.21,-5150.00,-572.21,0 --6182.98,-4700.00,-1482.98,-5522.21,-4300.00,-1222.21,0 --5982.98,-5400.00,-582.98,-5322.21,-4450.00,-872.21,0 --5782.98,-5900.00,117.02,-5122.21,-4850.00,-272.21,0 --5582.98,-5650.00,67.02,-4922.21,-4600.00,-322.21,0 --5382.98,-4750.00,-632.98,-4722.21,-3650.00,-1072.21,0 --5182.98,-4150.00,-1032.98,-4522.21,-3150.00,-1372.21,0 --4982.98,-4400.00,-582.98,-4322.21,-3550.00,-772.21,0 --4782.98,-4150.00,-632.98,-4122.21,-3500.00,-622.21,0 --4582.98,-3350.00,-1232.98,-3922.21,-2750.00,-1172.21,0 --4382.98,-3000.00,-1382.98,-3722.21,-2050.00,-1672.21,0 --4182.98,-3500.00,-682.98,-3522.21,-2750.00,-772.21,0 --3982.98,-3600.00,-382.98,-3322.21,-2700.00,-622.21,0 --3782.98,-2800.00,-982.98,-3122.21,-2100.00,-1022.21,0 --3582.98,-2150.00,-1432.98,-2922.21,-500.00,-2422.21,0 --3382.98,-1250.00,-2132.98,-2722.21,-500.00,-2222.21,0 --3182.98,-2450.00,-732.98,-2522.21,-2600.00,77.79,0 --2982.98,-3100.00,117.02,-2322.21,-3000.00,677.79,0 --2782.98,-2050.00,-732.98,-2122.21,-1850.00,-272.21,0 --2582.98,-1400.00,-1182.98,-1922.21,-1750.00,-172.21,0 --2382.98,-100.00,-2282.98,-1722.21,-50.00,-1672.21,0 --2182.98,-500.00,-1682.98,-1522.21,450.00,-1972.21,0 --1982.98,-2400.00,417.02,-1322.21,-200.00,-1122.21,0 --1782.98,-2650.00,867.02,-1122.21,200.00,-1322.21,0 --1582.98,-1000.00,-582.98,-922.21,450.00,-1372.21,0 --1382.98,50.00,-1432.98,-722.21,0.00,-722.21,0 --1182.98,400.00,-1582.98,-522.21,0.00,-522.21,0 --982.98,850.00,-1832.98,-322.21,0.00,-322.21,0 --782.98,150.00,-932.98,-122.21,0.00,-122.21,0 --582.98,-450.00,-132.98,0.00,0.00,0.00,0 --382.98,450.00,-832.98,0.00,0.00,0.00,0 --182.98,0.00,-182.98,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -200.00,0.00,200.00,200.00,0.00,200.00,0 -400.00,0.00,400.00,400.00,0.00,400.00,0 -600.00,0.00,600.00,600.00,0.00,600.00,0 -800.00,0.00,800.00,800.00,0.00,800.00,0 -1000.00,0.00,1000.00,1000.00,0.00,1000.00,0 -1200.00,0.00,1200.00,1200.00,0.00,1200.00,0 -1400.00,0.00,1400.00,1400.00,0.00,1400.00,0 -1600.00,0.00,1600.00,1600.00,0.00,1600.00,0 -1800.00,200.00,1600.00,1800.00,150.00,1650.00,0 -2000.00,250.00,1750.00,2000.00,200.00,1800.00,0 -2200.00,0.00,2200.00,2200.00,0.00,2200.00,0 -2400.00,250.00,2150.00,2400.00,200.00,2200.00,0 -2600.00,500.00,2100.00,2600.00,200.00,2400.00,0 -2800.00,1700.00,1100.00,2800.00,600.00,2200.00,0 -3000.00,2300.00,700.00,3000.00,1400.00,1600.00,0 -3200.00,1800.00,1400.00,3200.00,2200.00,1000.00,0 -3400.00,850.00,2550.00,3400.00,1900.00,1500.00,0 -3600.00,1800.00,1800.00,3600.00,1100.00,2500.00,0 -3800.00,3950.00,-150.00,3800.00,1000.00,2800.00,0 -4000.00,3950.00,50.00,4000.00,2750.00,1250.00,0 -4200.00,2800.00,1400.00,4200.00,3650.00,550.00,0 -4400.00,2000.00,2400.00,4400.00,3250.00,1150.00,0 -4600.00,3250.00,1350.00,4600.00,2550.00,2050.00,0 -4800.00,4450.00,350.00,4800.00,2700.00,2100.00,0 -5000.00,4500.00,500.00,5000.00,3500.00,1500.00,0 -5200.00,3400.00,1800.00,5200.00,4000.00,1200.00,0 -5400.00,3150.00,2250.00,5400.00,4050.00,1350.00,0 -5600.00,4900.00,700.00,5600.00,4300.00,1300.00,0 -5800.00,5850.00,-50.00,5800.00,4300.00,1500.00,0 -6000.00,5350.00,650.00,6000.00,4350.00,1650.00,0 -6200.00,4400.00,1800.00,6200.00,4700.00,1500.00,0 -6400.00,4950.00,1450.00,6400.00,5000.00,1400.00,0 -6600.00,6000.00,600.00,6600.00,5300.00,1300.00,0 -6800.00,6250.00,550.00,6800.00,5550.00,1250.00,0 -7000.00,6150.00,850.00,7000.00,5700.00,1300.00,0 -7200.00,6250.00,950.00,7200.00,5800.00,1400.00,0 -7400.00,6800.00,600.00,7400.00,6300.00,1100.00,0 -7600.00,6750.00,850.00,7600.00,6250.00,1350.00,0 -7800.00,6850.00,950.00,7800.00,6400.00,1400.00,0 -8000.00,7500.00,500.00,8000.00,7000.00,1000.00,0 -8200.00,7400.00,800.00,8200.00,7000.00,1200.00,0 -8400.00,7500.00,900.00,8400.00,7000.00,1400.00,0 -8600.00,7800.00,800.00,8600.00,7200.00,1400.00,0 -8800.00,8150.00,650.00,8800.00,7600.00,1200.00,0 -9000.00,8650.00,350.00,9000.00,8200.00,800.00,0 -9200.00,8400.00,800.00,9200.00,8050.00,1150.00,0 -9400.00,8400.00,1000.00,9400.00,8050.00,1350.00,0 -9600.00,8800.00,800.00,9600.00,8300.00,1300.00,0 -9800.00,9600.00,200.00,9800.00,8900.00,900.00,0 -10000.00,9400.00,600.00,10000.00,8900.00,1100.00,0 -10200.00,9700.00,500.00,10200.00,9350.00,850.00,0 -10400.00,9850.00,550.00,10400.00,9550.00,850.00,0 -10600.00,9700.00,900.00,10600.00,9250.00,1350.00,0 -10800.00,10450.00,350.00,10800.00,9850.00,950.00,0 -11000.00,10600.00,400.00,11000.00,10200.00,800.00,0 -11200.00,10800.00,400.00,11200.00,10350.00,850.00,0 -11400.00,10850.00,550.00,11400.00,10350.00,1050.00,0 -11600.00,11050.00,550.00,11600.00,10450.00,1150.00,0 -11800.00,10800.00,1000.00,11800.00,10300.00,1500.00,0 -12000.00,11550.00,450.00,12000.00,11150.00,850.00,0 -12200.00,12050.00,150.00,12200.00,11700.00,500.00,0 -12400.00,12050.00,350.00,12400.00,11700.00,700.00,0 -12600.00,11600.00,1000.00,12600.00,11200.00,1400.00,0 -12800.00,12300.00,500.00,12800.00,11900.00,900.00,0 -13000.00,12250.00,750.00,13000.00,11900.00,1100.00,0 -13200.00,12450.00,750.00,13200.00,12000.00,1200.00,0 -13400.00,13250.00,150.00,13400.00,12950.00,450.00,0 -13600.00,13350.00,250.00,13600.00,13250.00,350.00,0 -13800.00,12800.00,1000.00,13800.00,12600.00,1200.00,0 -14000.00,13500.00,500.00,14000.00,13200.00,800.00,0 -14200.00,14000.00,200.00,14200.00,13600.00,600.00,0 -14400.00,14100.00,300.00,14400.00,13750.00,650.00,0 -14600.00,13550.00,1050.00,14600.00,13250.00,1350.00,0 -14800.00,14350.00,450.00,14800.00,14100.00,700.00,0 -15000.00,14850.00,150.00,15000.00,14500.00,500.00,0 -15200.00,14900.00,300.00,15200.00,14600.00,600.00,0 -15400.00,14950.00,450.00,15400.00,14600.00,800.00,0 -15600.00,14650.00,950.00,15600.00,14150.00,1450.00,0 -15800.00,15800.00,0.00,15800.00,15150.00,650.00,0 -16000.00,16100.00,-100.00,16000.00,15700.00,300.00,0 -16200.00,15850.00,350.00,16200.00,15500.00,700.00,0 -16400.00,15250.00,1150.00,16400.00,15200.00,1200.00,0 -16600.00,16350.00,250.00,16600.00,16050.00,550.00,0 -16800.00,20200.00,-3400.00,16800.00,19650.00,-2850.00,0 -17000.00,15700.00,1300.00,17000.00,15300.00,1700.00,0 -17200.00,13250.00,3950.00,17200.00,13450.00,3750.00,0 -17400.00,16700.00,700.00,17400.00,15950.00,1450.00,0 -17600.00,20400.00,-2800.00,17600.00,18600.00,-1000.00,0 -17800.00,18600.00,-800.00,17800.00,18750.00,-950.00,0 -18000.00,14400.00,3600.00,18000.00,17700.00,300.00,0 -18200.00,15900.00,2300.00,18200.00,17000.00,1200.00,0 -18400.00,19600.00,-1200.00,18400.00,16350.00,2050.00,0 -18600.00,20250.00,-1650.00,18600.00,17250.00,1350.00,0 -18800.00,19200.00,-400.00,18800.00,19100.00,-300.00,0 -19000.00,17850.00,1150.00,19000.00,19400.00,-400.00,0 -19200.00,18250.00,950.00,19200.00,18950.00,250.00,0 -19400.00,19650.00,-250.00,19400.00,18500.00,900.00,0 -19600.00,20150.00,-550.00,19600.00,18500.00,1100.00,0 -19800.00,19500.00,300.00,19800.00,18900.00,900.00,0 -20000.00,19400.00,600.00,20000.00,19550.00,450.00,0 -20200.00,19750.00,450.00,20200.00,19900.00,300.00,0 -20400.00,20150.00,250.00,20400.00,19900.00,500.00,0 -20600.00,20350.00,250.00,20600.00,19950.00,650.00,0 -20800.00,20500.00,300.00,20800.00,20200.00,600.00,0 -21000.00,20700.00,300.00,21000.00,20400.00,600.00,0 -21200.00,20950.00,250.00,21200.00,20600.00,600.00,0 -21400.00,21250.00,150.00,21400.00,21150.00,250.00,0 -21600.00,21400.00,200.00,21600.00,21250.00,350.00,0 -21800.00,21700.00,100.00,21800.00,21300.00,500.00,0 -22000.00,21850.00,150.00,22000.00,21400.00,600.00,0 -22200.00,22150.00,50.00,22200.00,21650.00,550.00,0 -22400.00,22100.00,300.00,22400.00,21650.00,750.00,0 -22600.00,21900.00,700.00,22600.00,22300.00,300.00,0 -22800.00,22650.00,150.00,22800.00,22550.00,250.00,0 -23000.00,23050.00,-50.00,23000.00,22650.00,350.00,0 -23200.00,22900.00,300.00,23200.00,22500.00,700.00,0 -23400.00,23300.00,100.00,23400.00,22900.00,500.00,0 -23600.00,23750.00,-150.00,23600.00,23250.00,350.00,0 -23800.00,23850.00,-50.00,23800.00,23400.00,400.00,0 -24000.00,23850.00,150.00,23861.05,23600.00,261.05,0 -24183.88,24050.00,133.88,23661.05,23600.00,61.05,0 -23983.88,24200.00,-216.12,23461.05,23650.00,-188.95,0 -23783.88,24350.00,-566.12,23261.05,23100.00,161.05,0 -23583.88,24000.00,-416.12,23061.05,23150.00,-88.95,0 -23383.88,24600.00,-1216.12,22861.05,23950.00,-1088.95,0 -23183.88,23650.00,-466.12,22661.05,22750.00,-88.95,0 -22983.88,22800.00,183.88,22461.05,22050.00,411.05,0 -22783.88,22600.00,183.88,22261.05,22000.00,261.05,0 -22583.88,22800.00,-216.12,22061.05,22100.00,-38.95,0 -22383.88,22750.00,-366.12,21861.05,22050.00,-188.95,0 -22183.88,23500.00,-1316.12,21661.05,22750.00,-1088.95,0 -21983.88,23100.00,-1116.12,21461.05,22200.00,-738.95,0 -21783.88,21400.00,383.88,21261.05,20650.00,611.05,0 -21583.88,21150.00,433.88,21061.05,20300.00,761.05,0 -21383.88,21300.00,83.88,20861.05,20450.00,411.05,0 -21183.88,21900.00,-716.12,20661.05,20900.00,-238.95,0 -20983.88,22550.00,-1566.12,20461.05,21700.00,-1238.95,0 -20783.88,21600.00,-816.12,20261.05,21100.00,-838.95,0 -20583.88,20550.00,33.88,20061.05,20000.00,61.05,0 -20383.88,18900.00,1483.88,19861.05,18100.00,1761.05,0 -20183.88,20250.00,-66.12,19661.05,18850.00,811.05,0 -19983.88,20950.00,-966.12,19461.05,20050.00,-588.95,0 -19783.88,20500.00,-716.12,19261.05,20250.00,-988.95,0 -19583.88,19700.00,-116.12,19061.05,19300.00,-238.95,0 -19383.88,19500.00,-116.12,18861.05,18550.00,311.05,0 -19183.88,19600.00,-416.12,18661.05,18100.00,561.05,0 -18983.88,19550.00,-566.12,18461.05,18350.00,111.05,0 -18783.88,19100.00,-316.12,18261.05,18450.00,-188.95,0 -18583.88,18700.00,-116.12,18061.05,18100.00,-38.95,0 -18383.88,18550.00,-166.12,17861.05,17500.00,361.05,0 -18183.88,18550.00,-366.12,17661.05,17600.00,61.05,0 -17983.88,18350.00,-366.12,17461.05,17450.00,11.05,0 -17783.88,18050.00,-266.12,17261.05,17250.00,11.05,0 -17583.88,17850.00,-266.12,17061.05,16900.00,161.05,0 -17383.88,17700.00,-316.12,16861.05,16600.00,261.05,0 -17183.88,17400.00,-216.12,16661.05,16400.00,261.05,0 -16983.88,17200.00,-216.12,16461.05,16400.00,61.05,0 -16783.88,16900.00,-116.12,16261.05,16250.00,11.05,0 -16583.88,16050.00,533.88,16061.05,15150.00,911.05,0 -16383.88,16650.00,-266.12,15861.05,15900.00,-38.95,0 -16183.88,19900.00,-3716.12,15661.05,19050.00,-3388.95,0 -15983.88,15150.00,833.88,15461.05,14650.00,811.05,0 -15783.88,12600.00,3183.88,15261.05,12350.00,2911.05,0 -15583.88,15050.00,533.88,15061.05,13850.00,1211.05,0 -15383.88,17100.00,-1716.12,14861.05,15100.00,-238.95,0 -15183.88,16800.00,-1616.12,14661.05,15950.00,-1288.95,0 -14983.88,15000.00,-16.12,14461.05,15150.00,-688.95,0 -14783.88,14200.00,583.88,14261.05,14050.00,211.05,0 -14583.88,14750.00,-166.12,14061.05,13400.00,661.05,0 -14383.88,15150.00,-766.12,13861.05,13350.00,511.05,0 -14183.88,14500.00,-316.12,13661.05,13500.00,161.05,0 -13983.88,13650.00,333.88,13461.05,13300.00,161.05,0 -13783.88,13500.00,283.88,13261.05,13200.00,61.05,0 -13583.88,13650.00,-66.12,13061.05,12850.00,211.05,0 -13383.88,13700.00,-316.12,12861.05,12550.00,311.05,0 -13183.88,12950.00,233.88,12661.05,11850.00,811.05,0 -12983.88,13150.00,-166.12,12461.05,12350.00,111.05,0 -12783.88,13050.00,-266.12,12261.05,12500.00,-238.95,0 -12583.88,12800.00,-216.12,12061.05,12150.00,-88.95,0 -12383.88,12450.00,-66.12,11861.05,11550.00,311.05,0 -12183.88,12300.00,-116.12,11661.05,11250.00,411.05,0 -11983.88,12150.00,-166.12,11461.05,11100.00,361.05,0 -11783.88,11450.00,333.88,11261.05,10550.00,711.05,0 -11583.88,11800.00,-216.12,11061.05,10950.00,111.05,0 -11383.88,11700.00,-316.12,10861.05,10800.00,61.05,0 -11183.88,11400.00,-216.12,10661.05,10500.00,161.05,0 -10983.88,11000.00,-16.12,10461.05,10150.00,311.05,0 -10783.88,10400.00,383.88,10261.05,9400.00,861.05,0 -10583.88,10800.00,-216.12,10061.05,9700.00,361.05,0 -10383.88,10900.00,-516.12,9861.05,9800.00,61.05,0 -10183.88,10400.00,-216.12,9661.05,9450.00,211.05,0 -9983.88,9800.00,183.88,9461.05,9000.00,461.05,0 -9783.88,9650.00,133.88,9261.05,8750.00,511.05,0 -9583.88,9400.00,183.88,9061.05,8150.00,911.05,0 -9383.88,9450.00,-66.12,8861.05,8150.00,711.05,0 -9183.88,9200.00,-16.12,8661.05,8200.00,461.05,0 -8983.88,8900.00,83.88,8461.05,8100.00,361.05,0 -8783.88,8750.00,33.88,8261.05,7900.00,361.05,0 -8583.88,8600.00,-16.12,8061.05,7600.00,461.05,0 -8383.88,8600.00,-216.12,7861.05,7650.00,211.05,0 -8183.88,8400.00,-216.12,7661.05,7450.00,211.05,0 -7983.88,7650.00,333.88,7461.05,7000.00,461.05,0 -7783.88,6600.00,1183.88,7261.05,6500.00,761.05,0 -7583.88,6900.00,683.88,7061.05,6400.00,661.05,0 -7383.88,7250.00,133.88,6861.05,6350.00,511.05,0 -7183.88,7600.00,-416.12,6661.05,6450.00,211.05,0 -6983.88,7050.00,-66.12,6461.05,5900.00,561.05,0 -6783.88,5900.00,883.88,6261.05,5100.00,1161.05,0 -6583.88,5450.00,1133.88,6061.05,4900.00,1161.05,0 -6383.88,5750.00,633.88,5861.05,5050.00,811.05,0 -6183.88,6050.00,133.88,5661.05,5100.00,561.05,0 -5983.88,5800.00,183.88,5461.05,4850.00,611.05,0 -5783.88,5050.00,733.88,5261.05,4800.00,461.05,0 -5583.88,4300.00,1283.88,5061.05,4200.00,861.05,0 -5383.88,4800.00,583.88,4861.05,3500.00,1361.05,0 -5183.88,5050.00,133.88,4661.05,3550.00,1111.05,0 -4983.88,4950.00,33.88,4461.05,3700.00,761.05,0 -4783.88,4050.00,733.88,4261.05,3550.00,711.05,0 -4583.88,3350.00,1233.88,4061.05,2550.00,1511.05,0 -4383.88,3000.00,1383.88,3861.05,1950.00,1911.05,0 -4183.88,3500.00,683.88,3661.05,2600.00,1061.05,0 -3983.88,3700.00,283.88,3461.05,3200.00,261.05,0 -3783.88,3000.00,783.88,3261.05,2800.00,461.05,0 -3583.88,2100.00,1483.88,3061.05,1500.00,1561.05,0 -3383.88,1850.00,1533.88,2861.05,1800.00,1061.05,0 -3183.88,2600.00,583.88,2661.05,1050.00,1611.05,0 -2983.88,2500.00,483.88,2461.05,1000.00,1461.05,0 -2783.88,1650.00,1133.88,2261.05,1600.00,661.05,0 -2583.88,950.00,1633.88,2061.05,850.00,1211.05,0 -2383.88,1550.00,833.88,1861.05,500.00,1361.05,0 -2183.88,750.00,1433.88,1661.05,750.00,911.05,0 -1983.88,450.00,1533.88,1461.05,350.00,1111.05,0 -1783.88,1550.00,233.88,1261.05,0.00,1261.05,0 -1583.88,1400.00,183.88,1061.05,0.00,1061.05,0 -1383.88,700.00,683.88,861.05,0.00,861.05,0 -1183.88,900.00,283.88,661.05,0.00,661.05,0 -983.88,350.00,633.88,461.05,0.00,461.05,0 -783.88,-250.00,1033.88,261.05,0.00,261.05,0 -583.88,0.00,583.88,61.05,0.00,61.05,0 -383.88,0.00,383.88,0.00,0.00,0.00,0 -183.88,0.00,183.88,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 --250.00,0.00,-250.00,-250.00,0.00,-250.00,0 --500.00,0.00,-500.00,-500.00,0.00,-500.00,0 --750.00,0.00,-750.00,-750.00,0.00,-750.00,0 --1060.00,0.00,-1060.00,-1060.00,0.00,-1060.00,0 --1310.00,0.00,-1310.00,-1310.00,0.00,-1310.00,0 --1570.00,0.00,-1570.00,-1570.00,0.00,-1570.00,0 --1830.00,0.00,-1830.00,-1830.00,0.00,-1830.00,0 --2080.00,-240.00,-1840.00,-2080.00,-160.00,-1920.00,0 --2340.00,-384.62,-1955.38,-2340.00,-576.92,-1763.08,0 --2590.00,-440.00,-2150.00,-2590.00,-640.00,-1950.00,0 --2850.00,-1384.62,-1465.38,-2850.00,-1461.54,-1388.46,0 --3110.00,-2307.69,-802.31,-3110.00,-1807.69,-1302.31,0 --3370.00,-2153.85,-1216.15,-3370.00,-1923.08,-1446.92,0 --3630.00,-1846.15,-1783.85,-3630.00,-2038.46,-1591.54,0 --3890.00,-2230.77,-1659.23,-3890.00,-2153.85,-1736.15,0 --4150.00,-2961.54,-1188.46,-4150.00,-2384.62,-1765.38,0 --4410.00,-3269.23,-1140.77,-4410.00,-2769.23,-1640.77,0 --4680.00,-3407.41,-1272.59,-4680.00,-3148.15,-1531.85,0 --4940.00,-3538.46,-1401.54,-4940.00,-3423.08,-1516.92,0 --5210.00,-3925.93,-1284.07,-5210.00,-3703.70,-1506.30,0 --5470.00,-4192.31,-1277.69,-5470.00,-3846.15,-1623.85,0 --5740.00,-4518.52,-1221.48,-5740.00,-4222.22,-1517.78,0 --6000.00,-4807.69,-1192.31,-6000.00,-4576.92,-1423.08,0 --6270.00,-5000.00,-1270.00,-6270.00,-4814.81,-1455.19,0 --6540.00,-5296.30,-1243.70,-6540.00,-5074.07,-1465.93,0 --6800.00,-5538.46,-1261.54,-6800.00,-5384.62,-1415.38,0 --7070.00,-5888.89,-1181.11,-7070.00,-5629.63,-1440.37,0 --7330.00,-6192.31,-1137.69,-7330.00,-5884.62,-1445.38,0 --7600.00,-6370.37,-1229.63,-7600.00,-6111.11,-1488.89,0 --7860.00,-6538.46,-1321.54,-7860.00,-6384.62,-1475.38,0 --8130.00,-6851.85,-1278.15,-8130.00,-6666.67,-1463.33,0 --8400.00,-7148.15,-1251.85,-8400.00,-6925.93,-1474.07,0 --8660.00,-7423.08,-1236.92,-8660.00,-7153.85,-1506.15,0 --8930.00,-7666.67,-1263.33,-8930.00,-7407.41,-1522.59,0 --9190.00,-7961.54,-1228.46,-9190.00,-7807.69,-1382.31,0 --9460.00,-8259.26,-1200.74,-9460.00,-8000.00,-1460.00,0 --9720.00,-8384.62,-1335.38,-9720.00,-8230.77,-1489.23,0 --9990.00,-8518.52,-1471.48,-9990.00,-8518.52,-1471.48,0 --10260.00,-8851.85,-1408.15,-10260.00,-8703.70,-1556.30,0 --10530.00,-9296.30,-1233.70,-10530.00,-8888.89,-1641.11,0 --10800.00,-9703.70,-1096.30,-10800.00,-9148.15,-1651.85,0 --11070.00,-9925.93,-1144.07,-11070.00,-9518.52,-1551.48,0 --11340.00,-10074.07,-1265.93,-11340.00,-9814.81,-1525.19,0 --11610.00,-10259.26,-1350.74,-11610.00,-9962.96,-1647.04,0 --11870.00,-10576.92,-1293.08,-11870.00,-10153.85,-1716.15,0 --12140.00,-10962.96,-1177.04,-12140.00,-10481.48,-1658.52,0 --12410.00,-11296.30,-1113.70,-12410.00,-10703.70,-1706.30,0 --12680.00,-11481.48,-1198.52,-12680.00,-10962.96,-1717.04,0 --12950.00,-11592.59,-1357.41,-12950.00,-11259.26,-1690.74,0 --13220.00,-11814.81,-1405.19,-13220.00,-11555.56,-1664.44,0 --13490.00,-12148.15,-1341.85,-13490.00,-11740.74,-1749.26,0 --13760.00,-12518.52,-1241.48,-13760.00,-12000.00,-1760.00,0 --14030.00,-12814.81,-1215.19,-14030.00,-12296.30,-1733.70,0 --14290.00,-13000.00,-1290.00,-14290.00,-12615.38,-1674.62,0 --14550.00,-13269.23,-1280.77,-14550.00,-12961.54,-1588.46,0 --14820.00,-13518.52,-1301.48,-14820.00,-13222.22,-1597.78,0 --15080.00,-13884.62,-1195.38,-15080.00,-13384.62,-1695.38,0 --15350.00,-14111.11,-1238.89,-15350.00,-13777.78,-1572.22,0 --15620.00,-14333.33,-1286.67,-15620.00,-13962.96,-1657.04,0 --15890.00,-14592.59,-1297.41,-15890.00,-14222.22,-1667.78,0 --16160.00,-14740.74,-1419.26,-16160.00,-14555.56,-1604.44,0 --16430.00,-15037.04,-1392.96,-16430.00,-14777.78,-1652.22,0 --16700.00,-15296.30,-1403.70,-16700.00,-15111.11,-1588.89,0 --16970.00,-15592.59,-1377.41,-16970.00,-15370.37,-1599.63,0 --17240.00,-15925.93,-1314.07,-17240.00,-15629.63,-1610.37,0 --17510.00,-16148.15,-1361.85,-17510.00,-15925.93,-1584.07,0 --17780.00,-16222.22,-1557.78,-17780.00,-16222.22,-1557.78,0 --18050.00,-16740.74,-1309.26,-18050.00,-16407.41,-1642.59,0 --18320.00,-17111.11,-1208.89,-18320.00,-16629.63,-1690.37,0 --18590.00,-17407.41,-1182.59,-18590.00,-16888.89,-1701.11,0 --18860.00,-17370.37,-1489.63,-18860.00,-17185.19,-1674.81,0 --19130.00,-17518.52,-1611.48,-19130.00,-17407.41,-1722.59,0 --19390.00,-17846.15,-1543.85,-19390.00,-17615.38,-1774.62,0 --19660.00,-18148.15,-1511.85,-19660.00,-17703.70,-1956.30,0 --19930.00,-18518.52,-1411.48,-19930.00,-18222.22,-1707.78,0 --20190.00,-18730.77,-1459.23,-20190.00,-18307.69,-1882.31,0 --20460.00,-19074.07,-1385.93,-20460.00,-18666.67,-1793.33,0 --20730.00,-19296.30,-1433.70,-20730.00,-18814.81,-1915.19,0 --21000.00,-19666.67,-1333.33,-21000.00,-19111.11,-1888.89,0 --21320.00,-19937.50,-1382.50,-21320.00,-19250.00,-2070.00,0 --21590.00,-20074.07,-1515.93,-21590.00,-19666.67,-1923.33,0 --21860.00,-20259.26,-1600.74,-21860.00,-20037.04,-1822.96,0 --22130.00,-20629.63,-1500.37,-22130.00,-20296.30,-1833.70,0 --22400.00,-21074.07,-1325.93,-22400.00,-20592.59,-1807.41,0 --22670.00,-21222.22,-1447.78,-22670.00,-20740.74,-1929.26,0 --22940.00,-21370.37,-1569.63,-22940.00,-21111.11,-1828.89,0 --23210.00,-21518.52,-1691.48,-23210.00,-21296.30,-1913.70,0 --23480.00,-21814.81,-1665.19,-23022.90,-21703.70,-1319.20,0 --23295.93,-22296.30,-999.64,-22752.90,-21814.81,-938.09,0 --23025.93,-22407.41,-618.53,-22482.90,-21592.59,-890.31,0 --22755.93,-22000.00,-755.93,-22212.90,-21370.37,-842.53,0 --22485.93,-21740.74,-745.19,-21942.90,-21000.00,-942.90,0 --22215.93,-21481.48,-734.45,-21672.90,-20740.74,-932.16,0 --21955.93,-21307.69,-648.24,-21412.90,-20384.62,-1028.29,0 --21685.93,-21148.15,-537.79,-21142.90,-20296.30,-846.61,0 --21415.93,-20814.81,-601.12,-20872.90,-19888.89,-984.01,0 --21145.93,-20481.48,-664.45,-20602.90,-19481.48,-1121.42,0 --20875.93,-20259.26,-616.68,-20332.90,-19148.15,-1184.75,0 --20605.93,-19666.67,-939.27,-20062.90,-19000.00,-1062.90,0 --20335.93,-19370.37,-965.56,-19792.90,-18740.74,-1052.16,0 --20065.93,-19518.52,-547.42,-19522.90,-18518.52,-1004.38,0 --19795.93,-19333.33,-462.60,-19252.90,-18185.19,-1067.72,0 --19535.93,-18884.62,-651.32,-18992.90,-18038.46,-954.44,0 --19275.93,-18615.38,-660.55,-18732.90,-17807.69,-925.21,0 --19005.93,-18296.30,-709.64,-18462.90,-17592.59,-870.31,0 --18745.93,-18230.77,-515.17,-18202.90,-17307.69,-895.21,0 --18475.93,-18000.00,-475.93,-17932.90,-17037.04,-895.87,0 --18205.93,-17629.63,-576.31,-17662.90,-16740.74,-922.16,0 --17935.93,-17333.33,-602.60,-17392.90,-16592.59,-800.31,0 --17675.93,-17115.38,-560.55,-17132.90,-16384.62,-748.29,0 --17405.93,-16925.93,-480.01,-16862.90,-16185.19,-677.72,0 --17135.93,-16777.78,-358.16,-16592.90,-15888.89,-704.01,0 --16865.93,-16481.48,-384.45,-16322.90,-15629.63,-693.27,0 --16595.93,-16000.00,-595.93,-16052.90,-15407.41,-645.50,0 --16325.93,-15740.74,-585.19,-15782.90,-15037.04,-745.87,0 --16055.93,-15629.63,-426.31,-15512.90,-14777.78,-735.13,0 --15785.93,-15481.48,-304.45,-15242.90,-14518.52,-724.38,0 --15515.93,-15148.15,-367.79,-14972.90,-14259.26,-713.64,0 --15255.93,-14769.23,-486.70,-14712.90,-14038.46,-674.44,0 --14985.93,-14296.30,-689.64,-14442.90,-13740.74,-702.16,0 --14715.93,-14259.26,-456.68,-14172.90,-13481.48,-691.42,0 --14445.93,-14148.15,-297.79,-13902.90,-13148.15,-754.75,0 --14175.93,-13814.81,-361.12,-13632.90,-12777.78,-855.13,0 --13915.93,-13384.62,-531.32,-13372.90,-12538.46,-834.44,0 --13645.93,-13111.11,-534.82,-13102.90,-12259.26,-843.64,0 --13375.93,-12888.89,-487.05,-12832.90,-11925.93,-906.98,0 --13105.93,-12629.63,-476.31,-12562.90,-11740.74,-822.16,0 --12835.93,-12444.44,-391.49,-12292.90,-11444.44,-848.46,0 --12575.93,-12346.15,-229.78,-12032.90,-11230.77,-802.13,0 --12315.93,-12115.38,-200.55,-11772.90,-11000.00,-772.90,0 --12045.93,-11740.74,-305.19,-11502.90,-10777.78,-725.13,0 --11775.93,-11333.33,-442.60,-11232.90,-10444.44,-788.46,0 --11505.93,-11074.07,-431.86,-10962.90,-10185.19,-777.72,0 --11235.93,-10925.93,-310.01,-10692.90,-9962.96,-729.94,0 --10975.93,-10769.23,-206.70,-10432.90,-9730.77,-702.13,0 --10705.93,-10444.44,-261.49,-10162.90,-9592.59,-570.31,0 --10435.93,-9962.96,-472.97,-9892.90,-9222.22,-670.68,0 --10165.93,-9888.89,-277.05,-9622.90,-9037.04,-585.87,0 --9895.93,-9851.85,-44.08,-9352.90,-8740.74,-612.16,0 --9635.93,-9500.00,-135.93,-9092.90,-8423.08,-669.83,0 --9365.93,-9074.07,-291.86,-8822.90,-8185.19,-637.72,0 --9095.93,-8777.78,-318.16,-8552.90,-7925.93,-626.98,0 --8825.93,-8555.56,-270.38,-8282.90,-7703.70,-579.20,0 --8565.93,-8384.62,-181.32,-8022.90,-7423.08,-599.83,0 --8295.93,-8111.11,-184.82,-7752.90,-7148.15,-604.75,0 --8025.93,-7814.81,-211.12,-7482.90,-6925.93,-556.98,0 --7755.93,-7518.52,-237.42,-7212.90,-6666.67,-546.24,0 --7485.93,-7222.22,-263.71,-6942.90,-6481.48,-461.42,0 --7225.93,-6961.54,-264.40,-6682.90,-6192.31,-490.60,0 --6955.93,-6703.70,-252.23,-6412.90,-5925.93,-486.98,0 --6685.93,-6481.48,-204.45,-6142.90,-5666.67,-476.24,0 --6415.93,-6000.00,-415.93,-5872.90,-5444.44,-428.46,0 --6145.93,-5222.22,-923.71,-5602.90,-5037.04,-565.87,0 --5885.93,-5269.23,-616.70,-5342.90,-4307.69,-1035.21,0 --5565.93,-5406.25,-159.68,-5022.90,-4312.50,-710.40,0 --5305.93,-5076.92,-229.01,-4762.90,-4230.77,-532.13,0 --5045.93,-4269.23,-776.70,-4502.90,-4000.00,-502.90,0 --4785.93,-3692.31,-1093.63,-4242.90,-3192.31,-1050.60,0 --4515.93,-4000.00,-515.93,-3972.90,-2814.81,-1158.09,0 --4245.93,-4074.07,-171.86,-3702.90,-2851.85,-851.05,0 --3985.93,-3346.15,-639.78,-3442.90,-2769.23,-673.67,0 --3725.93,-2653.85,-1072.09,-3182.90,-1961.54,-1221.36,0 --3465.93,-2269.23,-1196.70,-2922.90,-1769.23,-1153.67,0 --3205.93,-2576.92,-629.01,-2662.90,-1653.85,-1009.06,0 --2945.93,-2692.31,-253.63,-2402.90,-692.31,-1710.60,0 --2685.93,-2153.85,-532.09,-2142.90,76.92,-2219.83,0 --2425.93,-1269.23,-1156.70,-1882.90,-423.08,-1459.83,0 --2165.93,-1192.31,-973.63,-1622.90,-1192.31,-430.60,0 --1905.93,153.85,-2059.78,-1362.90,-923.08,-439.83,0 --1645.93,307.69,-1953.63,-1102.90,307.69,-1410.60,0 --1385.93,-769.23,-616.70,-842.90,384.62,-1227.52,0 --1135.93,-640.00,-495.93,-592.90,-200.00,-392.90,0 --875.93,-269.23,-606.70,-332.90,-38.46,-294.44,0 --605.93,-222.22,-383.71,-62.90,0.00,-62.90,0 --355.93,-480.00,124.07,0.00,0.00,0.00,0 --95.93,-307.69,211.76,0.00,0.00,0.00,0 -0.00,80.00,-80.00,0.00,0.00,0.00,0 -0.00,40.00,-40.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -240.00,0.00,240.00,240.00,0.00,240.00,0 -490.00,0.00,490.00,490.00,0.00,490.00,0 -740.00,0.00,740.00,740.00,0.00,740.00,0 -990.00,0.00,990.00,990.00,0.00,990.00,0 -1240.00,0.00,1240.00,1240.00,0.00,1240.00,0 -1540.00,0.00,1540.00,1540.00,0.00,1540.00,0 -1790.00,0.00,1790.00,1790.00,0.00,1790.00,0 -2040.00,200.00,1840.00,2040.00,240.00,1800.00,0 -2290.00,400.00,1890.00,2290.00,400.00,1890.00,0 -2540.00,440.00,2100.00,2540.00,320.00,2220.00,0 -2790.00,1200.00,1590.00,2790.00,640.00,2150.00,0 -3040.00,2240.00,800.00,3040.00,1800.00,1240.00,0 -3300.00,2269.23,1030.77,3300.00,2153.85,1146.15,0 -3550.00,1720.00,1830.00,3550.00,2120.00,1430.00,0 -3800.00,1080.00,2720.00,3800.00,2080.00,1720.00,0 -4050.00,2640.00,1410.00,4050.00,2240.00,1810.00,0 -4300.00,4040.00,260.00,4300.00,2560.00,1740.00,0 -4560.00,3846.15,713.85,4560.00,2884.62,1675.38,0 -4810.00,2960.00,1850.00,4810.00,3320.00,1490.00,0 -5070.00,2769.23,2300.77,5070.00,3461.54,1608.46,0 -5330.00,3923.08,1406.92,5330.00,3576.92,1753.08,0 -5580.00,4960.00,620.00,5580.00,3960.00,1620.00,0 -5840.00,5192.31,647.69,5840.00,4192.31,1647.69,0 -6090.00,5000.00,1090.00,6090.00,4520.00,1570.00,0 -6350.00,4923.08,1426.92,6350.00,4769.23,1580.77,0 -6610.00,5346.15,1263.85,6610.00,5000.00,1610.00,0 -6860.00,5760.00,1100.00,6860.00,5240.00,1620.00,0 -7120.00,5961.54,1158.46,7120.00,5423.08,1696.92,0 -7370.00,6160.00,1210.00,7370.00,5760.00,1610.00,0 -7630.00,6461.54,1168.46,7630.00,6038.46,1591.54,0 -7890.00,6692.31,1197.69,7890.00,6346.15,1543.85,0 -8140.00,7040.00,1100.00,8140.00,6560.00,1580.00,0 -8400.00,7307.69,1092.31,8400.00,6769.23,1630.77,0 -8650.00,7480.00,1170.00,8650.00,7000.00,1650.00,0 -8900.00,7560.00,1340.00,8900.00,7320.00,1580.00,0 -9160.00,7846.15,1313.85,9160.00,7576.92,1583.08,0 -9410.00,8160.00,1250.00,9410.00,7760.00,1650.00,0 -9670.00,8461.54,1208.46,9670.00,8000.00,1670.00,0 -9930.00,8769.23,1160.77,9930.00,8307.69,1622.31,0 -10190.00,9038.46,1151.54,10190.00,8615.38,1574.62,0 -10450.00,9307.69,1142.31,10450.00,8961.54,1488.46,0 -10710.00,9423.08,1286.92,10710.00,9192.31,1517.69,0 -10970.00,9730.77,1239.23,10970.00,9576.92,1393.08,0 -11230.00,9961.54,1268.46,11230.00,9692.31,1537.69,0 -11480.00,10160.00,1320.00,11480.00,9760.00,1720.00,0 -11740.00,10423.08,1316.92,11740.00,10076.92,1663.08,0 -12000.00,10730.77,1269.23,12000.00,10423.08,1576.92,0 -12260.00,10923.08,1336.92,12260.00,10692.31,1567.69,0 -12520.00,11192.31,1327.69,12520.00,10846.15,1673.85,0 -12780.00,11461.54,1318.46,12780.00,11076.92,1703.08,0 -13040.00,11769.23,1270.77,13040.00,11423.08,1616.92,0 -13300.00,12000.00,1300.00,13300.00,11769.23,1530.77,0 -13560.00,12307.69,1252.31,13560.00,12076.92,1483.08,0 -13810.00,12560.00,1250.00,13810.00,12320.00,1490.00,0 -14070.00,12807.69,1262.31,14070.00,12538.46,1531.54,0 -14330.00,13000.00,1330.00,14330.00,12730.77,1599.23,0 -14590.00,13192.31,1397.69,14590.00,12884.62,1705.38,0 -14850.00,13538.46,1311.54,14850.00,13423.08,1426.92,0 -15100.00,13920.00,1180.00,15100.00,13520.00,1580.00,0 -15360.00,14230.77,1129.23,15360.00,13884.62,1475.38,0 -15620.00,14461.54,1158.46,15620.00,14192.31,1427.69,0 -15880.00,14615.38,1264.62,15880.00,14115.38,1764.62,0 -16140.00,14846.15,1293.85,16140.00,14461.54,1678.46,0 -16400.00,15153.85,1246.15,16400.00,14846.15,1553.85,0 -16660.00,15423.08,1236.92,16660.00,15346.15,1313.85,0 -16920.00,15769.23,1150.77,16920.00,15576.92,1343.08,0 -17180.00,15961.54,1218.46,17180.00,15692.31,1487.69,0 -17440.00,16153.85,1286.15,17440.00,15538.46,1901.54,0 -17700.00,16461.54,1238.46,17700.00,16038.46,1661.54,0 -17960.00,16769.23,1190.77,17960.00,16269.23,1690.77,0 -18220.00,16615.38,1604.62,18220.00,16730.77,1489.23,0 -18480.00,16807.69,1672.31,18480.00,16807.69,1672.31,0 -18730.00,17160.00,1570.00,18730.00,17000.00,1730.00,0 -18990.00,17538.46,1451.54,18990.00,17038.46,1951.54,0 -19250.00,17730.77,1519.23,19250.00,17461.54,1788.46,0 -19510.00,18038.46,1471.54,19510.00,17807.69,1702.31,0 -19770.00,18307.69,1462.31,19770.00,17961.54,1808.46,0 -20030.00,18461.54,1568.46,20030.00,18346.15,1683.85,0 -20290.00,18730.77,1559.23,20290.00,18692.31,1597.69,0 -20550.00,18846.15,1703.85,20550.00,18846.15,1703.85,0 -20810.00,19423.08,1386.92,20810.00,19153.85,1656.15,0 -21070.00,19692.31,1377.69,21070.00,19384.62,1685.38,0 -21330.00,19692.31,1637.69,21330.00,19653.85,1676.15,0 -21640.00,20096.77,1543.23,21640.00,19870.97,1769.03,0 -21890.00,20400.00,1490.00,21890.00,20320.00,1570.00,0 -22150.00,20576.92,1573.08,22150.00,20076.92,2073.08,0 -22410.00,20846.15,1563.85,22410.00,20769.23,1640.77,0 -22670.00,21230.77,1439.23,22670.00,21153.85,1516.15,0 -22930.00,21423.08,1506.92,22930.00,21346.15,1583.85,0 -23190.00,21500.00,1690.00,23190.00,21423.08,1766.92,0 -23440.00,21960.00,1480.00,23206.76,21680.00,1526.76,0 -23490.08,22160.00,1330.08,22956.76,21840.00,1116.76,0 -23230.08,22576.92,653.16,22696.76,21730.77,965.99,0 -22970.08,22538.46,431.62,22436.76,21807.69,629.07,0 -22710.08,21846.15,863.93,22176.76,21269.23,907.53,0 -22450.08,21384.62,1065.47,21916.76,21115.38,801.37,0 -22190.08,21192.31,997.77,21656.76,20461.54,1195.22,0 -21930.08,21115.38,814.70,21396.76,20307.69,1089.07,0 -21670.08,21000.00,670.08,21136.76,20115.38,1021.37,0 -21410.08,20576.92,833.16,20876.76,20115.38,761.37,0 -21150.08,20346.15,803.93,20616.76,19769.23,847.53,0 -20890.08,20076.92,813.16,20356.76,19384.62,972.14,0 -20630.08,19730.77,899.31,20096.76,19153.85,942.91,0 -20380.08,19520.00,860.08,19846.76,18960.00,886.76,0 -20120.08,19461.54,658.54,19586.76,18730.77,855.99,0 -19870.08,19320.00,550.08,19336.76,18560.00,776.76,0 -19620.08,19040.00,580.08,19086.76,18200.00,886.76,0 -19360.08,18615.38,744.70,18826.76,18076.92,749.83,0 -19100.08,18346.15,753.93,18566.76,17653.85,912.91,0 -18850.08,18120.00,730.08,18316.76,17400.00,916.76,0 -18590.08,18153.85,436.23,18056.76,17000.00,1056.76,0 -18330.08,17846.15,483.93,17796.76,16923.08,873.68,0 -18070.08,17461.54,608.54,17536.76,16769.23,767.53,0 -17810.08,17115.38,694.70,17276.76,16423.08,853.68,0 -17550.08,16961.54,588.54,17016.76,16038.46,978.30,0 -17290.08,16807.69,482.39,16756.76,15923.08,833.68,0 -17040.08,16640.00,400.08,16506.76,15760.00,746.76,0 -16780.08,16307.69,472.39,16246.76,15461.54,785.22,0 -16530.08,15960.00,570.08,15996.76,15280.00,716.76,0 -16290.08,15458.33,831.75,15756.76,14791.67,965.09,0 -16030.08,15384.62,645.47,15496.76,14730.77,765.99,0 -15770.08,15307.69,462.39,15236.76,14615.38,621.37,0 -15510.08,15115.38,394.70,14976.76,14269.23,707.53,0 -15260.08,14640.00,620.08,14726.76,13880.00,846.76,0 -15000.08,14346.15,653.93,14466.76,13576.92,889.83,0 -14750.08,14080.00,670.08,14216.76,13400.00,816.76,0 -14490.08,14000.00,490.08,13956.76,13115.38,841.37,0 -14230.08,13807.69,422.39,13696.76,13115.38,581.37,0 -13980.08,13360.00,620.08,13446.76,12840.00,606.76,0 -13720.08,13076.92,643.16,13186.76,12423.08,763.68,0 -13460.08,13038.46,421.62,12926.76,12076.92,849.83,0 -13200.08,12807.69,392.39,12666.76,11846.15,820.60,0 -12940.08,12538.46,401.62,12406.76,11384.62,1022.14,0 -12680.08,12230.77,449.31,12146.76,11423.08,723.68,0 -12430.08,11920.00,510.08,11896.76,11320.00,576.76,0 -12180.08,11800.00,380.08,11646.76,11040.00,606.76,0 -11920.08,11653.85,266.23,11386.76,10730.77,655.99,0 -11660.08,11384.62,275.47,11126.76,10500.00,626.76,0 -11400.08,11076.92,323.16,10866.76,10346.15,520.60,0 -11140.08,10846.15,293.93,10606.76,10038.46,568.30,0 -10880.08,10615.38,264.70,10346.76,9769.23,577.53,0 -10620.08,10384.62,235.47,10086.76,9615.38,471.37,0 -10360.08,10153.85,206.23,9826.76,9269.23,557.53,0 -10100.08,9846.15,253.93,9566.76,8961.54,605.22,0 -9840.08,9615.38,224.70,9306.76,8653.85,652.91,0 -9580.08,9423.08,157.00,9046.76,8423.08,623.68,0 -9320.08,9115.38,204.70,8786.76,8269.23,517.53,0 -9060.08,8807.69,252.39,8526.76,7884.62,642.14,0 -8800.08,8576.92,223.16,8266.76,7615.38,651.37,0 -8540.08,8384.62,155.47,8006.76,7461.54,545.22,0 -8280.08,8115.38,164.70,7746.76,7153.85,592.91,0 -8020.08,7884.62,135.47,7486.76,6923.08,563.68,0 -7760.08,7538.46,221.62,7226.76,6653.85,572.91,0 -7500.08,7307.69,192.39,6966.76,6346.15,620.60,0 -7240.08,7153.85,86.23,6706.76,6115.38,591.37,0 -6980.08,6615.38,364.70,6446.76,5846.15,600.60,0 -6730.08,5760.00,970.08,6196.76,5640.00,556.76,0 -6470.08,5846.15,623.93,5936.76,5384.62,552.14,0 -6220.08,6160.00,60.08,5686.76,5080.00,606.76,0 -5960.08,5769.23,190.85,5426.76,4769.23,657.53,0 -5700.08,4846.15,853.93,5166.76,4538.46,628.30,0 -5400.08,4366.67,1033.41,4866.76,4033.33,833.42,0 -5140.08,4807.69,332.39,4606.76,3307.69,1299.07,0 -4880.08,4769.23,110.85,4346.76,3192.31,1154.45,0 -4620.08,3961.54,658.54,4086.76,3307.69,779.07,0 -4360.08,3269.23,1090.85,3826.76,3000.00,826.76,0 -4110.08,3040.00,1070.08,3576.76,2200.00,1376.76,0 -3860.08,3480.00,380.08,3326.76,1680.00,1646.76,0 -3610.08,3440.00,170.08,3076.76,1920.00,1156.76,0 -3360.08,2640.00,720.08,2826.76,2000.00,826.76,0 -3100.08,2153.85,946.23,2566.76,1000.00,1566.76,0 -2850.08,1440.00,1410.08,2316.76,160.00,2156.76,0 -2600.08,1600.00,1000.08,2066.76,1080.00,986.76,0 -2350.08,1760.00,590.08,1816.76,1480.00,336.76,0 -2100.08,640.00,1460.08,1566.76,320.00,1246.76,0 -1850.08,-160.00,2010.08,1316.76,-40.00,1356.76,0 -1600.08,120.00,1480.08,1066.76,0.00,1066.76,0 -1350.08,200.00,1150.08,816.76,0.00,816.76,0 -1100.08,-360.00,1460.08,566.76,0.00,566.76,0 -850.08,-760.00,1610.08,316.76,0.00,316.76,0 -600.08,-160.00,760.08,66.76,0.00,66.76,0 -350.08,240.00,110.08,0.00,0.00,0.00,0 -110.08,-41.67,151.75,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,0 -0.00,0.00,0.00,0.00,0.00,0.00,252.58 -0.00,0.00,0.00,0.00,0.00,0.00,252.61 -0.00,0.00,0.00,0.00,0.00,0.00,252.63 -0.00,0.00,0.00,0.00,0.00,0.00,252.66 -0.00,0.00,0.00,0.00,0.00,0.00,252.68 -0.00,0.00,0.00,0.00,0.00,0.00,252.70 -0.00,0.00,0.00,0.00,0.00,0.00,252.69 -0.00,0.00,0.00,0.00,0.00,0.00,252.68 --280.00,0.00,-280.00,-280.00,0.00,-280.00,252.63 --610.00,0.00,-610.00,-610.00,0.00,-610.00,252.59 --890.00,0.00,-890.00,-890.00,0.00,-890.00,252.56 --1180.00,0.00,-1180.00,-1180.00,0.00,-1180.00,252.57 --1460.00,0.00,-1460.00,-1460.00,0.00,-1460.00,252.58 --1750.00,0.00,-1750.00,-1750.00,0.00,-1750.00,252.59 --2030.00,-178.57,-1851.43,-2030.00,-250.00,-1780.00,252.59 --2320.00,-275.86,-2044.14,-2320.00,-1448.28,-871.72,252.59 --2610.00,-206.90,-2403.10,-2610.00,-931.03,-1678.97,252.59 --2900.00,-758.62,-2141.38,-2900.00,-896.55,-2003.45,252.39 --3190.00,-2448.28,-741.72,-3190.00,-1172.41,-2017.59,252.22 --3480.00,-2862.07,-617.93,-3480.00,-1793.10,-1686.90,252.07 --3770.00,-1655.17,-2114.83,-3770.00,-2137.93,-1632.07,251.94 --4060.00,-1620.69,-2439.31,-4060.00,-2275.86,-1784.14,251.84 --4350.00,-3068.97,-1281.03,-4350.00,-2413.79,-1936.21,251.69 --4640.00,-4206.90,-433.10,-4640.00,-2827.59,-1812.41,251.56 --4930.00,-4000.00,-930.00,-4930.00,-3241.38,-1688.62,251.46 --5220.00,-3068.97,-2151.03,-5220.00,-3448.28,-1771.72,251.38 --5510.00,-3551.72,-1958.28,-5510.00,-3724.14,-1785.86,251.32 --5800.00,-4758.62,-1041.38,-5800.00,-4068.97,-1731.03,251.27 --6080.00,-5357.14,-722.86,-6080.00,-4392.86,-1687.14,251.21 --6370.00,-5275.86,-1094.14,-6370.00,-4620.69,-1749.31,251.16 --6660.00,-5172.41,-1487.59,-6660.00,-4931.03,-1728.97,251.14 --6940.00,-5500.00,-1440.00,-6940.00,-5250.00,-1690.00,251.11 --7230.00,-5965.52,-1264.48,-7230.00,-5551.72,-1678.28,251.10 --7510.00,-6392.86,-1117.14,-7510.00,-5857.14,-1652.86,251.11 --7800.00,-6551.72,-1248.28,-7800.00,-6137.93,-1662.07,251.12 --8090.00,-6827.59,-1262.41,-8090.00,-6551.72,-1538.28,251.13 --8380.00,-7103.45,-1276.55,-8380.00,-6896.55,-1483.45,251.11 --8670.00,-7448.28,-1221.72,-8670.00,-7103.45,-1566.55,251.09 --8960.00,-7724.14,-1235.86,-8960.00,-7379.31,-1580.69,251.07 --9250.00,-8000.00,-1250.00,-9250.00,-7724.14,-1525.86,251.05 --9540.00,-8241.38,-1298.62,-9540.00,-7965.52,-1574.48,251.04 --9830.00,-8517.24,-1312.76,-9830.00,-8275.86,-1554.14,251.02 --10110.00,-8857.14,-1252.86,-10110.00,-8607.14,-1502.86,251.02 --10400.00,-9206.90,-1193.10,-10400.00,-8931.03,-1468.97,251.02 --10690.00,-9482.76,-1207.24,-10690.00,-9172.41,-1517.59,250.93 --10980.00,-9724.14,-1255.86,-10980.00,-9413.79,-1566.21,250.85 --11270.00,-10034.48,-1235.52,-11270.00,-9724.14,-1545.86,250.79 --11560.00,-10241.38,-1318.62,-11560.00,-10103.45,-1456.55,250.85 --11850.00,-10586.21,-1263.79,-11850.00,-10379.31,-1470.69,250.89 --12140.00,-11000.00,-1140.00,-12140.00,-10689.66,-1450.34,250.93 --12440.00,-11233.33,-1206.67,-12440.00,-11066.67,-1373.33,250.93 --12730.00,-11413.79,-1316.21,-12730.00,-11310.34,-1419.66,250.92 --13020.00,-11689.66,-1330.34,-13020.00,-11551.72,-1468.28,250.92 --13310.00,-12034.48,-1275.52,-13310.00,-11827.59,-1482.41,250.93 --13610.00,-12400.00,-1210.00,-13610.00,-12166.67,-1443.33,250.94 --13910.00,-12700.00,-1210.00,-13910.00,-12433.33,-1476.67,251.00 --14210.00,-12966.67,-1243.33,-14210.00,-12666.67,-1543.33,251.04 --14500.00,-13206.90,-1293.10,-14500.00,-12827.59,-1672.41,251.08 --14800.00,-13500.00,-1300.00,-14800.00,-13066.67,-1733.33,251.10 --15100.00,-13833.33,-1266.67,-15100.00,-13466.67,-1633.33,251.11 --15400.00,-14133.33,-1266.67,-15400.00,-13733.33,-1666.67,251.12 --15700.00,-14333.33,-1366.67,-15700.00,-14066.67,-1633.33,251.16 --16000.00,-14500.00,-1500.00,-16000.00,-14400.00,-1600.00,251.19 --16290.00,-14931.03,-1358.97,-16290.00,-14586.21,-1703.79,251.17 --16590.00,-15400.00,-1190.00,-16590.00,-14866.67,-1723.33,251.16 --16890.00,-15700.00,-1190.00,-16890.00,-15133.33,-1756.67,251.14 --17190.00,-15833.33,-1356.67,-17190.00,-15433.33,-1756.67,251.16 --17490.00,-16066.67,-1423.33,-17490.00,-15666.67,-1823.33,251.18 --17790.00,-16133.33,-1656.67,-17790.00,-15933.33,-1856.67,251.19 --18090.00,-16766.67,-1323.33,-18090.00,-16133.33,-1956.67,251.16 --18390.00,-17166.67,-1223.33,-18390.00,-16600.00,-1790.00,251.13 --18690.00,-17566.67,-1123.33,-18690.00,-17000.00,-1690.00,251.10 --18990.00,-17600.00,-1390.00,-18990.00,-17200.00,-1790.00,251.08 --19290.00,-17600.00,-1690.00,-19290.00,-17433.33,-1856.67,251.07 --19590.00,-18166.67,-1423.33,-19590.00,-17766.67,-1823.33,251.01 --19890.00,-18566.67,-1323.33,-19890.00,-18066.67,-1823.33,250.97 --20180.00,-18931.03,-1248.97,-20180.00,-18448.28,-1731.72,250.93 --20480.00,-19100.00,-1380.00,-20480.00,-18800.00,-1680.00,250.96 --20830.00,-19228.57,-1601.43,-20830.00,-19028.57,-1801.43,250.98 --21130.00,-19533.33,-1596.67,-21130.00,-19400.00,-1730.00,250.98 --21430.00,-20066.67,-1363.33,-21430.00,-19700.00,-1730.00,250.98 --21730.00,-20266.67,-1463.33,-21730.00,-19933.33,-1796.67,250.98 --22030.00,-20633.33,-1396.67,-22030.00,-20100.00,-1930.00,251.04 --22330.00,-20900.00,-1430.00,-22330.00,-20433.33,-1896.67,251.09 --22630.00,-21200.00,-1430.00,-22630.00,-20733.33,-1896.67,251.17 --22930.00,-21266.67,-1663.33,-22930.00,-20933.33,-1996.67,251.24 --23230.00,-21566.67,-1663.33,-23230.00,-21233.33,-1996.67,251.29 --23488.72,-22033.33,-1455.39,-22932.89,-21600.00,-1332.89,251.20 --23188.72,-22200.00,-988.72,-22632.89,-21733.33,-899.56,251.13 --22888.72,-22333.33,-555.39,-22332.89,-21566.67,-766.22,251.08 --22598.72,-22413.79,-184.93,-22042.89,-21103.45,-939.44,251.04 --22298.72,-21666.67,-632.05,-21742.89,-20633.33,-1109.56,251.02 --21998.72,-21333.33,-665.39,-21442.89,-20233.33,-1209.56,251.00 --21698.72,-20900.00,-798.72,-21142.89,-20100.00,-1042.89,251.03 --21398.72,-20666.67,-732.05,-20842.89,-19933.33,-909.56,251.06 --21098.72,-20466.67,-632.05,-20542.89,-19666.67,-876.22,250.98 --20798.72,-20200.00,-598.72,-20242.89,-19300.00,-942.89,250.92 --20498.72,-19666.67,-832.05,-19942.89,-19100.00,-842.89,250.88 --20198.72,-19666.67,-532.05,-19642.89,-18800.00,-842.89,250.94 --19898.72,-19533.33,-365.39,-19342.89,-18533.33,-809.56,251.00 --19598.72,-19133.33,-465.39,-19042.89,-18233.33,-809.56,251.04 --19298.72,-18766.67,-532.05,-18742.89,-18000.00,-742.89,251.11 --18998.72,-18400.00,-598.72,-18442.89,-17566.67,-876.22,251.17 --18698.72,-18000.00,-698.72,-18142.89,-17200.00,-942.89,251.20 --18398.72,-17966.67,-432.05,-17842.89,-16900.00,-942.89,251.22 --18098.72,-17733.33,-365.39,-17542.89,-16666.67,-876.22,251.24 --17798.72,-17266.67,-532.05,-17242.89,-16333.33,-909.56,251.25 --17498.72,-16600.00,-898.72,-16942.89,-16000.00,-942.89,251.26 --17208.72,-16620.69,-588.03,-16652.89,-15758.62,-894.27,251.27 --16908.72,-16433.33,-475.39,-16352.89,-15500.00,-852.89,251.18 --16608.72,-16200.00,-408.72,-16052.89,-15133.33,-919.56,251.10 --16308.72,-15866.67,-442.05,-15752.89,-14800.00,-952.89,251.07 --16008.72,-15633.33,-375.39,-15452.89,-14400.00,-1052.89,251.04 --15708.72,-15366.67,-342.05,-15152.89,-14266.67,-886.22,251.02 --15418.72,-15000.00,-418.72,-14862.89,-14068.97,-793.92,251.01 --15118.72,-14666.67,-452.05,-14562.89,-13866.67,-696.22,251.01 --14828.72,-14482.76,-345.96,-14272.89,-13551.72,-721.16,251.01 --14528.72,-14166.67,-362.05,-13972.89,-13166.67,-806.22,251.00 --14238.72,-13827.59,-411.13,-13682.89,-12827.59,-855.30,251.00 --13948.72,-13551.72,-397.00,-13392.89,-12551.72,-841.16,251.01 --13658.72,-13310.34,-348.37,-13102.89,-12413.79,-689.10,251.02 --13358.72,-13100.00,-258.72,-12802.89,-12133.33,-669.56,251.03 --13058.72,-12833.33,-225.39,-12502.89,-11866.67,-636.22,251.04 --12768.72,-12482.76,-285.96,-12212.89,-11724.14,-488.75,251.05 --12478.72,-12137.93,-340.79,-11922.89,-11379.31,-543.58,251.06 --12188.72,-11827.59,-361.13,-11632.89,-11068.97,-563.92,251.08 --11898.72,-11551.72,-347.00,-11342.89,-10793.10,-549.78,251.10 --11608.72,-11275.86,-332.86,-11052.89,-10482.76,-570.13,251.12 --11308.72,-10966.67,-342.05,-10752.89,-10200.00,-552.89,251.14 --11018.72,-10724.14,-294.58,-10462.89,-9965.52,-497.37,251.16 --10728.72,-10482.76,-245.96,-10172.89,-9689.66,-483.23,251.13 --10438.72,-10137.93,-300.79,-9882.89,-9275.86,-607.03,251.11 --10158.72,-9892.86,-265.86,-9602.89,-8964.29,-638.60,251.09 --9868.72,-9655.17,-213.55,-9312.89,-8689.66,-623.23,251.08 --9578.72,-9344.83,-233.89,-9022.89,-8482.76,-540.13,251.07 --9288.72,-8931.03,-357.69,-8732.89,-8206.90,-525.99,251.06 --9008.72,-8607.14,-401.58,-8452.89,-7857.14,-595.75,251.10 --8718.72,-8482.76,-235.96,-8162.89,-7620.69,-542.20,251.14 --8428.72,-8206.90,-221.82,-7872.89,-7275.86,-597.03,251.17 --8138.72,-7862.07,-276.65,-7582.89,-7068.97,-513.92,251.19 --7848.72,-7586.21,-262.51,-7292.89,-6724.14,-568.75,251.21 --7568.72,-7285.71,-283.01,-7012.89,-6428.57,-584.32,251.24 --7288.72,-7035.71,-253.01,-6732.89,-6035.71,-697.17,251.27 --7008.72,-6750.00,-258.72,-6452.89,-5857.14,-595.75,251.29 --6728.72,-6428.57,-300.15,-6172.89,-5535.71,-637.17,251.28 --6448.72,-6214.29,-234.43,-5892.89,-5214.29,-678.60,251.27 --6108.72,-5735.29,-373.43,-5552.89,-4941.18,-611.71,251.27 --5818.72,-4655.17,-1163.55,-5262.89,-4586.21,-676.68,251.24 --5528.72,-4137.93,-1390.79,-4972.89,-4310.34,-662.54,251.21 --5248.72,-4750.00,-498.72,-4692.89,-3892.86,-800.03,251.20 --4968.72,-4678.57,-290.15,-4412.89,-3250.00,-1162.89,251.18 --4688.72,-3821.43,-867.29,-4132.89,-2928.57,-1204.32,251.17 --4398.72,-3310.34,-1088.37,-3842.89,-3034.48,-808.41,251.16 --4118.72,-3607.14,-511.58,-3562.89,-2857.14,-705.75,251.14 --3828.72,-3655.17,-173.55,-3272.89,-1965.52,-1307.37,251.13 --3548.72,-3000.00,-548.72,-2992.89,-1464.29,-1528.60,251.04 --3258.72,-2275.86,-982.86,-2702.89,-1310.34,-1392.54,250.97 --2978.72,-1571.43,-1407.29,-2422.89,-1571.43,-851.46,250.92 --2698.72,-1571.43,-1127.29,-2142.89,-1500.00,-642.89,250.92 --2408.72,-1758.62,-650.10,-1852.89,-137.93,-1714.96,250.92 --2118.72,-931.03,-1187.69,-1562.89,413.79,-1976.68,250.93 --1828.72,206.90,-2035.62,-1272.89,-206.90,-1065.99,250.89 --1548.72,392.86,-1941.58,-992.89,-35.71,-957.17,250.86 --1268.72,-285.71,-983.01,-712.89,571.43,-1284.32,250.83 --978.72,-275.86,-702.86,-422.89,68.97,-491.85,250.78 --688.72,275.86,-964.58,-132.89,-68.97,-63.92,250.74 --398.72,896.55,-1295.27,0.00,0.00,0.00,250.77 --118.72,-71.43,-47.29,0.00,0.00,0.00,250.80 -0.00,-214.29,214.29,0.00,0.00,0.00,250.82 -0.00,71.43,-71.43,0.00,0.00,0.00,250.87 -0.00,0.00,0.00,0.00,0.00,0.00,250.92 -0.00,0.00,0.00,0.00,0.00,0.00,250.95 -0.00,0.00,0.00,0.00,0.00,0.00,250.97 -0.00,0.00,0.00,0.00,0.00,0.00,250.98 -0.00,0.00,0.00,0.00,0.00,0.00,250.99 -0.00,0.00,0.00,0.00,0.00,0.00,250.98 -0.00,0.00,0.00,0.00,0.00,0.00,250.98 -0.00,0.00,0.00,0.00,0.00,0.00,250.97 -0.00,0.00,0.00,0.00,0.00,0.00,250.96 -0.00,0.00,0.00,0.00,0.00,0.00,250.96 -0.00,0.00,0.00,0.00,0.00,0.00,250.95 -0.00,0.00,0.00,0.00,0.00,0.00,250.94 -0.00,0.00,0.00,0.00,0.00,0.00,250.93 -0.00,0.00,0.00,0.00,0.00,0.00,250.93 -0.00,0.00,0.00,0.00,0.00,0.00,250.96 -0.00,0.00,0.00,0.00,0.00,0.00,250.99 -0.00,0.00,0.00,0.00,0.00,0.00,251.01 -0.00,0.00,0.00,0.00,0.00,0.00,251.00 -0.00,0.00,0.00,0.00,0.00,0.00,250.99 -0.00,0.00,0.00,0.00,0.00,0.00,250.99 -0.00,0.00,0.00,0.00,0.00,0.00,251.00 -0.00,0.00,0.00,0.00,0.00,0.00,251.01 -0.00,0.00,0.00,0.00,0.00,0.00,251.01 -0.00,0.00,0.00,0.00,0.00,0.00,251.03 -0.00,0.00,0.00,0.00,0.00,0.00,251.03 -0.00,0.00,0.00,0.00,0.00,0.00,251.03 -0.00,0.00,0.00,0.00,0.00,0.00,251.02 -0.00,0.00,0.00,0.00,0.00,0.00,251.02 -0.00,0.00,0.00,0.00,0.00,0.00,251.02 -0.00,0.00,0.00,0.00,0.00,0.00,251.03 -0.00,0.00,0.00,0.00,0.00,0.00,251.04 -0.00,0.00,0.00,0.00,0.00,0.00,251.08 -0.00,0.00,0.00,0.00,0.00,0.00,251.11 -0.00,0.00,0.00,0.00,0.00,0.00,251.13 -0.00,0.00,0.00,0.00,0.00,0.00,251.15 -0.00,0.00,0.00,0.00,0.00,0.00,251.17 -0.00,0.00,0.00,0.00,0.00,0.00,251.18 -0.00,0.00,0.00,0.00,0.00,0.00,251.17 -0.00,0.00,0.00,0.00,0.00,0.00,251.16 -0.00,0.00,0.00,0.00,0.00,0.00,251.15 -0.00,0.00,0.00,0.00,0.00,0.00,251.17 -0.00,0.00,0.00,0.00,0.00,0.00,251.18 -0.00,0.00,0.00,0.00,0.00,0.00,251.19 -0.00,0.00,0.00,0.00,0.00,0.00,251.17 -0.00,0.00,0.00,0.00,0.00,0.00,251.15 -0.00,0.00,0.00,0.00,0.00,0.00,251.14 -0.00,0.00,0.00,0.00,0.00,0.00,251.12 -0.00,0.00,0.00,0.00,0.00,0.00,251.12 -0.00,0.00,0.00,0.00,0.00,0.00,251.11 -0.00,0.00,0.00,0.00,0.00,0.00,251.11 -0.00,0.00,0.00,0.00,0.00,0.00,251.10 -0.00,0.00,0.00,0.00,0.00,0.00,251.13 -0.00,0.00,0.00,0.00,0.00,0.00,251.16 -0.00,0.00,0.00,0.00,0.00,0.00,251.18 -0.00,0.00,0.00,0.00,0.00,0.00,251.14 -0.00,0.00,0.00,0.00,0.00,0.00,251.11 -0.00,0.00,0.00,0.00,0.00,0.00,251.09 -0.00,0.00,0.00,0.00,0.00,0.00,251.07 -0.00,0.00,0.00,0.00,0.00,0.00,251.05 -0.00,0.00,0.00,0.00,0.00,0.00,251.04 -0.00,0.00,0.00,0.00,0.00,0.00,250.99 -0.00,0.00,0.00,0.00,0.00,0.00,250.95 -0.00,0.00,0.00,0.00,0.00,0.00,250.92 -0.00,0.00,0.00,0.00,0.00,0.00,250.96 -0.00,0.00,0.00,0.00,0.00,0.00,251.00 -0.00,0.00,0.00,0.00,0.00,0.00,251.02 -0.00,0.00,0.00,0.00,0.00,0.00,251.04 -0.00,0.00,0.00,0.00,0.00,0.00,251.06 -0.00,0.00,0.00,0.00,0.00,0.00,251.05 -0.00,0.00,0.00,0.00,0.00,0.00,251.04 -0.00,0.00,0.00,0.00,0.00,0.00,251.03 -0.00,0.00,0.00,0.00,0.00,0.00,251.08 -0.00,0.00,0.00,0.00,0.00,0.00,251.12 -0.00,0.00,0.00,0.00,0.00,0.00,251.16 -0.00,0.00,0.00,0.00,0.00,0.00,251.16 -0.00,0.00,0.00,0.00,0.00,0.00,251.16 -0.00,0.00,0.00,0.00,0.00,0.00,251.16 -0.00,0.00,0.00,0.00,0.00,0.00,251.20 -0.00,0.00,0.00,0.00,0.00,0.00,251.23 -0.00,0.00,0.00,0.00,0.00,0.00,251.25 -0.00,0.00,0.00,0.00,0.00,0.00,251.25 -0.00,0.00,0.00,0.00,0.00,0.00,251.24 -0.00,0.00,0.00,0.00,0.00,0.00,251.24 -0.00,0.00,0.00,0.00,0.00,0.00,251.25 -0.00,0.00,0.00,0.00,0.00,0.00,251.26 -0.00,0.00,0.00,0.00,0.00,0.00,251.27 -0.00,0.00,0.00,0.00,0.00,0.00,251.27 -0.00,0.00,0.00,0.00,0.00,0.00,251.28 -0.00,0.00,0.00,0.00,0.00,0.00,251.28 -0.00,0.00,0.00,0.00,0.00,0.00,251.24 -0.00,0.00,0.00,0.00,0.00,0.00,251.20 -0.00,0.00,0.00,0.00,0.00,0.00,251.24 -0.00,0.00,0.00,0.00,0.00,0.00,251.27 -0.00,0.00,0.00,0.00,0.00,0.00,251.29 -0.00,0.00,0.00,0.00,0.00,0.00,251.29 -0.00,0.00,0.00,0.00,0.00,0.00,251.28 -0.00,0.00,0.00,0.00,0.00,0.00,251.28 -0.00,0.00,0.00,0.00,0.00,0.00,251.29 -0.00,0.00,0.00,0.00,0.00,0.00,251.30 -0.00,0.00,0.00,0.00,0.00,0.00,251.31 -0.00,0.00,0.00,0.00,0.00,0.00,251.31 -0.00,0.00,0.00,0.00,0.00,0.00,251.31 -0.00,0.00,0.00,0.00,0.00,0.00,251.30 -0.00,0.00,0.00,0.00,0.00,0.00,251.33 -0.00,0.00,0.00,0.00,0.00,0.00,251.35 -0.00,0.00,0.00,0.00,0.00,0.00,251.37 -0.00,0.00,0.00,0.00,0.00,0.00,251.32 -0.00,0.00,0.00,0.00,0.00,0.00,251.29 -0.00,0.00,0.00,0.00,0.00,0.00,251.26 -0.00,0.00,0.00,0.00,0.00,0.00,251.25 -0.00,0.00,0.00,0.00,0.00,0.00,251.24 -0.00,0.00,0.00,0.00,0.00,0.00,251.23 -0.00,0.00,0.00,0.00,0.00,0.00,251.20 -0.00,0.00,0.00,0.00,0.00,0.00,251.17 -0.00,0.00,0.00,0.00,0.00,0.00,251.15 -0.00,0.00,0.00,0.00,0.00,0.00,251.15 -0.00,0.00,0.00,0.00,0.00,0.00,251.15 -0.00,0.00,0.00,0.00,0.00,0.00,251.15 -0.00,0.00,0.00,0.00,0.00,0.00,251.18 -0.00,0.00,0.00,0.00,0.00,0.00,251.21 -0.00,0.00,0.00,0.00,0.00,0.00,251.21 -0.00,0.00,0.00,0.00,0.00,0.00,251.21 -0.00,0.00,0.00,0.00,0.00,0.00,251.21 -0.00,0.00,0.00,0.00,0.00,0.00,251.19 -0.00,0.00,0.00,0.00,0.00,0.00,251.18 -0.00,0.00,0.00,0.00,0.00,0.00,251.17 -0.00,0.00,0.00,0.00,0.00,0.00,251.14 -0.00,0.00,0.00,0.00,0.00,0.00,251.12 -0.00,0.00,0.00,0.00,0.00,0.00,251.10 -0.00,0.00,0.00,0.00,0.00,0.00,251.07 -0.00,0.00,0.00,0.00,0.00,0.00,251.05 -0.00,0.00,0.00,0.00,0.00,0.00,251.03 -0.00,0.00,0.00,0.00,0.00,0.00,251.08 -0.00,0.00,0.00,0.00,0.00,0.00,251.11 -0.00,0.00,0.00,0.00,0.00,0.00,251.14 -0.00,0.00,0.00,0.00,0.00,0.00,251.13 -0.00,0.00,0.00,0.00,0.00,0.00,251.11 -0.00,0.00,0.00,0.00,0.00,0.00,251.13 -0.00,0.00,0.00,0.00,0.00,0.00,251.15 -0.00,0.00,0.00,0.00,0.00,0.00,251.17 -0.00,0.00,0.00,0.00,0.00,0.00,251.21 -0.00,0.00,0.00,0.00,0.00,0.00,251.25 -0.00,0.00,0.00,0.00,0.00,0.00,251.28 -0.00,0.00,0.00,0.00,0.00,0.00,251.26 -0.00,0.00,0.00,0.00,0.00,0.00,251.25 -0.00,0.00,0.00,0.00,0.00,0.00,251.24 -0.00,0.00,0.00,0.00,0.00,0.00,251.25 -0.00,0.00,0.00,0.00,0.00,0.00,251.26 -0.00,0.00,0.00,0.00,0.00,0.00,251.27 -0.00,0.00,0.00,0.00,0.00,0.00,251.27 -0.00,0.00,0.00,0.00,0.00,0.00,251.28 -0.00,0.00,0.00,0.00,0.00,0.00,251.29 -0.00,0.00,0.00,0.00,0.00,0.00,251.29 -0.00,0.00,0.00,0.00,0.00,0.00,251.29 -0.00,0.00,0.00,0.00,0.00,0.00,251.29 -0.00,0.00,0.00,0.00,0.00,0.00,251.28 -0.00,0.00,0.00,0.00,0.00,0.00,251.27 -0.00,0.00,0.00,0.00,0.00,0.00,251.26 -0.00,0.00,0.00,0.00,0.00,0.00,251.30 -0.00,0.00,0.00,0.00,0.00,0.00,251.33 -0.00,0.00,0.00,0.00,0.00,0.00,251.35 -0.00,0.00,0.00,0.00,0.00,0.00,251.32 -0.00,0.00,0.00,0.00,0.00,0.00,251.29 -0.00,0.00,0.00,0.00,0.00,0.00,251.24 -0.00,0.00,0.00,0.00,0.00,0.00,251.20 -0.00,0.00,0.00,0.00,0.00,0.00,251.17 -0.00,0.00,0.00,0.00,0.00,0.00,251.13 -0.00,0.00,0.00,0.00,0.00,0.00,251.09 -0.00,0.00,0.00,0.00,0.00,0.00,251.06 -0.00,0.00,0.00,0.00,0.00,0.00,251.11 -0.00,0.00,0.00,0.00,0.00,0.00,251.14 -0.00,0.00,0.00,0.00,0.00,0.00,251.17 -0.00,0.00,0.00,0.00,0.00,0.00,251.15 -0.00,0.00,0.00,0.00,0.00,0.00,251.14 -0.00,0.00,0.00,0.00,0.00,0.00,251.12 -0.00,0.00,0.00,0.00,0.00,0.00,251.13 -0.00,0.00,0.00,0.00,0.00,0.00,251.13 -0.00,0.00,0.00,0.00,0.00,0.00,251.14 -0.00,0.00,0.00,0.00,0.00,0.00,251.13 -0.00,0.00,0.00,0.00,0.00,0.00,251.11 -0.00,0.00,0.00,0.00,0.00,0.00,251.11 -0.00,0.00,0.00,0.00,0.00,0.00,251.10 -0.00,0.00,0.00,0.00,0.00,0.00,251.10 -0.00,0.00,0.00,0.00,0.00,0.00,251.10 -0.00,0.00,0.00,0.00,0.00,0.00,251.13 -0.00,0.00,0.00,0.00,0.00,0.00,251.15 -0.00,0.00,0.00,0.00,0.00,0.00,251.17 -0.00,0.00,0.00,0.00,0.00,0.00,251.29 -0.00,0.00,0.00,0.00,0.00,0.00,251.38 -0.00,0.00,0.00,0.00,0.00,0.00,251.46 -0.00,0.00,0.00,0.00,0.00,0.00,251.40 -0.00,0.00,0.00,0.00,0.00,0.00,251.35 -0.00,0.00,0.00,0.00,0.00,0.00,251.31 -0.00,0.00,0.00,0.00,0.00,0.00,251.33 -0.00,0.00,0.00,0.00,0.00,0.00,251.34 -0.00,0.00,0.00,0.00,0.00,0.00,251.32 -0.00,0.00,0.00,0.00,0.00,0.00,251.30 -0.00,0.00,0.00,0.00,0.00,0.00,251.29 -0.00,0.00,0.00,0.00,0.00,0.00,251.29 -0.00,0.00,0.00,0.00,0.00,0.00,251.29 -0.00,0.00,0.00,0.00,0.00,0.00,251.29 -0.00,0.00,0.00,0.00,0.00,0.00,251.29 -0.00,0.00,0.00,0.00,0.00,0.00,251.29 -0.00,0.00,0.00,0.00,0.00,0.00,251.29 -0.00,0.00,0.00,0.00,0.00,0.00,251.30 -0.00,0.00,0.00,0.00,0.00,0.00,251.32 -0.00,0.00,0.00,0.00,0.00,0.00,251.33 -0.00,0.00,0.00,0.00,0.00,0.00,251.31 -0.00,0.00,0.00,0.00,0.00,0.00,251.30 -0.00,0.00,0.00,0.00,0.00,0.00,251.29 -0.00,0.00,0.00,0.00,0.00,0.00,251.27 -0.00,0.00,0.00,0.00,0.00,0.00,251.25 -0.00,0.00,0.00,0.00,0.00,0.00,251.24 -0.00,0.00,0.00,0.00,0.00,0.00,251.24 -0.00,0.00,0.00,0.00,0.00,0.00,251.24 -0.00,0.00,0.00,0.00,0.00,0.00,251.24 -0.00,0.00,0.00,0.00,0.00,0.00,251.24 -0.00,0.00,0.00,0.00,0.00,0.00,251.24 -0.00,0.00,0.00,0.00,0.00,0.00,251.25 -0.00,0.00,0.00,0.00,0.00,0.00,251.26 -0.00,0.00,0.00,0.00,0.00,0.00,251.27 -0.00,0.00,0.00,0.00,0.00,0.00,251.27 -0.00,0.00,0.00,0.00,0.00,0.00,251.27 -0.00,0.00,0.00,0.00,0.00,0.00,251.27 -0.00,0.00,0.00,0.00,0.00,0.00,251.24 -0.00,0.00,0.00,0.00,0.00,0.00,251.22 -0.00,0.00,0.00,0.00,0.00,0.00,251.21 -0.00,0.00,0.00,0.00,0.00,0.00,251.20 -0.00,0.00,0.00,0.00,0.00,0.00,251.19 -0.00,0.00,0.00,0.00,0.00,0.00,251.18 -0.00,0.00,0.00,0.00,0.00,0.00,251.19 -0.00,0.00,0.00,0.00,0.00,0.00,251.20 -0.00,0.00,0.00,0.00,0.00,0.00,251.24 -0.00,0.00,0.00,0.00,0.00,0.00,251.26 -0.00,0.00,0.00,0.00,0.00,0.00,251.29 -0.00,0.00,0.00,0.00,0.00,0.00,251.28 -0.00,0.00,0.00,0.00,0.00,0.00,251.27 -0.00,0.00,0.00,0.00,0.00,0.00,251.27 -0.00,0.00,0.00,0.00,0.00,0.00,251.30 -0.00,0.00,0.00,0.00,0.00,0.00,251.32 -0.00,0.00,0.00,0.00,0.00,0.00,251.34 -0.00,0.00,0.00,0.00,0.00,0.00,251.32 -0.00,0.00,0.00,0.00,0.00,0.00,251.30 -0.00,0.00,0.00,0.00,0.00,0.00,251.28 -0.00,0.00,0.00,0.00,0.00,0.00,251.33 -0.00,0.00,0.00,0.00,0.00,0.00,251.37 -0.00,0.00,0.00,0.00,0.00,0.00,251.40 -0.00,0.00,0.00,0.00,0.00,0.00,251.39 -0.00,0.00,0.00,0.00,0.00,0.00,251.39 -0.00,0.00,0.00,0.00,0.00,0.00,251.38 -0.00,0.00,0.00,0.00,0.00,0.00,251.40 -0.00,0.00,0.00,0.00,0.00,0.00,251.41 -0.00,0.00,0.00,0.00,0.00,0.00,251.40 -0.00,0.00,0.00,0.00,0.00,0.00,251.39 -0.00,0.00,0.00,0.00,0.00,0.00,251.38 -0.00,0.00,0.00,0.00,0.00,0.00,251.37 -0.00,0.00,0.00,0.00,0.00,0.00,251.36 -0.00,0.00,0.00,0.00,0.00,0.00,251.36 -0.00,0.00,0.00,0.00,0.00,0.00,251.34 -0.00,0.00,0.00,0.00,0.00,0.00,251.33 -0.00,0.00,0.00,0.00,0.00,0.00,251.31 -0.00,0.00,0.00,0.00,0.00,0.00,251.30 -280.00,0.00,280.00,280.00,0.00,280.00,251.28 -570.00,0.00,570.00,570.00,0.00,570.00,251.27 -850.00,0.00,850.00,850.00,0.00,850.00,251.26 -1130.00,0.00,1130.00,1130.00,0.00,1130.00,251.26 -1460.00,0.00,1460.00,1460.00,0.00,1460.00,251.25 -1740.00,0.00,1740.00,1740.00,0.00,1740.00,251.27 -2020.00,178.57,1841.43,2020.00,142.86,1877.14,251.28 -2300.00,428.57,1871.43,2300.00,321.43,1978.57,251.32 -2580.00,392.86,2187.14,2580.00,178.57,2401.43,251.35 -2860.00,1464.29,1395.71,2860.00,678.57,2181.43,251.38 -3140.00,2571.43,568.57,3140.00,2035.71,1104.29,251.29 -3420.00,2607.14,812.86,3420.00,2214.29,1205.71,251.22 -3700.00,1714.29,1985.71,3700.00,1607.14,2092.86,251.16 -3980.00,1428.57,2551.43,3980.00,1714.29,2265.71,251.13 -4260.00,2714.29,1545.71,4260.00,2607.14,1652.86,251.11 -4540.00,4035.71,504.29,4540.00,3392.86,1147.14,251.09 -4820.00,3964.29,855.71,4820.00,3535.71,1284.29,251.18 -5100.00,3107.14,1992.86,5100.00,3571.43,1528.57,251.25 -5380.00,3428.57,1951.43,5380.00,3535.71,1844.29,251.31 -5660.00,4535.71,1124.29,5660.00,3928.57,1731.43,251.24 -5940.00,5178.57,761.43,5940.00,4357.14,1582.86,251.19 -6220.00,5178.57,1041.43,6220.00,4607.14,1612.86,251.15 -6500.00,5142.86,1357.14,6500.00,4892.86,1607.14,251.12 -6780.00,5500.00,1280.00,6780.00,5178.57,1601.43,251.10 -7060.00,6000.00,1060.00,7060.00,5464.29,1595.71,251.08 -7340.00,6250.00,1090.00,7340.00,5785.71,1554.29,251.10 -7620.00,6464.29,1155.71,7620.00,6000.00,1620.00,251.11 -7900.00,6714.29,1185.71,7900.00,6250.00,1650.00,251.07 -8180.00,7035.71,1144.29,8180.00,6642.86,1537.14,251.03 -8470.00,7310.34,1159.66,8470.00,6965.52,1504.48,251.00 -8750.00,7642.86,1107.14,8750.00,7250.00,1500.00,251.02 -9030.00,7857.14,1172.86,9030.00,7535.71,1494.29,251.03 -9310.00,8071.43,1238.57,9310.00,7750.00,1560.00,251.04 -9600.00,8379.31,1220.69,9600.00,8000.00,1600.00,251.04 -9890.00,8689.66,1200.34,9890.00,8275.86,1614.14,251.03 -10170.00,9035.71,1134.29,10170.00,8642.86,1527.14,251.03 -10450.00,9285.71,1164.29,10450.00,8928.57,1521.43,251.02 -10740.00,9586.21,1153.79,10740.00,9275.86,1464.14,251.02 -11020.00,9928.57,1091.43,11020.00,9535.71,1484.29,251.01 -11300.00,10214.29,1085.71,11300.00,9785.71,1514.29,251.07 -11580.00,10464.29,1115.71,11580.00,10035.71,1544.29,251.11 -11860.00,10678.57,1181.43,11860.00,10357.14,1502.86,251.17 -12140.00,11000.00,1140.00,12140.00,10607.14,1532.86,251.22 -12420.00,11178.57,1241.43,12420.00,10785.71,1634.29,251.27 -12710.00,11344.83,1365.17,12710.00,11068.97,1641.03,251.26 -12990.00,11678.57,1311.43,12990.00,11357.14,1632.86,251.26 -13280.00,12034.48,1245.52,13280.00,11620.69,1659.31,251.26 -13560.00,12321.43,1238.57,13560.00,12000.00,1560.00,251.21 -13850.00,12482.76,1367.24,13850.00,12275.86,1574.14,251.17 -14140.00,12689.66,1450.34,14140.00,12413.79,1726.21,251.14 -14420.00,13000.00,1420.00,14420.00,12714.29,1705.71,251.11 -14710.00,13275.86,1434.14,14710.00,13000.00,1710.00,251.09 -15000.00,13689.66,1310.34,15000.00,13275.86,1724.14,251.07 -15290.00,13931.03,1358.97,15290.00,13551.72,1738.28,251.05 -15580.00,14137.93,1442.07,15580.00,13689.66,1890.34,251.03 -15860.00,14357.14,1502.86,15860.00,14178.57,1681.43,250.98 -16150.00,14724.14,1425.86,16150.00,14620.69,1529.31,250.95 -16440.00,14931.03,1508.97,16440.00,14896.55,1543.45,250.92 -16730.00,15241.38,1488.62,16730.00,15034.48,1695.52,250.92 -17020.00,15586.21,1433.79,17020.00,15172.41,1847.59,250.91 -17310.00,16034.48,1275.52,17310.00,15551.72,1758.28,250.91 -17600.00,16241.38,1358.62,17600.00,15896.55,1703.45,250.89 -17890.00,16310.34,1579.66,17890.00,16379.31,1510.69,250.88 -18180.00,16482.76,1697.24,18180.00,16551.72,1628.28,250.87 -18470.00,17103.45,1366.55,18470.00,16827.59,1642.41,250.90 -18760.00,17379.31,1380.69,18760.00,17068.97,1691.03,250.92 -19050.00,17724.14,1325.86,19050.00,17206.90,1843.10,250.97 -19340.00,17896.55,1443.45,19340.00,17448.28,1891.72,251.01 -19630.00,18379.31,1250.69,19630.00,18068.97,1561.03,251.05 -19920.00,18827.59,1092.41,19920.00,18551.72,1368.28,251.05 -20210.00,18931.03,1278.97,20210.00,18793.10,1416.90,251.04 -20500.00,18965.52,1534.48,20500.00,18931.03,1568.97,251.04 -20780.00,19000.00,1780.00,20780.00,19000.00,1780.00,251.04 -21070.00,19241.38,1828.62,21070.00,19137.93,1932.07,251.04 -21360.00,19758.62,1601.38,21360.00,19586.21,1773.79,251.04 -21700.00,20088.24,1611.76,21700.00,19794.12,1905.88,251.03 -21990.00,20275.86,1714.14,21990.00,20068.97,1921.03,251.01 -22270.00,20714.29,1555.71,22270.00,20500.00,1770.00,251.02 -22560.00,20827.59,1732.41,22560.00,20931.03,1628.97,251.02 -22850.00,21137.93,1712.07,22850.00,20862.07,1987.93,251.02 -23140.00,21655.17,1484.83,23140.00,21137.93,2002.07,251.03 -23430.00,21896.55,1533.45,23182.02,21620.69,1561.33,251.04 -23412.15,22137.93,1274.22,22892.02,21931.03,960.98,251.05 -23122.15,22137.93,984.22,22602.02,21793.10,808.91,251.06 -22832.15,22068.97,763.19,22312.02,21586.21,725.81,251.07 -22542.15,21896.55,645.60,22022.02,21310.34,711.67,251.08 -22252.15,21482.76,769.40,21732.02,20586.21,1145.81,251.14 -21962.15,21344.83,617.33,21442.02,20482.76,959.26,251.19 -21672.15,21172.41,499.74,21152.02,20206.90,945.12,251.23 -21382.15,20620.69,761.46,20862.02,20068.97,793.05,251.25 -21092.15,20379.31,712.84,20572.02,19586.21,985.81,251.27 -20802.15,20241.38,560.78,20282.02,19413.79,868.22,251.25 -20512.15,20000.00,512.15,19992.02,19172.41,819.60,251.23 -20222.15,19620.69,601.46,19702.02,18965.52,736.50,251.22 -19932.15,18896.55,1035.60,19412.02,18241.38,1170.64,251.17 -19642.15,18517.24,1124.91,19122.02,18241.38,880.64,251.13 -19352.15,18586.21,765.95,18832.02,17827.59,1004.43,251.09 -19062.15,18344.83,717.33,18542.02,17689.66,852.36,251.08 -18772.15,18275.86,496.29,18252.02,17172.41,1079.60,251.07 -18482.15,17931.03,551.12,17962.02,17172.41,789.60,251.07 -18192.15,17689.66,502.50,17672.02,16896.55,775.46,251.07 -17902.15,17379.31,522.84,17382.02,16344.83,1037.19,251.07 -17612.15,16965.52,646.64,17092.02,16137.93,954.08,251.13 -17322.15,16724.14,598.02,16802.02,15931.03,870.98,251.18 -17032.15,16551.72,480.43,16512.02,15758.62,753.39,251.22 -16742.15,16275.86,466.29,16222.02,15344.83,877.19,251.23 -16452.15,16068.97,383.19,15932.02,15206.90,725.12,251.24 -16162.15,15724.14,438.02,15642.02,14931.03,710.98,251.25 -15872.15,15310.34,561.81,15352.02,14620.69,731.33,251.13 -15582.15,15206.90,375.26,15062.02,14310.34,751.67,251.04 -15292.15,15000.00,292.15,14772.02,14034.48,737.53,251.15 -15002.15,14758.62,243.53,14482.02,13448.28,1033.74,251.24 -14712.15,14344.83,367.33,14192.02,13482.76,709.26,251.32 -14422.15,14034.48,387.67,13902.02,13379.31,522.71,251.32 -14132.15,13793.10,339.05,13612.02,13068.97,543.05,251.33 -13842.15,13586.21,255.95,13322.02,12551.72,770.29,251.34 -13562.15,13250.00,312.15,13042.02,12392.86,649.16,251.31 -13272.15,12758.62,513.53,12752.02,11896.55,855.46,251.29 -12982.15,12344.83,637.33,12462.02,11758.62,703.39,251.27 -12692.15,12137.93,554.22,12172.02,11517.24,654.77,251.26 -12412.15,12142.86,269.30,11892.02,11250.00,642.02,251.26 -12122.15,11931.03,191.12,11602.02,10827.59,774.43,251.26 -11832.15,11379.31,452.84,11312.02,10620.69,691.33,251.29 -11542.15,11000.00,542.15,11022.02,10344.83,677.19,251.31 -11252.15,10793.10,459.05,10732.02,9931.03,800.98,251.25 -10972.15,10571.43,400.73,10452.02,9785.71,666.30,251.20 -10682.15,10344.83,337.33,10162.02,9517.24,644.77,251.16 -10402.15,10071.43,330.73,9882.02,9178.57,703.44,251.05 -10122.15,9857.14,265.01,9602.02,8928.57,673.44,250.95 -9842.15,9571.43,270.73,9322.02,8678.57,643.44,250.88 -9562.15,9250.00,312.15,9042.02,8321.43,720.59,251.09 -9282.15,8892.86,389.30,8762.02,8107.14,654.87,251.26 -9002.15,8642.86,359.30,8482.02,7928.57,553.44,251.39 -8712.15,8413.79,298.36,8192.02,7620.69,571.33,251.34 -8432.15,8142.86,289.30,7912.02,7214.29,697.73,251.31 -8152.15,7928.57,223.58,7632.02,6892.86,739.16,251.28 -7862.15,7689.66,172.50,7342.02,6620.69,721.33,251.20 -7582.15,7464.29,117.87,7062.02,6321.43,740.59,251.15 -7292.15,7206.90,85.26,6772.02,6103.45,668.57,251.28 -7002.15,6620.69,381.46,6482.02,5862.07,619.95,251.39 -6722.15,5607.14,1115.01,6202.02,5571.43,630.59,251.47 -6442.15,5750.00,692.15,5922.02,5285.71,636.30,251.43 -6162.15,6071.43,90.73,5642.02,4928.57,713.44,251.39 -5882.15,5857.14,25.01,5362.02,4607.14,754.87,251.36 -5602.15,4892.86,709.30,5082.02,4392.86,689.16,251.21 -5272.15,4303.03,969.12,4752.02,4121.21,630.80,251.08 -4992.15,4607.14,385.01,4472.02,3642.86,829.16,250.98 -4712.15,4678.57,33.58,4192.02,3071.43,1120.59,251.19 -4432.15,4000.00,432.15,3912.02,2928.57,983.44,251.35 -4152.15,3428.57,723.58,3632.02,2785.71,846.30,251.48 -3872.15,2821.43,1050.73,3352.02,2607.14,744.87,251.52 -3592.15,2464.29,1127.87,3072.02,1821.43,1250.59,251.56 -3312.15,2821.43,490.73,2792.02,785.71,2006.30,251.58 -3032.15,3000.00,32.15,2512.02,1500.00,1012.02,251.50 -2752.15,2321.43,430.73,2232.02,1714.29,517.73,251.43 -2472.15,1642.86,829.30,1952.02,928.57,1023.44,251.43 -2192.15,1107.14,1085.01,1672.02,-357.14,2029.16,251.43 -1912.15,642.86,1269.30,1392.02,-285.71,1677.73,251.43 -1632.15,-607.14,2239.30,1112.02,535.71,576.30,251.54 -1352.15,357.14,995.01,832.02,-107.14,939.16,251.62 -1072.15,785.71,286.44,552.02,-678.57,1230.59,251.69 -792.15,35.71,756.44,272.02,35.71,236.30,251.62 -512.15,-71.43,583.58,0.00,35.71,-35.71,251.57 -232.15,-71.43,303.58,0.00,0.00,0.00,251.52 -0.00,-285.71,285.71,0.00,0.00,0.00,251.48 -0.00,-888.89,888.89,0.00,0.00,0.00,251.44 -0.00,71.43,-71.43,0.00,0.00,0.00,251.41 -0.00,178.57,-178.57,0.00,0.00,0.00,251.59 -0.00,-71.43,71.43,0.00,0.00,0.00,251.73 -0.00,0.00,0.00,0.00,0.00,0.00,251.85 -0.00,0.00,0.00,0.00,0.00,0.00,251.88 -0.00,0.00,0.00,0.00,0.00,0.00,251.91 -0.00,0.00,0.00,0.00,0.00,0.00,251.93 -0.00,0.00,0.00,0.00,0.00,0.00,251.94 -0.00,0.00,0.00,0.00,0.00,0.00,251.96 -0.00,0.00,0.00,0.00,0.00,0.00,252.00 -0.00,0.00,0.00,0.00,0.00,0.00,252.03 -0.00,0.00,0.00,0.00,0.00,0.00,252.05 -0.00,0.00,0.00,0.00,0.00,0.00,252.06 -0.00,0.00,0.00,0.00,0.00,0.00,252.07 -0.00,0.00,0.00,0.00,0.00,0.00,252.07 -0.00,0.00,0.00,0.00,0.00,0.00,252.08 -0.00,0.00,0.00,0.00,0.00,0.00,252.08 -0.00,0.00,0.00,0.00,0.00,0.00,252.08 -0.00,0.00,0.00,0.00,0.00,0.00,252.07 -0.00,0.00,0.00,0.00,0.00,0.00,252.06 -0.00,0.00,0.00,0.00,0.00,0.00,252.05 -0.00,0.00,0.00,0.00,0.00,0.00,252.06 -0.00,0.00,0.00,0.00,0.00,0.00,252.07 -0.00,0.00,0.00,0.00,0.00,0.00,252.07 -0.00,0.00,0.00,0.00,0.00,0.00,252.09 -0.00,0.00,0.00,0.00,0.00,0.00,252.11 -0.00,0.00,0.00,0.00,0.00,0.00,252.12 -0.00,0.00,0.00,0.00,0.00,0.00,252.12 -0.00,0.00,0.00,0.00,0.00,0.00,252.12 -0.00,0.00,0.00,0.00,0.00,0.00,252.10 -0.00,0.00,0.00,0.00,0.00,0.00,252.09 -0.00,0.00,0.00,0.00,0.00,0.00,252.08 -0.00,0.00,0.00,0.00,0.00,0.00,252.08 -0.00,0.00,0.00,0.00,0.00,0.00,252.07 -0.00,0.00,0.00,0.00,0.00,0.00,252.07 -0.00,0.00,0.00,0.00,0.00,0.00,252.07 -0.00,0.00,0.00,0.00,0.00,0.00,252.07 -0.00,0.00,0.00,0.00,0.00,0.00,252.07 -0.00,0.00,0.00,0.00,0.00,0.00,252.07 -0.00,0.00,0.00,0.00,0.00,0.00,251.82 -0.00,0.00,0.00,0.00,0.00,0.00,251.82 -0.00,0.00,0.00,0.00,0.00,0.00,251.82 -0.00,0.00,0.00,0.00,0.00,0.00,251.82 -0.00,0.00,0.00,0.00,0.00,0.00,251.82 -0.00,0.00,0.00,0.00,0.00,0.00,251.86 -0.00,0.00,0.00,0.00,0.00,0.00,251.90 -0.00,0.00,0.00,0.00,0.00,0.00,251.92 -0.00,0.00,0.00,0.00,0.00,0.00,251.94 -0.00,0.00,0.00,0.00,0.00,0.00,251.96 -0.00,0.00,0.00,0.00,0.00,0.00,251.96 -0.00,0.00,0.00,0.00,0.00,0.00,251.96 -0.00,0.00,0.00,0.00,0.00,0.00,251.96 -0.00,0.00,0.00,0.00,0.00,0.00,251.96 -0.00,0.00,0.00,0.00,0.00,0.00,251.96 -0.00,0.00,0.00,0.00,0.00,0.00,251.96 -0.00,0.00,0.00,0.00,0.00,0.00,251.96 -0.00,0.00,0.00,0.00,0.00,0.00,251.96 -0.00,0.00,0.00,0.00,0.00,0.00,251.96 -0.00,0.00,0.00,0.00,0.00,0.00,251.95 -0.00,0.00,0.00,0.00,0.00,0.00,251.95 -0.00,0.00,0.00,0.00,0.00,0.00,251.94 --280.00,0.00,-280.00,-280.00,0.00,-280.00,251.96 --610.00,0.00,-610.00,-610.00,0.00,-610.00,251.97 --890.00,0.00,-890.00,-890.00,0.00,-890.00,251.98 --1160.00,0.00,-1160.00,-1160.00,0.00,-1160.00,251.92 --1440.00,0.00,-1440.00,-1440.00,0.00,-1440.00,251.88 --1720.00,0.00,-1720.00,-1720.00,0.00,-1720.00,251.84 --2000.00,-178.57,-1821.43,-2000.00,-178.57,-1821.43,251.80 --2290.00,-310.34,-1979.66,-2290.00,-344.83,-1945.17,251.76 --2570.00,-321.43,-2248.57,-2570.00,-214.29,-2355.71,251.78 --2850.00,-1214.29,-1635.71,-2850.00,-607.14,-2242.86,251.80 --3130.00,-2500.00,-630.00,-3130.00,-1928.57,-1201.43,251.81 --3420.00,-2586.21,-833.79,-3420.00,-2241.38,-1178.62,251.71 --3710.00,-1482.76,-2227.24,-3710.00,-2137.93,-1572.07,251.64 --3990.00,-1571.43,-2418.57,-3990.00,-2107.14,-1882.86,251.57 --4280.00,-3103.45,-1176.55,-4280.00,-2241.38,-2038.62,251.36 --4560.00,-4357.14,-202.86,-4560.00,-2821.43,-1738.57,251.20 --4850.00,-4206.90,-643.10,-4850.00,-3310.34,-1539.66,251.06 --5130.00,-3178.57,-1951.43,-5130.00,-3607.14,-1522.86,251.13 --5410.00,-2857.14,-2552.86,-5410.00,-3678.57,-1731.43,251.18 --5700.00,-4379.31,-1320.69,-5700.00,-3827.59,-1872.41,251.23 --5990.00,-5793.10,-196.90,-5990.00,-4241.38,-1748.62,251.16 --6280.00,-5551.72,-728.28,-6280.00,-4517.24,-1762.76,251.11 --6570.00,-4655.17,-1914.83,-6570.00,-4931.03,-1638.97,251.06 --6860.00,-4931.03,-1928.97,-6860.00,-5344.83,-1515.17,251.01 --7150.00,-5862.07,-1287.93,-7150.00,-5655.17,-1494.83,250.98 --7440.00,-6655.17,-784.83,-7440.00,-5827.59,-1612.41,251.01 --7710.00,-6777.78,-932.22,-7710.00,-6074.07,-1635.93,251.04 --7990.00,-6714.29,-1275.71,-7990.00,-6428.57,-1561.43,251.06 --8270.00,-6964.29,-1305.71,-8270.00,-6821.43,-1448.57,251.02 --8560.00,-7379.31,-1180.69,-8560.00,-7034.48,-1525.52,250.99 --8840.00,-7821.43,-1018.57,-8840.00,-7357.14,-1482.86,250.97 --9130.00,-8137.93,-992.07,-9130.00,-7689.66,-1440.34,250.95 --9400.00,-8407.41,-992.59,-9400.00,-8000.00,-1400.00,250.93 --9690.00,-8655.17,-1034.83,-9690.00,-8275.86,-1414.14,250.91 --9980.00,-8827.59,-1152.41,-9980.00,-8551.72,-1428.28,250.94 --10270.00,-8965.52,-1304.48,-10270.00,-8931.03,-1338.97,250.97 --10560.00,-9172.41,-1387.59,-10560.00,-9206.90,-1353.10,250.95 --10850.00,-9655.17,-1194.83,-10850.00,-9379.31,-1470.69,250.94 --11130.00,-10107.14,-1022.86,-11130.00,-9642.86,-1487.14,250.93 --11420.00,-10275.86,-1144.14,-11420.00,-9931.03,-1488.97,250.93 --11710.00,-10517.24,-1192.76,-11710.00,-10275.86,-1434.14,250.94 --12010.00,-10800.00,-1210.00,-12010.00,-10600.00,-1410.00,250.94 --12300.00,-11103.45,-1196.55,-12300.00,-10827.59,-1472.41,250.96 --12600.00,-11366.67,-1233.33,-12600.00,-11133.33,-1466.67,250.98 --12890.00,-11655.17,-1234.83,-12890.00,-11241.38,-1648.62,251.00 --13180.00,-12000.00,-1180.00,-13180.00,-11517.24,-1662.76,251.06 --13470.00,-12241.38,-1228.62,-13470.00,-11862.07,-1607.93,251.10 --13760.00,-12517.24,-1242.76,-13760.00,-12206.90,-1553.10,251.14 --14050.00,-12827.59,-1222.41,-14050.00,-12551.72,-1498.28,251.18 --14340.00,-13068.97,-1271.03,-14340.00,-12793.10,-1546.90,251.20 --14630.00,-13275.86,-1354.14,-14630.00,-12931.03,-1698.97,251.23 --14930.00,-13600.00,-1330.00,-14930.00,-13266.67,-1663.33,251.24 --15220.00,-14000.00,-1220.00,-15220.00,-13586.21,-1633.79,251.26 --15520.00,-14166.67,-1353.33,-15520.00,-13866.67,-1653.33,251.26 --15810.00,-14482.76,-1327.24,-15810.00,-14103.45,-1706.55,251.27 --16100.00,-14724.14,-1375.86,-16100.00,-14344.83,-1755.17,251.27 --16390.00,-14931.03,-1458.97,-16390.00,-14517.24,-1872.76,251.21 --16680.00,-15172.41,-1507.59,-16680.00,-14758.62,-1921.38,251.16 --16970.00,-15689.66,-1280.34,-16970.00,-15103.45,-1866.55,251.08 --17260.00,-16172.41,-1087.59,-17260.00,-15517.24,-1742.76,251.01 --17550.00,-16344.83,-1205.17,-17550.00,-15931.03,-1618.97,250.96 --17840.00,-16413.79,-1426.21,-17840.00,-16206.90,-1633.10,250.93 --18140.00,-16600.00,-1540.00,-18140.00,-16400.00,-1740.00,250.91 --18440.00,-17000.00,-1440.00,-18440.00,-16666.67,-1773.33,250.89 --18740.00,-17400.00,-1340.00,-18740.00,-16866.67,-1873.33,250.82 --19040.00,-17766.67,-1273.33,-19040.00,-17300.00,-1740.00,250.77 --19340.00,-17900.00,-1440.00,-19340.00,-17766.67,-1573.33,250.78 --19630.00,-18310.34,-1319.66,-19630.00,-18137.93,-1492.07,250.79 --19930.00,-18600.00,-1330.00,-19930.00,-18300.00,-1630.00,250.80 --20230.00,-18666.67,-1563.33,-20230.00,-18433.33,-1796.67,250.82 --20530.00,-18933.33,-1596.67,-20530.00,-18833.33,-1696.67,250.85 --20880.00,-19600.00,-1280.00,-20880.00,-19142.86,-1737.14,250.86 --21170.00,-20034.48,-1135.52,-21170.00,-19310.34,-1859.66,250.86 --21470.00,-20033.33,-1436.67,-21470.00,-19700.00,-1770.00,250.85 --21760.00,-20241.38,-1518.62,-21760.00,-20068.97,-1691.03,250.89 --22050.00,-20413.79,-1636.21,-22050.00,-20068.97,-1981.03,250.93 --22350.00,-20766.67,-1583.33,-22350.00,-20300.00,-2050.00,250.95 --22650.00,-21300.00,-1350.00,-22650.00,-20800.00,-1850.00,250.90 --22950.00,-21466.67,-1483.33,-22950.00,-21166.67,-1783.33,250.86 --23250.00,-21700.00,-1550.00,-23225.80,-21400.00,-1825.80,250.83 --23496.36,-21833.33,-1663.03,-22925.80,-21400.00,-1525.80,250.85 --23196.36,-22433.33,-763.03,-22625.80,-21700.00,-925.80,250.87 --22896.36,-22433.33,-463.03,-22325.80,-21566.67,-759.13,250.87 --22596.36,-21933.33,-663.03,-22025.80,-21233.33,-792.47,250.87 --22296.36,-21733.33,-563.03,-21725.80,-20766.67,-959.13,250.87 --21996.36,-21566.67,-429.69,-21425.80,-20433.33,-992.47,250.89 --21696.36,-21000.00,-696.36,-21125.80,-20233.33,-892.47,250.91 --21396.36,-20700.00,-696.36,-20825.80,-19966.67,-859.13,250.92 --21106.36,-20620.69,-485.67,-20535.80,-19758.62,-777.18,250.96 --20806.36,-20433.33,-373.03,-20235.80,-19466.67,-769.13,250.99 --20506.36,-20033.33,-473.03,-19935.80,-19133.33,-802.47,251.03 --20216.36,-19586.21,-630.15,-19645.80,-18689.66,-956.14,251.06 --19916.36,-19266.67,-649.69,-19345.80,-18600.00,-745.80,251.09 --19626.36,-19103.45,-522.91,-19055.80,-18310.34,-745.46,251.14 --19326.36,-18700.00,-626.36,-18755.80,-17900.00,-855.80,251.19 --19026.36,-18200.00,-826.36,-18455.80,-17300.00,-1155.80,251.22 --18726.36,-17966.67,-759.69,-18155.80,-17100.00,-1055.80,251.19 --18426.36,-17933.33,-493.03,-17855.80,-16933.33,-922.47,251.17 --18126.36,-17533.33,-593.03,-17555.80,-16666.67,-889.13,251.17 --17826.36,-17333.33,-493.03,-17255.80,-16366.67,-889.13,251.17 --17536.36,-17172.41,-363.95,-16965.80,-16034.48,-931.32,251.17 --17236.36,-16866.67,-369.69,-16665.80,-15666.67,-999.13,251.16 --16946.36,-16448.28,-498.08,-16375.80,-15586.21,-789.59,251.15 --16656.36,-16103.45,-552.91,-16085.80,-15310.34,-775.46,251.14 --16356.36,-15866.67,-489.69,-15785.80,-15000.00,-785.80,251.06 --16066.36,-15655.17,-411.19,-15495.80,-14689.66,-806.14,251.00 --15766.36,-15266.67,-499.69,-15195.80,-14133.33,-1062.47,250.95 --15476.36,-15000.00,-476.36,-14905.80,-12965.52,-1940.28,250.93 --15176.36,-14566.67,-609.69,-14605.80,-12866.67,-1739.13,250.91 --14886.36,-14206.90,-679.46,-14315.80,-12517.24,-1798.56,251.00 --14596.36,-13931.03,-665.33,-14025.80,-12034.48,-1991.32,251.07 --14296.36,-13733.33,-563.03,-13725.80,-11600.00,-2125.80,251.13 --14006.36,-13517.24,-489.12,-13435.80,-11137.93,-2297.87,251.08 --13716.36,-13137.93,-578.43,-13145.80,-11068.97,-2076.83,251.04 --13426.36,-12482.76,-943.60,-12855.80,-10344.83,-2510.97,251.00 --13136.36,-11793.10,-1343.26,-12565.80,-10137.93,-2427.87,250.97 --12856.36,-10892.86,-1963.50,-12285.80,-8928.57,-3357.23,250.94 --12566.36,-10275.86,-2290.50,-11995.80,-9034.48,-2961.32,250.92 --12276.36,-10172.41,-2103.95,-11705.80,-8310.34,-3395.46,250.83 --11986.36,-10000.00,-1986.36,-11415.80,-7275.86,-4139.94,250.75 --11696.36,-9827.59,-1868.77,-11125.80,-7724.14,-3401.66,250.80 --11406.36,-9241.38,-2164.98,-10835.80,-7344.83,-3490.97,250.83 --11116.36,-9344.83,-1771.53,-10545.80,-5896.55,-4649.25,250.85 --10826.36,-9344.83,-1481.53,-10255.80,-7172.41,-3083.39,250.80 --10536.36,-9379.31,-1157.05,-9965.80,-8275.86,-1689.94,250.76 --10246.36,-8793.10,-1453.26,-9675.80,-7034.48,-2641.32,250.73 --9956.36,-8448.28,-1508.08,-9385.80,-5310.34,-4075.46,250.54 --9676.36,-8071.43,-1604.93,-9105.80,-4714.29,-4391.51,250.39 --9386.36,-7965.52,-1420.84,-8815.80,-4793.10,-4022.70,250.26 --9096.36,-7586.21,-1510.15,-8525.80,-5482.76,-3043.04,250.23 --8806.36,-7241.38,-1564.98,-8235.80,-5482.76,-2753.04,250.21 --8516.36,-7448.28,-1068.08,-7945.80,-4172.41,-3773.39,250.04 --8226.36,-7310.34,-916.02,-7655.80,-2896.55,-4759.25,249.90 --7936.36,-6482.76,-1453.60,-7365.80,-3172.41,-4193.39,249.79 --7646.36,-5931.03,-1715.33,-7075.80,-5413.79,-1662.01,249.92 --7356.36,-5827.59,-1528.77,-6785.80,-4965.52,-1820.28,250.01 --7066.36,-5758.62,-1307.74,-6495.80,-1965.52,-4530.28,250.09 --6776.36,-5724.14,-1052.22,-6205.80,-965.52,-5240.28,250.12 --6486.36,-5275.86,-1210.50,-5915.80,-2551.72,-3364.08,250.14 --6146.36,-4823.53,-1322.83,-5575.80,-5147.06,-428.74,250.16 --5856.36,-4965.52,-890.84,-5285.80,-4310.34,-975.46,250.07 --5566.36,-5000.00,-566.36,-4995.80,-758.62,-4237.18,249.99 --5276.36,-4448.28,-828.08,-4705.80,-344.83,-4360.97,250.31 --4996.36,-4071.43,-924.93,-4425.80,-2071.43,-2354.37,250.56 --4706.36,-3862.07,-844.29,-4135.80,-3724.14,-411.66,250.76 --4416.36,-3793.10,-623.26,-3845.80,-3172.41,-673.39,250.57 --4126.36,-3241.38,-884.98,-3555.80,-1517.24,-2038.56,250.41 --3836.36,-2241.38,-1594.98,-3265.80,-758.62,-2507.18,250.29 --3556.36,-1678.57,-1877.79,-2985.80,-535.71,-2450.09,250.28 --3266.36,-2137.93,-1128.43,-2695.80,-827.59,-1868.21,250.27 --2986.36,-2428.57,-557.79,-2415.80,-1464.29,-951.51,250.26 --2696.36,-1862.07,-834.29,-2125.80,-517.24,-1608.56,250.24 --2416.36,-714.29,-1702.07,-1845.80,-35.71,-1810.09,250.23 --2136.36,-892.86,-1243.50,-1565.80,-214.29,-1351.51,250.08 --1846.36,-1034.48,-811.88,-1275.80,-758.62,-517.18,249.95 --1566.36,35.71,-1602.07,-995.80,-142.86,-852.94,249.86 --1286.36,0.00,-1286.36,-715.80,71.43,-787.23,249.90 --1006.36,-214.29,-792.07,-435.80,0.00,-435.80,249.93 --726.36,35.71,-762.07,-155.80,0.00,-155.80,249.96 --446.36,0.00,-446.36,0.00,0.00,0.00,249.96 --176.36,0.00,-176.36,0.00,0.00,0.00,249.96 -0.00,0.00,0.00,0.00,0.00,0.00,249.96 -0.00,0.00,0.00,0.00,0.00,0.00,250.02 -0.00,0.00,0.00,0.00,0.00,0.00,250.07 -0.00,0.00,0.00,0.00,0.00,0.00,250.11 -0.00,0.00,0.00,0.00,0.00,0.00,250.10 -0.00,0.00,0.00,0.00,0.00,0.00,250.10 -0.00,0.00,0.00,0.00,0.00,0.00,250.09 -0.00,0.00,0.00,0.00,0.00,0.00,250.08 -0.00,0.00,0.00,0.00,0.00,0.00,250.07 -0.00,0.00,0.00,0.00,0.00,0.00,250.07 -0.00,0.00,0.00,0.00,0.00,0.00,250.04 -0.00,0.00,0.00,0.00,0.00,0.00,250.02 -0.00,0.00,0.00,0.00,0.00,0.00,250.00 -0.00,0.00,0.00,0.00,0.00,0.00,250.01 -0.00,0.00,0.00,0.00,0.00,0.00,250.01 -0.00,0.00,0.00,0.00,0.00,0.00,250.01 -0.00,0.00,0.00,0.00,0.00,0.00,249.98 -0.00,0.00,0.00,0.00,0.00,0.00,249.96 -0.00,0.00,0.00,0.00,0.00,0.00,249.94 -0.00,0.00,0.00,0.00,0.00,0.00,249.93 -0.00,0.00,0.00,0.00,0.00,0.00,249.92 -0.00,0.00,0.00,0.00,0.00,0.00,249.95 -0.00,0.00,0.00,0.00,0.00,0.00,249.97 -0.00,0.00,0.00,0.00,0.00,0.00,249.98 -0.00,0.00,0.00,0.00,0.00,0.00,249.95 -0.00,0.00,0.00,0.00,0.00,0.00,249.92 -0.00,0.00,0.00,0.00,0.00,0.00,249.90 -0.00,0.00,0.00,0.00,0.00,0.00,249.91 -0.00,0.00,0.00,0.00,0.00,0.00,249.91 -0.00,0.00,0.00,0.00,0.00,0.00,249.92 -0.00,0.00,0.00,0.00,0.00,0.00,249.95 -0.00,0.00,0.00,0.00,0.00,0.00,249.97 -0.00,0.00,0.00,0.00,0.00,0.00,249.99 -0.00,0.00,0.00,0.00,0.00,0.00,249.98 -0.00,0.00,0.00,0.00,0.00,0.00,249.98 -0.00,0.00,0.00,0.00,0.00,0.00,249.97 -0.00,0.00,0.00,0.00,0.00,0.00,249.92 -0.00,0.00,0.00,0.00,0.00,0.00,249.87 -0.00,0.00,0.00,0.00,0.00,0.00,249.84 -0.00,0.00,0.00,0.00,0.00,0.00,249.85 -0.00,0.00,0.00,0.00,0.00,0.00,249.87 -0.00,0.00,0.00,0.00,0.00,0.00,249.88 -0.00,0.00,0.00,0.00,0.00,0.00,249.85 -0.00,0.00,0.00,0.00,0.00,0.00,249.83 -0.00,0.00,0.00,0.00,0.00,0.00,249.88 -0.00,0.00,0.00,0.00,0.00,0.00,249.92 -0.00,0.00,0.00,0.00,0.00,0.00,249.95 -0.00,0.00,0.00,0.00,0.00,0.00,249.94 -0.00,0.00,0.00,0.00,0.00,0.00,249.94 -0.00,0.00,0.00,0.00,0.00,0.00,249.93 -0.00,0.00,0.00,0.00,0.00,0.00,249.94 -0.00,0.00,0.00,0.00,0.00,0.00,249.94 -0.00,0.00,0.00,0.00,0.00,0.00,249.94 -0.00,0.00,0.00,0.00,0.00,0.00,249.97 -0.00,0.00,0.00,0.00,0.00,0.00,249.99 -0.00,0.00,0.00,0.00,0.00,0.00,250.00 -0.00,0.00,0.00,0.00,0.00,0.00,250.00 -0.00,0.00,0.00,0.00,0.00,0.00,250.00 -0.00,0.00,0.00,0.00,0.00,0.00,250.00 -0.00,0.00,0.00,0.00,0.00,0.00,249.95 -0.00,0.00,0.00,0.00,0.00,0.00,249.91 -0.00,0.00,0.00,0.00,0.00,0.00,249.88 -0.00,0.00,0.00,0.00,0.00,0.00,249.83 -0.00,0.00,0.00,0.00,0.00,0.00,249.79 -0.00,0.00,0.00,0.00,0.00,0.00,249.75 -0.00,0.00,0.00,0.00,0.00,0.00,249.78 -0.00,0.00,0.00,0.00,0.00,0.00,249.80 -0.00,0.00,0.00,0.00,0.00,0.00,249.83 -0.00,0.00,0.00,0.00,0.00,0.00,249.86 -0.00,0.00,0.00,0.00,0.00,0.00,249.87 -0.00,0.00,0.00,0.00,0.00,0.00,249.86 -0.00,0.00,0.00,0.00,0.00,0.00,249.85 -0.00,0.00,0.00,0.00,0.00,0.00,249.84 -0.00,0.00,0.00,0.00,0.00,0.00,249.91 -0.00,0.00,0.00,0.00,0.00,0.00,249.96 -0.00,0.00,0.00,0.00,0.00,0.00,250.00 -0.00,0.00,0.00,0.00,0.00,0.00,249.98 -0.00,0.00,0.00,0.00,0.00,0.00,249.97 -0.00,0.00,0.00,0.00,0.00,0.00,249.95 -0.00,0.00,0.00,0.00,0.00,0.00,249.95 -0.00,0.00,0.00,0.00,0.00,0.00,249.95 -0.00,0.00,0.00,0.00,0.00,0.00,249.94 -0.00,0.00,0.00,0.00,0.00,0.00,249.97 -0.00,0.00,0.00,0.00,0.00,0.00,249.99 -0.00,0.00,0.00,0.00,0.00,0.00,250.01 -0.00,0.00,0.00,0.00,0.00,0.00,249.97 -0.00,0.00,0.00,0.00,0.00,0.00,249.94 -0.00,0.00,0.00,0.00,0.00,0.00,249.91 -0.00,0.00,0.00,0.00,0.00,0.00,249.96 -0.00,0.00,0.00,0.00,0.00,0.00,250.00 -0.00,0.00,0.00,0.00,0.00,0.00,250.03 -0.00,0.00,0.00,0.00,0.00,0.00,250.07 -0.00,0.00,0.00,0.00,0.00,0.00,250.10 -0.00,0.00,0.00,0.00,0.00,0.00,250.10 -0.00,0.00,0.00,0.00,0.00,0.00,250.10 -0.00,0.00,0.00,0.00,0.00,0.00,250.10 -0.00,0.00,0.00,0.00,0.00,0.00,250.13 -0.00,0.00,0.00,0.00,0.00,0.00,250.16 -0.00,0.00,0.00,0.00,0.00,0.00,250.18 -0.00,0.00,0.00,0.00,0.00,0.00,250.15 -0.00,0.00,0.00,0.00,0.00,0.00,250.12 -0.00,0.00,0.00,0.00,0.00,0.00,250.10 -0.00,0.00,0.00,0.00,0.00,0.00,250.08 -0.00,0.00,0.00,0.00,0.00,0.00,250.07 -0.00,0.00,0.00,0.00,0.00,0.00,250.05 -0.00,0.00,0.00,0.00,0.00,0.00,250.01 -0.00,0.00,0.00,0.00,0.00,0.00,249.98 -0.00,0.00,0.00,0.00,0.00,0.00,249.95 -0.00,0.00,0.00,0.00,0.00,0.00,249.99 -0.00,0.00,0.00,0.00,0.00,0.00,250.01 -0.00,0.00,0.00,0.00,0.00,0.00,250.03 -0.00,0.00,0.00,0.00,0.00,0.00,250.07 -0.00,0.00,0.00,0.00,0.00,0.00,250.10 -0.00,0.00,0.00,0.00,0.00,0.00,250.12 -0.00,0.00,0.00,0.00,0.00,0.00,250.12 -0.00,0.00,0.00,0.00,0.00,0.00,250.11 -0.00,0.00,0.00,0.00,0.00,0.00,250.10 -0.00,0.00,0.00,0.00,0.00,0.00,250.08 -0.00,0.00,0.00,0.00,0.00,0.00,250.07 -0.00,0.00,0.00,0.00,0.00,0.00,250.05 -0.00,0.00,0.00,0.00,0.00,0.00,250.03 -0.00,0.00,0.00,0.00,0.00,0.00,250.02 -0.00,0.00,0.00,0.00,0.00,0.00,249.97 -0.00,0.00,0.00,0.00,0.00,0.00,249.94 -0.00,0.00,0.00,0.00,0.00,0.00,249.91 -0.00,0.00,0.00,0.00,0.00,0.00,249.93 -0.00,0.00,0.00,0.00,0.00,0.00,249.95 -0.00,0.00,0.00,0.00,0.00,0.00,249.96 -0.00,0.00,0.00,0.00,0.00,0.00,249.99 -0.00,0.00,0.00,0.00,0.00,0.00,250.02 -0.00,0.00,0.00,0.00,0.00,0.00,250.04 -0.00,0.00,0.00,0.00,0.00,0.00,250.03 -0.00,0.00,0.00,0.00,0.00,0.00,250.03 -0.00,0.00,0.00,0.00,0.00,0.00,250.03 -0.00,0.00,0.00,0.00,0.00,0.00,249.97 -0.00,0.00,0.00,0.00,0.00,0.00,249.92 -0.00,0.00,0.00,0.00,0.00,0.00,249.88 -0.00,0.00,0.00,0.00,0.00,0.00,249.86 -0.00,0.00,0.00,0.00,0.00,0.00,249.85 -0.00,0.00,0.00,0.00,0.00,0.00,249.84 -0.00,0.00,0.00,0.00,0.00,0.00,249.84 -0.00,0.00,0.00,0.00,0.00,0.00,249.85 -0.00,0.00,0.00,0.00,0.00,0.00,249.86 -0.00,0.00,0.00,0.00,0.00,0.00,249.89 -0.00,0.00,0.00,0.00,0.00,0.00,249.92 -0.00,0.00,0.00,0.00,0.00,0.00,249.92 -0.00,0.00,0.00,0.00,0.00,0.00,249.93 -0.00,0.00,0.00,0.00,0.00,0.00,249.93 -0.00,0.00,0.00,0.00,0.00,0.00,249.93 -0.00,0.00,0.00,0.00,0.00,0.00,249.93 -0.00,0.00,0.00,0.00,0.00,0.00,249.93 -0.00,0.00,0.00,0.00,0.00,0.00,249.91 -0.00,0.00,0.00,0.00,0.00,0.00,249.90 -0.00,0.00,0.00,0.00,0.00,0.00,249.88 -0.00,0.00,0.00,0.00,0.00,0.00,249.92 -0.00,0.00,0.00,0.00,0.00,0.00,249.95 -0.00,0.00,0.00,0.00,0.00,0.00,249.98 -0.00,0.00,0.00,0.00,0.00,0.00,250.00 -0.00,0.00,0.00,0.00,0.00,0.00,250.01 -0.00,0.00,0.00,0.00,0.00,0.00,250.02 -0.00,0.00,0.00,0.00,0.00,0.00,250.01 -0.00,0.00,0.00,0.00,0.00,0.00,250.01 -0.00,0.00,0.00,0.00,0.00,0.00,250.00 -0.00,0.00,0.00,0.00,0.00,0.00,250.04 -0.00,0.00,0.00,0.00,0.00,0.00,250.06 -0.00,0.00,0.00,0.00,0.00,0.00,250.09 -0.00,0.00,0.00,0.00,0.00,0.00,250.10 -0.00,0.00,0.00,0.00,0.00,0.00,250.11 -0.00,0.00,0.00,0.00,0.00,0.00,250.11 -0.00,0.00,0.00,0.00,0.00,0.00,250.12 -0.00,0.00,0.00,0.00,0.00,0.00,250.12 -0.00,0.00,0.00,0.00,0.00,0.00,250.10 -0.00,0.00,0.00,0.00,0.00,0.00,250.08 -0.00,0.00,0.00,0.00,0.00,0.00,250.07 -0.00,0.00,0.00,0.00,0.00,0.00,250.08 -0.00,0.00,0.00,0.00,0.00,0.00,250.08 -0.00,0.00,0.00,0.00,0.00,0.00,250.08 -0.00,0.00,0.00,0.00,0.00,0.00,250.11 -0.00,0.00,0.00,0.00,0.00,0.00,250.14 -0.00,0.00,0.00,0.00,0.00,0.00,250.16 -0.00,0.00,0.00,0.00,0.00,0.00,250.10 -0.00,0.00,0.00,0.00,0.00,0.00,250.06 -0.00,0.00,0.00,0.00,0.00,0.00,250.02 -0.00,0.00,0.00,0.00,0.00,0.00,250.05 -0.00,0.00,0.00,0.00,0.00,0.00,250.07 -0.00,0.00,0.00,0.00,0.00,0.00,250.08 -0.00,0.00,0.00,0.00,0.00,0.00,250.10 -0.00,0.00,0.00,0.00,0.00,0.00,250.11 -0.00,0.00,0.00,0.00,0.00,0.00,250.12 -0.00,0.00,0.00,0.00,0.00,0.00,250.10 -0.00,0.00,0.00,0.00,0.00,0.00,250.09 -0.00,0.00,0.00,0.00,0.00,0.00,250.09 -0.00,0.00,0.00,0.00,0.00,0.00,250.04 -0.00,0.00,0.00,0.00,0.00,0.00,250.01 -0.00,0.00,0.00,0.00,0.00,0.00,249.98 -0.00,0.00,0.00,0.00,0.00,0.00,249.95 -0.00,0.00,0.00,0.00,0.00,0.00,249.94 -0.00,0.00,0.00,0.00,0.00,0.00,249.97 -0.00,0.00,0.00,0.00,0.00,0.00,250.00 -0.00,0.00,0.00,0.00,0.00,0.00,250.02 -0.00,0.00,0.00,0.00,0.00,0.00,250.02 -0.00,0.00,0.00,0.00,0.00,0.00,250.02 -0.00,0.00,0.00,0.00,0.00,0.00,250.01 -0.00,0.00,0.00,0.00,0.00,0.00,250.03 -0.00,0.00,0.00,0.00,0.00,0.00,250.05 -0.00,0.00,0.00,0.00,0.00,0.00,250.06 -0.00,0.00,0.00,0.00,0.00,0.00,250.08 -0.00,0.00,0.00,0.00,0.00,0.00,250.09 -0.00,0.00,0.00,0.00,0.00,0.00,250.10 -0.00,0.00,0.00,0.00,0.00,0.00,250.11 -0.00,0.00,0.00,0.00,0.00,0.00,250.12 -0.00,0.00,0.00,0.00,0.00,0.00,250.13 -0.00,0.00,0.00,0.00,0.00,0.00,250.15 -0.00,0.00,0.00,0.00,0.00,0.00,250.18 -0.00,0.00,0.00,0.00,0.00,0.00,250.20 -0.00,0.00,0.00,0.00,0.00,0.00,250.22 -0.00,0.00,0.00,0.00,0.00,0.00,250.23 -0.00,0.00,0.00,0.00,0.00,0.00,250.24 -0.00,0.00,0.00,0.00,0.00,0.00,250.23 -0.00,0.00,0.00,0.00,0.00,0.00,250.22 -0.00,0.00,0.00,0.00,0.00,0.00,250.20 -0.00,0.00,0.00,0.00,0.00,0.00,250.18 -0.00,0.00,0.00,0.00,0.00,0.00,250.16 -0.00,0.00,0.00,0.00,0.00,0.00,250.10 -0.00,0.00,0.00,0.00,0.00,0.00,250.04 -0.00,0.00,0.00,0.00,0.00,0.00,250.00 -0.00,0.00,0.00,0.00,0.00,0.00,249.97 -0.00,0.00,0.00,0.00,0.00,0.00,249.95 -0.00,0.00,0.00,0.00,0.00,0.00,249.93 -0.00,0.00,0.00,0.00,0.00,0.00,249.97 -0.00,0.00,0.00,0.00,0.00,0.00,250.00 -0.00,0.00,0.00,0.00,0.00,0.00,250.02 -0.00,0.00,0.00,0.00,0.00,0.00,250.00 -0.00,0.00,0.00,0.00,0.00,0.00,249.98 -0.00,0.00,0.00,0.00,0.00,0.00,249.97 -0.00,0.00,0.00,0.00,0.00,0.00,249.99 -0.00,0.00,0.00,0.00,0.00,0.00,250.01 -0.00,0.00,0.00,0.00,0.00,0.00,250.02 -0.00,0.00,0.00,0.00,0.00,0.00,250.04 -0.00,0.00,0.00,0.00,0.00,0.00,250.05 -0.00,0.00,0.00,0.00,0.00,0.00,250.06 -0.00,0.00,0.00,0.00,0.00,0.00,250.06 -0.00,0.00,0.00,0.00,0.00,0.00,250.06 -0.00,0.00,0.00,0.00,0.00,0.00,250.03 -0.00,0.00,0.00,0.00,0.00,0.00,250.01 -0.00,0.00,0.00,0.00,0.00,0.00,250.00 -0.00,0.00,0.00,0.00,0.00,0.00,249.98 -0.00,0.00,0.00,0.00,0.00,0.00,249.97 -0.00,0.00,0.00,0.00,0.00,0.00,249.97 -0.00,0.00,0.00,0.00,0.00,0.00,249.98 -0.00,0.00,0.00,0.00,0.00,0.00,249.99 -0.00,0.00,0.00,0.00,0.00,0.00,250.00 -0.00,0.00,0.00,0.00,0.00,0.00,250.00 -0.00,0.00,0.00,0.00,0.00,0.00,250.00 -0.00,0.00,0.00,0.00,0.00,0.00,250.00 -0.00,0.00,0.00,0.00,0.00,0.00,249.95 -0.00,0.00,0.00,0.00,0.00,0.00,249.91 -0.00,0.00,0.00,0.00,0.00,0.00,249.88 -0.00,0.00,0.00,0.00,0.00,0.00,249.90 -0.00,0.00,0.00,0.00,0.00,0.00,249.92 -0.00,0.00,0.00,0.00,0.00,0.00,249.93 -0.00,0.00,0.00,0.00,0.00,0.00,249.93 -0.00,0.00,0.00,0.00,0.00,0.00,249.94 -0.00,0.00,0.00,0.00,0.00,0.00,249.94 -280.00,0.00,280.00,280.00,0.00,280.00,249.97 -560.00,0.00,560.00,560.00,0.00,560.00,249.98 -840.00,0.00,840.00,840.00,0.00,840.00,250.00 -1110.00,0.00,1110.00,1110.00,0.00,1110.00,250.01 -1440.00,0.00,1440.00,1440.00,0.00,1440.00,250.02 -1720.00,0.00,1720.00,1720.00,0.00,1720.00,250.01 -2000.00,250.00,1750.00,2000.00,142.86,1857.14,249.99 -2270.00,1370.37,899.63,2270.00,370.37,1899.63,249.98 -2550.00,1071.43,1478.57,2550.00,357.14,2192.86,249.94 -2830.00,1178.57,1651.43,2830.00,857.14,1972.86,249.91 -3110.00,1035.71,2074.29,3110.00,1357.14,1752.86,249.89 -3390.00,1964.29,1425.71,3390.00,892.86,2497.14,249.81 -3670.00,2642.86,1027.14,3670.00,1250.00,2420.00,249.75 -3950.00,2607.14,1342.86,3950.00,1035.71,2914.29,249.71 -4220.00,1777.78,2442.22,4220.00,1555.56,2664.44,249.62 -4500.00,1607.14,2892.86,4500.00,1571.43,2928.57,249.54 -4780.00,2607.14,2172.86,4780.00,1607.14,3172.86,249.49 -5060.00,3535.71,1524.29,5060.00,1857.14,3202.86,249.51 -5340.00,3678.57,1661.43,5340.00,2142.86,3197.14,249.52 -5620.00,3642.86,1977.14,5620.00,2714.29,2905.71,249.61 -5900.00,4071.43,1828.57,5900.00,3428.57,2471.43,249.68 -6180.00,4607.14,1572.86,6180.00,3821.43,2358.57,249.74 -6460.00,4821.43,1638.57,6460.00,3892.86,2567.14,249.97 -6740.00,4500.00,2240.00,6740.00,3785.71,2954.29,250.15 -7020.00,4714.29,2305.71,7020.00,3500.00,3520.00,250.29 -7300.00,5535.71,1764.29,7300.00,4178.57,3121.43,250.27 -7590.00,6172.41,1417.59,7590.00,5379.31,2210.69,250.26 -7870.00,5750.00,2120.00,7870.00,5821.43,2048.57,250.25 -8160.00,5862.07,2297.93,8160.00,4413.79,3746.21,250.36 -8440.00,6571.43,1868.57,8440.00,3714.29,4725.71,250.44 -8720.00,7035.71,1684.29,8720.00,5928.57,2791.43,250.50 -9010.00,6862.07,2147.93,9010.00,8310.34,699.66,250.41 -9290.00,7357.14,1932.86,9290.00,7428.57,1861.43,250.33 -9570.00,7607.14,1962.86,9570.00,5428.57,4141.43,250.27 -9850.00,7464.29,2385.71,9850.00,5607.14,4242.86,250.53 -10130.00,7964.29,2165.71,10130.00,7714.29,2415.71,250.73 -10410.00,8142.86,2267.14,10410.00,8285.71,2124.29,250.97 -10700.00,8206.90,2493.10,10700.00,7689.66,3010.34,251.16 -10980.00,9035.71,1944.29,10980.00,7035.71,3944.29,251.32 -11260.00,9178.57,2081.43,11260.00,7285.71,3974.29,251.31 -11550.00,9413.79,2136.21,11550.00,9034.48,2515.52,251.30 -11830.00,9607.14,2222.86,11830.00,9821.43,2008.57,251.29 -12110.00,10071.43,2038.57,12110.00,9107.14,3002.86,251.43 -12390.00,10571.43,1818.57,12390.00,8428.57,3961.43,251.54 -12680.00,10758.62,1921.38,12680.00,9000.00,3680.00,251.63 -12960.00,10785.71,2174.29,12960.00,10928.57,2031.43,251.46 -13250.00,11068.97,2181.03,13250.00,11103.45,2146.55,251.32 -13530.00,11142.86,2387.14,13530.00,10107.14,3422.86,251.21 -13820.00,11448.28,2371.72,13820.00,8931.03,4888.97,251.24 -14100.00,11500.00,2600.00,14100.00,10535.71,3564.29,251.27 -14390.00,11758.62,2631.38,14390.00,12517.24,1872.76,251.30 -14670.00,11892.86,2777.14,14670.00,12392.86,2277.14,251.33 -14960.00,12275.86,2684.14,14960.00,10448.28,4511.72,251.35 -15250.00,12448.28,2801.72,15250.00,10965.52,4284.48,251.18 -15540.00,12793.10,2746.90,15540.00,12931.03,2608.97,251.04 -15830.00,13379.31,2450.69,15830.00,13379.31,2450.69,250.93 -16120.00,13655.17,2464.83,16120.00,12310.34,3809.66,251.03 -16410.00,13862.07,2547.93,16410.00,11827.59,4582.41,251.10 -16690.00,14000.00,2690.00,16690.00,13392.86,3297.14,251.16 -16970.00,14214.29,2755.71,16970.00,14964.29,2005.71,251.01 -17260.00,14724.14,2535.86,17260.00,14068.97,3191.03,250.89 -17540.00,15071.43,2468.57,17540.00,13250.00,4290.00,250.80 -17820.00,15250.00,2570.00,17820.00,13964.29,3855.71,250.83 -18100.00,15178.57,2921.43,18100.00,15321.43,2778.57,250.85 -18380.00,15571.43,2808.57,18380.00,15535.71,2844.29,250.87 -18660.00,15892.86,2767.14,18660.00,14964.29,3695.71,250.90 -18950.00,16000.00,2950.00,18950.00,14931.03,4018.97,250.93 -19240.00,16137.93,3102.07,19240.00,16000.00,3240.00,250.81 -19530.00,16413.79,3116.21,19530.00,16413.79,3116.21,250.71 -19820.00,16862.07,2957.93,19820.00,16000.00,3820.00,250.64 -20110.00,17172.41,2937.59,20110.00,15827.59,4282.41,250.65 -20400.00,17482.76,2917.24,20400.00,16586.21,3813.79,250.66 -20690.00,17965.52,2724.48,20690.00,17793.10,2896.90,250.67 -20970.00,18000.00,2970.00,20970.00,17607.14,3362.86,250.67 -21260.00,18379.31,2880.69,21260.00,17137.93,4122.07,250.66 -21600.00,18852.94,2747.06,21600.00,17352.94,4247.06,250.53 -21890.00,18965.52,2924.48,21890.00,18103.45,3786.55,250.43 -22170.00,18892.86,3277.14,22170.00,18642.86,3527.14,250.34 -22460.00,19000.00,3460.00,22460.00,18793.10,3666.90,250.26 -22750.00,19275.86,3474.14,22750.00,18689.66,4060.34,250.19 -23040.00,20034.48,3005.52,22463.41,18758.62,3704.79,250.14 -23330.00,20482.76,2847.24,22173.41,18827.59,3345.82,249.92 -23127.41,20517.24,2610.16,21883.41,18620.69,3262.72,249.75 -22837.41,20000.00,2837.41,21593.41,18310.34,3283.06,249.61 -22547.41,20137.93,2409.48,21303.41,18172.41,3130.99,249.59 -22257.41,20413.79,1843.61,21013.41,17551.72,3461.68,249.57 -21977.41,19964.29,2013.12,20733.41,17142.86,3590.55,249.56 -21687.41,19206.90,2480.51,20443.41,17068.97,3374.44,249.55 -21397.41,18655.17,2742.23,20153.41,17413.79,2739.61,249.54 -21117.41,18464.29,2653.12,19873.41,17178.57,2694.84,249.51 -20837.41,18607.14,2230.26,19593.41,16571.43,3021.98,249.50 -20547.41,18413.79,2133.61,19303.41,15586.21,3717.20,249.48 -20257.41,18103.45,2153.96,19013.41,15000.00,4013.41,249.39 -19977.41,17642.86,2334.55,18733.41,15464.29,3269.12,249.31 -19697.41,17357.14,2340.26,18453.41,15964.29,2489.12,249.25 -19407.41,16965.52,2441.89,18163.41,15068.97,3094.44,249.27 -19127.41,16964.29,2163.12,17883.41,14107.14,3776.26,249.29 -18837.41,16827.59,2009.82,17593.41,14241.38,3352.03,249.31 -18547.41,16689.66,1857.75,17303.41,14896.55,2406.85,249.11 -18267.41,16500.00,1767.41,17023.41,14535.71,2487.69,248.95 -17977.41,16137.93,1839.48,16733.41,13482.76,3250.65,248.83 -17687.41,15724.14,1963.27,16443.41,13034.48,3408.92,248.83 -17407.41,15285.71,2121.69,16163.41,13571.43,2591.98,248.83 -17117.41,15241.38,1876.03,15873.41,13931.03,1942.37,248.78 -16837.41,14964.29,1873.12,15593.41,13000.00,2593.41,248.74 -16547.41,14827.59,1719.82,15303.41,12103.45,3199.96,248.70 -16257.41,14482.76,1774.65,15013.41,11896.55,3116.85,248.74 -15977.41,14142.86,1834.55,14733.41,12678.57,2054.84,248.76 -15687.41,14034.48,1652.92,14443.41,12517.24,1926.17,248.78 -15397.41,13862.07,1535.34,14153.41,11655.17,2498.23,248.78 -15117.41,13571.43,1545.98,13873.41,10714.29,3159.12,248.79 -14837.41,13178.57,1658.83,13593.41,10750.00,2843.41,248.79 -14557.41,12785.71,1771.69,13313.41,11500.00,1813.41,248.77 -14277.41,12714.29,1563.12,13033.41,11535.71,1497.69,248.75 -13997.41,12642.86,1354.55,12753.41,10785.71,1967.69,248.73 -13717.41,12678.57,1038.83,12473.41,9964.29,2509.12,248.81 -13437.41,12571.43,865.98,12193.41,9607.14,2586.26,248.88 -13157.41,12392.86,764.55,11913.41,10000.00,1913.41,248.91 -12867.41,11965.52,901.89,11623.41,10172.41,1450.99,248.94 -12577.41,11413.79,1163.61,11333.41,9827.59,1505.82,248.96 -12297.41,11142.86,1154.55,11053.41,9285.71,1767.69,248.90 -12017.41,11178.57,838.83,10773.41,8928.57,1844.84,248.86 -11737.41,11178.57,558.83,10493.41,9000.00,1493.41,248.82 -11447.41,10655.17,792.23,10203.41,8965.52,1237.89,248.72 -11167.41,10285.71,881.69,9923.41,8785.71,1137.69,248.64 -10877.41,10034.48,842.92,9633.41,8034.48,1598.92,248.58 -10597.41,9785.71,811.69,9353.41,7607.14,1746.26,248.64 -10317.41,9535.71,781.69,9073.41,7500.00,1573.41,248.68 -10037.41,9285.71,751.69,8793.41,7214.29,1579.12,248.71 -9747.41,8965.52,781.89,8503.41,7103.45,1399.96,248.73 -9457.41,8655.17,802.23,8213.41,6965.52,1247.89,248.74 -9177.41,8428.57,748.83,7933.41,6500.00,1433.41,248.70 -8887.41,8172.41,714.99,7643.41,6344.83,1298.58,248.68 -8607.41,8000.00,607.41,7363.41,6000.00,1363.41,248.66 -8327.41,7571.43,755.98,7083.41,5428.57,1654.84,248.69 -8047.41,7107.14,940.26,6803.41,5035.71,1767.69,248.71 -7767.41,6928.57,838.83,6523.41,4928.57,1594.84,248.73 -7477.41,6620.69,856.72,6233.41,4896.55,1336.85,248.66 -7197.41,6285.71,911.69,5953.41,4678.57,1274.84,248.61 -6917.41,6107.14,810.26,5673.41,4142.86,1530.55,248.57 -6637.41,5750.00,887.41,5393.41,3928.57,1464.84,248.48 -6367.41,5407.41,960.00,5123.41,4037.04,1086.37,248.42 -6087.41,5285.71,801.69,4843.41,3750.00,1093.41,248.36 -5807.41,5178.57,628.83,4563.41,3142.86,1420.55,248.45 -5527.41,4821.43,705.98,4283.41,2642.86,1640.55,248.52 -5247.41,4357.14,890.26,4003.41,2464.29,1539.12,248.58 -4907.41,4058.82,848.58,3663.41,2352.94,1310.47,248.46 -4627.41,3892.86,734.55,3383.41,2321.43,1061.98,248.36 -4347.41,3607.14,740.26,3103.41,1964.29,1139.12,248.41 -4067.41,2607.14,1460.26,2823.41,892.86,1930.55,248.45 -3797.41,2037.04,1760.37,2553.41,629.63,1923.78,248.48 -3517.41,2250.00,1267.41,2273.41,535.71,1737.69,248.36 -3237.41,2500.00,737.41,1993.41,357.14,1636.26,248.26 -2957.41,2357.14,600.26,1713.41,642.86,1070.55,248.18 -2677.41,1392.86,1284.55,1433.41,857.14,576.26,248.20 -2397.41,785.71,1611.69,1153.41,-178.57,1331.98,248.22 -2127.41,-148.15,2275.55,883.41,-185.19,1068.59,248.24 -1847.41,250.00,1597.41,603.41,35.71,567.69,248.37 -1567.41,607.14,960.26,323.41,0.00,323.41,248.47 -1287.41,821.43,465.98,43.41,0.00,43.41,248.55 -1017.41,703.70,313.70,0.00,0.00,0.00,248.61 -747.41,-185.19,932.59,0.00,0.00,0.00,248.66 -467.41,-71.43,538.83,0.00,0.00,0.00,248.70 -197.41,37.04,160.37,0.00,0.00,0.00,248.75 -0.00,0.00,0.00,0.00,0.00,0.00,248.79 -0.00,0.00,0.00,0.00,0.00,0.00,248.83 -0.00,0.00,0.00,0.00,0.00,0.00,248.83 -0.00,0.00,0.00,0.00,0.00,0.00,248.84 -0.00,0.00,0.00,0.00,0.00,0.00,248.84 -0.00,0.00,0.00,0.00,0.00,0.00,248.88 -0.00,0.00,0.00,0.00,0.00,0.00,248.91 -0.00,0.00,0.00,0.00,0.00,0.00,248.82 -0.00,0.00,0.00,0.00,0.00,0.00,248.75 -0.00,0.00,0.00,0.00,0.00,0.00,248.69 -0.00,0.00,0.00,0.00,0.00,0.00,248.66 -0.00,0.00,0.00,0.00,0.00,0.00,248.64 -0.00,0.00,0.00,0.00,0.00,0.00,248.63 -0.00,0.00,0.00,0.00,0.00,0.00,248.66 -0.00,0.00,0.00,0.00,0.00,0.00,248.68 -0.00,0.00,0.00,0.00,0.00,0.00,248.69 -0.00,0.00,0.00,0.00,0.00,0.00,248.75 -0.00,0.00,0.00,0.00,0.00,0.00,248.80 -0.00,0.00,0.00,0.00,0.00,0.00,248.83 -0.00,0.00,0.00,0.00,0.00,0.00,248.83 -0.00,0.00,0.00,0.00,0.00,0.00,248.83 -0.00,0.00,0.00,0.00,0.00,0.00,248.83 -0.00,0.00,0.00,0.00,0.00,0.00,248.85 -0.00,0.00,0.00,0.00,0.00,0.00,248.87 -0.00,0.00,0.00,0.00,0.00,0.00,248.88 -0.00,0.00,0.00,0.00,0.00,0.00,248.92 -0.00,0.00,0.00,0.00,0.00,0.00,248.96 -0.00,0.00,0.00,0.00,0.00,0.00,248.99 -0.00,0.00,0.00,0.00,0.00,0.00,249.03 -0.00,0.00,0.00,0.00,0.00,0.00,249.06 -0.00,0.00,0.00,0.00,0.00,0.00,249.09 -0.00,0.00,0.00,0.00,0.00,0.00,249.11 -0.00,0.00,0.00,0.00,0.00,0.00,249.13 -0.00,0.00,0.00,0.00,0.00,0.00,249.15 -0.00,0.00,0.00,0.00,0.00,0.00,249.14 -0.00,0.00,0.00,0.00,0.00,0.00,249.14 -0.00,0.00,0.00,0.00,0.00,0.00,249.14 -0.00,0.00,0.00,0.00,0.00,0.00,249.15 -0.00,0.00,0.00,0.00,0.00,0.00,249.15 -0.00,0.00,0.00,0.00,0.00,0.00,249.14 -0.00,0.00,0.00,0.00,0.00,0.00,249.13 -0.00,0.00,0.00,0.00,0.00,0.00,249.12 -0.00,0.00,0.00,0.00,0.00,0.00,249.11 -0.00,0.00,0.00,0.00,0.00,0.00,249.10 -0.00,0.00,0.00,0.00,0.00,0.00,249.10 -0.00,0.00,0.00,0.00,0.00,0.00,249.10 -0.00,0.00,0.00,0.00,0.00,0.00,249.11 -0.00,0.00,0.00,0.00,0.00,0.00,249.11 -0.00,0.00,0.00,0.00,0.00,0.00,248.38 -0.00,0.00,0.00,0.00,0.00,0.00,248.38 -0.00,0.00,0.00,0.00,0.00,0.00,248.38 -0.00,0.00,0.00,0.00,0.00,0.00,248.38 -0.00,0.00,0.00,0.00,0.00,0.00,248.38 -0.00,0.00,0.00,0.00,0.00,0.00,248.38 -0.00,0.00,0.00,0.00,0.00,0.00,248.37 -0.00,0.00,0.00,0.00,0.00,0.00,248.37 -0.00,0.00,0.00,0.00,0.00,0.00,248.37 -0.00,0.00,0.00,0.00,0.00,0.00,248.32 -0.00,0.00,0.00,0.00,0.00,0.00,248.32 -0.00,0.00,0.00,0.00,0.00,0.00,248.32 -0.00,0.00,0.00,0.00,0.00,0.00,248.22 -0.00,0.00,0.00,0.00,0.00,0.00,248.22 -0.00,0.00,0.00,0.00,0.00,0.00,248.22 -0.00,0.00,0.00,0.00,0.00,0.00,248.15 -0.00,35.71,-35.71,0.00,0.00,0.00,248.15 -0.00,0.00,0.00,0.00,0.00,0.00,248.15 -0.00,0.00,0.00,0.00,0.00,0.00,248.14 -0.00,0.00,0.00,0.00,0.00,0.00,248.14 -0.00,0.00,0.00,0.00,0.00,0.00,248.10 -0.00,0.00,0.00,0.00,0.00,0.00,248.10 -0.00,0.00,0.00,0.00,0.00,0.00,248.10 -0.00,0.00,0.00,0.00,0.00,0.00,248.05 -0.00,0.00,0.00,0.00,0.00,0.00,248.05 -0.00,0.00,0.00,0.00,0.00,0.00,248.05 -0.00,0.00,0.00,0.00,0.00,0.00,248.04 -0.00,0.00,0.00,0.00,0.00,0.00,248.04 -0.00,0.00,0.00,0.00,0.00,0.00,248.04 -0.00,0.00,0.00,0.00,0.00,0.00,248.07 -0.00,0.00,0.00,0.00,0.00,0.00,248.07 -0.00,0.00,0.00,0.00,0.00,0.00,248.07 -0.00,0.00,0.00,0.00,0.00,0.00,248.04 -0.00,0.00,0.00,0.00,0.00,0.00,248.04 -0.00,0.00,0.00,0.00,0.00,0.00,248.04 -0.00,0.00,0.00,0.00,0.00,0.00,248.07 -0.00,0.00,0.00,0.00,0.00,0.00,248.07 -0.00,0.00,0.00,0.00,0.00,0.00,248.07 -0.00,0.00,0.00,0.00,0.00,0.00,248.14 -0.00,0.00,0.00,0.00,0.00,0.00,248.14 -0.00,0.00,0.00,0.00,0.00,0.00,248.14 -0.00,0.00,0.00,0.00,0.00,0.00,248.18 -0.00,0.00,0.00,0.00,-35.71,35.71,248.18 -0.00,0.00,0.00,0.00,0.00,0.00,248.18 -0.00,0.00,0.00,0.00,0.00,0.00,248.25 -0.00,0.00,0.00,0.00,0.00,0.00,248.25 -0.00,0.00,0.00,0.00,0.00,0.00,248.25 -0.00,0.00,0.00,0.00,0.00,0.00,248.26 -0.00,0.00,0.00,0.00,0.00,0.00,248.26 -0.00,0.00,0.00,0.00,0.00,0.00,248.26 -0.00,0.00,0.00,0.00,0.00,0.00,248.21 -0.00,0.00,0.00,0.00,0.00,0.00,248.21 -0.00,0.00,0.00,0.00,0.00,0.00,248.21 -0.00,0.00,0.00,0.00,0.00,0.00,248.19 -0.00,0.00,0.00,0.00,0.00,0.00,248.19 -0.00,0.00,0.00,0.00,0.00,0.00,248.19 -0.00,0.00,0.00,0.00,0.00,0.00,248.19 -0.00,0.00,0.00,0.00,0.00,0.00,248.19 -0.00,0.00,0.00,0.00,0.00,0.00,248.19 -0.00,0.00,0.00,0.00,0.00,0.00,248.16 -0.00,0.00,0.00,0.00,0.00,0.00,248.16 -0.00,0.00,0.00,0.00,0.00,0.00,248.16 -0.00,0.00,0.00,0.00,0.00,0.00,248.18 -0.00,0.00,0.00,0.00,0.00,0.00,248.18 -0.00,0.00,0.00,0.00,0.00,0.00,248.18 -0.00,0.00,0.00,0.00,0.00,0.00,248.20 -0.00,0.00,0.00,0.00,0.00,0.00,248.20 -0.00,0.00,0.00,0.00,0.00,0.00,248.20 -0.00,0.00,0.00,0.00,0.00,0.00,248.23 -0.00,0.00,0.00,0.00,0.00,0.00,248.23 -0.00,0.00,0.00,0.00,0.00,0.00,248.23 -0.00,0.00,0.00,0.00,0.00,0.00,248.27 -0.00,0.00,0.00,0.00,0.00,0.00,248.27 -0.00,0.00,0.00,0.00,0.00,0.00,248.27 -0.00,0.00,0.00,0.00,0.00,0.00,248.30 -0.00,0.00,0.00,0.00,0.00,0.00,248.30 -0.00,0.00,0.00,0.00,0.00,0.00,248.30 -0.00,0.00,0.00,0.00,0.00,0.00,248.32 -0.00,0.00,0.00,0.00,71.43,-71.43,248.32 -0.00,0.00,0.00,0.00,0.00,0.00,248.32 -0.00,0.00,0.00,0.00,0.00,0.00,248.36 -0.00,0.00,0.00,0.00,0.00,0.00,248.36 -0.00,0.00,0.00,0.00,38.46,-38.46,248.36 -0.00,0.00,0.00,0.00,38.46,-38.46,248.30 -0.00,0.00,0.00,0.00,0.00,0.00,248.30 -0.00,0.00,0.00,0.00,0.00,0.00,248.30 -0.00,0.00,0.00,0.00,0.00,0.00,248.32 -0.00,0.00,0.00,0.00,0.00,0.00,248.32 -0.00,0.00,0.00,0.00,0.00,0.00,248.32 -0.00,0.00,0.00,0.00,0.00,0.00,248.24 -290.00,34.48,255.52,290.00,-34.48,324.48,248.24 -550.00,0.00,550.00,550.00,0.00,550.00,248.24 -810.00,0.00,810.00,810.00,0.00,810.00,248.23 -1090.00,0.00,1090.00,1090.00,0.00,1090.00,248.23 -1400.00,0.00,1400.00,1400.00,0.00,1400.00,248.23 -1660.00,38.46,1621.54,1660.00,-38.46,1698.46,248.22 -1950.00,172.41,1777.59,1950.00,0.00,1950.00,248.22 -2210.00,423.08,1786.92,2210.00,76.92,2133.08,248.22 -2480.00,888.89,1591.11,2480.00,37.04,2442.96,248.01 -2760.00,2250.00,510.00,2760.00,71.43,2688.57,248.01 -3030.00,2370.37,659.63,3030.00,111.11,2918.89,248.01 -3300.00,1666.67,1633.33,3300.00,74.07,3225.93,247.78 -3590.00,689.66,2900.34,3590.00,68.97,3521.03,247.78 -3850.00,2115.38,1734.62,3850.00,423.08,3426.92,247.78 -4120.00,3703.70,416.30,4120.00,888.89,3231.11,247.38 -4410.00,3655.17,754.83,4410.00,1620.69,2789.31,247.38 -4680.00,2518.52,2161.48,4680.00,1555.56,3124.44,247.38 -4940.00,2076.92,2863.08,4940.00,1269.23,3670.77,247.24 -5220.00,2928.57,2291.43,5220.00,2000.00,3220.00,247.24 -5490.00,4518.52,971.48,5490.00,2703.70,2786.30,247.24 -5760.00,5444.44,315.56,5760.00,2814.81,2945.19,247.12 -6050.00,5206.90,843.10,6050.00,2827.59,3222.41,247.12 -6320.00,4444.44,1875.56,6320.00,3333.33,2986.67,247.12 -6590.00,4666.67,1923.33,6590.00,4111.11,2478.89,247.04 -6880.00,5206.90,1673.10,6880.00,4655.17,2224.83,247.04 -7150.00,5814.81,1335.19,7150.00,4740.74,2409.26,247.07 -7440.00,6172.41,1267.59,7440.00,5241.38,2198.62,247.07 -7710.00,6259.26,1450.74,7710.00,5555.56,2154.44,247.07 -7980.00,6444.44,1535.56,7980.00,5259.26,2720.74,247.14 -8270.00,6586.21,1683.79,8270.00,5379.31,2890.69,247.14 -8540.00,6555.56,1984.44,8540.00,6259.26,2280.74,247.14 -8810.00,6814.81,1995.19,8810.00,6777.78,2032.22,247.27 -9100.00,7413.79,1686.21,9100.00,6586.21,2513.79,247.27 -9370.00,7481.48,1888.52,9370.00,6259.26,3110.74,247.27 -9640.00,7592.59,2047.41,9640.00,6370.37,3269.63,247.40 -9930.00,7965.52,1964.48,9930.00,7103.45,2826.55,247.40 -10200.00,8037.04,2162.96,10200.00,8111.11,2088.89,247.40 -10470.00,8296.30,2173.70,10470.00,8259.26,2210.74,247.63 -10760.00,8758.62,2001.38,10760.00,7793.10,2966.90,247.63 -11030.00,8962.96,2067.04,11030.00,7777.78,3252.22,247.63 -11300.00,9333.33,1966.67,11300.00,8111.11,3188.89,247.74 -11590.00,9379.31,2210.69,11590.00,9206.90,2383.10,247.74 -11860.00,9592.59,2267.41,11860.00,9851.85,2008.15,247.74 -12130.00,9925.93,2204.07,12130.00,9703.70,2426.30,247.87 -12420.00,10103.45,2316.55,12420.00,8827.59,3592.41,247.87 -12690.00,10666.67,2023.33,12690.00,8925.93,3764.07,247.87 -12960.00,10777.78,2182.22,12960.00,10185.19,2774.81,247.77 -13250.00,10965.52,2284.48,13250.00,10931.03,2318.97,247.77 -13520.00,11185.19,2334.81,13520.00,10851.85,2668.15,247.81 -13810.00,11620.69,2189.31,13810.00,10379.31,3430.69,247.81 -14080.00,11962.96,2117.04,14080.00,10555.56,3524.44,247.81 -14350.00,12333.33,2016.67,14350.00,10888.89,3461.11,247.89 -14640.00,12551.72,2088.28,14640.00,11931.03,2708.97,247.89 -14920.00,12714.29,2205.71,14920.00,12142.86,2777.14,247.89 -15190.00,13037.04,2152.96,15190.00,12148.15,3041.85,247.89 -15490.00,13166.67,2323.33,15490.00,12033.33,3456.67,247.89 -15760.00,13444.44,2315.56,15760.00,12148.15,3611.85,247.89 -16040.00,13785.71,2254.29,16040.00,12535.71,3504.29,247.89 -16330.00,13896.55,2433.45,16330.00,13241.38,3088.62,247.89 -16610.00,14142.86,2467.14,16610.00,13928.57,2681.43,247.89 -16870.00,14538.46,2331.54,16870.00,13846.15,3023.85,247.88 -17160.00,14758.62,2401.38,17160.00,13655.17,3504.83,247.88 -17430.00,15037.04,2392.96,17430.00,14148.15,3281.85,247.88 -17700.00,15185.19,2514.81,17700.00,14703.70,2996.30,247.83 -17990.00,15310.34,2679.66,17990.00,15206.90,2783.10,247.83 -18260.00,15851.85,2408.15,18260.00,15074.07,3185.93,247.83 -18530.00,16222.22,2307.78,18530.00,15222.22,3307.78,247.81 -18820.00,16448.28,2371.72,18820.00,15310.34,3509.66,247.81 -19100.00,16678.57,2421.43,19100.00,15392.86,3707.14,247.81 -19370.00,16851.85,2518.15,19370.00,16259.26,3110.74,247.79 -19670.00,16966.67,2703.33,19670.00,17133.33,2536.67,247.79 -19940.00,17259.26,2680.74,19940.00,17037.04,2902.96,247.92 -20240.00,17666.67,2573.33,20240.00,16633.33,3606.67,247.92 -20510.00,18074.07,2435.93,20510.00,16703.70,3806.30,247.92 -20790.00,18321.43,2468.57,20790.00,17500.00,3290.00,247.93 -21080.00,18379.31,2700.69,21080.00,18586.21,2493.79,247.93 -21350.00,18740.74,2609.26,21350.00,18703.70,2646.30,247.93 -21670.00,18906.25,2763.75,21670.00,18125.00,3545.00,248.01 -21970.00,19400.00,2570.00,21970.00,17766.67,4203.33,248.01 -22250.00,19785.71,2464.29,22250.00,18535.71,3714.29,248.01 -22520.00,19962.96,2557.04,22520.00,19555.56,2964.44,247.92 -22810.00,20241.38,2568.62,22810.00,20000.00,2810.00,247.92 -23090.00,20392.86,2697.14,23090.00,20035.71,3054.29,247.92 -23360.00,20555.56,2804.44,23288.47,19666.67,3621.81,247.89 -23512.27,20620.69,2891.58,22998.47,19448.28,3550.20,247.89 -23232.27,20821.43,2410.84,22718.47,19892.86,2825.62,247.90 -22942.27,20655.17,2287.10,22428.47,20103.45,2325.02,247.90 -22672.27,20444.44,2227.83,22158.47,19555.56,2602.92,247.90 -22402.27,20037.04,2365.24,21888.47,18814.81,3073.66,247.91 -22102.27,19966.67,2135.61,21588.47,18266.67,3321.81,247.91 -21822.27,19714.29,2107.99,21308.47,18107.14,3201.33,247.91 -21542.27,19607.14,1935.13,21028.47,18571.43,2457.04,247.86 -21252.27,19241.38,2010.89,20738.47,18482.76,2255.71,247.86 -20972.27,18857.14,2115.13,20458.47,17607.14,2851.33,247.86 -20702.27,18555.56,2146.72,20188.47,16518.52,3669.95,247.93 -20412.27,18413.79,1998.48,19898.47,16758.62,3139.85,247.93 -20142.27,18259.26,1883.01,19628.47,17740.74,1887.73,247.93 -19872.27,18037.04,1835.24,19358.47,17740.74,1617.73,248.00 -19572.27,17866.67,1705.61,19058.47,16666.67,2391.81,248.00 -19302.27,17555.56,1746.72,18788.47,15555.56,3232.92,248.00 -19022.27,17392.86,1629.42,18508.47,15071.43,3437.04,248.08 -18732.27,17137.93,1594.34,18218.47,15931.03,2287.44,248.08 -18452.27,16714.29,1737.99,17938.47,16428.57,1509.90,248.17 -18162.27,16310.34,1851.93,17648.47,15379.31,2269.16,248.17 -17882.27,16071.43,1810.84,17368.47,14142.86,3225.62,248.17 -17612.27,15777.78,1834.50,17098.47,13777.78,3320.69,248.11 -17322.27,15620.69,1701.58,16808.47,14689.66,2118.82,248.11 -17052.27,15407.41,1644.87,16538.47,15111.11,1427.36,248.11 -16782.27,15074.07,1708.20,16268.47,14222.22,2046.25,248.18 -16492.27,14931.03,1561.24,15978.47,13137.93,2840.54,248.18 -16222.27,14703.70,1518.57,15708.47,12555.56,3152.92,248.18 -15952.27,14407.41,1544.87,15438.47,13111.11,2327.36,248.13 -15662.27,14103.45,1558.82,15148.47,13620.69,1527.78,248.13 -15392.27,14037.04,1355.24,14878.47,13222.22,1656.25,248.13 -15122.27,14037.04,1085.24,14608.47,12222.22,2386.25,248.21 -14832.27,13724.14,1108.14,14318.47,11827.59,2490.89,248.21 -14562.27,13296.30,1265.98,14048.47,12037.04,2011.44,248.21 -14282.27,13035.71,1246.56,13768.47,12214.29,1554.19,248.11 -13992.27,12896.55,1095.72,13478.47,11827.59,1650.89,248.11 -13712.27,12678.57,1033.70,13198.47,10964.29,2234.19,248.11 -13442.27,12333.33,1108.94,12928.47,10740.74,2187.73,248.15 -13152.27,12103.45,1048.82,12638.47,11241.38,1397.09,248.15 -12882.27,12037.04,845.24,12368.47,11407.41,961.07,248.15 -12612.27,11814.81,797.46,12098.47,10962.96,1135.51,248.20 -12322.27,11551.72,770.55,11808.47,9862.07,1946.40,248.20 -12052.27,11259.26,793.01,11538.47,9259.26,2279.21,248.31 -11762.27,10965.52,796.76,11248.47,9448.28,1800.20,248.31 -11492.27,10629.63,862.64,10978.47,9962.96,1015.51,248.31 -11222.27,10370.37,851.90,10708.47,9888.89,819.58,248.29 -10932.27,10310.34,621.93,10418.47,9172.41,1246.06,248.29 -10662.27,10185.19,477.09,10148.47,8703.70,1444.77,248.29 -10402.27,9807.69,594.58,9888.47,8692.31,1196.16,248.28 -10112.27,9620.69,491.58,9598.47,8862.07,736.40,248.28 -9842.27,9259.26,583.01,9328.47,8407.41,921.07,248.28 -9582.27,9038.46,543.81,9068.47,7730.77,1337.70,248.35 -9292.27,8655.17,637.10,8778.47,7551.72,1226.75,248.35 -9032.27,8384.62,647.66,8518.47,7538.46,980.01,248.35 -8762.27,8185.19,577.09,8248.47,7518.52,729.95,248.24 -8472.27,7896.55,575.72,7958.47,7172.41,786.06,248.24 -8202.27,7629.63,572.64,7688.47,6444.44,1244.03,248.24 -7932.27,7296.30,635.98,7418.47,5814.81,1603.66,248.28 -7642.27,6862.07,780.20,7128.47,5758.62,1369.85,248.28 -7372.27,6666.67,705.61,6858.47,5962.96,895.51,248.28 -7102.27,6407.41,694.87,6588.47,5962.96,625.51,248.22 -6812.27,6172.41,639.86,6298.47,5586.21,712.27,248.22 -6542.27,5925.93,616.35,6028.47,5185.19,843.29,248.22 -6272.27,5740.74,531.53,5758.47,4740.74,1017.73,248.21 -5982.27,5379.31,602.96,5468.47,4344.83,1123.65,248.21 -5712.27,5037.04,675.24,5198.47,4185.19,1013.29,248.21 -5392.27,4750.00,642.27,4878.47,4062.50,815.97,248.23 -5112.27,4464.29,647.99,4598.47,3821.43,777.04,248.23 -4852.27,4153.85,698.43,4338.47,3346.15,992.32,248.32 -4572.27,3571.43,1000.84,4058.47,2535.71,1522.76,248.32 -4302.27,3000.00,1302.27,3788.47,2481.48,1306.99,248.32 -4032.27,3148.15,884.12,3518.47,2629.63,888.84,248.31 -3742.27,3068.97,673.31,3228.47,2379.31,849.16,248.31 -3472.27,2296.30,1175.98,2958.47,1740.74,1217.73,248.31 -3212.27,1769.23,1443.04,2698.47,923.08,1775.40,248.23 -2922.27,1655.17,1267.10,2408.47,1379.31,1029.16,248.23 -2662.27,1807.69,854.58,2148.47,1230.77,917.70,248.23 -2392.27,1740.74,651.53,1878.47,888.89,989.58,248.29 -2112.27,321.43,1790.84,1598.47,-178.57,1777.04,248.29 -1842.27,-111.11,1953.38,1328.47,37.04,1291.44,248.29 -1572.27,592.59,979.68,1058.47,74.07,984.40,248.23 -1292.27,1321.43,-29.16,778.47,-142.86,921.33,248.23 -1022.27,111.11,911.16,508.47,0.00,508.47,248.23 -762.27,-692.31,1454.58,248.47,0.00,248.47,248.31 -472.27,206.90,265.38,0.00,0.00,0.00,248.31 -202.27,74.07,128.20,0.00,0.00,0.00,248.31 -0.00,-38.46,38.46,0.00,0.00,0.00,248.37 -0.00,0.00,0.00,0.00,0.00,0.00,248.37 -0.00,0.00,0.00,0.00,0.00,0.00,248.37 -0.00,0.00,0.00,0.00,0.00,0.00,248.45 -0.00,0.00,0.00,0.00,0.00,0.00,248.45 -0.00,0.00,0.00,0.00,0.00,0.00,248.45 -0.00,0.00,0.00,0.00,0.00,0.00,248.48 -0.00,0.00,0.00,0.00,0.00,0.00,248.48 -0.00,0.00,0.00,0.00,0.00,0.00,248.48 -0.00,0.00,0.00,0.00,0.00,0.00,248.53 -0.00,0.00,0.00,0.00,0.00,0.00,248.53 -0.00,0.00,0.00,0.00,0.00,0.00,248.53 -0.00,0.00,0.00,0.00,0.00,0.00,248.56 -0.00,0.00,0.00,0.00,-35.71,35.71,248.56 -0.00,0.00,0.00,0.00,-38.46,38.46,248.56 -0.00,0.00,0.00,0.00,0.00,0.00,248.59 -0.00,0.00,0.00,0.00,-142.86,142.86,248.59 -0.00,0.00,0.00,0.00,-230.77,230.77,248.59 -0.00,0.00,0.00,0.00,-307.69,307.69,248.60 -0.00,0.00,0.00,0.00,-1000.00,1000.00,248.60 -0.00,0.00,0.00,0.00,-2500.00,2500.00,248.60 -0.00,0.00,0.00,0.00,-2666.67,2666.67,248.60 -0.00,0.00,0.00,0.00,-1310.34,1310.34,248.60 -0.00,38.46,-38.46,0.00,-576.92,576.92,248.60 -0.00,444.44,-444.44,0.00,-2703.70,2703.70,248.79 -0.00,1137.93,-1137.93,0.00,-3862.07,3862.07,248.79 -0.00,2074.07,-2074.07,0.00,-1925.93,1925.93,248.79 -0.00,2074.07,-2074.07,0.00,-592.59,592.59,248.36 -0.00,1413.79,-1413.79,0.00,-2482.76,2482.76,248.36 -0.00,1296.30,-1296.30,0.00,-4222.22,4222.22,248.36 -0.00,2407.41,-2407.41,0.00,-2851.85,2851.85,248.07 -0.00,2586.21,-2586.21,0.00,-1034.48,1034.48,248.07 -0.00,1777.78,-1777.78,0.00,-2777.78,2777.78,248.00 -0.00,1241.38,-1241.38,0.00,-4965.52,4965.52,248.00 -0.00,2148.15,-2148.15,0.00,-2814.81,2814.81,248.00 -0.00,1666.67,-1666.67,0.00,-37.04,37.04,248.10 -0.00,250.00,-250.00,0.00,-321.43,321.43,248.10 -0.00,1000.00,-1000.00,0.00,-1518.52,1518.52,248.10 -0.00,703.70,-703.70,0.00,-2259.26,2259.26,248.17 -0.00,-620.69,620.69,0.00,-1172.41,1172.41,248.17 -0.00,-148.15,148.15,0.00,1148.15,-1148.15,248.17 -0.00,269.23,-269.23,0.00,192.31,-192.31,248.24 -0.00,-68.97,68.97,0.00,-551.72,551.72,248.24 -0.00,0.00,0.00,0.00,74.07,-74.07,248.24 -0.00,0.00,0.00,0.00,37.04,-37.04,248.14 -0.00,0.00,0.00,0.00,0.00,0.00,248.14 -0.00,0.00,0.00,0.00,0.00,0.00,248.14 -0.00,0.00,0.00,0.00,0.00,0.00,248.12 -0.00,0.00,0.00,0.00,0.00,0.00,248.12 -0.00,0.00,0.00,0.00,0.00,0.00,248.12 -0.00,0.00,0.00,0.00,0.00,0.00,248.14 -0.00,0.00,0.00,0.00,0.00,0.00,248.14 -0.00,0.00,0.00,0.00,0.00,0.00,248.14 -0.00,0.00,0.00,0.00,0.00,0.00,248.19 -0.00,0.00,0.00,0.00,0.00,0.00,248.19 -0.00,0.00,0.00,0.00,0.00,0.00,248.19 -0.00,0.00,0.00,0.00,0.00,0.00,248.18 -0.00,0.00,0.00,0.00,0.00,0.00,248.18 -0.00,0.00,0.00,0.00,0.00,0.00,248.18 -0.00,0.00,0.00,0.00,0.00,0.00,248.23 -0.00,0.00,0.00,0.00,0.00,0.00,248.23 -0.00,0.00,0.00,0.00,0.00,0.00,248.23 -0.00,0.00,0.00,0.00,0.00,0.00,248.20 -0.00,0.00,0.00,0.00,35.71,-35.71,248.20 -0.00,0.00,0.00,0.00,74.07,-74.07,248.20 -0.00,0.00,0.00,0.00,0.00,0.00,248.16 -0.00,0.00,0.00,0.00,0.00,0.00,248.16 -0.00,0.00,0.00,0.00,0.00,0.00,248.16 -0.00,0.00,0.00,0.00,0.00,0.00,248.21 -0.00,0.00,0.00,0.00,0.00,0.00,248.21 -0.00,0.00,0.00,0.00,0.00,0.00,248.21 -0.00,0.00,0.00,0.00,38.46,-38.46,248.25 -0.00,0.00,0.00,0.00,71.43,-71.43,248.25 -0.00,0.00,0.00,0.00,38.46,-38.46,248.25 -0.00,0.00,0.00,0.00,148.15,-148.15,248.29 -0.00,0.00,0.00,0.00,103.45,-103.45,248.29 -0.00,0.00,0.00,0.00,0.00,0.00,248.31 -0.00,0.00,0.00,0.00,35.71,-35.71,248.31 -0.00,0.00,0.00,0.00,185.19,-185.19,248.31 -0.00,0.00,0.00,0.00,961.54,-961.54,248.26 -0.00,-34.48,34.48,0.00,3034.48,-3034.48,248.26 -0.00,-37.04,37.04,0.00,3407.41,-3407.41,248.26 -0.00,-37.04,37.04,0.00,1148.15,-1148.15,248.15 -0.00,-103.45,103.45,0.00,1068.97,-1068.97,248.15 -0.00,0.00,0.00,0.00,2962.96,-2962.96,248.15 -0.00,0.00,0.00,0.00,3444.44,-3444.44,248.18 -0.00,0.00,0.00,0.00,1137.93,-1137.93,248.18 -0.00,0.00,0.00,0.00,461.54,-461.54,248.18 -0.00,-37.04,37.04,0.00,2629.63,-2629.63,247.94 -0.00,0.00,0.00,0.00,2793.10,-2793.10,247.94 -0.00,0.00,0.00,0.00,730.77,-730.77,247.94 -0.00,0.00,0.00,0.00,-111.11,111.11,247.73 -0.00,0.00,0.00,0.00,0.00,0.00,247.73 -0.00,38.46,-38.46,0.00,0.00,0.00,247.73 -0.00,38.46,-38.46,0.00,0.00,0.00,247.76 -0.00,0.00,0.00,0.00,0.00,0.00,247.76 -0.00,0.00,0.00,0.00,0.00,0.00,247.76 -0.00,0.00,0.00,0.00,0.00,0.00,247.78 -0.00,0.00,0.00,0.00,0.00,0.00,247.78 -0.00,0.00,0.00,0.00,-76.92,76.92,247.78 -0.00,0.00,0.00,0.00,0.00,0.00,247.71 -0.00,35.71,-35.71,0.00,0.00,0.00,247.71 -0.00,38.46,-38.46,0.00,0.00,0.00,247.71 -0.00,0.00,0.00,0.00,0.00,0.00,247.66 -0.00,0.00,0.00,0.00,0.00,0.00,247.66 -0.00,0.00,0.00,0.00,0.00,0.00,247.66 -0.00,0.00,0.00,0.00,0.00,0.00,247.64 -0.00,0.00,0.00,0.00,0.00,0.00,247.64 -0.00,0.00,0.00,0.00,0.00,0.00,247.64 -0.00,0.00,0.00,0.00,0.00,0.00,247.62 -0.00,0.00,0.00,0.00,0.00,0.00,247.62 -0.00,0.00,0.00,0.00,0.00,0.00,247.62 -0.00,0.00,0.00,0.00,0.00,0.00,247.63 -0.00,0.00,0.00,0.00,0.00,0.00,247.63 -0.00,0.00,0.00,0.00,0.00,0.00,247.63 -0.00,0.00,0.00,0.00,0.00,0.00,247.65 -0.00,-35.71,35.71,0.00,0.00,0.00,247.65 -0.00,0.00,0.00,0.00,0.00,0.00,247.65 -0.00,0.00,0.00,0.00,0.00,0.00,247.66 -0.00,0.00,0.00,0.00,0.00,0.00,247.66 -0.00,0.00,0.00,0.00,0.00,0.00,247.66 -0.00,0.00,0.00,0.00,76.92,-76.92,247.61 -0.00,0.00,0.00,0.00,71.43,-71.43,247.61 -0.00,0.00,0.00,0.00,38.46,-38.46,247.61 -0.00,0.00,0.00,0.00,74.07,-74.07,247.65 -0.00,-35.71,35.71,0.00,357.14,-357.14,247.65 -0.00,0.00,0.00,0.00,653.85,-653.85,247.65 -0.00,-38.46,38.46,0.00,1730.77,-1730.77,247.68 -0.00,0.00,0.00,0.00,2242.42,-2242.42,247.68 -0.00,0.00,0.00,0.00,1961.54,-1961.54,247.68 -0.00,0.00,0.00,0.00,222.22,-222.22,247.85 -0.00,0.00,0.00,0.00,-142.86,142.86,247.85 -0.00,0.00,0.00,0.00,-153.85,153.85,247.85 -0.00,0.00,0.00,0.00,-38.46,38.46,247.85 -0.00,0.00,0.00,0.00,0.00,0.00,247.85 -0.00,0.00,0.00,0.00,0.00,0.00,247.85 -0.00,38.46,-38.46,0.00,0.00,0.00,247.78 -0.00,71.43,-71.43,0.00,0.00,0.00,247.78 -0.00,38.46,-38.46,0.00,-76.92,76.92,247.78 -0.00,0.00,0.00,0.00,0.00,0.00,247.73 -0.00,0.00,0.00,0.00,0.00,0.00,247.73 -0.00,0.00,0.00,0.00,0.00,0.00,247.73 -0.00,0.00,0.00,0.00,0.00,0.00,247.60 -0.00,0.00,0.00,0.00,0.00,0.00,247.60 -0.00,0.00,0.00,0.00,0.00,0.00,247.60 -0.00,0.00,0.00,0.00,0.00,0.00,247.59 -0.00,0.00,0.00,0.00,0.00,0.00,247.59 -0.00,0.00,0.00,0.00,0.00,0.00,247.59 -0.00,0.00,0.00,0.00,0.00,0.00,247.56 -0.00,0.00,0.00,0.00,0.00,0.00,247.56 -0.00,0.00,0.00,0.00,0.00,0.00,247.53 -0.00,0.00,0.00,0.00,0.00,0.00,247.53 -0.00,0.00,0.00,0.00,0.00,0.00,247.53 -0.00,0.00,0.00,0.00,0.00,0.00,247.45 -0.00,0.00,0.00,0.00,0.00,0.00,247.45 -0.00,0.00,0.00,0.00,0.00,0.00,247.45 -0.00,0.00,0.00,0.00,0.00,0.00,247.38 -0.00,0.00,0.00,0.00,0.00,0.00,247.38 -0.00,0.00,0.00,0.00,0.00,0.00,247.38 -0.00,0.00,0.00,0.00,0.00,0.00,247.41 -0.00,0.00,0.00,0.00,0.00,0.00,247.41 -0.00,0.00,0.00,0.00,0.00,0.00,247.41 -0.00,0.00,0.00,0.00,0.00,0.00,247.44 -0.00,0.00,0.00,0.00,0.00,0.00,247.44 -0.00,0.00,0.00,0.00,0.00,0.00,247.44 -0.00,0.00,0.00,0.00,0.00,0.00,247.46 -0.00,0.00,0.00,0.00,0.00,0.00,247.46 -0.00,0.00,0.00,0.00,0.00,0.00,247.46 -0.00,0.00,0.00,0.00,0.00,0.00,247.49 -0.00,0.00,0.00,0.00,0.00,0.00,247.49 -0.00,0.00,0.00,0.00,0.00,0.00,247.49 -0.00,0.00,0.00,0.00,0.00,0.00,247.46 -0.00,0.00,0.00,0.00,0.00,0.00,247.46 -0.00,0.00,0.00,0.00,0.00,0.00,247.46 -0.00,0.00,0.00,0.00,0.00,0.00,247.50 -0.00,0.00,0.00,0.00,0.00,0.00,247.50 -0.00,0.00,0.00,0.00,0.00,0.00,247.50 -0.00,0.00,0.00,0.00,0.00,0.00,247.51 -0.00,0.00,0.00,0.00,0.00,0.00,247.51 -0.00,0.00,0.00,0.00,0.00,0.00,247.51 -0.00,0.00,0.00,0.00,0.00,0.00,247.52 -0.00,0.00,0.00,0.00,0.00,0.00,247.52 -0.00,0.00,0.00,0.00,0.00,0.00,247.52 -0.00,0.00,0.00,0.00,0.00,0.00,247.49 -0.00,0.00,0.00,0.00,0.00,0.00,247.49 -0.00,0.00,0.00,0.00,0.00,0.00,247.49 -0.00,0.00,0.00,0.00,0.00,0.00,247.47 -0.00,0.00,0.00,0.00,0.00,0.00,247.47 -0.00,0.00,0.00,0.00,0.00,0.00,247.47 -0.00,0.00,0.00,0.00,0.00,0.00,247.45 -0.00,0.00,0.00,0.00,0.00,0.00,247.45 -0.00,0.00,0.00,0.00,0.00,0.00,247.45 -0.00,0.00,0.00,0.00,0.00,0.00,247.45 -0.00,0.00,0.00,0.00,0.00,0.00,247.45 -0.00,0.00,0.00,0.00,0.00,0.00,247.45 -0.00,0.00,0.00,0.00,0.00,0.00,247.46 -0.00,0.00,0.00,0.00,0.00,0.00,247.46 -0.00,0.00,0.00,0.00,0.00,0.00,247.46 -0.00,0.00,0.00,0.00,0.00,0.00,247.44 -0.00,0.00,0.00,0.00,0.00,0.00,247.44 -0.00,0.00,0.00,0.00,0.00,0.00,247.44 -0.00,0.00,0.00,0.00,0.00,0.00,247.44 -0.00,0.00,0.00,0.00,0.00,0.00,247.44 -0.00,0.00,0.00,0.00,0.00,0.00,247.44 -0.00,0.00,0.00,0.00,0.00,0.00,247.43 -0.00,0.00,0.00,0.00,0.00,0.00,247.43 -0.00,0.00,0.00,0.00,0.00,0.00,247.43 -0.00,0.00,0.00,0.00,0.00,0.00,247.42 -0.00,0.00,0.00,0.00,0.00,0.00,247.42 -0.00,0.00,0.00,0.00,0.00,0.00,247.42 -0.00,0.00,0.00,0.00,0.00,0.00,247.43 -0.00,0.00,0.00,0.00,0.00,0.00,247.43 -0.00,0.00,0.00,0.00,0.00,0.00,247.43 -0.00,0.00,0.00,0.00,0.00,0.00,247.42 -0.00,0.00,0.00,0.00,0.00,0.00,247.42 -0.00,0.00,0.00,0.00,0.00,0.00,247.42 -0.00,0.00,0.00,0.00,0.00,0.00,247.41 -0.00,0.00,0.00,0.00,0.00,0.00,247.41 -0.00,0.00,0.00,0.00,0.00,0.00,247.41 -0.00,0.00,0.00,0.00,0.00,0.00,247.45 -0.00,0.00,0.00,0.00,0.00,0.00,247.45 -0.00,0.00,0.00,0.00,0.00,0.00,247.45 -0.00,0.00,0.00,0.00,0.00,0.00,247.44 -0.00,0.00,0.00,0.00,0.00,0.00,247.44 -0.00,0.00,0.00,0.00,0.00,0.00,247.44 -0.00,0.00,0.00,0.00,0.00,0.00,247.49 -0.00,0.00,0.00,0.00,0.00,0.00,247.49 -0.00,0.00,0.00,0.00,0.00,0.00,247.49 -0.00,0.00,0.00,0.00,0.00,0.00,247.52 -0.00,0.00,0.00,0.00,0.00,0.00,247.52 -0.00,0.00,0.00,0.00,0.00,0.00,247.52 -0.00,0.00,0.00,0.00,0.00,0.00,247.54 -0.00,0.00,0.00,0.00,0.00,0.00,247.54 -0.00,0.00,0.00,0.00,0.00,0.00,247.54 -0.00,0.00,0.00,0.00,0.00,0.00,247.49 -0.00,0.00,0.00,0.00,0.00,0.00,247.49 -0.00,0.00,0.00,0.00,0.00,0.00,247.49 -0.00,0.00,0.00,0.00,0.00,0.00,247.44 -0.00,0.00,0.00,0.00,0.00,0.00,247.44 -0.00,0.00,0.00,0.00,0.00,0.00,247.44 -0.00,0.00,0.00,0.00,0.00,0.00,247.45 -0.00,0.00,0.00,0.00,0.00,0.00,247.45 -0.00,0.00,0.00,0.00,0.00,0.00,247.45 -0.00,0.00,0.00,0.00,0.00,0.00,247.48 -0.00,0.00,0.00,0.00,0.00,0.00,247.48 -0.00,0.00,0.00,0.00,0.00,0.00,247.48 -0.00,0.00,0.00,0.00,0.00,0.00,247.47 -0.00,0.00,0.00,0.00,0.00,0.00,247.47 -0.00,0.00,0.00,0.00,0.00,0.00,247.47 -0.00,0.00,0.00,0.00,0.00,0.00,247.50 -0.00,0.00,0.00,0.00,0.00,0.00,247.50 -0.00,0.00,0.00,0.00,0.00,0.00,247.50 -0.00,0.00,0.00,0.00,0.00,0.00,247.55 -0.00,0.00,0.00,0.00,0.00,0.00,247.55 -0.00,0.00,0.00,0.00,0.00,0.00,247.55 -0.00,0.00,0.00,0.00,0.00,0.00,247.52 -0.00,0.00,0.00,0.00,0.00,0.00,247.52 -0.00,0.00,0.00,0.00,0.00,0.00,247.52 -0.00,0.00,0.00,0.00,0.00,0.00,247.46 -0.00,0.00,0.00,0.00,0.00,0.00,247.46 -0.00,0.00,0.00,0.00,0.00,0.00,247.46 -0.00,0.00,0.00,0.00,0.00,0.00,247.39 -0.00,0.00,0.00,0.00,0.00,0.00,247.39 -0.00,0.00,0.00,0.00,0.00,0.00,247.39 -0.00,0.00,0.00,0.00,0.00,0.00,247.35 -0.00,0.00,0.00,0.00,0.00,0.00,247.35 -0.00,0.00,0.00,0.00,0.00,0.00,247.35 -0.00,0.00,0.00,0.00,0.00,0.00,247.28 -0.00,0.00,0.00,0.00,0.00,0.00,247.28 -0.00,0.00,0.00,0.00,0.00,0.00,247.28 -0.00,0.00,0.00,0.00,0.00,0.00,247.24 --290.00,0.00,-290.00,-290.00,0.00,-290.00,247.24 --550.00,0.00,-550.00,-550.00,0.00,-550.00,247.24 --820.00,0.00,-820.00,-820.00,0.00,-820.00,247.26 --1100.00,0.00,-1100.00,-1100.00,0.00,-1100.00,247.26 --1370.00,0.00,-1370.00,-1370.00,0.00,-1370.00,247.27 --1660.00,0.00,-1660.00,-1660.00,0.00,-1660.00,247.27 --1930.00,-111.11,-1818.89,-1930.00,-148.15,-1781.85,247.27 --2250.00,-218.75,-2031.25,-2250.00,-187.50,-2062.50,247.43 --2540.00,-172.41,-2367.59,-2540.00,-34.48,-2505.52,247.43 --2810.00,-740.74,-2069.26,-2810.00,-185.19,-2624.81,247.43 --3080.00,-2296.30,-783.70,-3080.00,-444.44,-2635.56,247.49 --3370.00,-2724.14,-645.86,-3370.00,-1068.97,-2301.03,247.49 --3640.00,-1962.96,-1677.04,-3640.00,-1814.81,-1825.19,247.49 --3910.00,-1444.44,-2465.56,-3910.00,-1740.74,-2169.26,247.25 --4200.00,-2413.79,-1786.21,-4200.00,-931.03,-3268.97,247.25 --4480.00,-3785.71,-694.29,-4480.00,-1678.57,-2801.43,247.25 --4750.00,-3370.37,-1379.63,-4750.00,-2518.52,-2231.48,247.26 --5050.00,-1800.00,-3250.00,-5050.00,-2800.00,-2250.00,247.26 --5320.00,-2777.78,-2542.22,-5320.00,-3037.04,-2282.96,247.26 --5600.00,-4428.57,-1171.43,-5600.00,-3500.00,-2100.00,247.04 --5900.00,-5233.33,-666.67,-5900.00,-4233.33,-1666.67,247.04 --6180.00,-5035.71,-1144.29,-6180.00,-4285.71,-1894.29,247.10 --6480.00,-4700.00,-1780.00,-6480.00,-3600.00,-2880.00,247.10 --6750.00,-4555.56,-2194.44,-6750.00,-3444.44,-3305.56,247.10 --7020.00,-5037.04,-1982.96,-7020.00,-4222.22,-2797.78,247.13 --7320.00,-5900.00,-1420.00,-7320.00,-5800.00,-1520.00,247.13 --7600.00,-6214.29,-1385.71,-7600.00,-6142.86,-1457.14,247.13 --7870.00,-5703.70,-2166.30,-7870.00,-5185.19,-2684.81,247.07 --8170.00,-5733.33,-2436.67,-8170.00,-4266.67,-3903.33,247.07 --8440.00,-6518.52,-1921.48,-8440.00,-5703.70,-2736.30,247.07 --8720.00,-6892.86,-1827.14,-8720.00,-7357.14,-1362.86,247.17 --9020.00,-6833.33,-2186.67,-9020.00,-7433.33,-1586.67,247.17 --9300.00,-7178.57,-2121.43,-9300.00,-7035.71,-2264.29,247.17 --9580.00,-7750.00,-1830.00,-9580.00,-6535.71,-3044.29,247.20 --9880.00,-7900.00,-1980.00,-9880.00,-6600.00,-3280.00,247.20 --10160.00,-8321.43,-1838.57,-10160.00,-8107.14,-2052.86,247.21 --10440.00,-8678.57,-1761.43,-10440.00,-8892.86,-1547.14,247.21 --10720.00,-9000.00,-1720.00,-10720.00,-8928.57,-1791.43,247.21 --11000.00,-9285.71,-1714.29,-11000.00,-8678.57,-2321.43,247.25 --11300.00,-9466.67,-1833.33,-11300.00,-8566.67,-2733.33,247.25 --11580.00,-9750.00,-1830.00,-11580.00,-9321.43,-2258.57,247.25 --11860.00,-9964.29,-1895.71,-11860.00,-10000.00,-1860.00,247.31 --12160.00,-10300.00,-1860.00,-12160.00,-10266.67,-1893.33,247.31 --12440.00,-10642.86,-1797.14,-12440.00,-10000.00,-2440.00,247.31 --12720.00,-11035.71,-1684.29,-12720.00,-10071.43,-2648.57,247.30 --13020.00,-11233.33,-1786.67,-13020.00,-10266.67,-2753.33,247.30 --13300.00,-11464.29,-1835.71,-13300.00,-11000.00,-2300.00,247.30 --13580.00,-11642.86,-1937.14,-13580.00,-11285.71,-2294.29,247.25 --13880.00,-12100.00,-1780.00,-13880.00,-11600.00,-2280.00,247.25 --14160.00,-12428.57,-1731.43,-14160.00,-11642.86,-2517.14,247.18 --14460.00,-12400.00,-2060.00,-14460.00,-12066.67,-2393.33,247.18 --14740.00,-12714.29,-2025.71,-14740.00,-12392.86,-2347.14,247.18 --15020.00,-13000.00,-2020.00,-15020.00,-12821.43,-2198.57,247.12 --15320.00,-13500.00,-1820.00,-15320.00,-13133.33,-2186.67,247.12 --15600.00,-13821.43,-1778.57,-15600.00,-13107.14,-2492.86,247.12 --15880.00,-13928.57,-1951.43,-15880.00,-13357.14,-2522.86,247.07 --16180.00,-14266.67,-1913.33,-16180.00,-13733.33,-2446.67,247.07 --16460.00,-14750.00,-1710.00,-16460.00,-14214.29,-2245.71,247.07 --16740.00,-15142.86,-1597.14,-16740.00,-14714.29,-2025.71,247.07 --17040.00,-15533.33,-1506.67,-17040.00,-14933.33,-2106.67,247.07 --17320.00,-15678.57,-1641.43,-17320.00,-15071.43,-2248.57,247.07 --17600.00,-15678.57,-1921.43,-17600.00,-15214.29,-2385.71,246.98 --17900.00,-16033.33,-1866.67,-17900.00,-15800.00,-2100.00,246.98 --18180.00,-16464.29,-1715.71,-18180.00,-16214.29,-1965.71,246.97 --18480.00,-16700.00,-1780.00,-18480.00,-16400.00,-2080.00,246.97 --18760.00,-16750.00,-2010.00,-18760.00,-16250.00,-2510.00,246.97 --19040.00,-16928.57,-2111.43,-19040.00,-16428.57,-2611.43,246.97 --19340.00,-17133.33,-2206.67,-19340.00,-16833.33,-2506.67,246.97 --19620.00,-17500.00,-2120.00,-19620.00,-17214.29,-2405.71,246.97 --19900.00,-17964.29,-1935.71,-19900.00,-17428.57,-2471.43,247.00 --20200.00,-18166.67,-2033.33,-20200.00,-17500.00,-2700.00,247.00 --20480.00,-18214.29,-2265.71,-20480.00,-17714.29,-2765.71,247.00 --20760.00,-18642.86,-2117.14,-20760.00,-17928.57,-2831.43,247.08 --21060.00,-19133.33,-1926.67,-21060.00,-17933.33,-3126.67,247.08 --21340.00,-19321.43,-2018.57,-21340.00,-18142.86,-3197.14,247.11 --21640.00,-19533.33,-2106.67,-21640.00,-18866.67,-2773.33,247.11 --21930.00,-19827.59,-2102.41,-21930.00,-19655.17,-2274.83,247.11 --22260.00,-20242.42,-2017.58,-22037.18,-19757.58,-2279.60,247.07 --22560.00,-20366.67,-2193.33,-21737.18,-19466.67,-2270.51,247.07 --22840.00,-20535.71,-2304.29,-21457.18,-19321.43,-2135.75,247.07 --22961.67,-20821.43,-2140.24,-21177.18,-19250.00,-1927.18,246.93 --22661.67,-21433.33,-1228.33,-20877.18,-19066.67,-1810.51,246.93 --22371.67,-21551.72,-819.94,-20587.18,-18827.59,-1759.59,246.93 --22091.67,-20750.00,-1341.67,-20307.18,-18357.14,-1950.04,246.87 --21781.67,-20290.32,-1491.34,-19997.18,-17967.74,-2029.44,246.87 --21501.67,-20214.29,-1287.38,-19717.18,-17892.86,-1824.32,246.88 --21201.67,-20033.33,-1168.33,-19417.18,-17566.67,-1850.51,246.88 --20921.67,-19678.57,-1243.10,-19137.18,-17178.57,-1958.61,246.88 --20641.67,-19357.14,-1284.52,-18857.18,-16928.57,-1928.61,246.93 --20341.67,-19233.33,-1108.33,-18557.18,-16766.67,-1790.51,246.93 --20061.67,-18928.57,-1133.10,-18277.18,-16464.29,-1812.89,246.93 --19781.67,-18500.00,-1281.67,-17997.18,-16035.71,-1961.46,246.95 --19471.67,-18225.81,-1245.86,-17687.18,-15516.13,-2171.05,246.95 --19191.67,-18107.14,-1084.52,-17407.18,-15250.00,-2157.18,246.95 --18911.67,-17928.57,-983.10,-17127.18,-15285.71,-1841.46,246.94 --18611.67,-17600.00,-1011.67,-16827.18,-15366.67,-1460.51,246.94 --18321.67,-17379.31,-942.36,-16537.18,-14758.62,-1778.56,246.96 --18021.67,-16800.00,-1221.67,-16237.18,-14233.33,-2003.84,246.96 --17741.67,-16607.14,-1134.52,-15957.18,-14250.00,-1707.18,246.96 --17461.67,-16428.57,-1033.10,-15677.18,-14214.29,-1462.89,247.06 --17161.67,-16133.33,-1028.33,-15377.18,-14033.33,-1343.84,247.06 --16881.67,-15857.14,-1024.52,-15097.18,-13857.14,-1240.04,247.06 --16591.67,-15689.66,-902.01,-14807.18,-13275.86,-1531.32,247.06 --16291.67,-15433.33,-858.33,-14507.18,-13000.00,-1507.18,247.06 --16011.67,-15250.00,-761.67,-14227.18,-12928.57,-1298.61,247.06 --15731.67,-15178.57,-553.10,-13947.18,-12821.43,-1125.75,247.06 --15421.67,-14903.23,-518.44,-13637.18,-12677.42,-959.76,247.06 --15141.67,-14571.43,-570.24,-13357.18,-12321.43,-1035.75,247.08 --14831.67,-14032.26,-799.41,-13047.18,-12064.52,-982.66,247.08 --14551.67,-13678.57,-873.10,-12767.18,-11892.86,-874.32,247.08 --14261.67,-13517.24,-744.43,-12477.18,-11620.69,-856.49,247.10 --13961.67,-13300.00,-661.67,-12177.18,-11366.67,-810.51,247.10 --13671.67,-13068.97,-602.70,-11887.18,-10965.52,-921.66,247.10 --13391.67,-12714.29,-677.38,-11607.18,-10642.86,-964.32,247.18 --13091.67,-12466.67,-625.00,-11307.18,-10366.67,-940.51,247.18 --12811.67,-12250.00,-561.67,-11027.18,-10178.57,-848.61,247.18 --12531.67,-11678.57,-853.10,-10747.18,-9928.57,-818.61,247.17 --12231.67,-11400.00,-831.67,-10447.18,-9533.33,-913.84,247.17 --11951.67,-11250.00,-701.67,-10167.18,-9178.57,-988.61,247.25 --11661.67,-10965.52,-696.15,-9877.18,-8862.07,-1015.11,247.25 --11381.67,-10857.14,-524.52,-9597.18,-8285.71,-1311.46,247.25 --11101.67,-10642.86,-458.81,-9317.18,-8107.14,-1210.04,247.26 --10801.67,-10333.33,-468.33,-9017.18,-7900.00,-1117.18,247.26 --10531.67,-10000.00,-531.67,-8747.18,-7740.74,-1006.44,247.26 --10251.67,-9750.00,-501.67,-8467.18,-7535.71,-931.46,247.23 --9951.67,-9400.00,-551.67,-8167.18,-7133.33,-1033.84,247.23 --9671.67,-9178.57,-493.10,-7887.18,-6857.14,-1030.04,247.23 --9391.67,-8892.86,-498.81,-7607.18,-6571.43,-1035.75,247.33 --9091.67,-8600.00,-491.67,-7307.18,-6266.67,-1040.51,247.33 --8811.67,-8321.43,-490.24,-7027.18,-6071.43,-955.75,247.33 --8531.67,-8035.71,-495.95,-6747.18,-5892.86,-854.32,247.35 --8231.67,-7833.33,-398.33,-6447.18,-5666.67,-780.51,247.35 --7951.67,-7535.71,-415.95,-6167.18,-5285.71,-881.46,247.31 --7651.67,-7233.33,-418.33,-5867.18,-4933.33,-933.84,247.31 --7371.67,-6928.57,-443.10,-5587.18,-4678.57,-908.61,247.31 --7091.67,-6571.43,-520.24,-5307.18,-4357.14,-950.04,247.27 --6801.67,-6275.86,-525.80,-5017.18,-3965.52,-1051.66,247.27 --6521.67,-6107.14,-414.52,-4737.18,-3714.29,-1022.89,247.27 --6251.67,-5740.74,-510.93,-4467.18,-3444.44,-1022.73,247.24 --5951.67,-5500.00,-451.67,-4167.18,-3233.33,-933.84,247.24 --5681.67,-5259.26,-422.41,-3897.18,-2962.96,-934.22,247.24 --5401.67,-4964.29,-437.38,-3617.18,-2535.71,-1081.46,247.17 --5111.67,-4103.45,-1008.22,-3327.18,-1724.14,-1603.04,247.17 --4841.67,-3592.59,-1249.07,-3057.18,-1555.56,-1501.62,247.17 --4571.67,-3740.74,-830.93,-2787.18,-1703.70,-1083.47,247.17 --4281.67,-3862.07,-419.60,-2497.18,-1379.31,-1117.87,247.17 --4011.67,-3777.78,-233.89,-2227.18,-666.67,-1560.51,247.17 --3681.67,-3000.00,-681.67,-1897.18,181.82,-2079.00,247.08 --3391.67,-2068.97,-1322.70,-1607.18,-137.93,-1469.25,247.08 --3121.67,-1740.74,-1380.93,-1337.18,74.07,-1411.25,246.96 --2831.67,-1931.03,-900.63,-1047.18,413.79,-1460.97,246.96 --2551.67,-2071.43,-480.24,-767.18,-35.71,-731.46,246.96 --2281.67,-1074.07,-1207.59,-497.18,0.00,-497.18,246.92 --1991.67,-965.52,-1026.15,-207.18,0.00,-207.18,246.92 --1721.67,-444.44,-1277.22,0.00,0.00,0.00,246.92 --1461.67,538.46,-2000.13,0.00,0.00,0.00,247.06 --1171.67,-344.83,-826.84,0.00,0.00,0.00,247.06 --901.67,-296.30,-605.37,0.00,0.00,0.00,247.06 --631.67,629.63,-1261.30,0.00,0.00,0.00,247.21 --341.67,0.00,-341.67,0.00,0.00,0.00,247.21 --81.67,-76.92,-4.74,0.00,0.00,0.00,247.21 -0.00,0.00,0.00,0.00,0.00,0.00,247.35 -0.00,0.00,0.00,0.00,0.00,0.00,247.35 -0.00,0.00,0.00,0.00,0.00,0.00,247.35 -0.00,0.00,0.00,0.00,0.00,0.00,247.40 -0.00,0.00,0.00,0.00,0.00,0.00,247.40 -0.00,0.00,0.00,0.00,0.00,0.00,247.40 -0.00,0.00,0.00,0.00,0.00,0.00,247.51 -0.00,0.00,0.00,0.00,0.00,0.00,247.51 -0.00,0.00,0.00,0.00,0.00,0.00,247.51 -0.00,0.00,0.00,0.00,0.00,0.00,247.50 -0.00,0.00,0.00,0.00,0.00,0.00,247.50 -0.00,0.00,0.00,0.00,0.00,0.00,247.50 -0.00,0.00,0.00,0.00,0.00,0.00,247.54 -0.00,0.00,0.00,0.00,0.00,0.00,247.54 -0.00,0.00,0.00,0.00,0.00,0.00,247.54 -0.00,0.00,0.00,0.00,0.00,0.00,247.59 -0.00,0.00,0.00,0.00,0.00,0.00,247.59 -0.00,0.00,0.00,0.00,0.00,0.00,247.59 -0.00,0.00,0.00,0.00,0.00,0.00,247.58 -0.00,0.00,0.00,0.00,0.00,0.00,247.58 -0.00,0.00,0.00,0.00,0.00,0.00,247.58 -0.00,0.00,0.00,0.00,0.00,0.00,247.58 -0.00,0.00,0.00,0.00,0.00,0.00,247.58 -0.00,0.00,0.00,0.00,0.00,0.00,247.58 \ 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,0.00,182.88,205.54 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.54 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.65 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.65 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.65 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.52 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.52 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.38 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.38 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.38 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.32 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.32 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.32 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.30 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.30 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.30 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.32 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.32 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.32 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.44 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.44 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.44 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.59 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.59 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.59 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.59 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.59 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.59 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.62 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.62 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.52 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.52 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.52 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.43 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.43 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.43 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.52 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.52 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.52 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.51 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.51 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.51 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.53 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.53 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.53 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.60 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.60 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.60 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.72 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.72 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.78 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.78 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.78 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.82 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.82 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.82 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.80 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.80 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.80 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.71 +310.00,0.00,310.00,310.00,0.00,310.00,0.00,205.71,205.71 +590.00,0.00,590.00,590.00,0.00,590.00,0.00,205.71,205.71 +870.00,0.00,870.00,870.00,0.00,870.00,0.00,205.71,205.71 +1160.00,0.00,1160.00,1160.00,0.00,1160.00,0.00,205.71,205.71 +1480.00,0.00,1480.00,1480.00,0.00,1480.00,0.00,205.71,205.51 +1770.00,0.00,1770.00,1770.00,0.00,1770.00,0.00,205.71,205.51 +2050.00,178.57,1871.43,2050.00,178.57,1871.43,0.00,205.71,205.51 +2330.00,428.57,1901.43,2330.00,142.86,2187.14,0.00,205.71,205.61 +2620.00,241.38,2378.62,2620.00,137.93,2482.07,0.00,205.71,205.61 +2900.00,1285.71,1614.29,2900.00,214.29,2685.71,0.00,205.71,205.61 +3180.00,2714.29,465.71,3180.00,357.14,2822.86,0.00,205.71,205.85 +3480.00,2733.33,746.67,3480.00,1000.00,2480.00,0.00,205.71,205.85 +3750.00,1703.70,2046.30,3750.00,1259.26,2490.74,0.00,205.71,205.85 +4030.00,1107.14,2922.86,4030.00,1678.57,2351.43,0.00,205.71,205.98 +4320.00,1793.10,2526.90,4320.00,1551.72,2768.28,0.00,205.71,205.98 +4600.00,2214.29,2385.71,4600.00,1642.86,2957.14,0.00,205.71,205.98 +4870.00,2666.67,2203.33,4870.00,2000.00,2870.00,0.00,205.71,206.22 +5160.00,2896.55,2263.45,5160.00,2413.79,2746.21,0.00,205.71,206.22 +5440.00,3142.86,2297.14,5440.00,2928.57,2511.43,0.00,205.71,206.22 +5720.00,3321.43,2398.57,5720.00,3392.86,2327.14,0.00,205.71,206.41 +6010.00,3482.76,2527.24,6010.00,3344.83,2665.17,0.00,205.71,206.41 +6290.00,3821.43,2468.57,6290.00,3785.71,2504.29,0.00,205.71,206.78 +6590.00,4200.00,2390.00,6590.00,4066.67,2523.33,0.00,205.71,206.78 +6860.00,4444.44,2415.56,6860.00,4148.15,2711.85,0.00,205.71,206.78 +7130.00,4814.81,2315.19,7130.00,4592.59,2537.41,0.00,205.71,207.34 +7430.00,5066.67,2363.33,7430.00,5000.00,2430.00,0.00,205.71,207.34 +7710.00,5392.86,2317.14,7710.00,5392.86,2317.14,0.00,205.71,207.34 +7990.00,5714.29,2275.71,7990.00,5500.00,2490.00,0.00,205.71,207.97 +8290.00,5833.33,2456.67,8290.00,5666.67,2623.33,0.00,205.71,207.97 +8570.00,6214.29,2355.71,8570.00,5750.00,2820.00,0.00,205.71,207.97 +8840.00,6629.63,2210.37,8840.00,6222.22,2617.78,0.00,205.71,208.87 +9140.00,7000.00,2140.00,9140.00,6500.00,2640.00,0.00,205.71,208.87 +9420.00,7107.14,2312.86,9420.00,6821.43,2598.57,0.00,205.71,208.87 +9700.00,7500.00,2200.00,9700.00,7000.00,2700.00,0.00,205.71,210.42 +10000.00,7866.67,2133.33,10000.00,7266.67,2733.33,0.00,205.71,210.42 +10280.00,8000.00,2280.00,10280.00,7285.71,2994.29,0.00,205.71,212.37 +10580.00,7966.67,2613.33,10580.00,7933.33,2646.67,0.00,205.71,212.37 +10860.00,8500.00,2360.00,10860.00,8750.00,2110.00,0.00,205.71,212.37 +11140.00,8857.14,2282.86,11140.00,8678.57,2461.43,0.00,205.71,214.65 +11440.00,8866.67,2573.33,11440.00,8666.67,2773.33,0.00,205.71,214.65 +11710.00,9333.33,2376.67,11710.00,9037.04,2672.96,0.00,205.71,214.65 +11990.00,9678.57,2311.43,11990.00,9642.86,2347.14,0.00,205.71,217.49 +12290.00,9766.67,2523.33,12290.00,9400.00,2890.00,0.00,205.71,217.49 +12570.00,10285.71,2284.29,12570.00,9892.86,2677.14,0.00,205.71,217.49 +12850.00,11142.86,1707.14,12850.00,10714.29,2135.71,0.00,205.71,220.60 +13150.00,10733.33,2416.67,13150.00,10233.33,2916.67,0.00,205.71,220.60 +13420.00,10777.78,2642.22,13420.00,10888.89,2531.11,0.00,205.71,220.60 +13700.00,11678.57,2021.43,13700.00,11214.29,2485.71,0.00,205.71,224.09 +14000.00,11433.33,2566.67,14000.00,11100.00,2900.00,0.00,205.71,224.09 +14280.00,11857.14,2422.86,14280.00,11392.86,2887.14,0.00,205.71,228.18 +14580.00,12366.67,2213.33,14580.00,12000.00,2580.00,0.00,205.71,228.18 +14860.00,12571.43,2288.57,14860.00,12428.57,2431.43,0.00,205.71,228.18 +15140.00,13035.71,2104.29,15140.00,12714.29,2425.71,0.00,205.71,232.21 +15440.00,12900.00,2540.00,15440.00,12666.67,2773.33,0.00,205.71,232.21 +15720.00,13178.57,2541.43,15720.00,12750.00,2970.00,0.00,205.71,232.21 +16000.00,13785.71,2214.29,16000.00,13392.86,2607.14,0.00,205.71,235.67 +16300.00,13900.00,2400.00,16300.00,13466.67,2833.33,0.00,205.71,235.67 +16580.00,14250.00,2330.00,16580.00,13821.43,2758.57,0.00,205.71,235.67 +16860.00,13892.86,2967.14,16860.00,13857.14,3002.86,0.00,205.71,237.85 +17160.00,14600.00,2560.00,17160.00,14633.33,2526.67,0.00,205.71,237.85 +17440.00,15357.14,2082.86,17440.00,15035.71,2404.29,0.00,205.71,237.85 +17720.00,14892.86,2827.14,17720.00,14928.57,2791.43,0.00,205.71,239.14 +18020.00,15766.67,2253.33,18020.00,15400.00,2620.00,0.00,205.71,239.14 +18300.00,16392.86,1907.14,18300.00,15821.43,2478.57,0.00,205.71,238.66 +18600.00,15866.67,2733.33,18600.00,15533.33,3066.67,0.00,205.71,238.66 +18880.00,16000.00,2880.00,18880.00,16000.00,2880.00,0.00,205.71,238.66 +19150.00,17000.00,2150.00,19150.00,16592.59,2557.41,0.00,205.71,237.07 +19450.00,17166.67,2283.33,19450.00,16666.67,2783.33,0.00,205.71,237.07 +19730.00,17321.43,2408.57,19730.00,16642.86,3087.14,0.00,205.71,237.07 +20010.00,17964.29,2045.71,20010.00,17250.00,2760.00,0.00,205.71,234.77 +20310.00,18133.33,2176.67,20310.00,17733.33,2576.67,0.00,205.71,234.77 +20590.00,17892.86,2697.14,20590.00,17714.29,2875.71,0.00,205.71,234.77 +20870.00,18464.29,2405.71,20870.00,18321.43,2548.57,0.00,205.71,231.93 +21170.00,19166.67,2003.33,21170.00,18200.00,2970.00,0.00,205.71,231.93 +21510.00,19147.06,2362.94,21510.00,18764.71,2745.29,0.00,205.71,229.09 +21810.00,19066.67,2743.33,21810.00,18866.67,2943.33,0.00,205.71,229.09 +22090.00,19678.57,2411.43,22090.00,19142.86,2947.14,0.00,205.71,229.09 +22380.00,19517.24,2862.76,22380.00,19586.21,2793.79,0.00,205.71,226.17 +22680.00,20366.67,2313.33,22680.00,20033.33,2646.67,0.00,205.71,226.17 +22960.00,20642.86,2317.14,22960.00,20071.43,2888.57,0.00,205.71,226.17 +23240.00,21000.00,2240.00,23240.00,20107.14,3132.86,0.00,205.71,223.49 +23540.00,20900.00,2640.00,23075.45,20366.67,2708.78,0.00,205.71,223.49 +23555.94,20750.00,2805.94,22795.45,20607.14,2188.31,0.00,205.71,223.49 +23285.94,21444.44,1841.50,22525.45,20925.93,1599.52,0.00,205.71,220.30 +22985.94,21700.00,1285.94,22225.45,21166.67,1058.78,0.00,205.71,220.30 +22705.94,21321.43,1384.51,21945.45,20321.43,1624.02,0.00,205.71,217.14 +22405.94,21033.33,1372.61,21645.45,20300.00,1345.45,0.00,205.71,217.14 +22115.94,21172.41,943.53,21355.45,20137.93,1217.52,0.00,205.71,217.14 +21835.94,21214.29,621.66,21075.45,19892.86,1182.59,0.00,205.71,213.76 +21545.94,20862.07,683.87,20785.45,19655.17,1130.28,0.00,205.71,213.76 +21265.94,20392.86,873.09,20505.45,19142.86,1362.59,0.00,205.71,213.76 +20985.94,19857.14,1128.80,20225.45,19392.86,832.59,0.00,205.71,210.77 +20685.94,19566.67,1119.28,19925.45,19033.33,892.11,0.00,205.71,210.77 +20405.94,19571.43,834.51,19645.45,18678.57,966.88,0.00,205.71,210.77 +20125.94,19750.00,375.94,19365.45,17892.86,1472.59,0.00,205.71,208.63 +19825.94,19466.67,359.28,19065.45,18033.33,1032.11,0.00,205.71,208.63 +19545.94,18964.29,581.66,18785.45,17750.00,1035.45,0.00,205.71,208.63 +19265.94,18214.29,1051.66,18505.45,16964.29,1541.16,0.00,205.71,207.09 +18965.94,17866.67,1099.28,18205.45,17133.33,1072.11,0.00,205.71,207.09 +18695.94,17925.93,770.02,17935.45,17407.41,528.04,0.00,205.71,206.01 +18395.94,17533.33,862.61,17635.45,16466.67,1168.78,0.00,205.71,206.01 +18115.94,17250.00,865.94,17355.45,16178.57,1176.88,0.00,205.71,206.01 +17835.94,17107.14,728.80,17075.45,15678.57,1396.88,0.00,205.71,205.52 +17535.94,16466.67,1069.28,16775.45,14900.00,1875.45,0.00,205.71,205.52 +17255.94,16107.14,1148.80,16495.45,14321.43,2174.02,0.00,205.71,205.52 +16985.94,16148.15,837.80,16225.45,15111.11,1114.34,0.00,205.71,205.48 +16685.94,16200.00,485.94,15925.45,14966.67,958.78,0.00,205.71,205.48 +16405.94,15821.43,584.51,15645.45,14857.14,788.31,0.00,205.71,205.48 +16125.94,15357.14,768.80,15365.45,14714.29,651.16,0.00,205.71,205.64 +15825.94,15000.00,825.94,15065.45,13966.67,1098.78,0.00,205.71,205.64 +15545.94,14750.00,795.94,14785.45,13928.57,856.88,0.00,205.71,205.64 +15265.94,14714.29,551.66,14505.45,13500.00,1005.45,0.00,205.71,205.88 +14965.94,14400.00,565.94,14205.45,13300.00,905.45,0.00,205.71,205.88 +14685.94,13964.29,721.66,13925.45,13107.14,818.31,0.00,205.71,206.09 +14395.94,13896.55,499.39,13635.45,12758.62,876.83,0.00,205.71,206.09 +14125.94,13740.74,385.20,13365.45,12629.63,735.82,0.00,205.71,206.09 +13845.94,12750.00,1095.94,13085.45,11928.57,1156.88,0.00,205.71,206.12 +13545.94,12300.00,1245.94,12785.45,11633.33,1152.11,0.00,205.71,206.12 +13265.94,12428.57,837.37,12505.45,11571.43,934.02,0.00,205.71,206.12 +12985.94,12464.29,521.66,12225.45,11357.14,868.31,0.00,205.71,206.00 +12685.94,12266.67,419.28,11925.45,11200.00,725.45,0.00,205.71,206.00 +12415.94,12074.07,341.87,11655.45,11000.00,655.45,0.00,205.71,206.00 +12135.94,11821.43,314.51,11375.45,10464.29,911.16,0.00,205.71,206.22 +11835.94,11600.00,235.94,11075.45,10300.00,775.45,0.00,205.71,206.22 +11555.94,10964.29,591.66,10795.45,10142.86,652.59,0.00,205.71,206.22 +11275.94,10464.29,811.66,10515.45,9785.71,729.73,0.00,205.71,205.90 +10975.94,10566.67,409.28,10215.45,9500.00,715.45,0.00,205.71,205.90 +10695.94,10250.00,445.94,9935.45,8714.29,1221.16,0.00,205.71,205.86 +10395.94,9500.00,895.94,9635.45,8600.00,1035.45,0.00,205.71,205.86 +10115.94,9214.29,901.66,9355.45,8500.00,855.45,0.00,205.71,205.86 +9835.94,9142.86,693.09,9075.45,8285.71,789.73,0.00,205.71,205.84 +9535.94,8900.00,635.94,8775.45,8000.00,775.45,0.00,205.71,205.84 +9255.94,8642.86,613.09,8495.45,8071.43,424.02,0.00,205.71,205.84 +8975.94,8285.71,690.23,8215.45,7392.86,822.59,0.00,205.71,206.11 +8675.94,7800.00,875.94,7915.45,7033.33,882.11,0.00,205.71,206.11 +8395.94,7321.43,1074.51,7635.45,6607.14,1028.31,0.00,205.71,206.11 +8115.94,7178.57,937.37,7355.45,6357.14,998.31,0.00,205.71,206.48 +7815.94,7100.00,715.94,7055.45,6133.33,922.11,0.00,205.71,206.48 +7535.94,6642.86,893.09,6775.45,5500.00,1275.45,0.00,205.71,207.22 +7235.94,6333.33,902.61,6475.45,5433.33,1042.11,0.00,205.71,207.22 +6975.94,6192.31,783.64,6215.45,5115.38,1100.06,0.00,205.71,207.22 +6695.94,5928.57,767.37,5935.45,4964.29,971.16,0.00,205.71,207.64 +6395.94,5766.67,629.28,5635.45,4666.67,968.78,0.00,205.71,207.64 +6115.94,5607.14,508.80,5355.45,4357.14,998.31,0.00,205.71,207.64 +5795.94,5062.50,733.44,5035.45,4062.50,972.95,0.00,205.71,207.66 +5505.94,4448.28,1057.67,4745.45,3862.07,883.38,0.00,205.71,207.66 +5225.94,4285.71,940.23,4465.45,3714.29,751.16,0.00,205.71,207.66 +4945.94,4000.00,945.94,4185.45,3142.86,1042.59,0.00,205.71,208.36 +4655.94,3724.14,931.81,3895.45,2758.62,1136.83,0.00,205.71,208.36 +4375.94,3428.57,947.37,3615.45,2857.14,758.31,0.00,205.71,208.36 +4105.94,3222.22,883.72,3345.45,2296.30,1049.15,0.00,205.71,208.83 +3815.94,2724.14,1091.81,3055.45,1551.72,1503.72,0.00,205.71,208.83 +3535.94,2107.14,1428.80,2775.45,1607.14,1168.31,0.00,205.71,209.04 +3235.94,2333.33,902.61,2475.45,1866.67,608.78,0.00,205.71,209.04 +2965.94,1814.81,1151.13,2205.45,444.44,1761.00,0.00,205.71,209.04 +2685.94,1321.43,1364.51,1925.45,214.29,1711.16,0.00,205.71,209.83 +2385.94,100.00,2285.94,1625.45,1400.00,225.45,0.00,205.71,209.83 +2105.94,214.29,1891.66,1345.45,-71.43,1416.88,0.00,205.71,209.83 +1825.94,678.57,1147.37,1065.45,-500.00,1565.45,0.00,205.71,209.93 +1535.94,1103.45,432.49,775.45,68.97,706.48,0.00,205.71,209.93 +1255.94,-285.71,1541.66,495.45,0.00,495.45,0.00,205.71,209.93 +975.94,0.00,975.94,215.45,-35.71,251.16,0.00,205.71,210.43 +675.94,-100.00,775.94,0.00,0.00,0.00,0.00,205.71,210.43 +405.94,0.00,405.94,0.00,0.00,0.00,0.00,205.71,210.43 +125.94,0.00,125.94,0.00,0.00,0.00,0.00,205.71,210.91 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,210.91 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,210.91 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.09 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.09 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.17 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.17 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.17 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.50 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.50 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.50 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.79 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.79 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.79 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.99 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.99 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.99 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.04 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.04 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.04 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.32 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.32 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.68 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.68 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.68 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.45 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.45 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.45 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.36 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.36 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.36 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.47 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.47 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.47 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.61 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.61 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.61 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.51 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.51 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.51 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.68 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.68 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.62 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.62 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.62 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.75 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.75 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.75 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.56 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.56 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.56 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.49 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.49 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.49 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.10 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.10 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.10 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.62 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.62 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.65 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.65 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.65 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.73 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.73 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.73 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.77 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.77 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.77 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.85 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.85 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.85 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.90 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.90 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.90 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.18 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.18 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.18 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.21 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.21 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.06 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.06 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.06 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.13 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.13 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.13 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.23 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.23 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.23 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.26 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.26 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.26 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.26 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.26 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.26 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.03 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.03 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.03 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.21 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.21 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.03 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.03 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.03 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.22 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.22 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.22 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.57 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.57 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.57 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.35 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.35 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.35 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.13 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.13 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.13 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.91 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.91 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.91 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.17 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.17 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.17 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.36 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.36 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.50 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.50 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.50 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.76 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.76 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.76 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.69 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.69 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.69 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.79 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.79 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.79 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.85 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.85 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.85 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.68 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.68 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.47 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.47 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.47 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.40 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.40 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.40 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.50 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.50 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.50 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.34 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.34 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.34 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.38 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.38 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.38 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.89 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.89 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.89 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.93 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.93 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.09 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.09 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.09 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.03 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.03 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.03 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.44 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.44 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.44 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.65 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.65 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.65 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.87 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.87 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.87 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.75 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.75 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.80 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.80 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.80 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.58 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.58 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.58 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.72 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.72 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.72 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.77 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.77 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.77 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.42 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.42 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.42 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.60 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.60 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.60 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.42 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.42 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.05 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.05 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.05 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.72 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.72 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.72 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.73 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.73 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.73 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.50 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.50 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.50 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.23 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.23 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.23 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.47 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.47 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.19 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.19 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.19 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.06 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.06 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.06 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.79 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.79 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.79 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.94 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.94 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.94 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.63 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.63 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.63 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.41 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.41 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.41 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.27 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.27 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.27 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.19 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.19 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.46 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.46 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.46 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.62 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.62 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.62 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.47 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.47 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.47 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.42 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.42 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.42 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.10 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.10 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.10 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.06 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.06 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.06 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.00 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.00 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,210.84 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,210.84 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,210.84 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.02 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.02 +-290.00,0.00,-290.00,-290.00,0.00,-290.00,0.00,211.02,211.02 +-570.00,0.00,-570.00,-570.00,0.00,-570.00,0.00,211.02,211.01 +-860.00,0.00,-860.00,-860.00,0.00,-860.00,0.00,211.02,211.01 +-1140.00,0.00,-1140.00,-1140.00,0.00,-1140.00,0.00,211.02,211.01 +-1420.00,0.00,-1420.00,-1420.00,0.00,-1420.00,0.00,211.02,211.49 +-1720.00,0.00,-1720.00,-1720.00,0.00,-1720.00,0.00,211.02,211.49 +-2040.00,-125.00,-1915.00,-2040.00,-187.50,-1852.50,0.00,211.02,211.49 +-2320.00,-321.43,-1998.57,-2320.00,-392.86,-1927.14,0.00,211.02,211.80 +-2620.00,-600.00,-2020.00,-2620.00,-400.00,-2220.00,0.00,211.02,211.80 +-2900.00,-1821.43,-1078.57,-2900.00,-750.00,-2150.00,0.00,211.02,212.09 +-3200.00,-2266.67,-933.33,-3200.00,-1033.33,-2166.67,0.00,211.02,212.09 +-3470.00,-1407.41,-2062.59,-3470.00,-1148.15,-2321.85,0.00,211.02,212.09 +-3750.00,-1250.00,-2500.00,-3750.00,-1178.57,-2571.43,0.00,211.02,211.77 +-4050.00,-2433.33,-1616.67,-4050.00,-1300.00,-2750.00,0.00,211.02,211.77 +-4330.00,-3821.43,-508.57,-4330.00,-1357.14,-2972.86,0.00,211.02,211.77 +-4610.00,-3571.43,-1038.57,-4610.00,-1785.71,-2824.29,0.00,211.02,210.44 +-4910.00,-1766.67,-3143.33,-4910.00,-1833.33,-3076.67,0.00,211.02,210.44 +-5190.00,-1785.71,-3404.29,-5190.00,-2142.86,-3047.14,0.00,211.02,210.44 +-5470.00,-3750.00,-1720.00,-5470.00,-2607.14,-2862.86,0.00,211.02,210.58 +-5770.00,-3366.67,-2403.33,-5770.00,-2933.33,-2836.67,0.00,211.02,210.58 +-6050.00,-3285.71,-2764.29,-6050.00,-2892.86,-3157.14,0.00,211.02,210.58 +-6330.00,-4321.43,-2008.57,-6330.00,-3642.86,-2687.14,0.00,211.02,210.44 +-6640.00,-4645.16,-1994.84,-6640.00,-4193.55,-2446.45,0.00,211.02,210.44 +-6920.00,-4750.00,-2170.00,-6920.00,-4392.86,-2527.14,0.00,211.02,209.60 +-7220.00,-5133.33,-2086.67,-7220.00,-4733.33,-2486.67,0.00,211.02,209.60 +-7500.00,-5535.71,-1964.29,-7500.00,-5107.14,-2392.86,0.00,211.02,209.60 +-7780.00,-5785.71,-1994.29,-7780.00,-5357.14,-2422.86,0.00,211.02,208.87 +-8080.00,-6000.00,-2080.00,-8080.00,-5633.33,-2446.67,0.00,211.02,208.87 +-8360.00,-6250.00,-2110.00,-8360.00,-5928.57,-2431.43,0.00,211.02,208.87 +-8650.00,-6310.34,-2339.66,-8650.00,-6137.93,-2512.07,0.00,211.02,208.21 +-8950.00,-6700.00,-2250.00,-8950.00,-6566.67,-2383.33,0.00,211.02,208.21 +-9230.00,-7107.14,-2122.86,-9230.00,-6821.43,-2408.57,0.00,211.02,208.21 +-9520.00,-7344.83,-2175.17,-9520.00,-7137.93,-2382.07,0.00,211.02,207.09 +-9830.00,-7612.90,-2217.10,-9830.00,-7032.26,-2797.74,0.00,211.02,207.09 +-10120.00,-8034.48,-2085.52,-10120.00,-7241.38,-2878.62,0.00,211.02,206.52 +-10420.00,-8333.33,-2086.67,-10420.00,-7600.00,-2820.00,0.00,211.02,206.52 +-10710.00,-8551.72,-2158.28,-10710.00,-8241.38,-2468.62,0.00,211.02,206.52 +-10990.00,-8678.57,-2311.43,-10990.00,-8535.71,-2454.29,0.00,211.02,205.93 +-11300.00,-9032.26,-2267.74,-11300.00,-8967.74,-2332.26,0.00,211.02,205.93 +-11590.00,-9241.38,-2348.62,-11590.00,-9000.00,-2590.00,0.00,211.02,205.93 +-11880.00,-9482.76,-2397.24,-11880.00,-9551.72,-2328.28,0.00,211.02,205.66 +-12190.00,-10032.26,-2157.74,-12190.00,-10000.00,-2190.00,0.00,211.02,205.66 +-12480.00,-10034.48,-2445.52,-12480.00,-10034.48,-2445.52,0.00,211.02,205.39 +-12790.00,-10193.55,-2596.45,-12790.00,-10096.77,-2693.23,0.00,211.02,205.39 +-13080.00,-10793.10,-2286.90,-13080.00,-10551.72,-2528.28,0.00,211.02,205.39 +-13370.00,-11724.14,-1645.86,-13370.00,-10931.03,-2438.97,0.00,211.02,205.30 +-13670.00,-11866.67,-1803.33,-13670.00,-11166.67,-2503.33,0.00,211.02,205.30 +-13960.00,-12103.45,-1856.55,-13960.00,-11551.72,-2408.28,0.00,211.02,205.30 +-14250.00,-11931.03,-2318.97,-14250.00,-11586.21,-2663.79,0.00,211.02,205.64 +-14560.00,-11935.48,-2624.52,-14560.00,-12161.29,-2398.71,0.00,211.02,205.64 +-14850.00,-12793.10,-2056.90,-14850.00,-12689.66,-2160.34,0.00,211.02,206.32 +-15160.00,-13516.13,-1643.87,-15160.00,-12806.45,-2353.55,0.00,211.02,206.32 +-15450.00,-13586.21,-1863.79,-15450.00,-12896.55,-2553.45,0.00,211.02,206.32 +-15740.00,-13482.76,-2257.24,-15740.00,-13000.00,-2740.00,0.00,211.02,206.98 +-16050.00,-13967.74,-2082.26,-16050.00,-13322.58,-2727.42,0.00,211.02,206.98 +-16340.00,-13931.03,-2408.97,-16340.00,-13620.69,-2719.31,0.00,211.02,206.98 +-16630.00,-14068.97,-2561.03,-16630.00,-13724.14,-2905.86,0.00,211.02,207.81 +-16940.00,-14483.87,-2456.13,-16940.00,-14451.61,-2488.39,0.00,211.02,207.81 +-17230.00,-15275.86,-1954.14,-17230.00,-14758.62,-2471.38,0.00,211.02,207.81 +-17520.00,-15172.41,-2347.59,-17520.00,-14413.79,-3106.21,0.00,211.02,208.86 +-17830.00,-15322.58,-2507.42,-17830.00,-15096.77,-2733.23,0.00,211.02,208.86 +-18120.00,-16275.86,-1844.14,-18120.00,-14896.55,-3223.45,0.00,211.02,209.61 +-18420.00,-16733.33,-1686.67,-18420.00,-16133.33,-2286.67,0.00,211.02,209.61 +-18710.00,-16068.97,-2641.03,-18710.00,-15586.21,-3123.79,0.00,211.02,209.61 +-19000.00,-16172.41,-2827.59,-19000.00,-15724.14,-3275.86,0.00,211.02,209.76 +-19310.00,-17419.35,-1890.65,-19310.00,-16903.23,-2406.77,0.00,211.02,209.76 +-19590.00,-17464.29,-2125.71,-19590.00,-16714.29,-2875.71,0.00,211.02,209.76 +-19870.00,-17714.29,-2155.71,-19870.00,-17178.57,-2691.43,0.00,211.02,209.51 +-20180.00,-18548.39,-1631.61,-20180.00,-17129.03,-3050.97,0.00,211.02,209.51 +-20470.00,-17965.52,-2504.48,-20470.00,-17586.21,-2883.79,0.00,211.02,209.18 +-20780.00,-17903.23,-2876.77,-20780.00,-18000.00,-2780.00,0.00,211.02,209.18 +-21070.00,-19034.48,-2035.52,-21070.00,-18344.83,-2725.17,0.00,211.02,209.18 +-21360.00,-19206.90,-2153.10,-21360.00,-18275.86,-3084.14,0.00,211.02,208.80 +-21670.00,-19838.71,-1831.29,-21670.00,-18838.71,-2831.29,0.00,211.02,208.80 +-21960.00,-19517.24,-2442.76,-21960.00,-19000.00,-2960.00,0.00,211.02,208.80 +-22300.00,-19676.47,-2623.53,-22300.00,-19764.71,-2535.29,0.00,211.02,208.27 +-22610.00,-20677.42,-1932.58,-22610.00,-19419.35,-3190.65,0.00,211.02,208.27 +-22900.00,-21103.45,-1796.55,-22556.35,-20379.31,-2177.04,0.00,211.02,207.82 +-22713.41,-20935.48,-1777.93,-22246.35,-20580.65,-1665.71,0.00,211.02,207.82 +-22423.41,-20724.14,-1699.28,-21956.35,-20310.34,-1646.01,0.00,211.02,207.82 +-22133.41,-20413.79,-1719.62,-21666.35,-19896.55,-1769.80,0.00,211.02,207.51 +-21823.41,-20483.87,-1339.54,-21356.35,-20064.52,-1291.84,0.00,211.02,207.51 +-21533.41,-20758.62,-774.79,-21066.35,-19655.17,-1411.18,0.00,211.02,207.51 +-21243.41,-20517.24,-726.17,-20776.35,-19448.28,-1328.08,0.00,211.02,207.16 +-20933.41,-20064.52,-868.90,-20466.35,-19258.06,-1208.29,0.00,211.02,207.16 +-20643.41,-19862.07,-781.35,-20176.35,-18724.14,-1452.21,0.00,211.02,206.56 +-20333.41,-19903.23,-430.19,-19866.35,-18580.65,-1285.71,0.00,211.02,206.56 +-20043.41,-19655.17,-388.24,-19576.35,-18068.97,-1507.39,0.00,211.02,206.56 +-19753.41,-19482.76,-270.66,-19286.35,-18137.93,-1148.42,0.00,211.02,205.80 +-19443.41,-19032.26,-411.16,-18976.35,-17741.94,-1234.42,0.00,211.02,205.80 +-19153.41,-18655.17,-498.24,-18686.35,-17931.03,-755.32,0.00,211.02,205.80 +-18863.41,-18379.31,-484.10,-18396.35,-16896.55,-1499.80,0.00,211.02,205.28 +-18553.41,-18322.58,-230.83,-18086.35,-17161.29,-925.06,0.00,211.02,205.28 +-18263.41,-18137.93,-125.48,-17796.35,-16586.21,-1210.15,0.00,211.02,205.05 +-17953.41,-17741.94,-211.48,-17486.35,-16193.55,-1292.80,0.00,211.02,205.05 +-17663.41,-17344.83,-318.59,-17196.35,-16724.14,-472.21,0.00,211.02,205.05 +-17373.41,-16965.52,-407.90,-16906.35,-15931.03,-975.32,0.00,211.02,205.64 +-17073.41,-16300.00,-773.41,-16606.35,-15500.00,-1106.35,0.00,211.02,205.64 +-16793.41,-16142.86,-650.56,-16326.35,-15750.00,-576.35,0.00,211.02,205.64 +-16503.41,-16448.28,-55.14,-16036.35,-15586.21,-450.15,0.00,211.02,207.86 +-16193.41,-16387.10,193.68,-15726.35,-14290.32,-1436.03,0.00,211.02,207.86 +-15913.41,-15714.29,-199.13,-15446.35,-14500.00,-946.35,0.00,211.02,207.86 +-15623.41,-14689.66,-933.76,-15156.35,-14034.48,-1121.87,0.00,211.02,211.09 +-15313.41,-14419.35,-894.06,-14846.35,-13612.90,-1233.45,0.00,211.02,211.09 +-15023.41,-14620.69,-402.72,-14556.35,-13827.59,-728.77,0.00,211.02,216.81 +-14723.41,-14633.33,-90.08,-14256.35,-13033.33,-1223.02,0.00,211.02,216.81 +-14433.41,-13551.72,-881.69,-13966.35,-12620.69,-1345.66,0.00,211.02,216.81 +-14143.41,-12931.03,-1212.38,-13676.35,-12689.66,-986.70,0.00,211.02,223.93 +-13843.41,-13066.67,-776.75,-13376.35,-12266.67,-1109.69,0.00,211.02,223.93 +-13563.41,-13107.14,-456.27,-13096.35,-11785.71,-1310.64,0.00,211.02,223.93 +-13273.41,-13103.45,-169.97,-12806.35,-12275.86,-530.49,0.00,211.02,230.09 +-12963.41,-12677.42,-286.00,-12496.35,-11225.81,-1270.55,0.00,211.02,230.09 +-12673.41,-12379.31,-294.10,-12206.35,-11206.90,-999.46,0.00,211.02,236.08 +-12373.41,-12200.00,-173.41,-11906.35,-11166.67,-739.69,0.00,211.02,236.08 +-12083.41,-11965.52,-117.90,-11616.35,-10724.14,-892.21,0.00,211.02,236.08 +-11793.41,-11586.21,-207.21,-11326.35,-10931.03,-395.32,0.00,211.02,241.72 +-11483.41,-11193.55,-289.87,-11016.35,-10451.61,-564.74,0.00,211.02,241.72 +-11193.41,-11000.00,-193.41,-10726.35,-9689.66,-1036.70,0.00,211.02,241.72 +-10903.41,-10793.10,-110.31,-10436.35,-9448.28,-988.08,0.00,211.02,245.35 +-10603.41,-10533.33,-70.08,-10136.35,-9166.67,-969.69,0.00,211.02,245.35 +-10313.41,-10103.45,-209.97,-9846.35,-8827.59,-1018.77,0.00,211.02,245.35 +-10023.41,-9586.21,-437.21,-9556.35,-8896.55,-659.80,0.00,211.02,247.55 +-9713.41,-9516.13,-197.29,-9246.35,-8580.65,-665.71,0.00,211.02,247.55 +-9423.41,-9586.21,162.79,-8956.35,-8068.97,-887.39,0.00,211.02,248.43 +-9113.41,-9419.35,305.94,-8646.35,-8258.06,-388.29,0.00,211.02,248.43 +-8833.41,-9000.00,166.59,-8366.35,-7357.14,-1009.21,0.00,211.02,248.43 +-8553.41,-8428.57,-124.84,-8086.35,-7428.57,-657.78,0.00,211.02,247.29 +-8253.41,-7800.00,-453.41,-7786.35,-7266.67,-519.69,0.00,211.02,247.29 +-7973.41,-7250.00,-723.41,-7506.35,-6571.43,-934.92,0.00,211.02,247.29 +-7693.41,-7107.14,-586.27,-7226.35,-6428.57,-797.78,0.00,211.02,245.34 +-7383.41,-7064.52,-318.90,-6916.35,-6322.58,-593.77,0.00,211.02,245.34 +-7093.41,-6827.59,-265.83,-6626.35,-6103.45,-522.90,0.00,211.02,243.00 +-6793.41,-6666.67,-126.75,-6326.35,-5833.33,-493.02,0.00,211.02,243.00 +-6503.41,-6310.34,-193.07,-6036.35,-5620.69,-415.66,0.00,211.02,243.00 +-6213.41,-5310.34,-903.07,-5746.35,-5482.76,-263.59,0.00,211.02,240.32 +-5903.41,-5032.26,-871.16,-5436.35,-5161.29,-275.06,0.00,211.02,240.32 +-5613.41,-5620.69,7.28,-5146.35,-4241.38,-904.97,0.00,211.02,240.32 +-5333.41,-5678.57,345.16,-4866.35,-3750.00,-1116.35,0.00,211.02,236.89 +-5033.41,-4833.33,-200.08,-4566.35,-4066.67,-499.69,0.00,211.02,236.89 +-4743.41,-3827.59,-915.83,-4276.35,-4000.00,-276.35,0.00,211.02,236.89 +-4463.41,-3250.00,-1213.41,-3996.35,-2642.86,-1353.50,0.00,211.02,233.90 +-4153.41,-3193.55,-959.87,-3686.35,-2193.55,-1492.80,0.00,211.02,233.90 +-3873.41,-3428.57,-444.84,-3406.35,-2857.14,-549.21,0.00,211.02,231.19 +-3513.41,-2861.11,-652.30,-3046.35,-2111.11,-935.24,0.00,211.02,231.19 +-3233.41,-2142.86,-1090.56,-2766.35,-1000.00,-1766.35,0.00,211.02,231.19 +-2943.41,-1724.14,-1219.28,-2476.35,-1724.14,-752.21,0.00,211.02,228.81 +-2643.41,-1133.33,-1510.08,-2176.35,-2300.00,123.65,0.00,211.02,228.81 +-2363.41,-1464.29,-899.13,-1896.35,-1535.71,-360.64,0.00,211.02,228.81 +-2083.41,-1821.43,-261.99,-1616.35,-214.29,-1402.07,0.00,211.02,226.50 +-1773.41,-483.87,-1289.54,-1306.35,64.52,-1370.87,0.00,211.02,226.50 +-1493.41,428.57,-1921.99,-1026.35,142.86,-1169.21,0.00,211.02,224.75 +-1193.41,266.67,-1460.08,-726.35,133.33,-859.69,0.00,211.02,224.75 +-913.41,-107.14,-806.27,-446.35,0.00,-446.35,0.00,211.02,224.75 +-633.41,428.57,-1061.99,-166.35,0.00,-166.35,0.00,211.02,223.08 +-333.41,-66.67,-266.75,0.00,0.00,0.00,0.00,211.02,223.08 +-63.41,0.00,-63.41,0.00,0.00,0.00,0.00,211.02,223.08 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,221.67 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,221.67 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,221.67 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,220.72 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,220.72 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,220.72 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,219.90 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,219.90 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,219.90 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,219.23 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,219.23 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,218.67 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,218.67 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,218.67 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,218.03 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,218.03 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,218.03 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.73 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.73 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.73 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.36 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.36 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.36 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.25 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.25 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.25 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.91 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.91 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.91 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.72 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.72 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.72 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.57 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.57 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.76 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.76 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.76 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.71 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.71 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.71 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.54 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.54 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.54 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.45 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.45 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.45 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.57 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.57 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.57 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.61 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.61 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.61 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.73 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.73 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.91 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.91 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.91 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.03 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.03 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.03 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.00 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.00 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.00 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.81 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.81 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.81 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.95 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.95 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.95 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.05 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.05 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.68 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.68 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.68 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.75 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.75 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.75 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.82 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.82 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.82 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.94 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.94 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.94 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.11 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.11 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.11 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.03 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.03 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.11 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.11 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.11 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.88 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.88 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.88 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.80 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.80 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.80 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.98 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.98 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.98 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.00 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.00 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.00 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.02 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.02 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.02 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.90 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.90 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.10 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.10 +0.00,0.00,0.00,0.00,0.00,0.00,207.44,200.31,202.81 +0.00,0.00,0.00,0.00,0.00,0.00,213.05,200.31,202.89 +0.00,0.00,0.00,0.00,0.00,0.00,213.52,200.31,202.89 +0.00,0.00,0.00,0.00,0.00,0.00,213.94,200.31,202.89 +0.00,0.00,0.00,0.00,0.00,0.00,213.82,200.31,202.88 +0.00,0.00,0.00,0.00,0.00,0.00,214.27,200.31,202.88 +0.00,0.00,0.00,0.00,0.00,0.00,214.71,200.31,202.88 +0.00,0.00,0.00,0.00,0.00,0.00,215.63,200.31,202.89 +0.00,0.00,0.00,0.00,0.00,0.00,216.08,200.31,202.89 +0.00,0.00,0.00,0.00,0.00,0.00,216.52,200.31,202.89 +0.00,0.00,0.00,0.00,0.00,0.00,221.52,200.31,202.96 +0.00,0.00,0.00,0.00,0.00,0.00,221.99,200.31,202.96 +0.00,0.00,0.00,0.00,0.00,0.00,222.42,200.31,202.96 +0.00,0.00,0.00,0.00,0.00,0.00,218.38,200.31,202.89 +0.00,0.00,0.00,0.00,0.00,0.00,218.84,200.31,202.89 +0.00,0.00,0.00,0.00,0.00,0.00,219.26,200.31,202.89 +0.00,0.00,0.00,0.00,0.00,0.00,216.01,200.31,202.83 +0.00,0.00,0.00,0.00,0.00,0.00,216.48,200.31,202.83 +0.00,0.00,0.00,0.00,0.00,0.00,216.89,200.31,202.83 +0.00,0.00,0.00,0.00,0.00,0.00,217.52,200.31,202.84 +0.00,0.00,0.00,0.00,0.00,0.00,217.97,200.31,202.84 +0.00,0.00,0.00,0.00,0.00,0.00,218.40,200.31,202.84 +0.00,0.00,0.00,0.00,0.00,0.00,220.66,200.31,202.87 +0.00,0.00,0.00,0.00,0.00,0.00,221.11,200.31,202.87 +0.00,0.00,0.00,0.00,0.00,0.00,221.53,200.31,202.87 +0.00,0.00,0.00,0.00,0.00,0.00,222.98,200.31,202.88 +0.00,0.00,0.00,0.00,0.00,0.00,223.43,200.31,202.88 +0.00,0.00,0.00,0.00,0.00,0.00,223.87,200.31,202.88 +0.00,0.00,0.00,0.00,0.00,0.00,226.66,200.31,202.92 +0.00,0.00,0.00,0.00,0.00,0.00,227.12,200.31,202.92 +0.00,0.00,0.00,0.00,0.00,0.00,227.56,200.31,202.92 +0.00,0.00,0.00,0.00,0.00,0.00,228.18,200.31,202.92 +0.00,0.00,0.00,0.00,0.00,0.00,228.64,200.31,202.92 +0.00,0.00,0.00,0.00,0.00,0.00,229.08,200.31,202.92 +0.00,0.00,0.00,0.00,0.00,0.00,227.62,200.31,202.89 +0.00,0.00,0.00,0.00,0.00,0.00,228.07,200.31,202.89 +0.00,0.00,0.00,0.00,0.00,0.00,228.51,200.31,202.89 +0.00,0.00,0.00,0.00,0.00,0.00,234.07,200.31,202.97 +0.00,0.00,0.00,0.00,0.00,0.00,234.54,200.31,202.97 +0.00,0.00,0.00,0.00,0.00,0.00,234.98,200.31,202.97 +0.00,0.00,0.00,0.00,0.00,0.00,240.05,200.31,203.05 +0.00,0.00,0.00,0.00,0.00,0.00,240.54,200.31,203.05 +0.00,0.00,0.00,0.00,0.00,0.00,241.00,200.31,203.05 +0.00,0.00,0.00,0.00,0.00,0.00,240.78,200.31,203.03 +0.00,0.00,0.00,0.00,0.00,0.00,241.26,200.31,203.03 +0.00,0.00,0.00,0.00,0.00,0.00,241.71,200.31,203.03 +0.00,0.00,0.00,0.00,0.00,0.00,241.47,200.31,203.02 +0.00,0.00,0.00,0.00,0.00,0.00,241.95,200.31,203.02 +0.00,0.00,0.00,0.00,0.00,0.00,242.41,200.31,203.02 +0.00,0.00,0.00,0.00,0.00,0.00,236.77,200.31,202.93 +0.00,0.00,0.00,0.00,0.00,0.00,237.23,200.31,202.93 +0.00,0.00,0.00,0.00,0.00,0.00,237.66,200.31,202.93 +0.00,0.00,0.00,0.00,0.00,0.00,235.48,200.31,202.89 +0.00,0.00,0.00,0.00,0.00,0.00,235.95,200.31,202.89 +0.00,0.00,0.00,0.00,0.00,0.00,246.18,200.31,203.04 +0.00,0.00,0.00,0.00,0.00,0.00,246.66,200.31,203.04 +0.00,0.00,0.00,0.00,0.00,0.00,247.13,200.31,203.04 +0.00,0.00,0.00,0.00,0.00,0.00,245.38,200.31,203.01 +0.00,0.00,0.00,0.00,0.00,0.00,245.85,200.31,203.01 +0.00,0.00,0.00,0.00,0.00,0.00,246.30,200.31,203.01 +0.00,0.00,0.00,0.00,0.00,0.00,242.87,200.31,202.94 +0.00,0.00,0.00,0.00,0.00,0.00,243.33,200.31,202.94 +0.00,0.00,0.00,0.00,0.00,0.00,243.76,200.31,202.94 +0.00,0.00,0.00,0.00,0.00,0.00,236.40,200.31,202.82 +300.00,0.00,300.00,300.00,0.00,300.00,0.00,202.82,202.82 +560.00,0.00,560.00,560.00,0.00,560.00,0.00,202.82,202.82 +830.00,0.00,830.00,830.00,0.00,830.00,0.00,202.82,202.89 +1110.00,0.00,1110.00,1110.00,0.00,1110.00,0.00,202.82,202.89 +1380.00,0.00,1380.00,1380.00,0.00,1380.00,0.00,202.82,202.89 +1650.00,0.00,1650.00,1650.00,0.00,1650.00,0.00,202.82,203.00 +1940.00,137.93,1802.07,1940.00,172.41,1767.59,0.00,202.82,203.00 +2210.00,222.22,1987.78,2210.00,407.41,1802.59,0.00,202.82,203.00 +2470.00,38.46,2431.54,2470.00,192.31,2277.69,0.00,202.82,203.09 +2760.00,241.38,2518.62,2760.00,172.41,2587.59,0.00,202.82,203.09 +3030.00,1222.22,1807.78,3030.00,703.70,2326.30,0.00,202.82,203.09 +3290.00,2615.38,674.62,3290.00,1230.77,2059.23,0.00,202.82,202.99 +3580.00,2517.24,1062.76,3580.00,1448.28,2131.72,0.00,202.82,202.99 +3850.00,851.85,2998.15,3850.00,1444.44,2405.56,0.00,202.82,202.99 +4120.00,629.63,3490.37,4120.00,1888.89,2231.11,0.00,202.82,202.85 +4410.00,2724.14,1685.86,4410.00,1655.17,2754.83,0.00,202.82,202.85 +4680.00,2222.22,2457.78,4680.00,1925.93,2754.07,0.00,202.82,202.85 +4950.00,2333.33,2616.67,4950.00,2222.22,2727.78,0.00,202.82,202.67 +5240.00,2965.52,2274.48,5240.00,2758.62,2481.38,0.00,202.82,202.67 +5510.00,3185.19,2324.81,5510.00,3000.00,2510.00,0.00,202.82,202.67 +5770.00,3230.77,2539.23,5770.00,3269.23,2500.77,0.00,202.82,202.58 +6050.00,3464.29,2585.71,6050.00,3500.00,2550.00,0.00,202.82,202.58 +6310.00,3884.62,2425.38,6310.00,4000.00,2310.00,0.00,202.82,202.58 +6580.00,4148.15,2431.85,6580.00,4074.07,2505.93,0.00,202.82,202.57 +6870.00,4344.83,2525.17,6870.00,4275.86,2594.14,0.00,202.82,202.57 +7130.00,4653.85,2476.15,7130.00,4615.38,2514.62,0.00,202.82,202.57 +7400.00,4777.78,2622.22,7400.00,4925.93,2474.07,0.00,202.82,202.79 +7680.00,5250.00,2430.00,7680.00,5035.71,2644.29,0.00,202.82,202.79 +7940.00,5653.85,2286.15,7940.00,5269.23,2670.77,0.00,202.82,202.79 +8200.00,6000.00,2200.00,8200.00,5576.92,2623.08,0.00,202.82,203.19 +8480.00,6428.57,2051.43,8480.00,5928.57,2551.43,0.00,202.82,203.19 +8750.00,6555.56,2194.44,8750.00,6518.52,2231.48,0.00,202.82,203.19 +9020.00,6777.78,2242.22,9020.00,6740.74,2279.26,0.00,202.82,203.77 +9310.00,7103.45,2206.55,9310.00,7034.48,2275.52,0.00,202.82,203.77 +9580.00,7259.26,2320.74,9580.00,6962.96,2617.04,199.53,202.82,204.74 +9920.00,7382.35,2537.65,9920.00,7382.35,2537.65,199.94,202.82,204.74 +10190.00,7777.78,2412.22,10190.00,8037.04,2152.96,200.27,202.82,204.74 +10460.00,8037.04,2422.96,10460.00,8444.44,2015.56,286.60,202.82,206.10 +10750.00,8172.41,2577.59,10750.00,8448.28,2301.72,287.20,202.82,206.10 +11010.00,8423.08,2586.92,11010.00,8538.46,2471.54,287.74,202.82,206.10 +11280.00,8814.81,2465.19,11280.00,9148.15,2131.85,377.09,202.82,207.51 +11570.00,8931.03,2638.97,11570.00,9379.31,2190.69,377.95,202.82,207.51 +11840.00,8888.89,2951.11,11840.00,9555.56,2284.44,378.75,202.82,207.51 +12110.00,9222.22,2887.78,12110.00,9888.89,2221.11,481.92,202.82,209.13 +12400.00,9655.17,2744.83,12400.00,10275.86,2124.14,483.07,202.82,209.13 +12670.00,10000.00,2670.00,12670.00,10703.70,1966.30,484.14,202.82,209.13 +12940.00,10296.30,2643.70,12940.00,11037.04,1902.96,624.92,202.82,211.34 +13230.00,10241.38,2988.62,13230.00,11344.83,1885.17,626.48,202.82,211.34 +13500.00,10370.37,3129.63,13500.00,11444.44,2055.56,627.93,202.82,211.34 +13770.00,10925.93,2844.07,13770.00,11925.93,1844.07,777.06,202.82,213.68 +14060.00,11310.34,2749.66,14060.00,12103.45,1956.55,779.04,202.82,213.68 +14330.00,11222.22,3107.78,14330.00,12444.44,1885.56,780.89,202.82,213.68 +14600.00,11666.67,2933.33,14600.00,12814.81,1785.19,940.41,202.82,216.18 +14890.00,11827.59,3062.41,14890.00,12931.03,1958.97,942.85,202.82,216.18 +15160.00,11481.48,3678.52,15160.00,12925.93,2234.07,1097.52,202.82,218.59 +15450.00,12000.00,3450.00,15450.00,13896.55,1553.45,1100.40,202.82,218.59 +15730.00,12714.29,3015.71,15730.00,14357.14,1372.86,1103.18,202.82,218.59 +16000.00,12444.44,3555.56,16000.00,14037.04,1962.96,1212.61,202.82,220.28 +16290.00,12586.21,3703.79,16290.00,14931.03,1358.97,1215.80,202.82,220.28 +16560.00,13777.78,2782.22,16560.00,15555.56,1004.44,1218.77,202.82,220.28 +16830.00,13629.63,3200.37,16830.00,15407.41,1422.59,1292.03,202.82,221.39 +17120.00,13862.07,3257.93,17120.00,15862.07,1257.93,1295.43,202.82,221.39 +17390.00,13888.89,3501.11,17390.00,15888.89,1501.11,1298.58,202.82,221.39 +17660.00,13814.81,3845.19,17660.00,16148.15,1511.85,1314.62,202.82,221.59 +17960.00,14200.00,3760.00,17960.00,16333.33,1626.67,1318.17,202.82,221.59 +18230.00,15074.07,3155.93,18230.00,16925.93,1304.07,1321.36,202.82,221.59 +18500.00,15518.52,2981.48,18500.00,16925.93,1574.07,1262.94,202.82,220.62 +18800.00,15000.00,3800.00,18800.00,17300.00,1500.00,1266.30,202.82,220.62 +19070.00,15296.30,3773.70,19070.00,17444.44,1625.56,1269.33,202.82,220.62 +19340.00,15962.96,3377.04,19340.00,17814.81,1525.19,1152.17,202.82,218.72 +19640.00,16266.67,3373.33,19640.00,18000.00,1640.00,1155.18,202.82,218.72 +19910.00,16518.52,3391.48,19910.00,18481.48,1428.52,1157.88,202.82,218.72 +20190.00,16464.29,3725.71,20190.00,18535.71,1654.29,1018.65,202.82,216.47 +20480.00,16931.03,3548.97,20480.00,18793.10,1686.90,1021.14,202.82,216.47 +20760.00,17607.14,3152.86,20760.00,18464.29,2295.71,809.89,202.82,213.09 +21050.00,18103.45,2946.55,21050.00,19517.24,1532.76,811.77,202.82,213.09 +21330.00,17642.86,3687.14,21330.00,19607.14,1722.86,813.58,202.82,213.09 +21610.00,18357.14,3252.86,21610.00,20000.00,1610.00,569.44,202.82,209.19 +21910.00,18766.67,3143.33,21910.00,19600.00,2310.00,570.65,202.82,209.19 +22180.00,19555.56,2624.44,22180.00,19925.93,2254.07,571.73,202.82,209.19 +22460.00,19357.14,3102.86,22460.00,19892.86,2567.14,330.83,202.82,205.36 +22750.00,19103.45,3646.55,22750.00,20413.79,2336.21,331.29,202.82,205.36 +23030.00,20035.71,2994.29,23030.00,20500.00,2530.00,331.74,202.82,205.36 +23310.00,20500.00,2810.00,23253.08,21071.43,2181.65,61.58,202.82,201.08 +23610.00,20566.67,3043.33,22953.08,20933.33,2019.74,-110.09,202.82,201.08 +23836.72,21535.71,2301.01,22673.08,20964.29,1708.79,-110.40,202.82,201.08 +23556.72,21607.14,1949.58,22393.08,21250.00,1143.08,-367.65,202.82,197.01 +23256.72,21733.33,1523.39,22093.08,20866.67,1226.41,-368.75,202.82,197.01 +22976.72,22250.00,726.72,21813.08,19892.86,1920.22,-596.12,202.82,193.43 +22676.72,22566.67,110.06,21513.08,19833.33,1679.74,-597.90,202.82,193.43 +22396.72,21928.57,468.15,21233.08,20214.29,1018.79,-599.56,202.82,193.43 +22116.72,21142.86,973.86,20953.08,19642.86,1310.22,-803.11,202.82,190.23 +21816.72,21066.67,750.06,20653.08,18800.00,1853.08,-805.49,202.82,190.23 +21536.72,21500.00,36.72,20373.08,18678.57,1694.50,-807.71,202.82,190.23 +21256.72,21464.29,-207.56,20093.08,19107.14,985.93,-967.13,202.82,187.75 +20956.72,20733.33,223.39,19793.08,17800.00,1993.08,-969.97,202.82,187.75 +20676.72,20428.57,248.15,19513.08,17000.00,2513.08,-972.63,202.82,187.75 +20396.72,20500.00,-103.28,19233.08,17785.71,1447.36,-1079.31,202.82,186.10 +20096.72,20333.33,-236.61,18933.08,17433.33,1499.74,-1082.47,202.82,186.10 +19816.72,19928.57,-111.85,18653.08,16321.43,2331.65,-1085.42,202.82,186.10 +19536.72,19428.57,108.15,18373.08,16214.29,2158.79,-1127.67,202.82,185.48 +19246.72,19206.90,39.83,18083.08,16137.93,1945.14,-1130.84,202.82,185.48 +18976.72,18518.52,458.20,17813.08,15370.37,2442.71,-1112.52,202.82,185.81 +18686.72,18413.79,272.93,17523.08,15448.28,2074.80,-1115.63,202.82,185.81 +18406.72,19035.71,-628.99,17243.08,15392.86,1850.22,-1118.63,202.82,185.81 +18136.72,18629.63,-492.91,16973.08,15074.07,1899.00,-1036.61,202.82,187.16 +17796.72,17558.82,237.90,16633.08,14794.12,1838.96,-1039.97,202.82,187.16 +17526.72,16925.93,600.80,16363.08,14259.26,2103.82,-1042.63,202.82,187.16 +17246.72,17107.14,139.58,16083.08,14392.86,1690.22,-926.50,202.82,189.04 +16956.72,17655.17,-698.45,15793.08,14379.31,1413.77,-929.01,202.82,189.04 +16676.72,17500.00,-823.28,15513.08,13714.29,1798.79,-931.44,202.82,189.04 +16406.72,16666.67,-259.94,15243.08,13518.52,1724.56,-766.71,202.82,191.68 +16106.72,15700.00,406.72,14943.08,13766.67,1176.41,-768.81,202.82,191.68 +15826.72,15500.00,326.72,14663.08,13178.57,1484.50,-770.77,202.82,191.68 +15546.72,15357.14,189.58,14383.08,12285.71,2097.36,-586.62,202.82,194.63 +15256.72,14862.07,394.65,14093.08,12448.28,1644.80,-588.12,202.82,194.63 +14986.72,14629.63,357.09,13823.08,12777.78,1045.30,-589.51,202.82,194.63 +14716.72,14518.52,198.20,13553.08,12111.11,1441.96,-385.37,202.82,197.88 +14426.72,14172.41,254.31,13263.08,11758.62,1504.45,-386.28,202.82,197.88 +14156.72,13703.70,453.02,12993.08,11925.93,1067.15,-173.38,202.82,201.27 +13866.72,13310.34,556.38,12703.08,11862.07,841.01,-173.66,202.82,201.27 +13596.72,13037.04,559.69,12433.08,11629.63,803.45,-173.93,202.82,201.27 +13326.72,12814.81,511.91,12163.08,11074.07,1089.00,28.01,202.82,204.47 +13036.72,12517.24,519.48,11873.08,10586.21,1286.87,104.08,202.82,204.47 +12756.72,12000.00,756.72,11593.08,10535.71,1057.36,104.37,202.82,204.47 +12486.72,11629.63,857.09,11323.08,10370.37,952.71,275.30,202.82,207.17 +12196.72,11448.28,748.45,11033.08,10172.41,860.66,276.10,202.82,207.17 +11926.72,11148.15,778.57,10763.08,10111.11,651.96,276.84,202.82,207.17 +11656.72,10740.74,915.98,10493.08,9740.74,752.33,426.30,202.82,209.52 +11366.72,10379.31,987.41,10203.08,9862.07,341.01,427.53,202.82,209.52 +11096.72,10111.11,985.61,9933.08,9481.48,451.59,428.67,202.82,209.52 +10826.72,9814.81,1011.91,9663.08,8629.63,1033.45,557.53,202.82,211.55 +10536.72,9689.66,847.07,9373.08,9034.48,338.59,559.13,202.82,211.55 +10266.72,9407.41,859.31,9103.08,8481.48,621.59,560.61,202.82,211.55 +9996.72,9000.00,996.72,8833.08,8296.30,536.78,657.50,202.82,213.06 +9706.72,8758.62,948.10,8543.08,8206.90,336.18,659.37,202.82,213.06 +9436.72,8703.70,733.02,8273.08,7740.74,532.33,661.11,202.82,213.06 +9166.72,8444.44,722.28,8003.08,7703.70,299.37,723.72,202.82,214.02 +8886.72,8000.00,886.72,7723.08,7357.14,365.93,725.70,202.82,214.02 +8616.72,7555.56,1061.17,7453.08,6851.85,601.22,727.60,202.82,214.02 +8346.72,6592.59,1754.13,7183.08,6962.96,220.11,769.31,202.82,214.65 +8066.72,6428.57,1638.15,6903.08,7000.00,-96.92,771.40,202.82,214.65 +7796.72,6407.41,1389.31,6633.08,6518.52,114.56,773.41,202.82,214.65 +7536.72,6000.00,1536.72,6373.08,6115.38,257.69,791.83,202.82,214.91 +7246.72,5689.66,1557.07,6083.08,5517.24,565.83,794.04,202.82,214.91 +6976.72,5518.52,1458.20,5813.08,5370.37,442.71,774.39,202.82,214.57 +6686.72,5517.24,1169.48,5523.08,5379.31,143.77,776.53,202.82,214.57 +6416.72,5000.00,1416.72,5253.08,5296.30,-43.22,778.53,202.82,214.57 +6146.72,4222.22,1924.50,4983.08,4925.93,57.15,778.51,202.82,214.54 +5856.72,4551.72,1305.00,4693.08,4827.59,-134.51,780.65,202.82,214.54 +5576.72,4857.14,719.58,4413.08,4428.57,-15.50,782.71,202.82,214.54 +5306.72,4037.04,1269.69,4143.08,3962.96,180.11,783.74,202.82,214.52 +5026.72,3321.43,1705.29,3863.08,3607.14,255.93,785.81,202.82,214.52 +4756.72,2962.96,1793.76,3593.08,3148.15,444.93,787.80,202.82,214.52 +4486.72,3111.11,1375.61,3323.08,3000.00,323.08,779.91,202.82,214.36 +4196.72,2724.14,1472.58,3033.08,2689.66,343.42,782.01,202.82,214.36 +3926.72,1666.67,2260.06,2763.08,2296.30,466.78,783.98,202.82,214.36 +3656.72,629.63,3027.09,2493.08,2000.00,493.08,759.86,202.82,213.95 +3376.72,1678.57,1698.15,2213.08,1678.57,534.50,761.82,202.82,213.95 +3116.72,1461.54,1655.18,1953.08,1576.92,376.15,763.65,202.82,213.95 +2856.72,153.85,2702.88,1693.08,461.54,1231.54,754.83,202.82,213.78 +2576.72,250.00,2326.72,1413.08,-142.86,1555.93,756.77,202.82,213.78 +2306.72,296.30,2010.43,1143.08,629.63,513.45,758.63,202.82,213.78 +2036.72,-259.26,2295.98,873.08,259.26,613.82,754.33,202.82,213.69 +1746.72,-448.28,2195.00,583.08,34.48,548.59,756.32,202.82,213.69 +1476.72,37.04,1439.69,313.08,0.00,313.08,758.17,202.82,213.69 +1216.72,0.00,1216.72,53.08,-38.46,91.54,751.14,202.82,213.55 +926.72,0.00,926.72,0.00,0.00,0.00,753.10,202.82,213.55 +666.72,0.00,666.72,0.00,0.00,0.00,754.85,202.82,213.55 +396.72,0.00,396.72,0.00,0.00,0.00,748.79,202.82,213.42 +106.72,0.00,106.72,0.00,0.00,0.00,750.73,202.82,213.42 +0.00,0.00,0.00,0.00,0.00,0.00,752.53,202.82,213.42 +0.00,0.00,0.00,0.00,0.00,0.00,743.89,202.82,213.26 +0.00,0.00,0.00,0.00,0.00,0.00,745.80,202.82,213.26 +0.00,0.00,0.00,0.00,0.00,0.00,747.51,202.82,213.26 +0.00,0.00,0.00,0.00,0.00,0.00,740.56,202.82,213.12 +0.00,0.00,0.00,0.00,0.00,0.00,742.44,202.82,213.12 +0.00,0.00,0.00,0.00,0.00,0.00,744.13,202.82,213.12 +0.00,0.00,0.00,0.00,0.00,0.00,736.58,202.82,212.97 +0.00,0.00,0.00,0.00,0.00,0.00,738.69,202.82,212.97 +0.00,0.00,0.00,0.00,0.00,0.00,731.15,202.82,212.83 +0.00,0.00,0.00,0.00,0.00,0.00,732.92,202.82,212.83 +0.00,0.00,0.00,0.00,0.00,0.00,734.62,202.82,212.83 +0.00,0.00,0.00,0.00,0.00,0.00,726.35,202.82,212.67 +0.00,0.00,0.00,0.00,0.00,0.00,728.09,202.82,212.67 +0.00,0.00,0.00,0.00,0.00,0.00,729.70,202.82,212.67 +0.00,0.00,0.00,0.00,0.00,0.00,726.14,202.82,212.59 +0.00,0.00,0.00,0.00,0.00,0.00,727.86,202.82,212.59 +0.00,0.00,0.00,0.00,0.00,0.00,729.52,202.82,212.59 +0.00,0.00,0.00,0.00,0.00,0.00,729.23,202.82,212.56 +0.00,0.00,0.00,0.00,0.00,0.00,730.95,202.82,212.56 +0.00,0.00,0.00,0.00,0.00,0.00,732.54,202.82,212.56 +0.00,0.00,0.00,0.00,0.00,0.00,735.69,202.82,212.58 +0.00,0.00,0.00,0.00,0.00,0.00,737.41,202.82,212.58 +0.00,0.00,0.00,0.00,0.00,0.00,739.07,202.82,212.58 +0.00,0.00,0.00,0.00,0.00,0.00,728.45,202.82,212.39 +0.00,0.00,0.00,0.00,0.00,0.00,730.20,202.82,212.39 +0.00,0.00,0.00,0.00,0.00,0.00,731.83,202.82,212.39 +0.00,0.00,0.00,0.00,0.00,0.00,722.68,202.82,212.22 +0.00,0.00,0.00,0.00,0.00,0.00,724.34,202.82,212.22 +0.00,0.00,0.00,0.00,0.00,0.00,725.94,202.82,212.22 +0.00,0.00,0.00,0.00,0.00,0.00,726.79,202.82,212.20 +0.00,0.00,0.00,0.00,0.00,0.00,728.44,202.82,212.20 +0.00,0.00,0.00,0.00,0.00,0.00,730.04,202.82,212.20 +0.00,0.00,0.00,0.00,0.00,0.00,716.60,202.82,211.97 +0.00,0.00,0.00,0.00,0.00,0.00,718.27,202.82,211.97 +0.00,0.00,0.00,0.00,0.00,0.00,719.77,202.82,211.97 +0.00,0.00,0.00,0.00,0.00,0.00,718.81,202.82,211.93 +0.00,0.00,0.00,0.00,0.00,0.00,720.42,202.82,211.93 +0.00,0.00,0.00,0.00,0.00,0.00,721.97,202.82,211.93 +0.00,0.00,0.00,0.00,0.00,0.00,725.04,202.82,211.95 +0.00,0.00,0.00,0.00,0.00,0.00,726.65,202.82,211.95 +0.00,0.00,0.00,0.00,0.00,0.00,728.15,202.82,211.95 +0.00,0.00,0.00,0.00,0.00,0.00,730.89,202.82,211.97 +0.00,0.00,0.00,0.00,0.00,0.00,732.57,202.82,211.97 +0.00,0.00,0.00,0.00,0.00,0.00,734.12,202.82,211.97 +0.00,0.00,0.00,0.00,0.00,0.00,731.67,202.82,211.91 +0.00,0.00,0.00,0.00,0.00,0.00,733.27,202.82,211.91 +0.00,0.00,0.00,0.00,0.00,0.00,734.82,202.82,211.91 +0.00,0.00,0.00,0.00,0.00,0.00,736.53,202.82,211.91 +0.00,0.00,0.00,0.00,0.00,0.00,738.14,202.82,211.91 +0.00,0.00,0.00,0.00,0.00,0.00,739.63,202.82,211.91 +0.00,0.00,0.00,0.00,0.00,0.00,738.30,202.82,211.87 +0.00,0.00,0.00,0.00,0.00,0.00,739.89,202.82,211.87 +0.00,0.00,0.00,0.00,0.00,0.00,741.43,202.82,211.87 +0.00,0.00,0.00,0.00,0.00,0.00,739.05,202.82,211.81 +0.00,0.00,0.00,0.00,0.00,0.00,740.64,202.82,211.81 +0.00,0.00,0.00,0.00,0.00,0.00,742.17,202.82,211.81 +0.00,0.00,0.00,0.00,0.00,0.00,745.34,202.82,211.83 +0.00,0.00,0.00,0.00,0.00,0.00,746.93,202.82,211.83 +0.00,0.00,0.00,0.00,0.00,0.00,754.65,202.82,211.93 +0.00,0.00,0.00,0.00,0.00,0.00,756.31,202.82,211.93 +0.00,0.00,0.00,0.00,0.00,0.00,757.80,202.82,211.93 +0.00,0.00,0.00,0.00,0.00,0.00,755.74,202.82,211.88 +0.00,0.00,0.00,0.00,0.00,0.00,757.34,202.82,211.88 +0.00,0.00,0.00,0.00,0.00,0.00,758.88,202.82,211.88 +0.00,0.00,0.00,0.00,0.00,0.00,752.91,202.82,211.76 +0.00,0.00,0.00,0.00,0.00,0.00,754.54,202.82,211.76 +0.00,0.00,0.00,0.00,0.00,0.00,756.06,202.82,211.76 +0.00,0.00,0.00,0.00,0.00,0.00,761.13,202.82,211.81 +0.00,0.00,0.00,0.00,0.00,0.00,762.72,202.82,211.81 +0.00,0.00,0.00,0.00,0.00,0.00,764.19,202.82,211.81 +0.00,0.00,0.00,0.00,0.00,0.00,766.63,202.82,211.83 +0.00,0.00,0.00,0.00,0.00,0.00,768.28,202.82,211.83 +0.00,0.00,0.00,0.00,0.00,0.00,769.81,202.82,211.83 +0.00,0.00,0.00,0.00,0.00,0.00,758.28,202.82,211.62 +0.00,0.00,0.00,0.00,0.00,0.00,759.83,202.82,211.62 +0.00,0.00,0.00,0.00,0.00,0.00,761.33,202.82,211.62 +0.00,0.00,0.00,0.00,0.00,0.00,765.11,202.82,211.66 +0.00,0.00,0.00,0.00,0.00,0.00,766.72,202.82,211.66 +0.00,0.00,0.00,0.00,0.00,0.00,768.23,202.82,211.66 +0.00,0.00,0.00,0.00,0.00,0.00,770.16,202.82,211.67 +0.00,0.00,0.00,0.00,0.00,0.00,771.72,202.82,211.67 +0.00,0.00,0.00,0.00,0.00,0.00,773.51,202.82,211.67 +0.00,0.00,0.00,0.00,0.00,0.00,776.33,202.82,211.69 +0.00,0.00,0.00,0.00,0.00,0.00,777.89,202.82,211.69 +0.00,0.00,0.00,0.00,0.00,0.00,779.35,202.82,211.69 +0.00,0.00,0.00,0.00,0.00,0.00,769.77,202.82,211.51 +0.00,0.00,0.00,0.00,0.00,0.00,771.30,202.82,211.51 +0.00,0.00,0.00,0.00,0.00,0.00,772.73,202.82,211.51 +0.00,0.00,0.00,0.00,0.00,0.00,771.01,202.82,211.46 +0.00,0.00,0.00,0.00,0.00,0.00,772.58,202.82,211.46 +0.00,0.00,0.00,0.00,0.00,0.00,774.00,202.82,211.46 +0.00,0.00,0.00,0.00,0.00,0.00,773.48,202.82,211.43 +0.00,0.00,0.00,0.00,0.00,0.00,775.00,202.82,211.43 +0.00,0.00,0.00,0.00,0.00,0.00,776.41,202.82,211.43 +0.00,0.00,0.00,0.00,0.00,0.00,776.84,202.82,211.41 +0.00,0.00,0.00,0.00,0.00,0.00,778.41,202.82,211.41 +0.00,0.00,0.00,0.00,0.00,0.00,779.87,202.82,211.41 +0.00,0.00,0.00,0.00,0.00,0.00,793.10,202.82,211.60 +0.00,0.00,0.00,0.00,0.00,0.00,794.64,202.82,211.60 +0.00,0.00,0.00,0.00,0.00,0.00,803.07,202.82,211.71 +0.00,0.00,0.00,0.00,0.00,0.00,804.63,202.82,211.71 +0.00,0.00,0.00,0.00,0.00,0.00,806.15,202.82,211.71 +0.00,0.00,0.00,0.00,0.00,0.00,809.89,202.82,211.75 +0.00,0.00,0.00,0.00,0.00,0.00,811.46,202.82,211.75 +0.00,0.00,0.00,0.00,0.00,0.00,812.93,202.82,211.75 +0.00,0.00,0.00,0.00,0.00,0.00,817.16,202.82,211.79 +0.00,0.00,0.00,0.00,0.00,0.00,818.80,202.82,211.79 +0.00,0.00,0.00,0.00,0.00,0.00,820.27,202.82,211.79 +0.00,0.00,0.00,0.00,0.00,0.00,809.02,202.82,211.59 +0.00,0.00,0.00,0.00,0.00,0.00,810.57,202.82,211.59 +0.00,0.00,0.00,0.00,0.00,0.00,812.00,202.82,211.59 +0.00,0.00,0.00,0.00,0.00,0.00,806.60,202.82,211.48 +0.00,0.00,0.00,0.00,0.00,0.00,808.13,202.82,211.48 +0.00,0.00,0.00,0.00,0.00,0.00,809.55,202.82,211.48 +0.00,0.00,0.00,0.00,0.00,0.00,815.33,202.82,211.55 +0.00,0.00,0.00,0.00,0.00,0.00,816.87,202.82,211.55 +0.00,0.00,0.00,0.00,0.00,0.00,818.36,202.82,211.55 +0.00,0.00,0.00,0.00,0.00,0.00,819.01,202.82,211.54 +0.00,0.00,0.00,0.00,0.00,0.00,820.60,202.82,211.54 +0.00,0.00,0.00,0.00,0.00,0.00,822.03,202.82,211.54 +0.00,0.00,0.00,0.00,0.00,0.00,822.42,202.82,211.52 +0.00,0.00,0.00,0.00,0.00,0.00,823.96,202.82,211.52 +0.00,0.00,0.00,0.00,0.00,0.00,825.38,202.82,211.52 +0.00,0.00,0.00,0.00,0.00,0.00,828.10,202.82,211.54 +0.00,0.00,0.00,0.00,0.00,0.00,829.64,202.82,211.54 +0.00,0.00,0.00,0.00,0.00,0.00,831.07,202.82,211.54 +0.00,0.00,0.00,0.00,0.00,0.00,839.37,202.82,211.65 +0.00,0.00,0.00,0.00,0.00,0.00,840.93,202.82,211.65 +0.00,0.00,0.00,0.00,0.00,0.00,842.43,202.82,211.65 +0.00,0.00,0.00,0.00,0.00,0.00,851.52,202.82,211.77 +0.00,0.00,0.00,0.00,0.00,0.00,853.10,202.82,211.77 +0.00,0.00,0.00,0.00,0.00,0.00,854.56,202.82,211.77 +0.00,0.00,0.00,0.00,0.00,0.00,855.09,202.82,211.75 +0.00,0.00,0.00,0.00,0.00,0.00,856.73,202.82,211.75 +0.00,0.00,0.00,0.00,0.00,0.00,858.25,202.82,211.75 +0.00,0.00,0.00,0.00,0.00,0.00,851.58,202.82,211.62 +0.00,0.00,0.00,0.00,0.00,0.00,853.14,202.82,211.62 +0.00,0.00,0.00,0.00,0.00,0.00,854.63,202.82,211.62 +0.00,0.00,0.00,0.00,0.00,0.00,856.92,202.82,211.64 +0.00,0.00,0.00,0.00,0.00,0.00,858.47,202.82,211.64 +0.00,0.00,0.00,0.00,0.00,0.00,859.92,202.82,211.64 +0.00,0.00,0.00,0.00,0.00,0.00,852.34,202.82,211.49 +0.00,0.00,0.00,0.00,0.00,0.00,853.87,202.82,211.49 +0.00,0.00,0.00,0.00,0.00,0.00,855.34,202.82,211.49 +0.00,0.00,0.00,0.00,0.00,0.00,848.15,202.82,211.36 +0.00,0.00,0.00,0.00,0.00,0.00,849.66,202.82,211.36 +0.00,0.00,0.00,0.00,0.00,0.00,851.06,202.82,211.36 +0.00,0.00,0.00,0.00,0.00,0.00,857.49,202.82,211.44 +0.00,0.00,0.00,0.00,0.00,0.00,858.95,202.82,211.44 +0.00,0.00,0.00,0.00,0.00,0.00,860.42,202.82,211.44 +0.00,0.00,0.00,0.00,0.00,0.00,852.11,202.82,211.28 +0.00,0.00,0.00,0.00,0.00,0.00,853.60,202.82,211.28 +0.00,0.00,0.00,0.00,0.00,0.00,854.99,202.82,211.28 +0.00,0.00,0.00,0.00,0.00,0.00,857.50,202.82,211.30 +0.00,0.00,0.00,0.00,0.00,0.00,859.00,202.82,211.30 +0.00,0.00,0.00,0.00,0.00,0.00,860.71,202.82,211.30 +0.00,0.00,0.00,0.00,0.00,0.00,860.20,202.82,211.27 +0.00,0.00,0.00,0.00,0.00,0.00,861.69,202.82,211.27 +0.00,0.00,0.00,0.00,0.00,0.00,865.46,202.82,211.31 +0.00,0.00,0.00,0.00,0.00,0.00,866.96,202.82,211.31 +0.00,0.00,0.00,0.00,0.00,0.00,868.35,202.82,211.31 +0.00,0.00,0.00,0.00,0.00,0.00,866.15,202.82,211.25 +0.00,0.00,0.00,0.00,0.00,0.00,867.69,202.82,211.25 +0.00,0.00,0.00,0.00,0.00,0.00,869.07,202.82,211.25 +0.00,0.00,0.00,0.00,0.00,0.00,864.37,202.82,211.15 +0.00,0.00,0.00,0.00,0.00,0.00,865.84,202.82,211.15 +0.00,0.00,0.00,0.00,0.00,0.00,867.26,202.82,211.15 +0.00,0.00,0.00,0.00,0.00,0.00,873.10,202.82,211.22 +0.00,0.00,0.00,0.00,0.00,0.00,874.58,202.82,211.22 +0.00,0.00,0.00,0.00,0.00,0.00,876.01,202.82,211.22 +0.00,0.00,0.00,0.00,0.00,0.00,878.60,202.82,211.24 +0.00,0.00,0.00,0.00,0.00,0.00,880.08,202.82,211.24 +0.00,0.00,0.00,0.00,0.00,0.00,881.51,202.82,211.24 +0.00,0.00,0.00,0.00,0.00,0.00,880.15,202.82,211.20 +0.00,0.00,0.00,0.00,0.00,0.00,881.63,202.82,211.20 +0.00,0.00,0.00,0.00,0.00,0.00,883.05,202.82,211.20 +0.00,0.00,0.00,0.00,0.00,0.00,879.51,202.82,211.12 +0.00,0.00,0.00,0.00,0.00,0.00,880.97,202.82,211.12 +0.00,0.00,0.00,0.00,0.00,0.00,882.38,202.82,211.12 +0.00,0.00,0.00,0.00,0.00,0.00,884.13,202.82,211.13 +0.00,0.00,0.00,0.00,0.00,0.00,885.60,202.82,211.13 +0.00,0.00,0.00,0.00,0.00,0.00,886.96,202.82,211.13 +0.00,0.00,0.00,0.00,0.00,0.00,888.64,202.82,211.13 +0.00,0.00,0.00,0.00,0.00,0.00,890.15,202.82,211.13 +0.00,0.00,0.00,0.00,0.00,0.00,891.57,202.82,211.13 +0.00,0.00,0.00,0.00,0.00,0.00,887.23,202.82,211.04 +0.00,0.00,0.00,0.00,0.00,0.00,888.68,202.82,211.04 +0.00,0.00,0.00,0.00,0.00,0.00,890.03,202.82,211.04 +0.00,0.00,0.00,0.00,0.00,0.00,893.90,202.82,211.08 +0.00,0.00,0.00,0.00,0.00,0.00,895.41,202.82,211.08 +0.00,0.00,0.00,0.00,0.00,0.00,896.76,202.82,211.08 +0.00,0.00,0.00,0.00,0.00,0.00,903.00,202.82,211.16 +0.00,0.00,0.00,0.00,0.00,0.00,904.47,202.82,211.16 +0.00,0.00,0.00,0.00,0.00,0.00,905.83,202.82,211.16 +0.00,0.00,0.00,0.00,0.00,0.00,916.75,202.82,211.31 +0.00,0.00,0.00,0.00,0.00,0.00,918.24,202.82,211.31 +0.00,0.00,0.00,0.00,0.00,0.00,919.63,202.82,211.31 +0.00,0.00,0.00,0.00,0.00,0.00,915.93,202.82,211.23 +0.00,0.00,0.00,0.00,0.00,0.00,917.41,202.82,211.23 +0.00,0.00,0.00,0.00,0.00,0.00,918.79,202.82,211.23 +0.00,0.00,0.00,0.00,0.00,0.00,922.57,202.82,211.26 +0.00,0.00,0.00,0.00,0.00,0.00,924.06,202.82,211.26 +0.00,0.00,0.00,0.00,0.00,0.00,925.45,202.82,211.26 +0.00,0.00,0.00,0.00,0.00,0.00,925.71,202.82,211.25 +0.00,0.00,0.00,0.00,0.00,0.00,927.19,202.82,211.25 +0.00,0.00,0.00,0.00,0.00,0.00,928.57,202.82,211.25 +0.00,0.00,0.00,0.00,0.00,0.00,931.68,202.82,211.27 +0.00,0.00,0.00,0.00,0.00,0.00,933.17,202.82,211.27 +0.00,0.00,0.00,0.00,0.00,0.00,934.61,202.82,211.27 +0.00,0.00,0.00,0.00,0.00,0.00,939.13,202.82,211.32 +0.00,0.00,0.00,0.00,0.00,0.00,940.63,202.82,211.32 +0.00,0.00,0.00,0.00,0.00,0.00,942.08,202.82,211.32 +0.00,0.00,0.00,0.00,0.00,0.00,944.01,202.82,211.33 +0.00,0.00,0.00,0.00,0.00,0.00,945.56,202.82,211.33 +0.00,0.00,0.00,0.00,0.00,0.00,946.96,202.82,211.33 +0.00,0.00,0.00,0.00,0.00,0.00,958.43,202.82,211.49 +0.00,0.00,0.00,0.00,0.00,0.00,959.96,202.82,211.49 +0.00,0.00,0.00,0.00,0.00,0.00,961.38,202.82,211.49 +0.00,0.00,0.00,0.00,0.00,0.00,962.93,202.82,211.49 +0.00,0.00,0.00,0.00,0.00,0.00,964.46,202.82,211.49 +0.00,0.00,0.00,0.00,0.00,0.00,965.88,202.82,211.49 +0.00,0.00,0.00,0.00,0.00,0.00,959.81,202.82,211.37 +0.00,0.00,0.00,0.00,0.00,0.00,961.31,202.82,211.37 +0.00,0.00,0.00,0.00,0.00,0.00,962.71,202.82,211.37 +0.00,0.00,0.00,0.00,0.00,0.00,967.95,202.82,211.43 +0.00,0.00,0.00,0.00,0.00,0.00,969.47,202.82,211.43 +0.00,0.00,0.00,0.00,0.00,0.00,970.88,202.82,211.43 +0.00,0.00,0.00,0.00,0.00,0.00,967.48,202.82,211.36 +0.00,0.00,0.00,0.00,0.00,0.00,968.98,202.82,211.36 +0.00,0.00,0.00,0.00,0.00,0.00,970.19,202.82,211.35 +0.00,0.00,0.00,0.00,0.00,0.00,971.75,202.82,211.35 +0.00,0.00,0.00,0.00,0.00,0.00,973.20,202.82,211.35 +0.00,0.00,0.00,0.00,0.00,0.00,976.89,202.82,211.38 +0.00,0.00,0.00,0.00,0.00,0.00,978.41,202.82,211.38 +0.00,0.00,0.00,0.00,0.00,0.00,979.81,202.82,211.38 +0.00,0.00,0.00,0.00,0.00,0.00,982.57,202.82,211.40 +0.00,0.00,0.00,0.00,0.00,0.00,984.13,202.82,211.40 +0.00,0.00,0.00,0.00,0.00,0.00,985.54,202.82,211.40 +0.00,0.00,0.00,0.00,0.00,0.00,987.12,202.82,211.41 +0.00,0.00,0.00,0.00,0.00,0.00,988.69,202.82,211.41 +0.00,0.00,0.00,0.00,0.00,0.00,990.10,202.82,211.41 +0.00,0.00,0.00,0.00,0.00,0.00,1011.32,202.82,211.72 +0.00,0.00,0.00,0.00,0.00,0.00,1012.89,202.82,211.72 +0.00,0.00,0.00,0.00,0.00,0.00,1014.40,202.82,211.72 +0.00,0.00,0.00,0.00,0.00,0.00,1027.33,202.82,211.90 +0.00,0.00,0.00,0.00,0.00,0.00,1028.93,202.82,211.90 +0.00,0.00,0.00,0.00,0.00,0.00,1030.47,202.82,211.90 +0.00,0.00,0.00,0.00,0.00,0.00,1027.92,202.82,211.84 +0.00,0.00,0.00,0.00,0.00,0.00,1029.51,202.82,211.84 +0.00,0.00,0.00,0.00,0.00,0.00,1031.04,202.82,211.84 +0.00,0.00,0.00,0.00,0.00,0.00,1037.90,202.82,211.92 +0.00,0.00,0.00,0.00,0.00,0.00,1039.50,202.82,211.92 +0.00,0.00,0.00,0.00,0.00,0.00,1041.05,202.82,211.92 +0.00,0.00,0.00,0.00,0.00,0.00,1042.22,202.82,211.92 +0.00,0.00,0.00,0.00,0.00,0.00,1043.88,202.82,211.92 +0.00,0.00,0.00,0.00,0.00,0.00,1045.43,202.82,211.92 +0.00,0.00,0.00,0.00,0.00,0.00,1043.66,202.82,211.86 +0.00,0.00,0.00,0.00,0.00,0.00,1045.31,202.82,211.86 +0.00,0.00,0.00,0.00,0.00,0.00,1046.79,202.82,211.86 +0.00,0.00,0.00,0.00,0.00,0.00,1053.63,202.82,211.95 +0.00,0.00,0.00,0.00,0.00,0.00,1055.24,202.82,211.95 +0.00,0.00,0.00,0.00,0.00,0.00,1056.73,202.82,211.95 +0.00,0.00,0.00,0.00,0.00,0.00,1056.27,202.82,211.92 +0.00,0.00,0.00,0.00,0.00,0.00,1057.87,202.82,211.92 +0.00,0.00,0.00,0.00,0.00,0.00,1059.42,202.82,211.92 +0.00,0.00,0.00,0.00,0.00,0.00,1054.80,202.82,211.82 +-300.00,0.00,-300.00,-300.00,0.00,-300.00,0.00,211.82,211.82 +-570.00,0.00,-570.00,-570.00,0.00,-570.00,0.00,211.82,211.94 +-860.00,0.00,-860.00,-860.00,0.00,-860.00,0.00,211.82,211.94 +-1130.00,0.00,-1130.00,-1130.00,0.00,-1130.00,0.00,211.82,211.94 +-1380.00,0.00,-1380.00,-1380.00,0.00,-1380.00,0.00,211.82,211.94 +-1670.00,0.00,-1670.00,-1670.00,0.00,-1670.00,0.00,211.82,211.94 +-1940.00,-37.04,-1902.96,-1940.00,-111.11,-1828.89,0.00,211.82,211.94 +-2210.00,-148.15,-2061.85,-2210.00,-1074.07,-1135.93,0.00,211.82,211.89 +-2500.00,-413.79,-2086.21,-2500.00,-620.69,-1879.31,0.00,211.82,211.89 +-2780.00,-1392.86,-1387.14,-2780.00,71.43,-2851.43,0.00,211.82,211.89 +-3050.00,-2518.52,-531.48,-3050.00,-1296.30,-1753.70,0.00,211.82,211.64 +-3340.00,-2482.76,-857.24,-3340.00,-1241.38,-2098.62,0.00,211.82,211.64 +-3610.00,-1148.15,-2461.85,-3610.00,-777.78,-2832.22,0.00,211.82,211.64 +-3890.00,-1285.71,-2604.29,-3890.00,-2000.00,-1890.00,0.00,211.82,211.51 +-4180.00,-3034.48,-1145.52,-4180.00,-1655.17,-2524.83,0.00,211.82,211.51 +-4460.00,-4035.71,-424.29,-4460.00,-1857.14,-2602.86,0.00,211.82,211.51 +-4730.00,-3518.52,-1211.48,-4730.00,-2000.00,-2730.00,0.00,211.82,211.39 +-5030.00,-2300.00,-2730.00,-5030.00,-2500.00,-2530.00,0.00,211.82,211.39 +-5300.00,-2444.44,-2855.56,-5300.00,-2925.93,-2374.07,0.00,211.82,211.39 +-5570.00,-3592.59,-1977.41,-5570.00,-3185.19,-2384.81,0.00,211.82,211.51 +-5870.00,-3200.00,-2670.00,-5870.00,-3300.00,-2570.00,0.00,211.82,211.51 +-6140.00,-3333.33,-2806.67,-6140.00,-3629.63,-2510.37,0.00,211.82,211.51 +-6420.00,-4178.57,-2241.43,-6420.00,-4071.43,-2348.57,0.00,211.82,211.80 +-6720.00,-4466.67,-2253.33,-6720.00,-4233.33,-2486.67,0.00,211.82,211.80 +-7000.00,-4642.86,-2357.14,-7000.00,-4464.29,-2535.71,0.00,211.82,212.06 +-7290.00,-5000.00,-2290.00,-7290.00,-4827.59,-2462.41,0.00,211.82,212.06 +-7570.00,-5464.29,-2105.71,-7570.00,-5178.57,-2391.43,0.00,211.82,212.06 +-7850.00,-5500.00,-2350.00,-7850.00,-5428.57,-2421.43,0.00,211.82,212.16 +-8140.00,-5655.17,-2484.83,-8140.00,-5793.10,-2346.90,0.00,211.82,212.16 +-8410.00,-6074.07,-2335.93,-8410.00,-6148.15,-2261.85,0.00,211.82,212.16 +-8690.00,-6571.43,-2118.57,-8690.00,-6607.14,-2082.86,0.00,211.82,212.26 +-8980.00,-6965.52,-2014.48,-8980.00,-6724.14,-2255.86,0.00,211.82,212.26 +-9250.00,-7296.30,-1953.70,-9250.00,-6851.85,-2398.15,0.00,211.82,212.26 +-9530.00,-7642.86,-1887.14,-9530.00,-6821.43,-2708.57,0.00,211.82,212.61 +-9820.00,-7896.55,-1923.45,-9820.00,-7379.31,-2440.69,0.00,211.82,212.61 +-10100.00,-7857.14,-2242.86,-10100.00,-7785.71,-2314.29,0.00,211.82,212.61 +-10430.00,-7787.88,-2642.12,-10430.00,-8000.00,-2430.00,569.24,211.82,213.11 +-10730.00,-8400.00,-2330.00,-10730.00,-8266.67,-2463.33,569.48,211.82,213.11 +-11000.00,-9111.11,-1888.89,-11000.00,-8444.44,-2555.56,619.03,211.82,213.89 +-11290.00,-9517.24,-1772.76,-11290.00,-8413.79,-2876.21,619.40,211.82,213.89 +-11570.00,-9607.14,-1962.86,-11570.00,-8250.00,-3320.00,619.77,211.82,213.89 +-11850.00,-10071.43,-1778.57,-11850.00,-8750.00,-3100.00,651.41,211.82,214.38 +-12140.00,-10827.59,-1312.41,-12140.00,-9517.24,-2622.76,651.87,211.82,214.38 +-12420.00,-11107.14,-1312.86,-12420.00,-9714.29,-2705.71,652.33,211.82,214.38 +-12700.00,-11250.00,-1450.00,-12700.00,-9642.86,-3057.14,665.07,211.82,214.58 +-12990.00,-11413.79,-1576.21,-12990.00,-9241.38,-3748.62,665.57,211.82,214.58 +-13270.00,-11214.29,-2055.71,-13270.00,-10000.00,-3270.00,666.06,211.82,214.58 +-13550.00,-11928.57,-1621.43,-13550.00,-10678.57,-2871.43,677.85,211.82,214.75 +-13840.00,-12827.59,-1012.41,-13840.00,-11103.45,-2736.55,678.39,211.82,214.75 +-14120.00,-12392.86,-1727.14,-14120.00,-11035.71,-3084.29,678.91,211.82,214.75 +-14400.00,-12321.43,-2078.57,-14400.00,-10857.14,-3542.86,663.44,211.82,214.50 +-14690.00,-12931.03,-1758.97,-14690.00,-11379.31,-3310.69,663.93,211.82,214.50 +-14960.00,-13666.67,-1293.33,-14960.00,-12222.22,-2737.78,639.36,211.82,214.11 +-15250.00,-14000.00,-1250.00,-15250.00,-12344.83,-2905.17,639.78,211.82,214.11 +-15520.00,-14148.15,-1371.85,-15520.00,-12518.52,-3001.48,640.17,211.82,214.11 +-15800.00,-13892.86,-1907.14,-15800.00,-12428.57,-3371.43,579.09,211.82,213.13 +-16100.00,-14266.67,-1833.33,-16100.00,-12933.33,-3166.67,579.33,211.82,213.13 +-16380.00,-14500.00,-1880.00,-16380.00,-13321.43,-3058.57,579.57,211.82,213.13 +-16660.00,-14607.14,-2052.86,-16660.00,-14000.00,-2660.00,0.00,211.82,211.72 +-16960.00,-14400.00,-2560.00,-16960.00,-14266.67,-2693.33,0.00,211.82,211.72 +-17240.00,-15035.71,-2204.29,-17240.00,-14535.71,-2704.29,0.00,211.82,211.72 +-17520.00,-15642.86,-1877.14,-17520.00,-15000.00,-2520.00,382.87,211.82,210.02 +-17820.00,-16000.00,-1820.00,-17820.00,-14766.67,-3053.33,-113.99,211.82,210.02 +-18100.00,-15928.57,-2171.43,-18100.00,-15321.43,-2778.57,-114.31,211.82,210.02 +-18380.00,-15785.71,-2594.29,-18380.00,-15714.29,-2665.71,-244.83,211.82,207.95 +-18680.00,-16433.33,-2246.67,-18680.00,-16066.67,-2613.33,-245.56,211.82,207.95 +-18960.00,-17071.43,-1888.57,-18960.00,-16178.57,-2781.43,-389.37,211.82,205.69 +-19250.00,-17551.72,-1698.28,-19250.00,-16827.59,-2422.41,-390.49,211.82,205.69 +-19530.00,-17178.57,-2351.43,-19530.00,-17035.71,-2494.29,-391.57,211.82,205.69 +-19810.00,-16642.86,-3167.14,-19810.00,-17035.71,-2774.29,-531.00,211.82,203.50 +-20110.00,-17000.00,-3110.00,-20110.00,-17566.67,-2543.33,-532.57,211.82,203.50 +-20390.00,-17821.43,-2568.57,-20390.00,-18178.57,-2211.43,-534.04,211.82,203.50 +-20670.00,-18142.86,-2527.14,-20670.00,-18178.57,-2491.43,-671.06,211.82,201.35 +-20970.00,-18100.00,-2870.00,-20970.00,-18600.00,-2370.00,-673.04,211.82,201.35 +-21250.00,-18214.29,-3035.71,-21250.00,-18678.57,-2571.43,-674.89,211.82,201.35 +-21530.00,-18785.71,-2744.29,-21530.00,-19214.29,-2315.71,-811.61,211.82,199.22 +-21830.00,-19400.00,-2430.00,-21830.00,-19266.67,-2563.33,-813.99,211.82,199.22 +-22110.00,-19178.57,-2931.43,-22110.00,-20071.43,-2038.57,-816.22,211.82,199.22 +-22390.00,-19428.57,-2961.43,-22390.00,-20178.57,-2211.43,-911.50,211.82,197.75 +-22700.00,-19548.39,-3151.61,-22700.00,-20774.19,-1925.81,-914.25,211.82,197.75 +-22456.55,-19321.43,-3135.12,-22980.00,-20785.71,-2194.29,-987.53,211.82,196.62 +-22156.55,-19900.00,-2256.55,-22748.69,-20833.33,-1915.35,-990.40,211.82,196.62 +-21866.55,-19310.34,-2556.20,-22458.69,-21413.79,-1044.89,-993.17,211.82,196.62 +-21586.55,-19500.00,-2086.55,-22178.69,-22071.43,-107.26,-1042.10,211.82,195.89 +-21286.55,-20300.00,-986.55,-21878.69,-21566.67,-312.02,-1045.11,211.82,195.89 +-21006.55,-20357.14,-649.41,-21598.69,-21392.86,-205.83,-1047.92,211.82,195.89 +-20726.55,-19285.71,-1440.83,-21318.69,-21321.43,2.74,-1074.99,211.82,195.51 +-20426.55,-18333.33,-2093.22,-21018.69,-20766.67,-252.02,-1078.07,211.82,195.51 +-20146.55,-18285.71,-1860.83,-20738.69,-19500.00,-1238.69,-1080.94,211.82,195.51 +-19866.55,-18357.14,-1509.41,-20458.69,-20535.71,77.03,-1058.51,211.82,195.91 +-19566.55,-18366.67,-1199.88,-20158.69,-19933.33,-225.35,-1061.52,211.82,195.91 +-19286.55,-18142.86,-1143.69,-19878.69,-19607.14,-271.54,-1006.80,211.82,196.82 +-18986.55,-17233.33,-1753.22,-19578.69,-19200.00,-378.69,-1009.64,211.82,196.82 +-18706.55,-16750.00,-1956.55,-19298.69,-19071.43,-227.26,-1012.28,211.82,196.82 +-18426.55,-16892.86,-1533.69,-19018.69,-18821.43,-197.26,-891.53,211.82,198.77 +-18126.55,-16933.33,-1193.22,-18718.69,-18033.33,-685.35,-894.00,211.82,198.77 +-17846.55,-16785.71,-1060.83,-18438.69,-18142.86,-295.83,-896.30,211.82,198.77 +-17566.55,-16321.43,-1245.12,-18158.69,-17714.29,-444.40,-687.20,211.82,202.12 +-17266.55,-15800.00,-1466.55,-17858.69,-17566.67,-292.02,-689.04,211.82,202.12 +-16986.55,-15678.57,-1307.98,-17578.69,-17035.71,-542.97,-690.75,211.82,202.12 +-16696.55,-15586.21,-1110.34,-17288.69,-16482.76,-805.93,-368.84,211.82,207.24 +-16396.55,-15433.33,-963.22,-16988.69,-16400.00,-588.69,-369.70,211.82,207.24 +-16126.55,-15518.52,-608.03,-16718.69,-16444.44,-274.24,-370.48,211.82,207.24 +-15846.55,-15428.57,-417.98,-16438.69,-16071.43,-367.26,46.58,211.82,213.86 +-15546.55,-15000.00,-546.55,-16138.69,-14533.33,-1605.35,128.73,211.82,213.86 +-15266.55,-14678.57,-587.98,-15858.69,-15000.00,-858.69,624.56,211.82,221.70 +-14916.55,-14942.86,26.31,-15508.69,-15657.14,148.46,626.74,211.82,221.70 +-14636.55,-15071.43,434.88,-15228.69,-13714.29,-1514.40,628.48,211.82,221.70 +-14366.55,-14555.56,189.01,-14958.69,-13000.00,-1958.69,1134.40,211.82,229.68 +-14066.55,-14300.00,233.45,-14658.69,-13266.67,-1392.02,1137.78,211.82,229.68 +-13796.55,-14629.63,833.08,-14388.69,-13185.19,-1203.50,1140.82,211.82,229.68 +-13516.55,-14714.29,1197.74,-14108.69,-12178.57,-1930.12,1593.48,211.82,236.80 +-13226.55,-13551.72,325.17,-13818.69,-11655.17,-2163.51,1598.05,211.82,236.80 +-12946.55,-13500.00,553.45,-13538.69,-11464.29,-2074.40,1602.45,211.82,236.80 +-12666.55,-13750.00,1083.45,-13258.69,-11357.14,-1901.54,1933.07,211.82,241.96 +-12366.55,-13400.00,1033.45,-12958.69,-10433.33,-2525.35,1938.77,211.82,241.96 +-12096.55,-13370.37,1273.82,-12688.69,-9777.78,-2910.91,2119.14,211.82,244.73 +-11806.55,-13620.69,1814.14,-12398.69,-10551.72,-1846.96,2125.16,211.82,244.73 +-11526.55,-13000.00,1473.45,-12118.69,-9500.00,-2618.69,2130.96,211.82,244.73 +-11256.55,-12259.26,1002.71,-11848.69,-8814.81,-3033.87,2145.39,211.82,244.87 +-10956.55,-11966.67,1010.12,-11548.69,-8866.67,-2682.02,2151.64,211.82,244.87 +-10676.55,-11892.86,1216.31,-11268.69,-9000.00,-2268.69,2157.47,211.82,244.87 +-10406.55,-11814.81,1408.27,-10998.69,-8740.74,-2257.95,2044.98,211.82,243.00 +-10106.55,-11500.00,1393.45,-10698.69,-7733.33,-2965.35,2050.88,211.82,243.00 +-9836.55,-11296.30,1459.75,-10428.69,-7703.70,-2724.98,2056.18,211.82,243.00 +-9556.55,-11392.86,1836.31,-10148.69,-8000.00,-2148.69,1851.24,211.82,239.67 +-9266.55,-11000.00,1733.45,-9858.69,-8034.48,-1824.20,1856.32,211.82,239.67 +-8996.55,-10370.37,1373.82,-9588.69,-7703.70,-1884.98,1861.06,211.82,239.67 +-8716.55,-10035.71,1319.17,-9308.69,-6928.57,-2380.12,1581.46,211.82,235.17 +-8426.55,-9758.62,1332.07,-9018.69,-6379.31,-2639.38,1585.72,211.82,235.17 +-8146.55,-9357.14,1210.59,-8738.69,-6607.14,-2131.54,1589.84,211.82,235.17 +-7876.55,-9074.07,1197.52,-8468.69,-6037.04,-2431.65,1267.64,211.82,230.01 +-7576.55,-8766.67,1190.12,-8168.69,-5766.67,-2402.02,1271.08,211.82,230.01 +-7306.55,-8333.33,1026.78,-7898.69,-5925.93,-1972.76,1274.17,211.82,230.01 +-7026.55,-8035.71,1009.17,-7618.69,-5678.57,-1940.12,957.23,211.82,224.94 +-6736.55,-7724.14,987.59,-7328.69,-5517.24,-1811.45,959.63,211.82,224.94 +-6456.55,-7428.57,972.02,-7048.69,-5714.29,-1334.40,661.20,211.82,220.18 +-6166.55,-6862.07,695.52,-6758.69,-5689.66,-1069.03,662.73,211.82,220.18 +-5896.55,-5777.78,-118.77,-6488.69,-5481.48,-1007.21,664.15,211.82,220.18 +-5626.55,-5185.19,-441.36,-6218.69,-4925.93,-1292.76,365.74,211.82,215.43 +-5326.55,-5500.00,173.45,-5918.69,-4366.67,-1552.02,366.42,211.82,215.43 +-5056.55,-5481.48,424.93,-5648.69,-4666.67,-982.02,367.04,211.82,215.43 +-4786.55,-4666.67,-119.88,-5378.69,-4629.63,-749.06,0.00,211.82,211.29 +-4496.55,-4034.48,-462.07,-5088.69,-3827.59,-1261.10,0.00,211.82,211.29 +-4216.55,-3392.86,-823.69,-4808.69,-3571.43,-1237.26,0.00,211.82,211.29 +-3946.55,-3000.00,-946.55,-4538.69,-3481.48,-1057.21,-103.07,211.82,207.98 +-3656.55,-2724.14,-932.41,-4248.69,-3000.00,-1248.69,-242.55,211.82,207.98 +-3386.55,-2481.48,-905.07,-3978.69,-2814.81,-1163.87,-243.20,211.82,207.98 +-3116.55,-2037.04,-1079.51,-3708.69,-2740.74,-967.95,-414.29,211.82,205.28 +-2826.55,-1586.21,-1240.34,-3418.69,-2448.28,-970.41,-415.48,211.82,205.28 +-2546.55,-1035.71,-1510.83,-3138.69,-2178.57,-960.12,-416.63,211.82,205.28 +-2276.55,-962.96,-1313.59,-2868.69,-2037.04,-831.65,-571.59,211.82,202.85 +-1986.55,206.90,-2193.45,-2578.69,-1827.59,-751.10,-573.23,211.82,202.85 +-1716.55,0.00,-1716.55,-2308.69,-1629.63,-679.06,-574.76,211.82,202.85 +-1446.55,37.04,-1483.59,-2038.69,-1074.07,-964.61,-695.16,211.82,200.96 +-1156.55,103.45,-1260.00,-1748.69,-1172.41,-576.27,-697.15,211.82,200.96 +-886.55,0.00,-886.55,-1478.69,-333.33,-1145.35,-794.43,211.82,199.45 +-596.55,34.48,-631.03,-1188.69,-103.45,-1085.24,-796.69,211.82,199.45 +-326.55,0.00,-326.55,-918.69,-444.44,-474.24,-798.79,211.82,199.45 +-56.55,0.00,-56.55,-648.69,185.19,-833.87,-875.86,211.82,198.27 +0.00,0.00,0.00,-358.69,413.79,-772.48,-878.34,211.82,198.27 +0.00,0.00,0.00,-88.69,-37.04,-51.65,-880.64,211.82,198.27 +0.00,37.04,-37.04,0.00,111.11,-111.11,-945.73,211.82,197.27 +0.00,0.00,0.00,0.00,0.00,0.00,-948.39,211.82,197.27 +0.00,0.00,0.00,0.00,0.00,0.00,-950.87,211.82,197.27 +0.00,0.00,0.00,0.00,0.00,0.00,-994.51,211.82,196.62 +0.00,0.00,0.00,0.00,0.00,0.00,-997.28,211.82,196.62 +0.00,0.00,0.00,0.00,0.00,0.00,-999.87,211.82,196.62 +0.00,0.00,0.00,0.00,0.00,0.00,-1031.16,211.82,196.17 +0.00,0.00,0.00,0.00,0.00,0.00,-1034.02,211.82,196.17 +0.00,0.00,0.00,0.00,0.00,0.00,-1036.58,211.82,196.17 +0.00,0.00,0.00,0.00,0.00,0.00,-1069.85,211.82,195.68 +0.00,0.00,0.00,0.00,0.00,0.00,-1072.80,211.82,195.68 +0.00,0.00,0.00,0.00,0.00,0.00,-1075.55,211.82,195.68 +0.00,0.00,0.00,0.00,0.00,0.00,-1095.50,211.82,195.41 +0.00,0.00,0.00,0.00,0.00,0.00,-1098.50,211.82,195.41 +0.00,0.00,0.00,0.00,0.00,0.00,-1101.29,211.82,195.41 +0.00,0.00,0.00,0.00,0.00,0.00,-1128.09,211.82,195.03 +0.00,0.00,0.00,0.00,0.00,0.00,-1131.58,211.82,195.03 +0.00,0.00,0.00,0.00,0.00,0.00,-1148.71,211.82,194.80 +0.00,0.00,0.00,0.00,0.00,0.00,-1151.71,211.82,194.80 +0.00,0.00,0.00,0.00,0.00,0.00,-1154.61,211.82,194.80 +0.00,0.00,0.00,0.00,0.00,0.00,-1171.24,211.82,194.59 +0.00,0.00,0.00,0.00,0.00,0.00,-1174.28,211.82,194.59 +0.00,0.00,0.00,0.00,0.00,0.00,-1177.21,211.82,194.59 +0.00,0.00,0.00,0.00,0.00,0.00,-1194.27,211.82,194.36 +0.00,0.00,0.00,0.00,0.00,0.00,-1197.35,211.82,194.36 +0.00,0.00,0.00,0.00,0.00,0.00,-1200.32,211.82,194.36 +0.00,0.00,0.00,0.00,0.00,0.00,-1206.06,211.82,194.32 +0.00,0.00,0.00,0.00,0.00,0.00,-1209.15,211.82,194.32 +0.00,0.00,0.00,0.00,0.00,0.00,-1212.12,211.82,194.32 +0.00,0.00,0.00,0.00,0.00,0.00,-1219.64,211.82,194.24 +0.00,0.00,0.00,0.00,0.00,0.00,-1222.74,211.82,194.24 +0.00,0.00,0.00,0.00,0.00,0.00,-1225.73,211.82,194.24 +0.00,0.00,0.00,0.00,0.00,0.00,-1227.79,211.82,194.26 +0.00,0.00,0.00,0.00,0.00,0.00,-1230.89,211.82,194.26 +0.00,0.00,0.00,0.00,0.00,0.00,-1233.88,211.82,194.26 +0.00,0.00,0.00,0.00,0.00,0.00,-1244.06,211.82,194.14 +0.00,0.00,0.00,0.00,0.00,0.00,-1247.18,211.82,194.14 +0.00,0.00,0.00,0.00,0.00,0.00,-1250.08,211.82,194.14 +0.00,0.00,0.00,0.00,0.00,0.00,-1263.49,211.82,193.98 +0.00,0.00,0.00,0.00,0.00,0.00,-1266.63,211.82,193.98 +0.00,0.00,0.00,0.00,0.00,0.00,-1269.55,211.82,193.98 +0.00,0.00,0.00,0.00,0.00,0.00,-1272.71,211.82,193.98 +0.00,0.00,0.00,0.00,0.00,0.00,-1275.86,211.82,193.98 +0.00,0.00,0.00,0.00,0.00,0.00,-1278.89,211.82,193.98 +0.00,0.00,0.00,0.00,0.00,0.00,-1283.99,211.82,193.94 +0.00,0.00,0.00,0.00,0.00,0.00,-1287.26,211.82,193.94 +0.00,0.00,0.00,0.00,0.00,0.00,-1290.30,211.82,193.94 +0.00,0.00,0.00,0.00,0.00,0.00,-1287.91,211.82,194.03 +0.00,0.00,0.00,0.00,0.00,0.00,-1291.16,211.82,194.03 +0.00,0.00,0.00,0.00,0.00,0.00,-1294.19,211.82,194.03 +0.00,0.00,0.00,0.00,0.00,0.00,-1298.87,211.82,194.00 +0.00,0.00,0.00,0.00,0.00,0.00,-1302.13,211.82,194.00 +0.00,0.00,0.00,0.00,0.00,0.00,-1305.16,211.82,194.00 +0.00,0.00,0.00,0.00,0.00,0.00,-1303.02,211.82,194.08 +0.00,0.00,0.00,0.00,0.00,0.00,-1306.15,211.82,194.08 +0.00,0.00,0.00,0.00,0.00,0.00,-1309.17,211.82,194.08 +0.00,0.00,0.00,0.00,0.00,0.00,-1304.95,211.82,194.20 +0.00,0.00,0.00,0.00,0.00,0.00,-1308.17,211.82,194.20 +0.00,0.00,0.00,0.00,0.00,0.00,-1301.00,211.82,194.36 +0.00,0.00,0.00,0.00,0.00,0.00,-1304.08,211.82,194.36 +0.00,0.00,0.00,0.00,0.00,0.00,-1307.05,211.82,194.36 +0.00,0.00,0.00,0.00,0.00,0.00,-1308.47,211.82,194.38 +0.00,0.00,0.00,0.00,0.00,0.00,-1311.66,211.82,194.38 +0.00,0.00,0.00,0.00,0.00,0.00,-1314.62,211.82,194.38 +0.00,0.00,0.00,0.00,0.00,0.00,-1320.68,211.82,194.33 +0.00,0.00,0.00,0.00,0.00,0.00,-1323.77,211.82,194.33 +0.00,0.00,0.00,0.00,0.00,0.00,-1326.63,211.82,194.33 +0.00,0.00,0.00,0.00,0.00,0.00,-1331.80,211.82,194.29 +0.00,0.00,0.00,0.00,0.00,0.00,-1334.89,211.82,194.29 +0.00,0.00,0.00,0.00,0.00,0.00,-1337.87,211.82,194.29 +0.00,0.00,0.00,0.00,0.00,0.00,-1333.37,211.82,194.41 +0.00,0.00,0.00,0.00,0.00,0.00,-1336.55,211.82,194.41 +0.00,0.00,0.00,0.00,0.00,0.00,-1339.51,211.82,194.41 +0.00,0.00,0.00,0.00,0.00,0.00,-1337.75,211.82,194.49 +0.00,0.00,0.00,0.00,0.00,0.00,-1340.91,211.82,194.49 +0.00,0.00,0.00,0.00,0.00,0.00,-1343.86,211.82,194.49 +0.00,0.00,0.00,0.00,0.00,0.00,-1351.47,211.82,194.41 +0.00,0.00,0.00,0.00,0.00,0.00,-1354.65,211.82,194.41 +0.00,0.00,0.00,0.00,0.00,0.00,-1357.61,211.82,194.41 +0.00,0.00,0.00,0.00,0.00,0.00,-1355.34,211.82,194.49 +0.00,0.00,0.00,0.00,0.00,0.00,-1358.39,211.82,194.49 +0.00,0.00,0.00,0.00,0.00,0.00,-1361.23,211.82,194.49 \ No newline at end of file diff --git a/pid_vis.py b/pid_vis.py index e298db5..27ffc9a 100644 --- a/pid_vis.py +++ b/pid_vis.py @@ -9,7 +9,7 @@ lists = defaultdict(list) # header = "EncoderLeft,EncoderRight,DesiredVelocityLeft,DesiredVelocityRight,CurrentVelocityLeft,CurrentVelocityRight,LeftPower,RightPower,EncoderTargetLeft,EncoderTargetRight" - header = "LeftSetpoint,LeftVelocity,LeftError,RightSetpoint,RightVelocity,RightError,Heading" + header = "LeftSetpoint,LeftVelocity,LeftError,RightSetpoint,RightVelocity,RightError,HeadingVelocityCorrection,HeadingSetpoint,Heading" keys = header.split(",") for row in reader: for k in keys: @@ -17,6 +17,7 @@ # 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"]) @@ -44,15 +45,17 @@ # Velocity plot (top left) ax_vel = plt.subplot2grid((2, 2), (0, 0)) ax_vel.set_title("Velocity Values") -ax_vel.plot(lists["LeftSetpoint"], "-b", lists["LeftVelocity"], "-r", lists["LeftError"], "-g", - lists["RightSetpoint"], "--c", lists["RightVelocity"], "--m", lists["RightError"], "--y") -ax_vel.legend(["Left Setpoint", "Left Velocity", "Left Error", "Right Setpoint", "Right Velocity", "Right Error"]) +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.legend(["Heading"]) +ax_heading.plot(lists["HeadingSetpoint"], "--c") +ax_heading.legend(["Heading", "Heading Setpoint"]) ax_heading.set_xlabel("Time (index)") # Polar plot (right, spans both rows) @@ -61,6 +64,7 @@ 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 plt.tight_layout() diff --git a/src/robot/control.cpp b/src/robot/control.cpp index ab62835..37ae65b 100644 --- a/src/robot/control.cpp +++ b/src/robot/control.cpp @@ -37,7 +37,7 @@ TrapezoidProfile rightProfile(profileConstraints); TrapezoidProfile::State leftSetpoint, rightSetpoint; PIDController encoderAVelocityController(0.00006, 0.000000, 0.00000, -1, +1, 100); // blue on graph // input ticks per second, output duty cycle PIDController encoderBVelocityController(0.00006, 0.000000, 0.00000, -1, +1, 100); // red on graph // input ticks per second, output duty cycle -PIDController headingController(0.007, 0.00000, 0.0000, -0.3, +0.3, 0.5); // input degrees, output duty cycle +ContinuousPIDController headingController(0.001, 0.0001, 0.0000, -0.3, +0.3, 1.0, 0, 360); // 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; @@ -285,7 +285,8 @@ void controlLoop(int loopDelayMs, int8_t framesUntilPrint) { prevPositionB = currentPositionEncoderB; double currentHeading = magnet->readDegrees(); - double controllerOutput = headingController.Compute(headingTarget, currentHeading, loopDelaySeconds); + // double controllerOutput = headingController.Compute(headingTarget, currentHeading, loopDelaySeconds); + double controllerOutput = 0; double velocityOffsetFromHeading = controllerOutput * THEORETICAL_MAX_VELOCITY_TPS * MAGNET_CCW_IS_POSITIVE; // if error is positive, then assume we need to turn CCW, so slow left and speed up right double desiredVelocityLeft = leftSetpoint.velocity - velocityOffsetFromHeading; diff --git a/src/robot/magnet.cpp b/src/robot/magnet.cpp index 84afed3..beb3550 100644 --- a/src/robot/magnet.cpp +++ b/src/robot/magnet.cpp @@ -25,7 +25,7 @@ Magnet::Magnet() serialLogln("BMM350 detected.", 1); } bmm350.setOperationMode(eBmm350NormalMode); - bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY, BMM350_DATA_RATE_12_5HZ); + bmm350.setPresetMode(BMM350_PRESETMODE_ENHANCED, BMM350_DATA_RATE_12_5HZ); bmm350.setMeasurementXYZ(); bmm350.setDataReadyPin(BMM350_ENABLE_INTERRUPT, BMM350_ACTIVE_LOW); pinMode(/*Pin */ 13, INPUT_PULLUP); @@ -99,8 +99,8 @@ float Magnet::readDegreesRaw() { float Magnet::readDegrees() { // Only works if data ready interrupt is enabled - if (!bmm350.getDataReadyState()) { - return previousReading; // Return the last reading if data is not ready + 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 diff --git a/src/robot/pidController.cpp b/src/robot/pidController.cpp index a562cbe..293a06a 100644 --- a/src/robot/pidController.cpp +++ b/src/robot/pidController.cpp @@ -9,7 +9,7 @@ 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) < errorTolerance) { return 0; From 1045c015273f14edd2e4c3c54efc78310ebfd066 Mon Sep 17 00:00:00 2001 From: ymmot239 Date: Mon, 20 Oct 2025 20:52:54 -0500 Subject: [PATCH 37/47] normalize current reading, ignore low pass filter for now --- src/robot/magnet.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/robot/magnet.cpp b/src/robot/magnet.cpp index beb3550..d540a43 100644 --- a/src/robot/magnet.cpp +++ b/src/robot/magnet.cpp @@ -115,7 +115,9 @@ float Magnet::readDegrees() { previousReading -= 360; } // Simple low-pass filter - currentReading = previousReading * 0.8 + currentReading * 0.2; + // currentReading = previousReading * 0.8 + currentReading * 0.2; + if (currentReading >= 360) currentReading -= 360; + else if (currentReading < 0) currentReading += 360; previousReading = currentReading; return currentReading; } From c087d7c4f840741b26a2d9fbd4abffcbcf2f5763 Mon Sep 17 00:00:00 2001 From: Mason Thomas Date: Mon, 20 Oct 2025 21:54:49 -0500 Subject: [PATCH 38/47] fix calibration, disable interrupt pin again for more consistent analysis --- include/robot/magnet.h | 8 ++++---- src/robot/magnet.cpp | 35 ++++++++++++++++++----------------- 2 files changed, 22 insertions(+), 21 deletions(-) diff --git a/include/robot/magnet.h b/include/robot/magnet.h index fd82c71..72f5be5 100644 --- a/include/robot/magnet.h +++ b/include/robot/magnet.h @@ -22,11 +22,11 @@ class Magnet { bool isDataReady(); bool isActive(); private: - float hard_iron_offset[3] = { -23.71, -5.45, -8.27 }; + float hard_iron_offset[3] = { -10.20, -2.62, -13.21 }; float soft_iron_matrix[3][3] = { - { 1.017, -0.024, 0.023 }, - { -0.024, 0.994, 0.002 }, - { 0.023, 0.002, .991 } + { 1.024, -0.020, 0.027 }, + { -0.020, 0.968, 0.008 }, + { 0.027, 0.008, 1.011 } }; DFRobot_BMM350_I2C bmm350; diff --git a/src/robot/magnet.cpp b/src/robot/magnet.cpp index d540a43..2c2ab99 100644 --- a/src/robot/magnet.cpp +++ b/src/robot/magnet.cpp @@ -27,19 +27,20 @@ Magnet::Magnet() bmm350.setOperationMode(eBmm350NormalMode); bmm350.setPresetMode(BMM350_PRESETMODE_ENHANCED, BMM350_DATA_RATE_12_5HZ); bmm350.setMeasurementXYZ(); - 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); - } + 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() { @@ -98,10 +99,10 @@ float Magnet::readDegreesRaw() { } 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 - } + // // 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) { From 533b2499e139ad400f65b8d2a404dc14ad5ebf82 Mon Sep 17 00:00:00 2001 From: Mason Thomas Date: Mon, 20 Oct 2025 22:24:28 -0500 Subject: [PATCH 39/47] back to high accuracy... --- src/robot/control.cpp | 7 ++++--- src/robot/magnet.cpp | 2 +- src/utils/config.cpp | 2 +- 3 files changed, 6 insertions(+), 5 deletions(-) diff --git a/src/robot/control.cpp b/src/robot/control.cpp index 37ae65b..118c0ab 100644 --- a/src/robot/control.cpp +++ b/src/robot/control.cpp @@ -37,7 +37,7 @@ TrapezoidProfile rightProfile(profileConstraints); TrapezoidProfile::State leftSetpoint, rightSetpoint; PIDController encoderAVelocityController(0.00006, 0.000000, 0.00000, -1, +1, 100); // blue on graph // input ticks per second, output duty cycle PIDController encoderBVelocityController(0.00006, 0.000000, 0.00000, -1, +1, 100); // red on graph // input ticks per second, output duty cycle -ContinuousPIDController headingController(0.001, 0.0001, 0.0000, -0.3, +0.3, 1.0, 0, 360); // input degrees, output duty cycle +ContinuousPIDController headingController(0.005, 0.0001, 0.0000, -0.3, +0.3, 1.0, 0, 360); // 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; @@ -285,8 +285,9 @@ void controlLoop(int loopDelayMs, int8_t framesUntilPrint) { prevPositionB = currentPositionEncoderB; double currentHeading = magnet->readDegrees(); - // double controllerOutput = headingController.Compute(headingTarget, currentHeading, loopDelaySeconds); - double controllerOutput = 0; + // double currentHeading = getHeadingTarget(); + double controllerOutput = headingController.Compute(headingTarget, currentHeading, loopDelaySeconds); + // double controllerOutput = 0; double velocityOffsetFromHeading = controllerOutput * THEORETICAL_MAX_VELOCITY_TPS * MAGNET_CCW_IS_POSITIVE; // if error is positive, then assume we need to turn CCW, so slow left and speed up right double desiredVelocityLeft = leftSetpoint.velocity - velocityOffsetFromHeading; diff --git a/src/robot/magnet.cpp b/src/robot/magnet.cpp index 2c2ab99..3db6b4d 100644 --- a/src/robot/magnet.cpp +++ b/src/robot/magnet.cpp @@ -25,7 +25,7 @@ Magnet::Magnet() serialLogln("BMM350 detected.", 1); } bmm350.setOperationMode(eBmm350NormalMode); - bmm350.setPresetMode(BMM350_PRESETMODE_ENHANCED, BMM350_DATA_RATE_12_5HZ); + bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY, BMM350_DATA_RATE_25HZ); bmm350.setMeasurementXYZ(); activeFlag = true; // bmm350.setDataReadyPin(BMM350_ENABLE_INTERRUPT, BMM350_ACTIVE_LOW); diff --git a/src/utils/config.cpp b/src/utils/config.cpp index 1e4ae7a..86a1bb0 100644 --- a/src/utils/config.cpp +++ b/src/utils/config.cpp @@ -44,7 +44,7 @@ float ACCELERATION_LIMIT_TPSPS = 10000; float MIN_MOTOR_POWER = 0.12; // Minimum motor power to elicit motor response, empirically determined 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 +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; From a932e38faf412f09c8b278212554e5f075322c71 Mon Sep 17 00:00:00 2001 From: Mason Thomas Date: Mon, 20 Oct 2025 22:25:20 -0500 Subject: [PATCH 40/47] add calibration script --- pid_test.csv | 2180 ++++++++++++++------------------------------- src/calibrate.cpp | 93 ++ 2 files changed, 776 insertions(+), 1497 deletions(-) create mode 100644 src/calibrate.cpp diff --git a/pid_test.csv b/pid_test.csv index 7d6fc3f..52be84a 100644 --- a/pid_test.csv +++ b/pid_test.csv @@ -1,1498 +1,684 @@ LeftSetpoint,LeftVelocity,LeftError,RightSetpoint,RightVelocity,RightError,HeadingVelocityCorrection,HeadingSetpoint,Heading -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.54 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.54 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.65 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.65 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.65 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.52 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.52 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.38 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.38 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.38 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.32 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.32 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.32 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.30 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.30 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.30 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.32 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.32 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.32 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.44 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.44 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.44 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.59 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.59 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.59 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.59 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.59 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.59 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.62 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.62 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.52 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.52 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.52 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.43 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.43 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.43 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.52 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.52 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.52 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.51 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.51 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.51 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.53 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.53 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.53 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.60 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.60 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.60 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.72 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.72 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.78 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.78 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.78 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.82 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.82 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.82 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.80 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.80 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.80 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,182.88,205.71 -310.00,0.00,310.00,310.00,0.00,310.00,0.00,205.71,205.71 -590.00,0.00,590.00,590.00,0.00,590.00,0.00,205.71,205.71 -870.00,0.00,870.00,870.00,0.00,870.00,0.00,205.71,205.71 -1160.00,0.00,1160.00,1160.00,0.00,1160.00,0.00,205.71,205.71 -1480.00,0.00,1480.00,1480.00,0.00,1480.00,0.00,205.71,205.51 -1770.00,0.00,1770.00,1770.00,0.00,1770.00,0.00,205.71,205.51 -2050.00,178.57,1871.43,2050.00,178.57,1871.43,0.00,205.71,205.51 -2330.00,428.57,1901.43,2330.00,142.86,2187.14,0.00,205.71,205.61 -2620.00,241.38,2378.62,2620.00,137.93,2482.07,0.00,205.71,205.61 -2900.00,1285.71,1614.29,2900.00,214.29,2685.71,0.00,205.71,205.61 -3180.00,2714.29,465.71,3180.00,357.14,2822.86,0.00,205.71,205.85 -3480.00,2733.33,746.67,3480.00,1000.00,2480.00,0.00,205.71,205.85 -3750.00,1703.70,2046.30,3750.00,1259.26,2490.74,0.00,205.71,205.85 -4030.00,1107.14,2922.86,4030.00,1678.57,2351.43,0.00,205.71,205.98 -4320.00,1793.10,2526.90,4320.00,1551.72,2768.28,0.00,205.71,205.98 -4600.00,2214.29,2385.71,4600.00,1642.86,2957.14,0.00,205.71,205.98 -4870.00,2666.67,2203.33,4870.00,2000.00,2870.00,0.00,205.71,206.22 -5160.00,2896.55,2263.45,5160.00,2413.79,2746.21,0.00,205.71,206.22 -5440.00,3142.86,2297.14,5440.00,2928.57,2511.43,0.00,205.71,206.22 -5720.00,3321.43,2398.57,5720.00,3392.86,2327.14,0.00,205.71,206.41 -6010.00,3482.76,2527.24,6010.00,3344.83,2665.17,0.00,205.71,206.41 -6290.00,3821.43,2468.57,6290.00,3785.71,2504.29,0.00,205.71,206.78 -6590.00,4200.00,2390.00,6590.00,4066.67,2523.33,0.00,205.71,206.78 -6860.00,4444.44,2415.56,6860.00,4148.15,2711.85,0.00,205.71,206.78 -7130.00,4814.81,2315.19,7130.00,4592.59,2537.41,0.00,205.71,207.34 -7430.00,5066.67,2363.33,7430.00,5000.00,2430.00,0.00,205.71,207.34 -7710.00,5392.86,2317.14,7710.00,5392.86,2317.14,0.00,205.71,207.34 -7990.00,5714.29,2275.71,7990.00,5500.00,2490.00,0.00,205.71,207.97 -8290.00,5833.33,2456.67,8290.00,5666.67,2623.33,0.00,205.71,207.97 -8570.00,6214.29,2355.71,8570.00,5750.00,2820.00,0.00,205.71,207.97 -8840.00,6629.63,2210.37,8840.00,6222.22,2617.78,0.00,205.71,208.87 -9140.00,7000.00,2140.00,9140.00,6500.00,2640.00,0.00,205.71,208.87 -9420.00,7107.14,2312.86,9420.00,6821.43,2598.57,0.00,205.71,208.87 -9700.00,7500.00,2200.00,9700.00,7000.00,2700.00,0.00,205.71,210.42 -10000.00,7866.67,2133.33,10000.00,7266.67,2733.33,0.00,205.71,210.42 -10280.00,8000.00,2280.00,10280.00,7285.71,2994.29,0.00,205.71,212.37 -10580.00,7966.67,2613.33,10580.00,7933.33,2646.67,0.00,205.71,212.37 -10860.00,8500.00,2360.00,10860.00,8750.00,2110.00,0.00,205.71,212.37 -11140.00,8857.14,2282.86,11140.00,8678.57,2461.43,0.00,205.71,214.65 -11440.00,8866.67,2573.33,11440.00,8666.67,2773.33,0.00,205.71,214.65 -11710.00,9333.33,2376.67,11710.00,9037.04,2672.96,0.00,205.71,214.65 -11990.00,9678.57,2311.43,11990.00,9642.86,2347.14,0.00,205.71,217.49 -12290.00,9766.67,2523.33,12290.00,9400.00,2890.00,0.00,205.71,217.49 -12570.00,10285.71,2284.29,12570.00,9892.86,2677.14,0.00,205.71,217.49 -12850.00,11142.86,1707.14,12850.00,10714.29,2135.71,0.00,205.71,220.60 -13150.00,10733.33,2416.67,13150.00,10233.33,2916.67,0.00,205.71,220.60 -13420.00,10777.78,2642.22,13420.00,10888.89,2531.11,0.00,205.71,220.60 -13700.00,11678.57,2021.43,13700.00,11214.29,2485.71,0.00,205.71,224.09 -14000.00,11433.33,2566.67,14000.00,11100.00,2900.00,0.00,205.71,224.09 -14280.00,11857.14,2422.86,14280.00,11392.86,2887.14,0.00,205.71,228.18 -14580.00,12366.67,2213.33,14580.00,12000.00,2580.00,0.00,205.71,228.18 -14860.00,12571.43,2288.57,14860.00,12428.57,2431.43,0.00,205.71,228.18 -15140.00,13035.71,2104.29,15140.00,12714.29,2425.71,0.00,205.71,232.21 -15440.00,12900.00,2540.00,15440.00,12666.67,2773.33,0.00,205.71,232.21 -15720.00,13178.57,2541.43,15720.00,12750.00,2970.00,0.00,205.71,232.21 -16000.00,13785.71,2214.29,16000.00,13392.86,2607.14,0.00,205.71,235.67 -16300.00,13900.00,2400.00,16300.00,13466.67,2833.33,0.00,205.71,235.67 -16580.00,14250.00,2330.00,16580.00,13821.43,2758.57,0.00,205.71,235.67 -16860.00,13892.86,2967.14,16860.00,13857.14,3002.86,0.00,205.71,237.85 -17160.00,14600.00,2560.00,17160.00,14633.33,2526.67,0.00,205.71,237.85 -17440.00,15357.14,2082.86,17440.00,15035.71,2404.29,0.00,205.71,237.85 -17720.00,14892.86,2827.14,17720.00,14928.57,2791.43,0.00,205.71,239.14 -18020.00,15766.67,2253.33,18020.00,15400.00,2620.00,0.00,205.71,239.14 -18300.00,16392.86,1907.14,18300.00,15821.43,2478.57,0.00,205.71,238.66 -18600.00,15866.67,2733.33,18600.00,15533.33,3066.67,0.00,205.71,238.66 -18880.00,16000.00,2880.00,18880.00,16000.00,2880.00,0.00,205.71,238.66 -19150.00,17000.00,2150.00,19150.00,16592.59,2557.41,0.00,205.71,237.07 -19450.00,17166.67,2283.33,19450.00,16666.67,2783.33,0.00,205.71,237.07 -19730.00,17321.43,2408.57,19730.00,16642.86,3087.14,0.00,205.71,237.07 -20010.00,17964.29,2045.71,20010.00,17250.00,2760.00,0.00,205.71,234.77 -20310.00,18133.33,2176.67,20310.00,17733.33,2576.67,0.00,205.71,234.77 -20590.00,17892.86,2697.14,20590.00,17714.29,2875.71,0.00,205.71,234.77 -20870.00,18464.29,2405.71,20870.00,18321.43,2548.57,0.00,205.71,231.93 -21170.00,19166.67,2003.33,21170.00,18200.00,2970.00,0.00,205.71,231.93 -21510.00,19147.06,2362.94,21510.00,18764.71,2745.29,0.00,205.71,229.09 -21810.00,19066.67,2743.33,21810.00,18866.67,2943.33,0.00,205.71,229.09 -22090.00,19678.57,2411.43,22090.00,19142.86,2947.14,0.00,205.71,229.09 -22380.00,19517.24,2862.76,22380.00,19586.21,2793.79,0.00,205.71,226.17 -22680.00,20366.67,2313.33,22680.00,20033.33,2646.67,0.00,205.71,226.17 -22960.00,20642.86,2317.14,22960.00,20071.43,2888.57,0.00,205.71,226.17 -23240.00,21000.00,2240.00,23240.00,20107.14,3132.86,0.00,205.71,223.49 -23540.00,20900.00,2640.00,23075.45,20366.67,2708.78,0.00,205.71,223.49 -23555.94,20750.00,2805.94,22795.45,20607.14,2188.31,0.00,205.71,223.49 -23285.94,21444.44,1841.50,22525.45,20925.93,1599.52,0.00,205.71,220.30 -22985.94,21700.00,1285.94,22225.45,21166.67,1058.78,0.00,205.71,220.30 -22705.94,21321.43,1384.51,21945.45,20321.43,1624.02,0.00,205.71,217.14 -22405.94,21033.33,1372.61,21645.45,20300.00,1345.45,0.00,205.71,217.14 -22115.94,21172.41,943.53,21355.45,20137.93,1217.52,0.00,205.71,217.14 -21835.94,21214.29,621.66,21075.45,19892.86,1182.59,0.00,205.71,213.76 -21545.94,20862.07,683.87,20785.45,19655.17,1130.28,0.00,205.71,213.76 -21265.94,20392.86,873.09,20505.45,19142.86,1362.59,0.00,205.71,213.76 -20985.94,19857.14,1128.80,20225.45,19392.86,832.59,0.00,205.71,210.77 -20685.94,19566.67,1119.28,19925.45,19033.33,892.11,0.00,205.71,210.77 -20405.94,19571.43,834.51,19645.45,18678.57,966.88,0.00,205.71,210.77 -20125.94,19750.00,375.94,19365.45,17892.86,1472.59,0.00,205.71,208.63 -19825.94,19466.67,359.28,19065.45,18033.33,1032.11,0.00,205.71,208.63 -19545.94,18964.29,581.66,18785.45,17750.00,1035.45,0.00,205.71,208.63 -19265.94,18214.29,1051.66,18505.45,16964.29,1541.16,0.00,205.71,207.09 -18965.94,17866.67,1099.28,18205.45,17133.33,1072.11,0.00,205.71,207.09 -18695.94,17925.93,770.02,17935.45,17407.41,528.04,0.00,205.71,206.01 -18395.94,17533.33,862.61,17635.45,16466.67,1168.78,0.00,205.71,206.01 -18115.94,17250.00,865.94,17355.45,16178.57,1176.88,0.00,205.71,206.01 -17835.94,17107.14,728.80,17075.45,15678.57,1396.88,0.00,205.71,205.52 -17535.94,16466.67,1069.28,16775.45,14900.00,1875.45,0.00,205.71,205.52 -17255.94,16107.14,1148.80,16495.45,14321.43,2174.02,0.00,205.71,205.52 -16985.94,16148.15,837.80,16225.45,15111.11,1114.34,0.00,205.71,205.48 -16685.94,16200.00,485.94,15925.45,14966.67,958.78,0.00,205.71,205.48 -16405.94,15821.43,584.51,15645.45,14857.14,788.31,0.00,205.71,205.48 -16125.94,15357.14,768.80,15365.45,14714.29,651.16,0.00,205.71,205.64 -15825.94,15000.00,825.94,15065.45,13966.67,1098.78,0.00,205.71,205.64 -15545.94,14750.00,795.94,14785.45,13928.57,856.88,0.00,205.71,205.64 -15265.94,14714.29,551.66,14505.45,13500.00,1005.45,0.00,205.71,205.88 -14965.94,14400.00,565.94,14205.45,13300.00,905.45,0.00,205.71,205.88 -14685.94,13964.29,721.66,13925.45,13107.14,818.31,0.00,205.71,206.09 -14395.94,13896.55,499.39,13635.45,12758.62,876.83,0.00,205.71,206.09 -14125.94,13740.74,385.20,13365.45,12629.63,735.82,0.00,205.71,206.09 -13845.94,12750.00,1095.94,13085.45,11928.57,1156.88,0.00,205.71,206.12 -13545.94,12300.00,1245.94,12785.45,11633.33,1152.11,0.00,205.71,206.12 -13265.94,12428.57,837.37,12505.45,11571.43,934.02,0.00,205.71,206.12 -12985.94,12464.29,521.66,12225.45,11357.14,868.31,0.00,205.71,206.00 -12685.94,12266.67,419.28,11925.45,11200.00,725.45,0.00,205.71,206.00 -12415.94,12074.07,341.87,11655.45,11000.00,655.45,0.00,205.71,206.00 -12135.94,11821.43,314.51,11375.45,10464.29,911.16,0.00,205.71,206.22 -11835.94,11600.00,235.94,11075.45,10300.00,775.45,0.00,205.71,206.22 -11555.94,10964.29,591.66,10795.45,10142.86,652.59,0.00,205.71,206.22 -11275.94,10464.29,811.66,10515.45,9785.71,729.73,0.00,205.71,205.90 -10975.94,10566.67,409.28,10215.45,9500.00,715.45,0.00,205.71,205.90 -10695.94,10250.00,445.94,9935.45,8714.29,1221.16,0.00,205.71,205.86 -10395.94,9500.00,895.94,9635.45,8600.00,1035.45,0.00,205.71,205.86 -10115.94,9214.29,901.66,9355.45,8500.00,855.45,0.00,205.71,205.86 -9835.94,9142.86,693.09,9075.45,8285.71,789.73,0.00,205.71,205.84 -9535.94,8900.00,635.94,8775.45,8000.00,775.45,0.00,205.71,205.84 -9255.94,8642.86,613.09,8495.45,8071.43,424.02,0.00,205.71,205.84 -8975.94,8285.71,690.23,8215.45,7392.86,822.59,0.00,205.71,206.11 -8675.94,7800.00,875.94,7915.45,7033.33,882.11,0.00,205.71,206.11 -8395.94,7321.43,1074.51,7635.45,6607.14,1028.31,0.00,205.71,206.11 -8115.94,7178.57,937.37,7355.45,6357.14,998.31,0.00,205.71,206.48 -7815.94,7100.00,715.94,7055.45,6133.33,922.11,0.00,205.71,206.48 -7535.94,6642.86,893.09,6775.45,5500.00,1275.45,0.00,205.71,207.22 -7235.94,6333.33,902.61,6475.45,5433.33,1042.11,0.00,205.71,207.22 -6975.94,6192.31,783.64,6215.45,5115.38,1100.06,0.00,205.71,207.22 -6695.94,5928.57,767.37,5935.45,4964.29,971.16,0.00,205.71,207.64 -6395.94,5766.67,629.28,5635.45,4666.67,968.78,0.00,205.71,207.64 -6115.94,5607.14,508.80,5355.45,4357.14,998.31,0.00,205.71,207.64 -5795.94,5062.50,733.44,5035.45,4062.50,972.95,0.00,205.71,207.66 -5505.94,4448.28,1057.67,4745.45,3862.07,883.38,0.00,205.71,207.66 -5225.94,4285.71,940.23,4465.45,3714.29,751.16,0.00,205.71,207.66 -4945.94,4000.00,945.94,4185.45,3142.86,1042.59,0.00,205.71,208.36 -4655.94,3724.14,931.81,3895.45,2758.62,1136.83,0.00,205.71,208.36 -4375.94,3428.57,947.37,3615.45,2857.14,758.31,0.00,205.71,208.36 -4105.94,3222.22,883.72,3345.45,2296.30,1049.15,0.00,205.71,208.83 -3815.94,2724.14,1091.81,3055.45,1551.72,1503.72,0.00,205.71,208.83 -3535.94,2107.14,1428.80,2775.45,1607.14,1168.31,0.00,205.71,209.04 -3235.94,2333.33,902.61,2475.45,1866.67,608.78,0.00,205.71,209.04 -2965.94,1814.81,1151.13,2205.45,444.44,1761.00,0.00,205.71,209.04 -2685.94,1321.43,1364.51,1925.45,214.29,1711.16,0.00,205.71,209.83 -2385.94,100.00,2285.94,1625.45,1400.00,225.45,0.00,205.71,209.83 -2105.94,214.29,1891.66,1345.45,-71.43,1416.88,0.00,205.71,209.83 -1825.94,678.57,1147.37,1065.45,-500.00,1565.45,0.00,205.71,209.93 -1535.94,1103.45,432.49,775.45,68.97,706.48,0.00,205.71,209.93 -1255.94,-285.71,1541.66,495.45,0.00,495.45,0.00,205.71,209.93 -975.94,0.00,975.94,215.45,-35.71,251.16,0.00,205.71,210.43 -675.94,-100.00,775.94,0.00,0.00,0.00,0.00,205.71,210.43 -405.94,0.00,405.94,0.00,0.00,0.00,0.00,205.71,210.43 -125.94,0.00,125.94,0.00,0.00,0.00,0.00,205.71,210.91 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,210.91 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,210.91 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.09 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.09 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.17 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.17 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.17 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.50 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.50 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.50 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.79 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.79 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.79 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.99 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.99 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.99 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.04 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.04 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.04 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.32 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.32 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.68 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.68 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.68 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.45 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.45 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.45 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.36 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.36 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.36 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.47 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.47 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.47 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.61 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.61 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.61 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.51 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.51 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.51 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.68 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.68 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.62 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.62 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.62 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.75 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.75 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.75 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.56 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.56 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.56 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.49 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.49 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.49 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.10 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.10 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.10 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.62 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.62 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.65 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.65 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.65 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.73 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.73 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.73 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.77 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.77 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.77 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.85 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.85 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.85 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.90 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.90 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.90 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.18 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.18 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.18 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.21 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.21 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.06 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.06 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.06 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.13 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.13 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.13 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.23 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.23 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.23 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.26 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.26 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.26 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.26 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.26 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.26 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.03 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.03 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.03 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.21 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.21 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.03 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.03 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.03 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.22 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.22 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.22 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.57 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.57 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.57 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.35 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.35 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.35 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.13 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.13 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.13 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.91 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.91 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.91 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.17 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.17 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.17 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.36 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.36 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.50 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.50 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.50 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.76 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.76 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.76 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.69 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.69 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.69 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.79 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.79 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.79 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.85 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.85 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.85 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.68 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.68 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.47 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.47 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.47 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.40 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.40 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.40 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.50 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.50 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.50 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.34 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.34 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.34 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.38 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.38 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.38 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.89 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.89 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.89 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.93 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.93 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.09 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.09 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.09 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.03 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.03 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.03 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.44 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.44 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.44 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.65 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.65 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.65 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.87 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.87 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.87 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.75 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.75 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.80 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.80 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.80 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.58 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.58 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.58 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.72 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.72 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.72 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.77 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.77 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.77 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.42 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.42 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.42 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.60 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.60 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.60 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.42 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.42 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.05 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.05 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,213.05 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.72 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.72 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.72 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.73 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.73 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.73 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.50 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.50 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.50 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.23 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.23 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.23 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.47 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.47 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.19 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.19 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.19 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.06 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.06 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,212.06 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.79 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.79 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.79 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.94 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.94 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.94 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.63 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.63 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.63 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.41 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.41 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.41 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.27 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.27 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.27 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.19 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.19 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.46 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.46 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.46 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.62 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.62 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.62 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.47 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.47 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.47 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.42 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.42 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.42 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.10 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.10 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.10 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.06 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.06 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.06 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.00 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.00 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,210.84 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,210.84 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,210.84 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.02 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,205.71,211.02 --290.00,0.00,-290.00,-290.00,0.00,-290.00,0.00,211.02,211.02 --570.00,0.00,-570.00,-570.00,0.00,-570.00,0.00,211.02,211.01 --860.00,0.00,-860.00,-860.00,0.00,-860.00,0.00,211.02,211.01 --1140.00,0.00,-1140.00,-1140.00,0.00,-1140.00,0.00,211.02,211.01 --1420.00,0.00,-1420.00,-1420.00,0.00,-1420.00,0.00,211.02,211.49 --1720.00,0.00,-1720.00,-1720.00,0.00,-1720.00,0.00,211.02,211.49 --2040.00,-125.00,-1915.00,-2040.00,-187.50,-1852.50,0.00,211.02,211.49 --2320.00,-321.43,-1998.57,-2320.00,-392.86,-1927.14,0.00,211.02,211.80 --2620.00,-600.00,-2020.00,-2620.00,-400.00,-2220.00,0.00,211.02,211.80 --2900.00,-1821.43,-1078.57,-2900.00,-750.00,-2150.00,0.00,211.02,212.09 --3200.00,-2266.67,-933.33,-3200.00,-1033.33,-2166.67,0.00,211.02,212.09 --3470.00,-1407.41,-2062.59,-3470.00,-1148.15,-2321.85,0.00,211.02,212.09 --3750.00,-1250.00,-2500.00,-3750.00,-1178.57,-2571.43,0.00,211.02,211.77 --4050.00,-2433.33,-1616.67,-4050.00,-1300.00,-2750.00,0.00,211.02,211.77 --4330.00,-3821.43,-508.57,-4330.00,-1357.14,-2972.86,0.00,211.02,211.77 --4610.00,-3571.43,-1038.57,-4610.00,-1785.71,-2824.29,0.00,211.02,210.44 --4910.00,-1766.67,-3143.33,-4910.00,-1833.33,-3076.67,0.00,211.02,210.44 --5190.00,-1785.71,-3404.29,-5190.00,-2142.86,-3047.14,0.00,211.02,210.44 --5470.00,-3750.00,-1720.00,-5470.00,-2607.14,-2862.86,0.00,211.02,210.58 --5770.00,-3366.67,-2403.33,-5770.00,-2933.33,-2836.67,0.00,211.02,210.58 --6050.00,-3285.71,-2764.29,-6050.00,-2892.86,-3157.14,0.00,211.02,210.58 --6330.00,-4321.43,-2008.57,-6330.00,-3642.86,-2687.14,0.00,211.02,210.44 --6640.00,-4645.16,-1994.84,-6640.00,-4193.55,-2446.45,0.00,211.02,210.44 --6920.00,-4750.00,-2170.00,-6920.00,-4392.86,-2527.14,0.00,211.02,209.60 --7220.00,-5133.33,-2086.67,-7220.00,-4733.33,-2486.67,0.00,211.02,209.60 --7500.00,-5535.71,-1964.29,-7500.00,-5107.14,-2392.86,0.00,211.02,209.60 --7780.00,-5785.71,-1994.29,-7780.00,-5357.14,-2422.86,0.00,211.02,208.87 --8080.00,-6000.00,-2080.00,-8080.00,-5633.33,-2446.67,0.00,211.02,208.87 --8360.00,-6250.00,-2110.00,-8360.00,-5928.57,-2431.43,0.00,211.02,208.87 --8650.00,-6310.34,-2339.66,-8650.00,-6137.93,-2512.07,0.00,211.02,208.21 --8950.00,-6700.00,-2250.00,-8950.00,-6566.67,-2383.33,0.00,211.02,208.21 --9230.00,-7107.14,-2122.86,-9230.00,-6821.43,-2408.57,0.00,211.02,208.21 --9520.00,-7344.83,-2175.17,-9520.00,-7137.93,-2382.07,0.00,211.02,207.09 --9830.00,-7612.90,-2217.10,-9830.00,-7032.26,-2797.74,0.00,211.02,207.09 --10120.00,-8034.48,-2085.52,-10120.00,-7241.38,-2878.62,0.00,211.02,206.52 --10420.00,-8333.33,-2086.67,-10420.00,-7600.00,-2820.00,0.00,211.02,206.52 --10710.00,-8551.72,-2158.28,-10710.00,-8241.38,-2468.62,0.00,211.02,206.52 --10990.00,-8678.57,-2311.43,-10990.00,-8535.71,-2454.29,0.00,211.02,205.93 --11300.00,-9032.26,-2267.74,-11300.00,-8967.74,-2332.26,0.00,211.02,205.93 --11590.00,-9241.38,-2348.62,-11590.00,-9000.00,-2590.00,0.00,211.02,205.93 --11880.00,-9482.76,-2397.24,-11880.00,-9551.72,-2328.28,0.00,211.02,205.66 --12190.00,-10032.26,-2157.74,-12190.00,-10000.00,-2190.00,0.00,211.02,205.66 --12480.00,-10034.48,-2445.52,-12480.00,-10034.48,-2445.52,0.00,211.02,205.39 --12790.00,-10193.55,-2596.45,-12790.00,-10096.77,-2693.23,0.00,211.02,205.39 --13080.00,-10793.10,-2286.90,-13080.00,-10551.72,-2528.28,0.00,211.02,205.39 --13370.00,-11724.14,-1645.86,-13370.00,-10931.03,-2438.97,0.00,211.02,205.30 --13670.00,-11866.67,-1803.33,-13670.00,-11166.67,-2503.33,0.00,211.02,205.30 --13960.00,-12103.45,-1856.55,-13960.00,-11551.72,-2408.28,0.00,211.02,205.30 --14250.00,-11931.03,-2318.97,-14250.00,-11586.21,-2663.79,0.00,211.02,205.64 --14560.00,-11935.48,-2624.52,-14560.00,-12161.29,-2398.71,0.00,211.02,205.64 --14850.00,-12793.10,-2056.90,-14850.00,-12689.66,-2160.34,0.00,211.02,206.32 --15160.00,-13516.13,-1643.87,-15160.00,-12806.45,-2353.55,0.00,211.02,206.32 --15450.00,-13586.21,-1863.79,-15450.00,-12896.55,-2553.45,0.00,211.02,206.32 --15740.00,-13482.76,-2257.24,-15740.00,-13000.00,-2740.00,0.00,211.02,206.98 --16050.00,-13967.74,-2082.26,-16050.00,-13322.58,-2727.42,0.00,211.02,206.98 --16340.00,-13931.03,-2408.97,-16340.00,-13620.69,-2719.31,0.00,211.02,206.98 --16630.00,-14068.97,-2561.03,-16630.00,-13724.14,-2905.86,0.00,211.02,207.81 --16940.00,-14483.87,-2456.13,-16940.00,-14451.61,-2488.39,0.00,211.02,207.81 --17230.00,-15275.86,-1954.14,-17230.00,-14758.62,-2471.38,0.00,211.02,207.81 --17520.00,-15172.41,-2347.59,-17520.00,-14413.79,-3106.21,0.00,211.02,208.86 --17830.00,-15322.58,-2507.42,-17830.00,-15096.77,-2733.23,0.00,211.02,208.86 --18120.00,-16275.86,-1844.14,-18120.00,-14896.55,-3223.45,0.00,211.02,209.61 --18420.00,-16733.33,-1686.67,-18420.00,-16133.33,-2286.67,0.00,211.02,209.61 --18710.00,-16068.97,-2641.03,-18710.00,-15586.21,-3123.79,0.00,211.02,209.61 --19000.00,-16172.41,-2827.59,-19000.00,-15724.14,-3275.86,0.00,211.02,209.76 --19310.00,-17419.35,-1890.65,-19310.00,-16903.23,-2406.77,0.00,211.02,209.76 --19590.00,-17464.29,-2125.71,-19590.00,-16714.29,-2875.71,0.00,211.02,209.76 --19870.00,-17714.29,-2155.71,-19870.00,-17178.57,-2691.43,0.00,211.02,209.51 --20180.00,-18548.39,-1631.61,-20180.00,-17129.03,-3050.97,0.00,211.02,209.51 --20470.00,-17965.52,-2504.48,-20470.00,-17586.21,-2883.79,0.00,211.02,209.18 --20780.00,-17903.23,-2876.77,-20780.00,-18000.00,-2780.00,0.00,211.02,209.18 --21070.00,-19034.48,-2035.52,-21070.00,-18344.83,-2725.17,0.00,211.02,209.18 --21360.00,-19206.90,-2153.10,-21360.00,-18275.86,-3084.14,0.00,211.02,208.80 --21670.00,-19838.71,-1831.29,-21670.00,-18838.71,-2831.29,0.00,211.02,208.80 --21960.00,-19517.24,-2442.76,-21960.00,-19000.00,-2960.00,0.00,211.02,208.80 --22300.00,-19676.47,-2623.53,-22300.00,-19764.71,-2535.29,0.00,211.02,208.27 --22610.00,-20677.42,-1932.58,-22610.00,-19419.35,-3190.65,0.00,211.02,208.27 --22900.00,-21103.45,-1796.55,-22556.35,-20379.31,-2177.04,0.00,211.02,207.82 --22713.41,-20935.48,-1777.93,-22246.35,-20580.65,-1665.71,0.00,211.02,207.82 --22423.41,-20724.14,-1699.28,-21956.35,-20310.34,-1646.01,0.00,211.02,207.82 --22133.41,-20413.79,-1719.62,-21666.35,-19896.55,-1769.80,0.00,211.02,207.51 --21823.41,-20483.87,-1339.54,-21356.35,-20064.52,-1291.84,0.00,211.02,207.51 --21533.41,-20758.62,-774.79,-21066.35,-19655.17,-1411.18,0.00,211.02,207.51 --21243.41,-20517.24,-726.17,-20776.35,-19448.28,-1328.08,0.00,211.02,207.16 --20933.41,-20064.52,-868.90,-20466.35,-19258.06,-1208.29,0.00,211.02,207.16 --20643.41,-19862.07,-781.35,-20176.35,-18724.14,-1452.21,0.00,211.02,206.56 --20333.41,-19903.23,-430.19,-19866.35,-18580.65,-1285.71,0.00,211.02,206.56 --20043.41,-19655.17,-388.24,-19576.35,-18068.97,-1507.39,0.00,211.02,206.56 --19753.41,-19482.76,-270.66,-19286.35,-18137.93,-1148.42,0.00,211.02,205.80 --19443.41,-19032.26,-411.16,-18976.35,-17741.94,-1234.42,0.00,211.02,205.80 --19153.41,-18655.17,-498.24,-18686.35,-17931.03,-755.32,0.00,211.02,205.80 --18863.41,-18379.31,-484.10,-18396.35,-16896.55,-1499.80,0.00,211.02,205.28 --18553.41,-18322.58,-230.83,-18086.35,-17161.29,-925.06,0.00,211.02,205.28 --18263.41,-18137.93,-125.48,-17796.35,-16586.21,-1210.15,0.00,211.02,205.05 --17953.41,-17741.94,-211.48,-17486.35,-16193.55,-1292.80,0.00,211.02,205.05 --17663.41,-17344.83,-318.59,-17196.35,-16724.14,-472.21,0.00,211.02,205.05 --17373.41,-16965.52,-407.90,-16906.35,-15931.03,-975.32,0.00,211.02,205.64 --17073.41,-16300.00,-773.41,-16606.35,-15500.00,-1106.35,0.00,211.02,205.64 --16793.41,-16142.86,-650.56,-16326.35,-15750.00,-576.35,0.00,211.02,205.64 --16503.41,-16448.28,-55.14,-16036.35,-15586.21,-450.15,0.00,211.02,207.86 --16193.41,-16387.10,193.68,-15726.35,-14290.32,-1436.03,0.00,211.02,207.86 --15913.41,-15714.29,-199.13,-15446.35,-14500.00,-946.35,0.00,211.02,207.86 --15623.41,-14689.66,-933.76,-15156.35,-14034.48,-1121.87,0.00,211.02,211.09 --15313.41,-14419.35,-894.06,-14846.35,-13612.90,-1233.45,0.00,211.02,211.09 --15023.41,-14620.69,-402.72,-14556.35,-13827.59,-728.77,0.00,211.02,216.81 --14723.41,-14633.33,-90.08,-14256.35,-13033.33,-1223.02,0.00,211.02,216.81 --14433.41,-13551.72,-881.69,-13966.35,-12620.69,-1345.66,0.00,211.02,216.81 --14143.41,-12931.03,-1212.38,-13676.35,-12689.66,-986.70,0.00,211.02,223.93 --13843.41,-13066.67,-776.75,-13376.35,-12266.67,-1109.69,0.00,211.02,223.93 --13563.41,-13107.14,-456.27,-13096.35,-11785.71,-1310.64,0.00,211.02,223.93 --13273.41,-13103.45,-169.97,-12806.35,-12275.86,-530.49,0.00,211.02,230.09 --12963.41,-12677.42,-286.00,-12496.35,-11225.81,-1270.55,0.00,211.02,230.09 --12673.41,-12379.31,-294.10,-12206.35,-11206.90,-999.46,0.00,211.02,236.08 --12373.41,-12200.00,-173.41,-11906.35,-11166.67,-739.69,0.00,211.02,236.08 --12083.41,-11965.52,-117.90,-11616.35,-10724.14,-892.21,0.00,211.02,236.08 --11793.41,-11586.21,-207.21,-11326.35,-10931.03,-395.32,0.00,211.02,241.72 --11483.41,-11193.55,-289.87,-11016.35,-10451.61,-564.74,0.00,211.02,241.72 --11193.41,-11000.00,-193.41,-10726.35,-9689.66,-1036.70,0.00,211.02,241.72 --10903.41,-10793.10,-110.31,-10436.35,-9448.28,-988.08,0.00,211.02,245.35 --10603.41,-10533.33,-70.08,-10136.35,-9166.67,-969.69,0.00,211.02,245.35 --10313.41,-10103.45,-209.97,-9846.35,-8827.59,-1018.77,0.00,211.02,245.35 --10023.41,-9586.21,-437.21,-9556.35,-8896.55,-659.80,0.00,211.02,247.55 --9713.41,-9516.13,-197.29,-9246.35,-8580.65,-665.71,0.00,211.02,247.55 --9423.41,-9586.21,162.79,-8956.35,-8068.97,-887.39,0.00,211.02,248.43 --9113.41,-9419.35,305.94,-8646.35,-8258.06,-388.29,0.00,211.02,248.43 --8833.41,-9000.00,166.59,-8366.35,-7357.14,-1009.21,0.00,211.02,248.43 --8553.41,-8428.57,-124.84,-8086.35,-7428.57,-657.78,0.00,211.02,247.29 --8253.41,-7800.00,-453.41,-7786.35,-7266.67,-519.69,0.00,211.02,247.29 --7973.41,-7250.00,-723.41,-7506.35,-6571.43,-934.92,0.00,211.02,247.29 --7693.41,-7107.14,-586.27,-7226.35,-6428.57,-797.78,0.00,211.02,245.34 --7383.41,-7064.52,-318.90,-6916.35,-6322.58,-593.77,0.00,211.02,245.34 --7093.41,-6827.59,-265.83,-6626.35,-6103.45,-522.90,0.00,211.02,243.00 --6793.41,-6666.67,-126.75,-6326.35,-5833.33,-493.02,0.00,211.02,243.00 --6503.41,-6310.34,-193.07,-6036.35,-5620.69,-415.66,0.00,211.02,243.00 --6213.41,-5310.34,-903.07,-5746.35,-5482.76,-263.59,0.00,211.02,240.32 --5903.41,-5032.26,-871.16,-5436.35,-5161.29,-275.06,0.00,211.02,240.32 --5613.41,-5620.69,7.28,-5146.35,-4241.38,-904.97,0.00,211.02,240.32 --5333.41,-5678.57,345.16,-4866.35,-3750.00,-1116.35,0.00,211.02,236.89 --5033.41,-4833.33,-200.08,-4566.35,-4066.67,-499.69,0.00,211.02,236.89 --4743.41,-3827.59,-915.83,-4276.35,-4000.00,-276.35,0.00,211.02,236.89 --4463.41,-3250.00,-1213.41,-3996.35,-2642.86,-1353.50,0.00,211.02,233.90 --4153.41,-3193.55,-959.87,-3686.35,-2193.55,-1492.80,0.00,211.02,233.90 --3873.41,-3428.57,-444.84,-3406.35,-2857.14,-549.21,0.00,211.02,231.19 --3513.41,-2861.11,-652.30,-3046.35,-2111.11,-935.24,0.00,211.02,231.19 --3233.41,-2142.86,-1090.56,-2766.35,-1000.00,-1766.35,0.00,211.02,231.19 --2943.41,-1724.14,-1219.28,-2476.35,-1724.14,-752.21,0.00,211.02,228.81 --2643.41,-1133.33,-1510.08,-2176.35,-2300.00,123.65,0.00,211.02,228.81 --2363.41,-1464.29,-899.13,-1896.35,-1535.71,-360.64,0.00,211.02,228.81 --2083.41,-1821.43,-261.99,-1616.35,-214.29,-1402.07,0.00,211.02,226.50 --1773.41,-483.87,-1289.54,-1306.35,64.52,-1370.87,0.00,211.02,226.50 --1493.41,428.57,-1921.99,-1026.35,142.86,-1169.21,0.00,211.02,224.75 --1193.41,266.67,-1460.08,-726.35,133.33,-859.69,0.00,211.02,224.75 --913.41,-107.14,-806.27,-446.35,0.00,-446.35,0.00,211.02,224.75 --633.41,428.57,-1061.99,-166.35,0.00,-166.35,0.00,211.02,223.08 --333.41,-66.67,-266.75,0.00,0.00,0.00,0.00,211.02,223.08 --63.41,0.00,-63.41,0.00,0.00,0.00,0.00,211.02,223.08 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,221.67 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,221.67 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,221.67 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,220.72 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,220.72 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,220.72 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,219.90 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,219.90 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,219.90 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,219.23 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,219.23 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,218.67 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,218.67 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,218.67 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,218.03 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,218.03 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,218.03 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.73 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.73 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.73 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.36 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.36 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.36 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.25 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.25 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.25 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.91 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.91 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.91 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.72 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.72 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.72 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.57 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.57 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.76 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.76 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.76 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.71 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.71 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.71 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.54 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.54 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.54 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.45 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.45 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.45 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.57 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.57 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.57 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.61 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.61 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.61 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.73 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.73 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.91 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.91 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.91 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.03 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.03 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.03 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.00 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.00 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.00 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.81 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.81 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.81 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.95 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.95 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.95 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.05 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.05 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.68 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.68 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.68 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.75 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.75 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.75 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.82 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.82 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.82 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.94 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.94 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.94 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.11 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.11 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.11 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.03 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.03 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.11 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.11 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.11 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.88 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.88 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.88 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.80 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.80 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.80 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.98 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.98 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.98 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.00 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.00 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.00 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.02 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.02 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.02 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.90 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,216.90 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.10 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,211.02,217.10 -0.00,0.00,0.00,0.00,0.00,0.00,207.44,200.31,202.81 -0.00,0.00,0.00,0.00,0.00,0.00,213.05,200.31,202.89 -0.00,0.00,0.00,0.00,0.00,0.00,213.52,200.31,202.89 -0.00,0.00,0.00,0.00,0.00,0.00,213.94,200.31,202.89 -0.00,0.00,0.00,0.00,0.00,0.00,213.82,200.31,202.88 -0.00,0.00,0.00,0.00,0.00,0.00,214.27,200.31,202.88 -0.00,0.00,0.00,0.00,0.00,0.00,214.71,200.31,202.88 -0.00,0.00,0.00,0.00,0.00,0.00,215.63,200.31,202.89 -0.00,0.00,0.00,0.00,0.00,0.00,216.08,200.31,202.89 -0.00,0.00,0.00,0.00,0.00,0.00,216.52,200.31,202.89 -0.00,0.00,0.00,0.00,0.00,0.00,221.52,200.31,202.96 -0.00,0.00,0.00,0.00,0.00,0.00,221.99,200.31,202.96 -0.00,0.00,0.00,0.00,0.00,0.00,222.42,200.31,202.96 -0.00,0.00,0.00,0.00,0.00,0.00,218.38,200.31,202.89 -0.00,0.00,0.00,0.00,0.00,0.00,218.84,200.31,202.89 -0.00,0.00,0.00,0.00,0.00,0.00,219.26,200.31,202.89 -0.00,0.00,0.00,0.00,0.00,0.00,216.01,200.31,202.83 -0.00,0.00,0.00,0.00,0.00,0.00,216.48,200.31,202.83 -0.00,0.00,0.00,0.00,0.00,0.00,216.89,200.31,202.83 -0.00,0.00,0.00,0.00,0.00,0.00,217.52,200.31,202.84 -0.00,0.00,0.00,0.00,0.00,0.00,217.97,200.31,202.84 -0.00,0.00,0.00,0.00,0.00,0.00,218.40,200.31,202.84 -0.00,0.00,0.00,0.00,0.00,0.00,220.66,200.31,202.87 -0.00,0.00,0.00,0.00,0.00,0.00,221.11,200.31,202.87 -0.00,0.00,0.00,0.00,0.00,0.00,221.53,200.31,202.87 -0.00,0.00,0.00,0.00,0.00,0.00,222.98,200.31,202.88 -0.00,0.00,0.00,0.00,0.00,0.00,223.43,200.31,202.88 -0.00,0.00,0.00,0.00,0.00,0.00,223.87,200.31,202.88 -0.00,0.00,0.00,0.00,0.00,0.00,226.66,200.31,202.92 -0.00,0.00,0.00,0.00,0.00,0.00,227.12,200.31,202.92 -0.00,0.00,0.00,0.00,0.00,0.00,227.56,200.31,202.92 -0.00,0.00,0.00,0.00,0.00,0.00,228.18,200.31,202.92 -0.00,0.00,0.00,0.00,0.00,0.00,228.64,200.31,202.92 -0.00,0.00,0.00,0.00,0.00,0.00,229.08,200.31,202.92 -0.00,0.00,0.00,0.00,0.00,0.00,227.62,200.31,202.89 -0.00,0.00,0.00,0.00,0.00,0.00,228.07,200.31,202.89 -0.00,0.00,0.00,0.00,0.00,0.00,228.51,200.31,202.89 -0.00,0.00,0.00,0.00,0.00,0.00,234.07,200.31,202.97 -0.00,0.00,0.00,0.00,0.00,0.00,234.54,200.31,202.97 -0.00,0.00,0.00,0.00,0.00,0.00,234.98,200.31,202.97 -0.00,0.00,0.00,0.00,0.00,0.00,240.05,200.31,203.05 -0.00,0.00,0.00,0.00,0.00,0.00,240.54,200.31,203.05 -0.00,0.00,0.00,0.00,0.00,0.00,241.00,200.31,203.05 -0.00,0.00,0.00,0.00,0.00,0.00,240.78,200.31,203.03 -0.00,0.00,0.00,0.00,0.00,0.00,241.26,200.31,203.03 -0.00,0.00,0.00,0.00,0.00,0.00,241.71,200.31,203.03 -0.00,0.00,0.00,0.00,0.00,0.00,241.47,200.31,203.02 -0.00,0.00,0.00,0.00,0.00,0.00,241.95,200.31,203.02 -0.00,0.00,0.00,0.00,0.00,0.00,242.41,200.31,203.02 -0.00,0.00,0.00,0.00,0.00,0.00,236.77,200.31,202.93 -0.00,0.00,0.00,0.00,0.00,0.00,237.23,200.31,202.93 -0.00,0.00,0.00,0.00,0.00,0.00,237.66,200.31,202.93 -0.00,0.00,0.00,0.00,0.00,0.00,235.48,200.31,202.89 -0.00,0.00,0.00,0.00,0.00,0.00,235.95,200.31,202.89 -0.00,0.00,0.00,0.00,0.00,0.00,246.18,200.31,203.04 -0.00,0.00,0.00,0.00,0.00,0.00,246.66,200.31,203.04 -0.00,0.00,0.00,0.00,0.00,0.00,247.13,200.31,203.04 -0.00,0.00,0.00,0.00,0.00,0.00,245.38,200.31,203.01 -0.00,0.00,0.00,0.00,0.00,0.00,245.85,200.31,203.01 -0.00,0.00,0.00,0.00,0.00,0.00,246.30,200.31,203.01 -0.00,0.00,0.00,0.00,0.00,0.00,242.87,200.31,202.94 -0.00,0.00,0.00,0.00,0.00,0.00,243.33,200.31,202.94 -0.00,0.00,0.00,0.00,0.00,0.00,243.76,200.31,202.94 -0.00,0.00,0.00,0.00,0.00,0.00,236.40,200.31,202.82 -300.00,0.00,300.00,300.00,0.00,300.00,0.00,202.82,202.82 -560.00,0.00,560.00,560.00,0.00,560.00,0.00,202.82,202.82 -830.00,0.00,830.00,830.00,0.00,830.00,0.00,202.82,202.89 -1110.00,0.00,1110.00,1110.00,0.00,1110.00,0.00,202.82,202.89 -1380.00,0.00,1380.00,1380.00,0.00,1380.00,0.00,202.82,202.89 -1650.00,0.00,1650.00,1650.00,0.00,1650.00,0.00,202.82,203.00 -1940.00,137.93,1802.07,1940.00,172.41,1767.59,0.00,202.82,203.00 -2210.00,222.22,1987.78,2210.00,407.41,1802.59,0.00,202.82,203.00 -2470.00,38.46,2431.54,2470.00,192.31,2277.69,0.00,202.82,203.09 -2760.00,241.38,2518.62,2760.00,172.41,2587.59,0.00,202.82,203.09 -3030.00,1222.22,1807.78,3030.00,703.70,2326.30,0.00,202.82,203.09 -3290.00,2615.38,674.62,3290.00,1230.77,2059.23,0.00,202.82,202.99 -3580.00,2517.24,1062.76,3580.00,1448.28,2131.72,0.00,202.82,202.99 -3850.00,851.85,2998.15,3850.00,1444.44,2405.56,0.00,202.82,202.99 -4120.00,629.63,3490.37,4120.00,1888.89,2231.11,0.00,202.82,202.85 -4410.00,2724.14,1685.86,4410.00,1655.17,2754.83,0.00,202.82,202.85 -4680.00,2222.22,2457.78,4680.00,1925.93,2754.07,0.00,202.82,202.85 -4950.00,2333.33,2616.67,4950.00,2222.22,2727.78,0.00,202.82,202.67 -5240.00,2965.52,2274.48,5240.00,2758.62,2481.38,0.00,202.82,202.67 -5510.00,3185.19,2324.81,5510.00,3000.00,2510.00,0.00,202.82,202.67 -5770.00,3230.77,2539.23,5770.00,3269.23,2500.77,0.00,202.82,202.58 -6050.00,3464.29,2585.71,6050.00,3500.00,2550.00,0.00,202.82,202.58 -6310.00,3884.62,2425.38,6310.00,4000.00,2310.00,0.00,202.82,202.58 -6580.00,4148.15,2431.85,6580.00,4074.07,2505.93,0.00,202.82,202.57 -6870.00,4344.83,2525.17,6870.00,4275.86,2594.14,0.00,202.82,202.57 -7130.00,4653.85,2476.15,7130.00,4615.38,2514.62,0.00,202.82,202.57 -7400.00,4777.78,2622.22,7400.00,4925.93,2474.07,0.00,202.82,202.79 -7680.00,5250.00,2430.00,7680.00,5035.71,2644.29,0.00,202.82,202.79 -7940.00,5653.85,2286.15,7940.00,5269.23,2670.77,0.00,202.82,202.79 -8200.00,6000.00,2200.00,8200.00,5576.92,2623.08,0.00,202.82,203.19 -8480.00,6428.57,2051.43,8480.00,5928.57,2551.43,0.00,202.82,203.19 -8750.00,6555.56,2194.44,8750.00,6518.52,2231.48,0.00,202.82,203.19 -9020.00,6777.78,2242.22,9020.00,6740.74,2279.26,0.00,202.82,203.77 -9310.00,7103.45,2206.55,9310.00,7034.48,2275.52,0.00,202.82,203.77 -9580.00,7259.26,2320.74,9580.00,6962.96,2617.04,199.53,202.82,204.74 -9920.00,7382.35,2537.65,9920.00,7382.35,2537.65,199.94,202.82,204.74 -10190.00,7777.78,2412.22,10190.00,8037.04,2152.96,200.27,202.82,204.74 -10460.00,8037.04,2422.96,10460.00,8444.44,2015.56,286.60,202.82,206.10 -10750.00,8172.41,2577.59,10750.00,8448.28,2301.72,287.20,202.82,206.10 -11010.00,8423.08,2586.92,11010.00,8538.46,2471.54,287.74,202.82,206.10 -11280.00,8814.81,2465.19,11280.00,9148.15,2131.85,377.09,202.82,207.51 -11570.00,8931.03,2638.97,11570.00,9379.31,2190.69,377.95,202.82,207.51 -11840.00,8888.89,2951.11,11840.00,9555.56,2284.44,378.75,202.82,207.51 -12110.00,9222.22,2887.78,12110.00,9888.89,2221.11,481.92,202.82,209.13 -12400.00,9655.17,2744.83,12400.00,10275.86,2124.14,483.07,202.82,209.13 -12670.00,10000.00,2670.00,12670.00,10703.70,1966.30,484.14,202.82,209.13 -12940.00,10296.30,2643.70,12940.00,11037.04,1902.96,624.92,202.82,211.34 -13230.00,10241.38,2988.62,13230.00,11344.83,1885.17,626.48,202.82,211.34 -13500.00,10370.37,3129.63,13500.00,11444.44,2055.56,627.93,202.82,211.34 -13770.00,10925.93,2844.07,13770.00,11925.93,1844.07,777.06,202.82,213.68 -14060.00,11310.34,2749.66,14060.00,12103.45,1956.55,779.04,202.82,213.68 -14330.00,11222.22,3107.78,14330.00,12444.44,1885.56,780.89,202.82,213.68 -14600.00,11666.67,2933.33,14600.00,12814.81,1785.19,940.41,202.82,216.18 -14890.00,11827.59,3062.41,14890.00,12931.03,1958.97,942.85,202.82,216.18 -15160.00,11481.48,3678.52,15160.00,12925.93,2234.07,1097.52,202.82,218.59 -15450.00,12000.00,3450.00,15450.00,13896.55,1553.45,1100.40,202.82,218.59 -15730.00,12714.29,3015.71,15730.00,14357.14,1372.86,1103.18,202.82,218.59 -16000.00,12444.44,3555.56,16000.00,14037.04,1962.96,1212.61,202.82,220.28 -16290.00,12586.21,3703.79,16290.00,14931.03,1358.97,1215.80,202.82,220.28 -16560.00,13777.78,2782.22,16560.00,15555.56,1004.44,1218.77,202.82,220.28 -16830.00,13629.63,3200.37,16830.00,15407.41,1422.59,1292.03,202.82,221.39 -17120.00,13862.07,3257.93,17120.00,15862.07,1257.93,1295.43,202.82,221.39 -17390.00,13888.89,3501.11,17390.00,15888.89,1501.11,1298.58,202.82,221.39 -17660.00,13814.81,3845.19,17660.00,16148.15,1511.85,1314.62,202.82,221.59 -17960.00,14200.00,3760.00,17960.00,16333.33,1626.67,1318.17,202.82,221.59 -18230.00,15074.07,3155.93,18230.00,16925.93,1304.07,1321.36,202.82,221.59 -18500.00,15518.52,2981.48,18500.00,16925.93,1574.07,1262.94,202.82,220.62 -18800.00,15000.00,3800.00,18800.00,17300.00,1500.00,1266.30,202.82,220.62 -19070.00,15296.30,3773.70,19070.00,17444.44,1625.56,1269.33,202.82,220.62 -19340.00,15962.96,3377.04,19340.00,17814.81,1525.19,1152.17,202.82,218.72 -19640.00,16266.67,3373.33,19640.00,18000.00,1640.00,1155.18,202.82,218.72 -19910.00,16518.52,3391.48,19910.00,18481.48,1428.52,1157.88,202.82,218.72 -20190.00,16464.29,3725.71,20190.00,18535.71,1654.29,1018.65,202.82,216.47 -20480.00,16931.03,3548.97,20480.00,18793.10,1686.90,1021.14,202.82,216.47 -20760.00,17607.14,3152.86,20760.00,18464.29,2295.71,809.89,202.82,213.09 -21050.00,18103.45,2946.55,21050.00,19517.24,1532.76,811.77,202.82,213.09 -21330.00,17642.86,3687.14,21330.00,19607.14,1722.86,813.58,202.82,213.09 -21610.00,18357.14,3252.86,21610.00,20000.00,1610.00,569.44,202.82,209.19 -21910.00,18766.67,3143.33,21910.00,19600.00,2310.00,570.65,202.82,209.19 -22180.00,19555.56,2624.44,22180.00,19925.93,2254.07,571.73,202.82,209.19 -22460.00,19357.14,3102.86,22460.00,19892.86,2567.14,330.83,202.82,205.36 -22750.00,19103.45,3646.55,22750.00,20413.79,2336.21,331.29,202.82,205.36 -23030.00,20035.71,2994.29,23030.00,20500.00,2530.00,331.74,202.82,205.36 -23310.00,20500.00,2810.00,23253.08,21071.43,2181.65,61.58,202.82,201.08 -23610.00,20566.67,3043.33,22953.08,20933.33,2019.74,-110.09,202.82,201.08 -23836.72,21535.71,2301.01,22673.08,20964.29,1708.79,-110.40,202.82,201.08 -23556.72,21607.14,1949.58,22393.08,21250.00,1143.08,-367.65,202.82,197.01 -23256.72,21733.33,1523.39,22093.08,20866.67,1226.41,-368.75,202.82,197.01 -22976.72,22250.00,726.72,21813.08,19892.86,1920.22,-596.12,202.82,193.43 -22676.72,22566.67,110.06,21513.08,19833.33,1679.74,-597.90,202.82,193.43 -22396.72,21928.57,468.15,21233.08,20214.29,1018.79,-599.56,202.82,193.43 -22116.72,21142.86,973.86,20953.08,19642.86,1310.22,-803.11,202.82,190.23 -21816.72,21066.67,750.06,20653.08,18800.00,1853.08,-805.49,202.82,190.23 -21536.72,21500.00,36.72,20373.08,18678.57,1694.50,-807.71,202.82,190.23 -21256.72,21464.29,-207.56,20093.08,19107.14,985.93,-967.13,202.82,187.75 -20956.72,20733.33,223.39,19793.08,17800.00,1993.08,-969.97,202.82,187.75 -20676.72,20428.57,248.15,19513.08,17000.00,2513.08,-972.63,202.82,187.75 -20396.72,20500.00,-103.28,19233.08,17785.71,1447.36,-1079.31,202.82,186.10 -20096.72,20333.33,-236.61,18933.08,17433.33,1499.74,-1082.47,202.82,186.10 -19816.72,19928.57,-111.85,18653.08,16321.43,2331.65,-1085.42,202.82,186.10 -19536.72,19428.57,108.15,18373.08,16214.29,2158.79,-1127.67,202.82,185.48 -19246.72,19206.90,39.83,18083.08,16137.93,1945.14,-1130.84,202.82,185.48 -18976.72,18518.52,458.20,17813.08,15370.37,2442.71,-1112.52,202.82,185.81 -18686.72,18413.79,272.93,17523.08,15448.28,2074.80,-1115.63,202.82,185.81 -18406.72,19035.71,-628.99,17243.08,15392.86,1850.22,-1118.63,202.82,185.81 -18136.72,18629.63,-492.91,16973.08,15074.07,1899.00,-1036.61,202.82,187.16 -17796.72,17558.82,237.90,16633.08,14794.12,1838.96,-1039.97,202.82,187.16 -17526.72,16925.93,600.80,16363.08,14259.26,2103.82,-1042.63,202.82,187.16 -17246.72,17107.14,139.58,16083.08,14392.86,1690.22,-926.50,202.82,189.04 -16956.72,17655.17,-698.45,15793.08,14379.31,1413.77,-929.01,202.82,189.04 -16676.72,17500.00,-823.28,15513.08,13714.29,1798.79,-931.44,202.82,189.04 -16406.72,16666.67,-259.94,15243.08,13518.52,1724.56,-766.71,202.82,191.68 -16106.72,15700.00,406.72,14943.08,13766.67,1176.41,-768.81,202.82,191.68 -15826.72,15500.00,326.72,14663.08,13178.57,1484.50,-770.77,202.82,191.68 -15546.72,15357.14,189.58,14383.08,12285.71,2097.36,-586.62,202.82,194.63 -15256.72,14862.07,394.65,14093.08,12448.28,1644.80,-588.12,202.82,194.63 -14986.72,14629.63,357.09,13823.08,12777.78,1045.30,-589.51,202.82,194.63 -14716.72,14518.52,198.20,13553.08,12111.11,1441.96,-385.37,202.82,197.88 -14426.72,14172.41,254.31,13263.08,11758.62,1504.45,-386.28,202.82,197.88 -14156.72,13703.70,453.02,12993.08,11925.93,1067.15,-173.38,202.82,201.27 -13866.72,13310.34,556.38,12703.08,11862.07,841.01,-173.66,202.82,201.27 -13596.72,13037.04,559.69,12433.08,11629.63,803.45,-173.93,202.82,201.27 -13326.72,12814.81,511.91,12163.08,11074.07,1089.00,28.01,202.82,204.47 -13036.72,12517.24,519.48,11873.08,10586.21,1286.87,104.08,202.82,204.47 -12756.72,12000.00,756.72,11593.08,10535.71,1057.36,104.37,202.82,204.47 -12486.72,11629.63,857.09,11323.08,10370.37,952.71,275.30,202.82,207.17 -12196.72,11448.28,748.45,11033.08,10172.41,860.66,276.10,202.82,207.17 -11926.72,11148.15,778.57,10763.08,10111.11,651.96,276.84,202.82,207.17 -11656.72,10740.74,915.98,10493.08,9740.74,752.33,426.30,202.82,209.52 -11366.72,10379.31,987.41,10203.08,9862.07,341.01,427.53,202.82,209.52 -11096.72,10111.11,985.61,9933.08,9481.48,451.59,428.67,202.82,209.52 -10826.72,9814.81,1011.91,9663.08,8629.63,1033.45,557.53,202.82,211.55 -10536.72,9689.66,847.07,9373.08,9034.48,338.59,559.13,202.82,211.55 -10266.72,9407.41,859.31,9103.08,8481.48,621.59,560.61,202.82,211.55 -9996.72,9000.00,996.72,8833.08,8296.30,536.78,657.50,202.82,213.06 -9706.72,8758.62,948.10,8543.08,8206.90,336.18,659.37,202.82,213.06 -9436.72,8703.70,733.02,8273.08,7740.74,532.33,661.11,202.82,213.06 -9166.72,8444.44,722.28,8003.08,7703.70,299.37,723.72,202.82,214.02 -8886.72,8000.00,886.72,7723.08,7357.14,365.93,725.70,202.82,214.02 -8616.72,7555.56,1061.17,7453.08,6851.85,601.22,727.60,202.82,214.02 -8346.72,6592.59,1754.13,7183.08,6962.96,220.11,769.31,202.82,214.65 -8066.72,6428.57,1638.15,6903.08,7000.00,-96.92,771.40,202.82,214.65 -7796.72,6407.41,1389.31,6633.08,6518.52,114.56,773.41,202.82,214.65 -7536.72,6000.00,1536.72,6373.08,6115.38,257.69,791.83,202.82,214.91 -7246.72,5689.66,1557.07,6083.08,5517.24,565.83,794.04,202.82,214.91 -6976.72,5518.52,1458.20,5813.08,5370.37,442.71,774.39,202.82,214.57 -6686.72,5517.24,1169.48,5523.08,5379.31,143.77,776.53,202.82,214.57 -6416.72,5000.00,1416.72,5253.08,5296.30,-43.22,778.53,202.82,214.57 -6146.72,4222.22,1924.50,4983.08,4925.93,57.15,778.51,202.82,214.54 -5856.72,4551.72,1305.00,4693.08,4827.59,-134.51,780.65,202.82,214.54 -5576.72,4857.14,719.58,4413.08,4428.57,-15.50,782.71,202.82,214.54 -5306.72,4037.04,1269.69,4143.08,3962.96,180.11,783.74,202.82,214.52 -5026.72,3321.43,1705.29,3863.08,3607.14,255.93,785.81,202.82,214.52 -4756.72,2962.96,1793.76,3593.08,3148.15,444.93,787.80,202.82,214.52 -4486.72,3111.11,1375.61,3323.08,3000.00,323.08,779.91,202.82,214.36 -4196.72,2724.14,1472.58,3033.08,2689.66,343.42,782.01,202.82,214.36 -3926.72,1666.67,2260.06,2763.08,2296.30,466.78,783.98,202.82,214.36 -3656.72,629.63,3027.09,2493.08,2000.00,493.08,759.86,202.82,213.95 -3376.72,1678.57,1698.15,2213.08,1678.57,534.50,761.82,202.82,213.95 -3116.72,1461.54,1655.18,1953.08,1576.92,376.15,763.65,202.82,213.95 -2856.72,153.85,2702.88,1693.08,461.54,1231.54,754.83,202.82,213.78 -2576.72,250.00,2326.72,1413.08,-142.86,1555.93,756.77,202.82,213.78 -2306.72,296.30,2010.43,1143.08,629.63,513.45,758.63,202.82,213.78 -2036.72,-259.26,2295.98,873.08,259.26,613.82,754.33,202.82,213.69 -1746.72,-448.28,2195.00,583.08,34.48,548.59,756.32,202.82,213.69 -1476.72,37.04,1439.69,313.08,0.00,313.08,758.17,202.82,213.69 -1216.72,0.00,1216.72,53.08,-38.46,91.54,751.14,202.82,213.55 -926.72,0.00,926.72,0.00,0.00,0.00,753.10,202.82,213.55 -666.72,0.00,666.72,0.00,0.00,0.00,754.85,202.82,213.55 -396.72,0.00,396.72,0.00,0.00,0.00,748.79,202.82,213.42 -106.72,0.00,106.72,0.00,0.00,0.00,750.73,202.82,213.42 -0.00,0.00,0.00,0.00,0.00,0.00,752.53,202.82,213.42 -0.00,0.00,0.00,0.00,0.00,0.00,743.89,202.82,213.26 -0.00,0.00,0.00,0.00,0.00,0.00,745.80,202.82,213.26 -0.00,0.00,0.00,0.00,0.00,0.00,747.51,202.82,213.26 -0.00,0.00,0.00,0.00,0.00,0.00,740.56,202.82,213.12 -0.00,0.00,0.00,0.00,0.00,0.00,742.44,202.82,213.12 -0.00,0.00,0.00,0.00,0.00,0.00,744.13,202.82,213.12 -0.00,0.00,0.00,0.00,0.00,0.00,736.58,202.82,212.97 -0.00,0.00,0.00,0.00,0.00,0.00,738.69,202.82,212.97 -0.00,0.00,0.00,0.00,0.00,0.00,731.15,202.82,212.83 -0.00,0.00,0.00,0.00,0.00,0.00,732.92,202.82,212.83 -0.00,0.00,0.00,0.00,0.00,0.00,734.62,202.82,212.83 -0.00,0.00,0.00,0.00,0.00,0.00,726.35,202.82,212.67 -0.00,0.00,0.00,0.00,0.00,0.00,728.09,202.82,212.67 -0.00,0.00,0.00,0.00,0.00,0.00,729.70,202.82,212.67 -0.00,0.00,0.00,0.00,0.00,0.00,726.14,202.82,212.59 -0.00,0.00,0.00,0.00,0.00,0.00,727.86,202.82,212.59 -0.00,0.00,0.00,0.00,0.00,0.00,729.52,202.82,212.59 -0.00,0.00,0.00,0.00,0.00,0.00,729.23,202.82,212.56 -0.00,0.00,0.00,0.00,0.00,0.00,730.95,202.82,212.56 -0.00,0.00,0.00,0.00,0.00,0.00,732.54,202.82,212.56 -0.00,0.00,0.00,0.00,0.00,0.00,735.69,202.82,212.58 -0.00,0.00,0.00,0.00,0.00,0.00,737.41,202.82,212.58 -0.00,0.00,0.00,0.00,0.00,0.00,739.07,202.82,212.58 -0.00,0.00,0.00,0.00,0.00,0.00,728.45,202.82,212.39 -0.00,0.00,0.00,0.00,0.00,0.00,730.20,202.82,212.39 -0.00,0.00,0.00,0.00,0.00,0.00,731.83,202.82,212.39 -0.00,0.00,0.00,0.00,0.00,0.00,722.68,202.82,212.22 -0.00,0.00,0.00,0.00,0.00,0.00,724.34,202.82,212.22 -0.00,0.00,0.00,0.00,0.00,0.00,725.94,202.82,212.22 -0.00,0.00,0.00,0.00,0.00,0.00,726.79,202.82,212.20 -0.00,0.00,0.00,0.00,0.00,0.00,728.44,202.82,212.20 -0.00,0.00,0.00,0.00,0.00,0.00,730.04,202.82,212.20 -0.00,0.00,0.00,0.00,0.00,0.00,716.60,202.82,211.97 -0.00,0.00,0.00,0.00,0.00,0.00,718.27,202.82,211.97 -0.00,0.00,0.00,0.00,0.00,0.00,719.77,202.82,211.97 -0.00,0.00,0.00,0.00,0.00,0.00,718.81,202.82,211.93 -0.00,0.00,0.00,0.00,0.00,0.00,720.42,202.82,211.93 -0.00,0.00,0.00,0.00,0.00,0.00,721.97,202.82,211.93 -0.00,0.00,0.00,0.00,0.00,0.00,725.04,202.82,211.95 -0.00,0.00,0.00,0.00,0.00,0.00,726.65,202.82,211.95 -0.00,0.00,0.00,0.00,0.00,0.00,728.15,202.82,211.95 -0.00,0.00,0.00,0.00,0.00,0.00,730.89,202.82,211.97 -0.00,0.00,0.00,0.00,0.00,0.00,732.57,202.82,211.97 -0.00,0.00,0.00,0.00,0.00,0.00,734.12,202.82,211.97 -0.00,0.00,0.00,0.00,0.00,0.00,731.67,202.82,211.91 -0.00,0.00,0.00,0.00,0.00,0.00,733.27,202.82,211.91 -0.00,0.00,0.00,0.00,0.00,0.00,734.82,202.82,211.91 -0.00,0.00,0.00,0.00,0.00,0.00,736.53,202.82,211.91 -0.00,0.00,0.00,0.00,0.00,0.00,738.14,202.82,211.91 -0.00,0.00,0.00,0.00,0.00,0.00,739.63,202.82,211.91 -0.00,0.00,0.00,0.00,0.00,0.00,738.30,202.82,211.87 -0.00,0.00,0.00,0.00,0.00,0.00,739.89,202.82,211.87 -0.00,0.00,0.00,0.00,0.00,0.00,741.43,202.82,211.87 -0.00,0.00,0.00,0.00,0.00,0.00,739.05,202.82,211.81 -0.00,0.00,0.00,0.00,0.00,0.00,740.64,202.82,211.81 -0.00,0.00,0.00,0.00,0.00,0.00,742.17,202.82,211.81 -0.00,0.00,0.00,0.00,0.00,0.00,745.34,202.82,211.83 -0.00,0.00,0.00,0.00,0.00,0.00,746.93,202.82,211.83 -0.00,0.00,0.00,0.00,0.00,0.00,754.65,202.82,211.93 -0.00,0.00,0.00,0.00,0.00,0.00,756.31,202.82,211.93 -0.00,0.00,0.00,0.00,0.00,0.00,757.80,202.82,211.93 -0.00,0.00,0.00,0.00,0.00,0.00,755.74,202.82,211.88 -0.00,0.00,0.00,0.00,0.00,0.00,757.34,202.82,211.88 -0.00,0.00,0.00,0.00,0.00,0.00,758.88,202.82,211.88 -0.00,0.00,0.00,0.00,0.00,0.00,752.91,202.82,211.76 -0.00,0.00,0.00,0.00,0.00,0.00,754.54,202.82,211.76 -0.00,0.00,0.00,0.00,0.00,0.00,756.06,202.82,211.76 -0.00,0.00,0.00,0.00,0.00,0.00,761.13,202.82,211.81 -0.00,0.00,0.00,0.00,0.00,0.00,762.72,202.82,211.81 -0.00,0.00,0.00,0.00,0.00,0.00,764.19,202.82,211.81 -0.00,0.00,0.00,0.00,0.00,0.00,766.63,202.82,211.83 -0.00,0.00,0.00,0.00,0.00,0.00,768.28,202.82,211.83 -0.00,0.00,0.00,0.00,0.00,0.00,769.81,202.82,211.83 -0.00,0.00,0.00,0.00,0.00,0.00,758.28,202.82,211.62 -0.00,0.00,0.00,0.00,0.00,0.00,759.83,202.82,211.62 -0.00,0.00,0.00,0.00,0.00,0.00,761.33,202.82,211.62 -0.00,0.00,0.00,0.00,0.00,0.00,765.11,202.82,211.66 -0.00,0.00,0.00,0.00,0.00,0.00,766.72,202.82,211.66 -0.00,0.00,0.00,0.00,0.00,0.00,768.23,202.82,211.66 -0.00,0.00,0.00,0.00,0.00,0.00,770.16,202.82,211.67 -0.00,0.00,0.00,0.00,0.00,0.00,771.72,202.82,211.67 -0.00,0.00,0.00,0.00,0.00,0.00,773.51,202.82,211.67 -0.00,0.00,0.00,0.00,0.00,0.00,776.33,202.82,211.69 -0.00,0.00,0.00,0.00,0.00,0.00,777.89,202.82,211.69 -0.00,0.00,0.00,0.00,0.00,0.00,779.35,202.82,211.69 -0.00,0.00,0.00,0.00,0.00,0.00,769.77,202.82,211.51 -0.00,0.00,0.00,0.00,0.00,0.00,771.30,202.82,211.51 -0.00,0.00,0.00,0.00,0.00,0.00,772.73,202.82,211.51 -0.00,0.00,0.00,0.00,0.00,0.00,771.01,202.82,211.46 -0.00,0.00,0.00,0.00,0.00,0.00,772.58,202.82,211.46 -0.00,0.00,0.00,0.00,0.00,0.00,774.00,202.82,211.46 -0.00,0.00,0.00,0.00,0.00,0.00,773.48,202.82,211.43 -0.00,0.00,0.00,0.00,0.00,0.00,775.00,202.82,211.43 -0.00,0.00,0.00,0.00,0.00,0.00,776.41,202.82,211.43 -0.00,0.00,0.00,0.00,0.00,0.00,776.84,202.82,211.41 -0.00,0.00,0.00,0.00,0.00,0.00,778.41,202.82,211.41 -0.00,0.00,0.00,0.00,0.00,0.00,779.87,202.82,211.41 -0.00,0.00,0.00,0.00,0.00,0.00,793.10,202.82,211.60 -0.00,0.00,0.00,0.00,0.00,0.00,794.64,202.82,211.60 -0.00,0.00,0.00,0.00,0.00,0.00,803.07,202.82,211.71 -0.00,0.00,0.00,0.00,0.00,0.00,804.63,202.82,211.71 -0.00,0.00,0.00,0.00,0.00,0.00,806.15,202.82,211.71 -0.00,0.00,0.00,0.00,0.00,0.00,809.89,202.82,211.75 -0.00,0.00,0.00,0.00,0.00,0.00,811.46,202.82,211.75 -0.00,0.00,0.00,0.00,0.00,0.00,812.93,202.82,211.75 -0.00,0.00,0.00,0.00,0.00,0.00,817.16,202.82,211.79 -0.00,0.00,0.00,0.00,0.00,0.00,818.80,202.82,211.79 -0.00,0.00,0.00,0.00,0.00,0.00,820.27,202.82,211.79 -0.00,0.00,0.00,0.00,0.00,0.00,809.02,202.82,211.59 -0.00,0.00,0.00,0.00,0.00,0.00,810.57,202.82,211.59 -0.00,0.00,0.00,0.00,0.00,0.00,812.00,202.82,211.59 -0.00,0.00,0.00,0.00,0.00,0.00,806.60,202.82,211.48 -0.00,0.00,0.00,0.00,0.00,0.00,808.13,202.82,211.48 -0.00,0.00,0.00,0.00,0.00,0.00,809.55,202.82,211.48 -0.00,0.00,0.00,0.00,0.00,0.00,815.33,202.82,211.55 -0.00,0.00,0.00,0.00,0.00,0.00,816.87,202.82,211.55 -0.00,0.00,0.00,0.00,0.00,0.00,818.36,202.82,211.55 -0.00,0.00,0.00,0.00,0.00,0.00,819.01,202.82,211.54 -0.00,0.00,0.00,0.00,0.00,0.00,820.60,202.82,211.54 -0.00,0.00,0.00,0.00,0.00,0.00,822.03,202.82,211.54 -0.00,0.00,0.00,0.00,0.00,0.00,822.42,202.82,211.52 -0.00,0.00,0.00,0.00,0.00,0.00,823.96,202.82,211.52 -0.00,0.00,0.00,0.00,0.00,0.00,825.38,202.82,211.52 -0.00,0.00,0.00,0.00,0.00,0.00,828.10,202.82,211.54 -0.00,0.00,0.00,0.00,0.00,0.00,829.64,202.82,211.54 -0.00,0.00,0.00,0.00,0.00,0.00,831.07,202.82,211.54 -0.00,0.00,0.00,0.00,0.00,0.00,839.37,202.82,211.65 -0.00,0.00,0.00,0.00,0.00,0.00,840.93,202.82,211.65 -0.00,0.00,0.00,0.00,0.00,0.00,842.43,202.82,211.65 -0.00,0.00,0.00,0.00,0.00,0.00,851.52,202.82,211.77 -0.00,0.00,0.00,0.00,0.00,0.00,853.10,202.82,211.77 -0.00,0.00,0.00,0.00,0.00,0.00,854.56,202.82,211.77 -0.00,0.00,0.00,0.00,0.00,0.00,855.09,202.82,211.75 -0.00,0.00,0.00,0.00,0.00,0.00,856.73,202.82,211.75 -0.00,0.00,0.00,0.00,0.00,0.00,858.25,202.82,211.75 -0.00,0.00,0.00,0.00,0.00,0.00,851.58,202.82,211.62 -0.00,0.00,0.00,0.00,0.00,0.00,853.14,202.82,211.62 -0.00,0.00,0.00,0.00,0.00,0.00,854.63,202.82,211.62 -0.00,0.00,0.00,0.00,0.00,0.00,856.92,202.82,211.64 -0.00,0.00,0.00,0.00,0.00,0.00,858.47,202.82,211.64 -0.00,0.00,0.00,0.00,0.00,0.00,859.92,202.82,211.64 -0.00,0.00,0.00,0.00,0.00,0.00,852.34,202.82,211.49 -0.00,0.00,0.00,0.00,0.00,0.00,853.87,202.82,211.49 -0.00,0.00,0.00,0.00,0.00,0.00,855.34,202.82,211.49 -0.00,0.00,0.00,0.00,0.00,0.00,848.15,202.82,211.36 -0.00,0.00,0.00,0.00,0.00,0.00,849.66,202.82,211.36 -0.00,0.00,0.00,0.00,0.00,0.00,851.06,202.82,211.36 -0.00,0.00,0.00,0.00,0.00,0.00,857.49,202.82,211.44 -0.00,0.00,0.00,0.00,0.00,0.00,858.95,202.82,211.44 -0.00,0.00,0.00,0.00,0.00,0.00,860.42,202.82,211.44 -0.00,0.00,0.00,0.00,0.00,0.00,852.11,202.82,211.28 -0.00,0.00,0.00,0.00,0.00,0.00,853.60,202.82,211.28 -0.00,0.00,0.00,0.00,0.00,0.00,854.99,202.82,211.28 -0.00,0.00,0.00,0.00,0.00,0.00,857.50,202.82,211.30 -0.00,0.00,0.00,0.00,0.00,0.00,859.00,202.82,211.30 -0.00,0.00,0.00,0.00,0.00,0.00,860.71,202.82,211.30 -0.00,0.00,0.00,0.00,0.00,0.00,860.20,202.82,211.27 -0.00,0.00,0.00,0.00,0.00,0.00,861.69,202.82,211.27 -0.00,0.00,0.00,0.00,0.00,0.00,865.46,202.82,211.31 -0.00,0.00,0.00,0.00,0.00,0.00,866.96,202.82,211.31 -0.00,0.00,0.00,0.00,0.00,0.00,868.35,202.82,211.31 -0.00,0.00,0.00,0.00,0.00,0.00,866.15,202.82,211.25 -0.00,0.00,0.00,0.00,0.00,0.00,867.69,202.82,211.25 -0.00,0.00,0.00,0.00,0.00,0.00,869.07,202.82,211.25 -0.00,0.00,0.00,0.00,0.00,0.00,864.37,202.82,211.15 -0.00,0.00,0.00,0.00,0.00,0.00,865.84,202.82,211.15 -0.00,0.00,0.00,0.00,0.00,0.00,867.26,202.82,211.15 -0.00,0.00,0.00,0.00,0.00,0.00,873.10,202.82,211.22 -0.00,0.00,0.00,0.00,0.00,0.00,874.58,202.82,211.22 -0.00,0.00,0.00,0.00,0.00,0.00,876.01,202.82,211.22 -0.00,0.00,0.00,0.00,0.00,0.00,878.60,202.82,211.24 -0.00,0.00,0.00,0.00,0.00,0.00,880.08,202.82,211.24 -0.00,0.00,0.00,0.00,0.00,0.00,881.51,202.82,211.24 -0.00,0.00,0.00,0.00,0.00,0.00,880.15,202.82,211.20 -0.00,0.00,0.00,0.00,0.00,0.00,881.63,202.82,211.20 -0.00,0.00,0.00,0.00,0.00,0.00,883.05,202.82,211.20 -0.00,0.00,0.00,0.00,0.00,0.00,879.51,202.82,211.12 -0.00,0.00,0.00,0.00,0.00,0.00,880.97,202.82,211.12 -0.00,0.00,0.00,0.00,0.00,0.00,882.38,202.82,211.12 -0.00,0.00,0.00,0.00,0.00,0.00,884.13,202.82,211.13 -0.00,0.00,0.00,0.00,0.00,0.00,885.60,202.82,211.13 -0.00,0.00,0.00,0.00,0.00,0.00,886.96,202.82,211.13 -0.00,0.00,0.00,0.00,0.00,0.00,888.64,202.82,211.13 -0.00,0.00,0.00,0.00,0.00,0.00,890.15,202.82,211.13 -0.00,0.00,0.00,0.00,0.00,0.00,891.57,202.82,211.13 -0.00,0.00,0.00,0.00,0.00,0.00,887.23,202.82,211.04 -0.00,0.00,0.00,0.00,0.00,0.00,888.68,202.82,211.04 -0.00,0.00,0.00,0.00,0.00,0.00,890.03,202.82,211.04 -0.00,0.00,0.00,0.00,0.00,0.00,893.90,202.82,211.08 -0.00,0.00,0.00,0.00,0.00,0.00,895.41,202.82,211.08 -0.00,0.00,0.00,0.00,0.00,0.00,896.76,202.82,211.08 -0.00,0.00,0.00,0.00,0.00,0.00,903.00,202.82,211.16 -0.00,0.00,0.00,0.00,0.00,0.00,904.47,202.82,211.16 -0.00,0.00,0.00,0.00,0.00,0.00,905.83,202.82,211.16 -0.00,0.00,0.00,0.00,0.00,0.00,916.75,202.82,211.31 -0.00,0.00,0.00,0.00,0.00,0.00,918.24,202.82,211.31 -0.00,0.00,0.00,0.00,0.00,0.00,919.63,202.82,211.31 -0.00,0.00,0.00,0.00,0.00,0.00,915.93,202.82,211.23 -0.00,0.00,0.00,0.00,0.00,0.00,917.41,202.82,211.23 -0.00,0.00,0.00,0.00,0.00,0.00,918.79,202.82,211.23 -0.00,0.00,0.00,0.00,0.00,0.00,922.57,202.82,211.26 -0.00,0.00,0.00,0.00,0.00,0.00,924.06,202.82,211.26 -0.00,0.00,0.00,0.00,0.00,0.00,925.45,202.82,211.26 -0.00,0.00,0.00,0.00,0.00,0.00,925.71,202.82,211.25 -0.00,0.00,0.00,0.00,0.00,0.00,927.19,202.82,211.25 -0.00,0.00,0.00,0.00,0.00,0.00,928.57,202.82,211.25 -0.00,0.00,0.00,0.00,0.00,0.00,931.68,202.82,211.27 -0.00,0.00,0.00,0.00,0.00,0.00,933.17,202.82,211.27 -0.00,0.00,0.00,0.00,0.00,0.00,934.61,202.82,211.27 -0.00,0.00,0.00,0.00,0.00,0.00,939.13,202.82,211.32 -0.00,0.00,0.00,0.00,0.00,0.00,940.63,202.82,211.32 -0.00,0.00,0.00,0.00,0.00,0.00,942.08,202.82,211.32 -0.00,0.00,0.00,0.00,0.00,0.00,944.01,202.82,211.33 -0.00,0.00,0.00,0.00,0.00,0.00,945.56,202.82,211.33 -0.00,0.00,0.00,0.00,0.00,0.00,946.96,202.82,211.33 -0.00,0.00,0.00,0.00,0.00,0.00,958.43,202.82,211.49 -0.00,0.00,0.00,0.00,0.00,0.00,959.96,202.82,211.49 -0.00,0.00,0.00,0.00,0.00,0.00,961.38,202.82,211.49 -0.00,0.00,0.00,0.00,0.00,0.00,962.93,202.82,211.49 -0.00,0.00,0.00,0.00,0.00,0.00,964.46,202.82,211.49 -0.00,0.00,0.00,0.00,0.00,0.00,965.88,202.82,211.49 -0.00,0.00,0.00,0.00,0.00,0.00,959.81,202.82,211.37 -0.00,0.00,0.00,0.00,0.00,0.00,961.31,202.82,211.37 -0.00,0.00,0.00,0.00,0.00,0.00,962.71,202.82,211.37 -0.00,0.00,0.00,0.00,0.00,0.00,967.95,202.82,211.43 -0.00,0.00,0.00,0.00,0.00,0.00,969.47,202.82,211.43 -0.00,0.00,0.00,0.00,0.00,0.00,970.88,202.82,211.43 -0.00,0.00,0.00,0.00,0.00,0.00,967.48,202.82,211.36 -0.00,0.00,0.00,0.00,0.00,0.00,968.98,202.82,211.36 -0.00,0.00,0.00,0.00,0.00,0.00,970.19,202.82,211.35 -0.00,0.00,0.00,0.00,0.00,0.00,971.75,202.82,211.35 -0.00,0.00,0.00,0.00,0.00,0.00,973.20,202.82,211.35 -0.00,0.00,0.00,0.00,0.00,0.00,976.89,202.82,211.38 -0.00,0.00,0.00,0.00,0.00,0.00,978.41,202.82,211.38 -0.00,0.00,0.00,0.00,0.00,0.00,979.81,202.82,211.38 -0.00,0.00,0.00,0.00,0.00,0.00,982.57,202.82,211.40 -0.00,0.00,0.00,0.00,0.00,0.00,984.13,202.82,211.40 -0.00,0.00,0.00,0.00,0.00,0.00,985.54,202.82,211.40 -0.00,0.00,0.00,0.00,0.00,0.00,987.12,202.82,211.41 -0.00,0.00,0.00,0.00,0.00,0.00,988.69,202.82,211.41 -0.00,0.00,0.00,0.00,0.00,0.00,990.10,202.82,211.41 -0.00,0.00,0.00,0.00,0.00,0.00,1011.32,202.82,211.72 -0.00,0.00,0.00,0.00,0.00,0.00,1012.89,202.82,211.72 -0.00,0.00,0.00,0.00,0.00,0.00,1014.40,202.82,211.72 -0.00,0.00,0.00,0.00,0.00,0.00,1027.33,202.82,211.90 -0.00,0.00,0.00,0.00,0.00,0.00,1028.93,202.82,211.90 -0.00,0.00,0.00,0.00,0.00,0.00,1030.47,202.82,211.90 -0.00,0.00,0.00,0.00,0.00,0.00,1027.92,202.82,211.84 -0.00,0.00,0.00,0.00,0.00,0.00,1029.51,202.82,211.84 -0.00,0.00,0.00,0.00,0.00,0.00,1031.04,202.82,211.84 -0.00,0.00,0.00,0.00,0.00,0.00,1037.90,202.82,211.92 -0.00,0.00,0.00,0.00,0.00,0.00,1039.50,202.82,211.92 -0.00,0.00,0.00,0.00,0.00,0.00,1041.05,202.82,211.92 -0.00,0.00,0.00,0.00,0.00,0.00,1042.22,202.82,211.92 -0.00,0.00,0.00,0.00,0.00,0.00,1043.88,202.82,211.92 -0.00,0.00,0.00,0.00,0.00,0.00,1045.43,202.82,211.92 -0.00,0.00,0.00,0.00,0.00,0.00,1043.66,202.82,211.86 -0.00,0.00,0.00,0.00,0.00,0.00,1045.31,202.82,211.86 -0.00,0.00,0.00,0.00,0.00,0.00,1046.79,202.82,211.86 -0.00,0.00,0.00,0.00,0.00,0.00,1053.63,202.82,211.95 -0.00,0.00,0.00,0.00,0.00,0.00,1055.24,202.82,211.95 -0.00,0.00,0.00,0.00,0.00,0.00,1056.73,202.82,211.95 -0.00,0.00,0.00,0.00,0.00,0.00,1056.27,202.82,211.92 -0.00,0.00,0.00,0.00,0.00,0.00,1057.87,202.82,211.92 -0.00,0.00,0.00,0.00,0.00,0.00,1059.42,202.82,211.92 -0.00,0.00,0.00,0.00,0.00,0.00,1054.80,202.82,211.82 --300.00,0.00,-300.00,-300.00,0.00,-300.00,0.00,211.82,211.82 --570.00,0.00,-570.00,-570.00,0.00,-570.00,0.00,211.82,211.94 --860.00,0.00,-860.00,-860.00,0.00,-860.00,0.00,211.82,211.94 --1130.00,0.00,-1130.00,-1130.00,0.00,-1130.00,0.00,211.82,211.94 --1380.00,0.00,-1380.00,-1380.00,0.00,-1380.00,0.00,211.82,211.94 --1670.00,0.00,-1670.00,-1670.00,0.00,-1670.00,0.00,211.82,211.94 --1940.00,-37.04,-1902.96,-1940.00,-111.11,-1828.89,0.00,211.82,211.94 --2210.00,-148.15,-2061.85,-2210.00,-1074.07,-1135.93,0.00,211.82,211.89 --2500.00,-413.79,-2086.21,-2500.00,-620.69,-1879.31,0.00,211.82,211.89 --2780.00,-1392.86,-1387.14,-2780.00,71.43,-2851.43,0.00,211.82,211.89 --3050.00,-2518.52,-531.48,-3050.00,-1296.30,-1753.70,0.00,211.82,211.64 --3340.00,-2482.76,-857.24,-3340.00,-1241.38,-2098.62,0.00,211.82,211.64 --3610.00,-1148.15,-2461.85,-3610.00,-777.78,-2832.22,0.00,211.82,211.64 --3890.00,-1285.71,-2604.29,-3890.00,-2000.00,-1890.00,0.00,211.82,211.51 --4180.00,-3034.48,-1145.52,-4180.00,-1655.17,-2524.83,0.00,211.82,211.51 --4460.00,-4035.71,-424.29,-4460.00,-1857.14,-2602.86,0.00,211.82,211.51 --4730.00,-3518.52,-1211.48,-4730.00,-2000.00,-2730.00,0.00,211.82,211.39 --5030.00,-2300.00,-2730.00,-5030.00,-2500.00,-2530.00,0.00,211.82,211.39 --5300.00,-2444.44,-2855.56,-5300.00,-2925.93,-2374.07,0.00,211.82,211.39 --5570.00,-3592.59,-1977.41,-5570.00,-3185.19,-2384.81,0.00,211.82,211.51 --5870.00,-3200.00,-2670.00,-5870.00,-3300.00,-2570.00,0.00,211.82,211.51 --6140.00,-3333.33,-2806.67,-6140.00,-3629.63,-2510.37,0.00,211.82,211.51 --6420.00,-4178.57,-2241.43,-6420.00,-4071.43,-2348.57,0.00,211.82,211.80 --6720.00,-4466.67,-2253.33,-6720.00,-4233.33,-2486.67,0.00,211.82,211.80 --7000.00,-4642.86,-2357.14,-7000.00,-4464.29,-2535.71,0.00,211.82,212.06 --7290.00,-5000.00,-2290.00,-7290.00,-4827.59,-2462.41,0.00,211.82,212.06 --7570.00,-5464.29,-2105.71,-7570.00,-5178.57,-2391.43,0.00,211.82,212.06 --7850.00,-5500.00,-2350.00,-7850.00,-5428.57,-2421.43,0.00,211.82,212.16 --8140.00,-5655.17,-2484.83,-8140.00,-5793.10,-2346.90,0.00,211.82,212.16 --8410.00,-6074.07,-2335.93,-8410.00,-6148.15,-2261.85,0.00,211.82,212.16 --8690.00,-6571.43,-2118.57,-8690.00,-6607.14,-2082.86,0.00,211.82,212.26 --8980.00,-6965.52,-2014.48,-8980.00,-6724.14,-2255.86,0.00,211.82,212.26 --9250.00,-7296.30,-1953.70,-9250.00,-6851.85,-2398.15,0.00,211.82,212.26 --9530.00,-7642.86,-1887.14,-9530.00,-6821.43,-2708.57,0.00,211.82,212.61 --9820.00,-7896.55,-1923.45,-9820.00,-7379.31,-2440.69,0.00,211.82,212.61 --10100.00,-7857.14,-2242.86,-10100.00,-7785.71,-2314.29,0.00,211.82,212.61 --10430.00,-7787.88,-2642.12,-10430.00,-8000.00,-2430.00,569.24,211.82,213.11 --10730.00,-8400.00,-2330.00,-10730.00,-8266.67,-2463.33,569.48,211.82,213.11 --11000.00,-9111.11,-1888.89,-11000.00,-8444.44,-2555.56,619.03,211.82,213.89 --11290.00,-9517.24,-1772.76,-11290.00,-8413.79,-2876.21,619.40,211.82,213.89 --11570.00,-9607.14,-1962.86,-11570.00,-8250.00,-3320.00,619.77,211.82,213.89 --11850.00,-10071.43,-1778.57,-11850.00,-8750.00,-3100.00,651.41,211.82,214.38 --12140.00,-10827.59,-1312.41,-12140.00,-9517.24,-2622.76,651.87,211.82,214.38 --12420.00,-11107.14,-1312.86,-12420.00,-9714.29,-2705.71,652.33,211.82,214.38 --12700.00,-11250.00,-1450.00,-12700.00,-9642.86,-3057.14,665.07,211.82,214.58 --12990.00,-11413.79,-1576.21,-12990.00,-9241.38,-3748.62,665.57,211.82,214.58 --13270.00,-11214.29,-2055.71,-13270.00,-10000.00,-3270.00,666.06,211.82,214.58 --13550.00,-11928.57,-1621.43,-13550.00,-10678.57,-2871.43,677.85,211.82,214.75 --13840.00,-12827.59,-1012.41,-13840.00,-11103.45,-2736.55,678.39,211.82,214.75 --14120.00,-12392.86,-1727.14,-14120.00,-11035.71,-3084.29,678.91,211.82,214.75 --14400.00,-12321.43,-2078.57,-14400.00,-10857.14,-3542.86,663.44,211.82,214.50 --14690.00,-12931.03,-1758.97,-14690.00,-11379.31,-3310.69,663.93,211.82,214.50 --14960.00,-13666.67,-1293.33,-14960.00,-12222.22,-2737.78,639.36,211.82,214.11 --15250.00,-14000.00,-1250.00,-15250.00,-12344.83,-2905.17,639.78,211.82,214.11 --15520.00,-14148.15,-1371.85,-15520.00,-12518.52,-3001.48,640.17,211.82,214.11 --15800.00,-13892.86,-1907.14,-15800.00,-12428.57,-3371.43,579.09,211.82,213.13 --16100.00,-14266.67,-1833.33,-16100.00,-12933.33,-3166.67,579.33,211.82,213.13 --16380.00,-14500.00,-1880.00,-16380.00,-13321.43,-3058.57,579.57,211.82,213.13 --16660.00,-14607.14,-2052.86,-16660.00,-14000.00,-2660.00,0.00,211.82,211.72 --16960.00,-14400.00,-2560.00,-16960.00,-14266.67,-2693.33,0.00,211.82,211.72 --17240.00,-15035.71,-2204.29,-17240.00,-14535.71,-2704.29,0.00,211.82,211.72 --17520.00,-15642.86,-1877.14,-17520.00,-15000.00,-2520.00,382.87,211.82,210.02 --17820.00,-16000.00,-1820.00,-17820.00,-14766.67,-3053.33,-113.99,211.82,210.02 --18100.00,-15928.57,-2171.43,-18100.00,-15321.43,-2778.57,-114.31,211.82,210.02 --18380.00,-15785.71,-2594.29,-18380.00,-15714.29,-2665.71,-244.83,211.82,207.95 --18680.00,-16433.33,-2246.67,-18680.00,-16066.67,-2613.33,-245.56,211.82,207.95 --18960.00,-17071.43,-1888.57,-18960.00,-16178.57,-2781.43,-389.37,211.82,205.69 --19250.00,-17551.72,-1698.28,-19250.00,-16827.59,-2422.41,-390.49,211.82,205.69 --19530.00,-17178.57,-2351.43,-19530.00,-17035.71,-2494.29,-391.57,211.82,205.69 --19810.00,-16642.86,-3167.14,-19810.00,-17035.71,-2774.29,-531.00,211.82,203.50 --20110.00,-17000.00,-3110.00,-20110.00,-17566.67,-2543.33,-532.57,211.82,203.50 --20390.00,-17821.43,-2568.57,-20390.00,-18178.57,-2211.43,-534.04,211.82,203.50 --20670.00,-18142.86,-2527.14,-20670.00,-18178.57,-2491.43,-671.06,211.82,201.35 --20970.00,-18100.00,-2870.00,-20970.00,-18600.00,-2370.00,-673.04,211.82,201.35 --21250.00,-18214.29,-3035.71,-21250.00,-18678.57,-2571.43,-674.89,211.82,201.35 --21530.00,-18785.71,-2744.29,-21530.00,-19214.29,-2315.71,-811.61,211.82,199.22 --21830.00,-19400.00,-2430.00,-21830.00,-19266.67,-2563.33,-813.99,211.82,199.22 --22110.00,-19178.57,-2931.43,-22110.00,-20071.43,-2038.57,-816.22,211.82,199.22 --22390.00,-19428.57,-2961.43,-22390.00,-20178.57,-2211.43,-911.50,211.82,197.75 --22700.00,-19548.39,-3151.61,-22700.00,-20774.19,-1925.81,-914.25,211.82,197.75 --22456.55,-19321.43,-3135.12,-22980.00,-20785.71,-2194.29,-987.53,211.82,196.62 --22156.55,-19900.00,-2256.55,-22748.69,-20833.33,-1915.35,-990.40,211.82,196.62 --21866.55,-19310.34,-2556.20,-22458.69,-21413.79,-1044.89,-993.17,211.82,196.62 --21586.55,-19500.00,-2086.55,-22178.69,-22071.43,-107.26,-1042.10,211.82,195.89 --21286.55,-20300.00,-986.55,-21878.69,-21566.67,-312.02,-1045.11,211.82,195.89 --21006.55,-20357.14,-649.41,-21598.69,-21392.86,-205.83,-1047.92,211.82,195.89 --20726.55,-19285.71,-1440.83,-21318.69,-21321.43,2.74,-1074.99,211.82,195.51 --20426.55,-18333.33,-2093.22,-21018.69,-20766.67,-252.02,-1078.07,211.82,195.51 --20146.55,-18285.71,-1860.83,-20738.69,-19500.00,-1238.69,-1080.94,211.82,195.51 --19866.55,-18357.14,-1509.41,-20458.69,-20535.71,77.03,-1058.51,211.82,195.91 --19566.55,-18366.67,-1199.88,-20158.69,-19933.33,-225.35,-1061.52,211.82,195.91 --19286.55,-18142.86,-1143.69,-19878.69,-19607.14,-271.54,-1006.80,211.82,196.82 --18986.55,-17233.33,-1753.22,-19578.69,-19200.00,-378.69,-1009.64,211.82,196.82 --18706.55,-16750.00,-1956.55,-19298.69,-19071.43,-227.26,-1012.28,211.82,196.82 --18426.55,-16892.86,-1533.69,-19018.69,-18821.43,-197.26,-891.53,211.82,198.77 --18126.55,-16933.33,-1193.22,-18718.69,-18033.33,-685.35,-894.00,211.82,198.77 --17846.55,-16785.71,-1060.83,-18438.69,-18142.86,-295.83,-896.30,211.82,198.77 --17566.55,-16321.43,-1245.12,-18158.69,-17714.29,-444.40,-687.20,211.82,202.12 --17266.55,-15800.00,-1466.55,-17858.69,-17566.67,-292.02,-689.04,211.82,202.12 --16986.55,-15678.57,-1307.98,-17578.69,-17035.71,-542.97,-690.75,211.82,202.12 --16696.55,-15586.21,-1110.34,-17288.69,-16482.76,-805.93,-368.84,211.82,207.24 --16396.55,-15433.33,-963.22,-16988.69,-16400.00,-588.69,-369.70,211.82,207.24 --16126.55,-15518.52,-608.03,-16718.69,-16444.44,-274.24,-370.48,211.82,207.24 --15846.55,-15428.57,-417.98,-16438.69,-16071.43,-367.26,46.58,211.82,213.86 --15546.55,-15000.00,-546.55,-16138.69,-14533.33,-1605.35,128.73,211.82,213.86 --15266.55,-14678.57,-587.98,-15858.69,-15000.00,-858.69,624.56,211.82,221.70 --14916.55,-14942.86,26.31,-15508.69,-15657.14,148.46,626.74,211.82,221.70 --14636.55,-15071.43,434.88,-15228.69,-13714.29,-1514.40,628.48,211.82,221.70 --14366.55,-14555.56,189.01,-14958.69,-13000.00,-1958.69,1134.40,211.82,229.68 --14066.55,-14300.00,233.45,-14658.69,-13266.67,-1392.02,1137.78,211.82,229.68 --13796.55,-14629.63,833.08,-14388.69,-13185.19,-1203.50,1140.82,211.82,229.68 --13516.55,-14714.29,1197.74,-14108.69,-12178.57,-1930.12,1593.48,211.82,236.80 --13226.55,-13551.72,325.17,-13818.69,-11655.17,-2163.51,1598.05,211.82,236.80 --12946.55,-13500.00,553.45,-13538.69,-11464.29,-2074.40,1602.45,211.82,236.80 --12666.55,-13750.00,1083.45,-13258.69,-11357.14,-1901.54,1933.07,211.82,241.96 --12366.55,-13400.00,1033.45,-12958.69,-10433.33,-2525.35,1938.77,211.82,241.96 --12096.55,-13370.37,1273.82,-12688.69,-9777.78,-2910.91,2119.14,211.82,244.73 --11806.55,-13620.69,1814.14,-12398.69,-10551.72,-1846.96,2125.16,211.82,244.73 --11526.55,-13000.00,1473.45,-12118.69,-9500.00,-2618.69,2130.96,211.82,244.73 --11256.55,-12259.26,1002.71,-11848.69,-8814.81,-3033.87,2145.39,211.82,244.87 --10956.55,-11966.67,1010.12,-11548.69,-8866.67,-2682.02,2151.64,211.82,244.87 --10676.55,-11892.86,1216.31,-11268.69,-9000.00,-2268.69,2157.47,211.82,244.87 --10406.55,-11814.81,1408.27,-10998.69,-8740.74,-2257.95,2044.98,211.82,243.00 --10106.55,-11500.00,1393.45,-10698.69,-7733.33,-2965.35,2050.88,211.82,243.00 --9836.55,-11296.30,1459.75,-10428.69,-7703.70,-2724.98,2056.18,211.82,243.00 --9556.55,-11392.86,1836.31,-10148.69,-8000.00,-2148.69,1851.24,211.82,239.67 --9266.55,-11000.00,1733.45,-9858.69,-8034.48,-1824.20,1856.32,211.82,239.67 --8996.55,-10370.37,1373.82,-9588.69,-7703.70,-1884.98,1861.06,211.82,239.67 --8716.55,-10035.71,1319.17,-9308.69,-6928.57,-2380.12,1581.46,211.82,235.17 --8426.55,-9758.62,1332.07,-9018.69,-6379.31,-2639.38,1585.72,211.82,235.17 --8146.55,-9357.14,1210.59,-8738.69,-6607.14,-2131.54,1589.84,211.82,235.17 --7876.55,-9074.07,1197.52,-8468.69,-6037.04,-2431.65,1267.64,211.82,230.01 --7576.55,-8766.67,1190.12,-8168.69,-5766.67,-2402.02,1271.08,211.82,230.01 --7306.55,-8333.33,1026.78,-7898.69,-5925.93,-1972.76,1274.17,211.82,230.01 --7026.55,-8035.71,1009.17,-7618.69,-5678.57,-1940.12,957.23,211.82,224.94 --6736.55,-7724.14,987.59,-7328.69,-5517.24,-1811.45,959.63,211.82,224.94 --6456.55,-7428.57,972.02,-7048.69,-5714.29,-1334.40,661.20,211.82,220.18 --6166.55,-6862.07,695.52,-6758.69,-5689.66,-1069.03,662.73,211.82,220.18 --5896.55,-5777.78,-118.77,-6488.69,-5481.48,-1007.21,664.15,211.82,220.18 --5626.55,-5185.19,-441.36,-6218.69,-4925.93,-1292.76,365.74,211.82,215.43 --5326.55,-5500.00,173.45,-5918.69,-4366.67,-1552.02,366.42,211.82,215.43 --5056.55,-5481.48,424.93,-5648.69,-4666.67,-982.02,367.04,211.82,215.43 --4786.55,-4666.67,-119.88,-5378.69,-4629.63,-749.06,0.00,211.82,211.29 --4496.55,-4034.48,-462.07,-5088.69,-3827.59,-1261.10,0.00,211.82,211.29 --4216.55,-3392.86,-823.69,-4808.69,-3571.43,-1237.26,0.00,211.82,211.29 --3946.55,-3000.00,-946.55,-4538.69,-3481.48,-1057.21,-103.07,211.82,207.98 --3656.55,-2724.14,-932.41,-4248.69,-3000.00,-1248.69,-242.55,211.82,207.98 --3386.55,-2481.48,-905.07,-3978.69,-2814.81,-1163.87,-243.20,211.82,207.98 --3116.55,-2037.04,-1079.51,-3708.69,-2740.74,-967.95,-414.29,211.82,205.28 --2826.55,-1586.21,-1240.34,-3418.69,-2448.28,-970.41,-415.48,211.82,205.28 --2546.55,-1035.71,-1510.83,-3138.69,-2178.57,-960.12,-416.63,211.82,205.28 --2276.55,-962.96,-1313.59,-2868.69,-2037.04,-831.65,-571.59,211.82,202.85 --1986.55,206.90,-2193.45,-2578.69,-1827.59,-751.10,-573.23,211.82,202.85 --1716.55,0.00,-1716.55,-2308.69,-1629.63,-679.06,-574.76,211.82,202.85 --1446.55,37.04,-1483.59,-2038.69,-1074.07,-964.61,-695.16,211.82,200.96 --1156.55,103.45,-1260.00,-1748.69,-1172.41,-576.27,-697.15,211.82,200.96 --886.55,0.00,-886.55,-1478.69,-333.33,-1145.35,-794.43,211.82,199.45 --596.55,34.48,-631.03,-1188.69,-103.45,-1085.24,-796.69,211.82,199.45 --326.55,0.00,-326.55,-918.69,-444.44,-474.24,-798.79,211.82,199.45 --56.55,0.00,-56.55,-648.69,185.19,-833.87,-875.86,211.82,198.27 -0.00,0.00,0.00,-358.69,413.79,-772.48,-878.34,211.82,198.27 -0.00,0.00,0.00,-88.69,-37.04,-51.65,-880.64,211.82,198.27 -0.00,37.04,-37.04,0.00,111.11,-111.11,-945.73,211.82,197.27 -0.00,0.00,0.00,0.00,0.00,0.00,-948.39,211.82,197.27 -0.00,0.00,0.00,0.00,0.00,0.00,-950.87,211.82,197.27 -0.00,0.00,0.00,0.00,0.00,0.00,-994.51,211.82,196.62 -0.00,0.00,0.00,0.00,0.00,0.00,-997.28,211.82,196.62 -0.00,0.00,0.00,0.00,0.00,0.00,-999.87,211.82,196.62 -0.00,0.00,0.00,0.00,0.00,0.00,-1031.16,211.82,196.17 -0.00,0.00,0.00,0.00,0.00,0.00,-1034.02,211.82,196.17 -0.00,0.00,0.00,0.00,0.00,0.00,-1036.58,211.82,196.17 -0.00,0.00,0.00,0.00,0.00,0.00,-1069.85,211.82,195.68 -0.00,0.00,0.00,0.00,0.00,0.00,-1072.80,211.82,195.68 -0.00,0.00,0.00,0.00,0.00,0.00,-1075.55,211.82,195.68 -0.00,0.00,0.00,0.00,0.00,0.00,-1095.50,211.82,195.41 -0.00,0.00,0.00,0.00,0.00,0.00,-1098.50,211.82,195.41 -0.00,0.00,0.00,0.00,0.00,0.00,-1101.29,211.82,195.41 -0.00,0.00,0.00,0.00,0.00,0.00,-1128.09,211.82,195.03 -0.00,0.00,0.00,0.00,0.00,0.00,-1131.58,211.82,195.03 -0.00,0.00,0.00,0.00,0.00,0.00,-1148.71,211.82,194.80 -0.00,0.00,0.00,0.00,0.00,0.00,-1151.71,211.82,194.80 -0.00,0.00,0.00,0.00,0.00,0.00,-1154.61,211.82,194.80 -0.00,0.00,0.00,0.00,0.00,0.00,-1171.24,211.82,194.59 -0.00,0.00,0.00,0.00,0.00,0.00,-1174.28,211.82,194.59 -0.00,0.00,0.00,0.00,0.00,0.00,-1177.21,211.82,194.59 -0.00,0.00,0.00,0.00,0.00,0.00,-1194.27,211.82,194.36 -0.00,0.00,0.00,0.00,0.00,0.00,-1197.35,211.82,194.36 -0.00,0.00,0.00,0.00,0.00,0.00,-1200.32,211.82,194.36 -0.00,0.00,0.00,0.00,0.00,0.00,-1206.06,211.82,194.32 -0.00,0.00,0.00,0.00,0.00,0.00,-1209.15,211.82,194.32 -0.00,0.00,0.00,0.00,0.00,0.00,-1212.12,211.82,194.32 -0.00,0.00,0.00,0.00,0.00,0.00,-1219.64,211.82,194.24 -0.00,0.00,0.00,0.00,0.00,0.00,-1222.74,211.82,194.24 -0.00,0.00,0.00,0.00,0.00,0.00,-1225.73,211.82,194.24 -0.00,0.00,0.00,0.00,0.00,0.00,-1227.79,211.82,194.26 -0.00,0.00,0.00,0.00,0.00,0.00,-1230.89,211.82,194.26 -0.00,0.00,0.00,0.00,0.00,0.00,-1233.88,211.82,194.26 -0.00,0.00,0.00,0.00,0.00,0.00,-1244.06,211.82,194.14 -0.00,0.00,0.00,0.00,0.00,0.00,-1247.18,211.82,194.14 -0.00,0.00,0.00,0.00,0.00,0.00,-1250.08,211.82,194.14 -0.00,0.00,0.00,0.00,0.00,0.00,-1263.49,211.82,193.98 -0.00,0.00,0.00,0.00,0.00,0.00,-1266.63,211.82,193.98 -0.00,0.00,0.00,0.00,0.00,0.00,-1269.55,211.82,193.98 -0.00,0.00,0.00,0.00,0.00,0.00,-1272.71,211.82,193.98 -0.00,0.00,0.00,0.00,0.00,0.00,-1275.86,211.82,193.98 -0.00,0.00,0.00,0.00,0.00,0.00,-1278.89,211.82,193.98 -0.00,0.00,0.00,0.00,0.00,0.00,-1283.99,211.82,193.94 -0.00,0.00,0.00,0.00,0.00,0.00,-1287.26,211.82,193.94 -0.00,0.00,0.00,0.00,0.00,0.00,-1290.30,211.82,193.94 -0.00,0.00,0.00,0.00,0.00,0.00,-1287.91,211.82,194.03 -0.00,0.00,0.00,0.00,0.00,0.00,-1291.16,211.82,194.03 -0.00,0.00,0.00,0.00,0.00,0.00,-1294.19,211.82,194.03 -0.00,0.00,0.00,0.00,0.00,0.00,-1298.87,211.82,194.00 -0.00,0.00,0.00,0.00,0.00,0.00,-1302.13,211.82,194.00 -0.00,0.00,0.00,0.00,0.00,0.00,-1305.16,211.82,194.00 -0.00,0.00,0.00,0.00,0.00,0.00,-1303.02,211.82,194.08 -0.00,0.00,0.00,0.00,0.00,0.00,-1306.15,211.82,194.08 -0.00,0.00,0.00,0.00,0.00,0.00,-1309.17,211.82,194.08 -0.00,0.00,0.00,0.00,0.00,0.00,-1304.95,211.82,194.20 -0.00,0.00,0.00,0.00,0.00,0.00,-1308.17,211.82,194.20 -0.00,0.00,0.00,0.00,0.00,0.00,-1301.00,211.82,194.36 -0.00,0.00,0.00,0.00,0.00,0.00,-1304.08,211.82,194.36 -0.00,0.00,0.00,0.00,0.00,0.00,-1307.05,211.82,194.36 -0.00,0.00,0.00,0.00,0.00,0.00,-1308.47,211.82,194.38 -0.00,0.00,0.00,0.00,0.00,0.00,-1311.66,211.82,194.38 -0.00,0.00,0.00,0.00,0.00,0.00,-1314.62,211.82,194.38 -0.00,0.00,0.00,0.00,0.00,0.00,-1320.68,211.82,194.33 -0.00,0.00,0.00,0.00,0.00,0.00,-1323.77,211.82,194.33 -0.00,0.00,0.00,0.00,0.00,0.00,-1326.63,211.82,194.33 -0.00,0.00,0.00,0.00,0.00,0.00,-1331.80,211.82,194.29 -0.00,0.00,0.00,0.00,0.00,0.00,-1334.89,211.82,194.29 -0.00,0.00,0.00,0.00,0.00,0.00,-1337.87,211.82,194.29 -0.00,0.00,0.00,0.00,0.00,0.00,-1333.37,211.82,194.41 -0.00,0.00,0.00,0.00,0.00,0.00,-1336.55,211.82,194.41 -0.00,0.00,0.00,0.00,0.00,0.00,-1339.51,211.82,194.41 -0.00,0.00,0.00,0.00,0.00,0.00,-1337.75,211.82,194.49 -0.00,0.00,0.00,0.00,0.00,0.00,-1340.91,211.82,194.49 -0.00,0.00,0.00,0.00,0.00,0.00,-1343.86,211.82,194.49 -0.00,0.00,0.00,0.00,0.00,0.00,-1351.47,211.82,194.41 -0.00,0.00,0.00,0.00,0.00,0.00,-1354.65,211.82,194.41 -0.00,0.00,0.00,0.00,0.00,0.00,-1357.61,211.82,194.41 -0.00,0.00,0.00,0.00,0.00,0.00,-1355.34,211.82,194.49 -0.00,0.00,0.00,0.00,0.00,0.00,-1358.39,211.82,194.49 -0.00,0.00,0.00,0.00,0.00,0.00,-1361.23,211.82,194.49 \ No newline at end of file +6699.79,7193.55,-493.75,6699.79,5741.94,957.86,631.69,317.59,315.58 +6389.79,6129.03,260.76,6389.79,6064.52,325.28,640.91,317.59,315.55 +6079.79,5290.32,789.47,6079.79,6645.16,-565.37,370.10,317.59,316.41 +5779.79,4500.00,1279.79,5779.79,6466.67,-686.87,-396.70,317.59,318.85 +5479.79,4300.00,1179.79,5479.79,5400.00,79.79,0.00,317.59,318.53 +5179.79,4833.33,346.46,5179.79,4633.33,546.46,0.00,317.59,318.11 +4879.79,4966.67,-86.87,4879.79,3933.33,946.46,0.00,317.59,317.18 +4579.79,4366.67,213.13,4579.79,3300.00,1279.79,0.00,317.59,316.78 +4279.79,3733.33,546.46,4279.79,3633.33,646.46,596.54,317.59,315.69 +3979.79,3133.33,846.46,3979.79,3766.67,213.13,0.00,317.59,317.42 +3679.79,2600.00,1079.79,3679.79,3733.33,-53.54,-892.31,317.59,320.42 +3369.79,2483.87,885.92,3369.79,3129.03,240.76,0.00,317.59,318.31 +3069.79,3000.00,69.79,3069.79,2366.67,703.13,-387.66,317.59,318.81 +2769.79,2400.00,369.79,2769.79,1733.33,1036.46,0.00,317.59,318.54 +2469.79,2033.33,436.46,2469.79,800.00,1669.79,0.00,317.59,317.71 +2179.79,1379.31,800.48,2179.79,413.79,1766.00,945.10,317.59,314.59 +1879.79,900.00,979.79,1879.79,1733.33,146.46,400.61,317.59,316.31 +1579.79,-633.33,2213.13,1579.79,2600.00,-1020.21,-469.35,317.59,319.07 +1279.79,133.33,1146.46,1279.79,1966.67,-686.87,-1230.05,317.59,321.49 +979.79,1533.33,-553.54,979.79,1666.67,-686.87,-445.67,317.59,319.00 +679.79,2366.67,-1686.87,679.79,500.00,179.79,0.00,317.59,316.89 +379.79,1833.33,-1453.54,379.79,-166.67,546.46,0.00,317.59,317.28 +89.79,1482.76,-1392.96,89.79,-586.21,676.00,0.00,317.59,316.87 +0.00,517.24,-517.24,0.00,-517.24,517.24,0.00,317.59,316.92 +0.00,310.34,-310.34,0.00,241.38,-241.38,0.00,317.59,317.41 +0.00,833.33,-833.33,0.00,66.67,-66.67,0.00,317.59,318.38 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.43 +0.00,-137.93,137.93,0.00,0.00,0.00,-338.72,317.59,318.66 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.57 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.33 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.36 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.56 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.54 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.14 +0.00,0.00,0.00,0.00,0.00,0.00,-392.92,317.59,318.83 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.54 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.25 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.29 +0.00,0.00,0.00,0.00,0.00,0.00,-367.88,317.59,318.75 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.39 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.44 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.53 +0.00,0.00,0.00,0.00,0.00,0.00,-323.02,317.59,318.60 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.46 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.36 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.28 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.34 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.47 +0.00,0.00,0.00,0.00,0.00,0.00,-327.57,317.59,318.62 +0.00,0.00,0.00,0.00,0.00,0.00,-405.40,317.59,318.86 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.40 +0.00,0.00,0.00,0.00,0.00,0.00,-383.01,317.59,318.79 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.52 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.30 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.50 +0.00,0.00,0.00,0.00,0.00,0.00,-324.44,317.59,318.61 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.45 +0.00,0.00,0.00,0.00,0.00,0.00,-318.22,317.59,318.59 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.38 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.24 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.47 +0.00,0.00,0.00,0.00,0.00,0.00,-415.92,317.59,318.90 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.21 +0.00,0.00,0.00,0.00,0.00,0.00,-353.33,317.59,318.70 +0.00,0.00,0.00,0.00,0.00,0.00,-407.62,317.59,318.87 +0.00,0.00,0.00,0.00,0.00,0.00,-326.32,317.59,318.61 +0.00,0.00,0.00,0.00,0.00,0.00,-418.74,317.59,318.90 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.51 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.54 +0.00,0.00,0.00,0.00,0.00,0.00,-348.75,317.59,318.68 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.53 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.33 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.36 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.07 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.36 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.41 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.37 +0.00,0.00,0.00,0.00,0.00,0.00,-368.21,317.59,318.74 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.43 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.27 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.57 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.08 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.12 +0.00,0.00,0.00,0.00,0.00,0.00,-322.22,317.59,318.59 +0.00,0.00,0.00,0.00,0.00,0.00,-394.72,317.59,318.82 +0.00,0.00,0.00,0.00,0.00,0.00,-336.49,317.59,318.64 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.41 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.46 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.56 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.23 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.48 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.37 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.57 +0.00,0.00,0.00,0.00,0.00,0.00,-400.65,317.59,318.84 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.26 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.39 +0.00,0.00,0.00,0.00,0.00,0.00,-335.81,317.59,318.63 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.29 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.52 +0.00,0.00,0.00,0.00,0.00,0.00,-402.21,317.59,318.84 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.48 +0.00,0.00,0.00,0.00,0.00,0.00,-421.24,317.59,318.90 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.52 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.12 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.56 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.21 +0.00,0.00,0.00,0.00,0.00,0.00,-342.48,317.59,318.65 +0.00,0.00,0.00,0.00,0.00,0.00,-372.57,317.59,318.75 +0.00,0.00,0.00,0.00,0.00,0.00,-374.67,317.59,318.75 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.22 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.30 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.37 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.47 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.42 +0.00,0.00,0.00,0.00,0.00,0.00,-324.18,317.59,318.59 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.55 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.39 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.39 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.33 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.48 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.58 +0.00,0.00,0.00,0.00,0.00,0.00,-342.60,317.59,318.65 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.31 +0.00,0.00,0.00,0.00,0.00,0.00,-364.77,317.59,318.72 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.48 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.52 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.43 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.18 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.27 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.46 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.47 +0.00,0.00,0.00,0.00,0.00,0.00,-387.89,317.59,318.79 +0.00,0.00,0.00,0.00,0.00,0.00,-333.81,317.59,318.62 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.52 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.54 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.16 +0.00,0.00,0.00,0.00,0.00,0.00,-402.17,317.59,318.84 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.45 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.47 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.57 +0.00,0.00,0.00,0.00,0.00,0.00,-389.54,317.59,318.80 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.57 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.48 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.45 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.40 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.45 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.58 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.55 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.54 +0.00,0.00,0.00,0.00,0.00,0.00,-325.94,317.59,318.59 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.46 +0.00,0.00,0.00,0.00,0.00,0.00,-347.99,317.59,318.66 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.54 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.15 +0.00,0.00,0.00,0.00,0.00,0.00,-354.28,317.59,318.68 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.45 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.58 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.35 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.41 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.57 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.57 +0.00,0.00,0.00,0.00,0.00,0.00,-358.56,317.59,318.70 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.31 +0.00,0.00,0.00,0.00,0.00,0.00,-404.60,317.59,318.84 +0.00,0.00,0.00,0.00,0.00,0.00,-335.34,317.59,318.62 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.32 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.52 +0.00,0.00,0.00,0.00,0.00,0.00,-341.15,317.59,318.64 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.40 +0.00,0.00,0.00,0.00,0.00,0.00,-381.33,317.59,318.77 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.55 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.26 +0.00,0.00,0.00,0.00,0.00,0.00,-337.87,317.59,318.63 +0.00,0.00,0.00,0.00,0.00,0.00,-350.78,317.59,318.67 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.44 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.47 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.48 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.43 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.45 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.54 +0.00,0.00,0.00,0.00,0.00,0.00,-344.93,317.59,318.65 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.37 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.07 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.46 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.14 +0.00,0.00,0.00,0.00,0.00,0.00,-415.19,317.59,318.87 +0.00,0.00,0.00,0.00,0.00,0.00,-331.89,317.59,318.60 +0.00,0.00,0.00,0.00,0.00,0.00,-352.15,317.59,318.67 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.48 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.40 +0.00,0.00,0.00,0.00,0.00,0.00,-366.91,317.59,318.71 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.57 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.30 +0.00,0.00,0.00,0.00,0.00,0.00,-351.67,317.59,318.67 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.13 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.51 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.48 +-320.00,0.00,-320.00,-320.00,0.00,-320.00,0.00,318.52,318.52 +-610.00,0.00,-610.00,-610.00,0.00,-610.00,0.00,318.52,318.32 +-960.00,0.00,-960.00,-960.00,0.00,-960.00,0.00,318.52,318.47 +-1260.00,0.00,-1260.00,-1260.00,0.00,-1260.00,0.00,318.52,318.29 +-1550.00,0.00,-1550.00,-1550.00,0.00,-1550.00,0.00,318.52,318.46 +-1850.00,0.00,-1850.00,-1850.00,0.00,-1850.00,0.00,318.52,318.55 +-2140.00,-137.93,-2002.07,-2140.00,-206.90,-1933.10,0.00,318.52,318.40 +-2440.00,-333.33,-2106.67,-2440.00,-600.00,-1840.00,0.00,318.52,318.18 +-2740.00,-400.00,-2340.00,-2740.00,-566.67,-2173.33,377.07,318.52,317.29 +-3050.00,-1516.13,-1533.87,-3050.00,-1483.87,-1566.13,708.54,318.52,316.28 +-3360.00,-2967.74,-392.26,-3360.00,-1580.65,-1779.35,1209.31,318.52,314.69 +-3670.00,-3903.23,233.23,-3670.00,-580.65,-3089.35,1073.21,318.52,315.12 +-3980.00,-4193.55,213.55,-3980.00,129.03,-4109.03,-526.79,318.52,320.20 +-4290.00,-4129.03,-160.97,-4290.00,-1161.29,-3128.71,-737.32,318.52,320.86 +-4590.00,-3366.67,-1223.33,-4590.00,-4800.00,210.00,0.00,318.52,317.88 +-4890.00,-3033.33,-1856.67,-4890.00,-6533.33,1643.33,1817.96,318.52,312.75 +-5190.00,-3866.67,-1323.33,-5190.00,-4900.00,-290.00,3548.73,318.52,307.26 +-5490.00,-6800.00,1310.00,-5490.00,-1633.33,-3856.67,1241.66,318.52,314.59 +-5790.00,-9466.67,3676.67,-5790.00,-733.33,-5056.67,-1317.25,318.52,322.71 +-6100.00,-7129.03,1029.03,-6100.00,-3419.35,-2680.65,-586.18,318.52,320.38 +-6410.00,-2451.61,-3958.39,-6410.00,-8451.61,2041.61,328.84,318.52,317.48 +-6720.00,-2483.87,-4236.13,-6720.00,-9161.29,2441.29,2307.88,318.52,311.20 +-7020.00,-6766.67,-253.33,-7020.00,-6666.67,-353.33,4478.34,318.52,304.32 +-7330.00,-12258.06,4928.06,-7330.00,-1548.39,-5781.61,1410.36,318.52,314.06 +-7630.00,-13866.67,6236.67,-7630.00,-366.67,-7263.33,385.10,318.52,317.32 +-7940.00,-10161.29,2221.29,-7940.00,-5032.26,-2907.74,0.00,318.52,318.53 +-8250.00,-4612.90,-3637.10,-8250.00,-10193.55,1943.55,0.00,318.52,318.80 +-8560.00,-4096.77,-4463.23,-8560.00,-10645.16,2085.16,3304.65,318.52,308.06 +-8870.00,-8161.29,-708.71,-8870.00,-7516.13,-1353.87,4803.27,318.52,303.31 +-9200.00,-14696.97,5496.97,-9200.00,-1939.39,-7260.61,1808.23,318.52,312.82 +-9510.00,-16967.74,7457.74,-9510.00,-645.16,-8864.84,-1128.71,318.52,322.14 +-9810.00,-11966.67,2156.67,-9810.00,-6466.67,-3343.33,-1733.74,318.52,324.02 +-10180.00,-3810.81,-6369.19,-10180.00,-13243.24,3063.24,1595.92,318.52,313.46 +-10490.00,-3838.71,-6651.29,-10490.00,-14612.90,4122.90,5037.82,318.52,302.54 +-10830.00,-11764.71,934.71,-10830.00,-8176.47,-2653.53,5692.86,318.52,300.47 +-11180.00,-18514.29,7334.29,-11180.00,-257.14,-10922.86,0.00,318.52,317.69 +-11490.00,-18322.58,6832.58,-11490.00,-1935.48,-9554.52,-340.21,318.52,319.62 +-11840.00,-9685.71,-2154.29,-11840.00,-10200.00,-1640.00,1078.23,318.52,315.10 +-12170.00,-4424.24,-7745.76,-12170.00,-15939.39,3769.39,3429.17,318.52,307.64 +-12480.00,-10129.03,-2350.97,-12480.00,-13967.74,1487.74,5723.53,318.52,300.37 +-12820.00,-16882.35,4062.35,-12820.00,-6058.82,-6761.18,5914.35,318.52,299.78 +-13140.00,-20781.25,7641.25,-13140.00,-687.50,-12452.50,-952.12,318.52,321.58 +-13460.00,-19062.50,5602.50,-13460.00,-2843.75,-10616.25,-789.41,318.52,321.03 +-13810.00,-10400.00,-3410.00,-13810.00,-11171.43,-2638.57,344.14,318.52,317.43 +-14140.00,-6333.33,-7806.67,-14140.00,-17545.45,3405.45,2985.37,318.52,309.05 +-14460.00,-10937.50,-3522.50,-14460.00,-16531.25,2071.25,5309.11,318.52,301.69 +-14790.00,-18121.21,3331.21,-14790.00,-9090.91,-5699.09,4944.67,318.52,302.85 +-15110.00,-23031.25,7921.25,-15110.00,-3000.00,-12110.00,0.00,318.52,319.00 +-15420.00,-20838.71,5418.71,-15420.00,-5064.52,-10355.48,0.00,318.52,319.02 +-15770.00,-12914.29,-2855.71,-15770.00,-13057.14,-2712.86,1208.60,318.52,314.72 +-16090.00,-10781.25,-5308.75,-16090.00,-19250.00,3160.00,2826.53,318.52,309.59 +-16410.00,-14937.50,-1472.50,-16410.00,-17906.25,1496.25,4807.93,318.52,303.31 +-16740.00,-20848.48,4108.48,-16740.00,-10606.06,-6133.94,4106.84,318.52,305.54 +-17060.00,-24125.00,7065.00,-17060.00,-5531.25,-11528.75,0.00,318.52,319.26 +-17370.00,-20483.87,3113.87,-17370.00,-8451.61,-8918.39,-1635.20,318.52,323.77 +-17710.00,-13647.06,-4062.94,-17710.00,-16176.47,-1533.53,0.00,318.52,318.01 +-18030.00,-11593.75,-6436.25,-18030.00,-22093.75,4063.75,1132.94,318.52,314.93 +-18350.00,-15656.25,-2693.75,-18350.00,-20781.25,2431.25,4840.90,318.52,303.17 +-18670.00,-21812.50,3142.50,-18670.00,-14781.25,-3888.75,4996.32,318.52,302.68 +-18990.00,-25875.00,6885.00,-18990.00,-7875.00,-11115.00,0.00,318.52,318.62 +-19310.00,-23625.00,4315.00,-19310.00,-8843.75,-10466.25,-706.66,318.52,320.79 +-19630.00,-17781.25,-1848.75,-19630.00,-16656.25,-2973.75,-460.53,318.52,319.98 +-19960.00,-14151.52,-5808.48,-19960.00,-22757.58,2797.58,1785.45,318.52,312.86 +-20280.00,-16093.75,-4186.25,-20280.00,-22343.75,2063.75,4579.69,318.52,303.99 +-20610.00,-22303.03,1693.03,-20610.00,-16151.52,-4458.48,5390.62,318.52,301.43 +-20990.00,-27578.95,6588.95,-20990.00,-9894.74,-11095.26,1009.04,318.52,315.34 +-21320.00,-27000.00,5680.00,-21320.00,-10727.27,-10592.73,0.00,318.52,317.83 +-21650.00,-19909.09,-1740.91,-21650.00,-18151.52,-3498.48,500.17,318.52,316.96 +-21970.00,-15500.00,-6470.00,-21970.00,-23968.75,1998.75,2468.80,318.52,310.71 +-22300.00,-18757.58,-3542.42,-22300.00,-23333.33,1033.33,5187.84,318.52,302.09 +-22630.00,-25424.24,2794.24,-22630.00,-17333.33,-5296.67,4584.06,318.52,304.02 +-22950.00,-29593.75,6643.75,-22950.00,-13312.50,-9637.50,484.10,318.52,317.04 +-23270.00,-28031.25,4761.25,-23270.00,-14812.50,-8457.50,0.00,318.52,319.41 +-23104.60,-20727.27,-2377.33,-23600.00,-21303.03,-2296.97,0.00,318.52,317.72 +-22784.60,-16187.50,-6597.10,-23775.28,-26218.75,2443.47,1902.96,318.52,312.54 +-22464.60,-19000.00,-3464.60,-23455.28,-25093.75,1638.47,1934.45,318.52,312.44 +-22134.60,-24787.88,2653.28,-23125.28,-19060.61,-4064.68,2422.45,318.52,310.90 +-21814.60,-27125.00,5310.40,-22805.28,-16562.50,-6242.78,0.00,318.52,318.23 +-21484.60,-24636.36,3151.76,-22475.28,-18181.82,-4293.46,413.39,318.52,317.28 +-21164.60,-18531.25,-2633.35,-22155.28,-22562.50,407.22,868.37,318.52,315.83 +-20844.60,-17531.25,-3313.35,-21835.28,-23656.25,1820.97,2463.15,318.52,310.77 +-20524.60,-20437.50,-87.10,-21515.28,-20906.25,-609.03,4784.52,318.52,303.41 +-20204.60,-24562.50,4357.90,-21195.28,-15312.50,-5882.78,2725.88,318.52,309.96 +-19884.60,-26562.50,6677.90,-20875.28,-12437.50,-8437.78,1268.69,318.52,314.58 +-19554.60,-23060.61,3506.00,-20545.28,-15515.15,-5030.13,0.00,318.52,318.97 +-19234.60,-16812.50,-2422.10,-20225.28,-20968.75,743.47,973.03,318.52,315.52 +-18914.60,-14000.00,-4914.60,-19905.28,-22875.00,2969.72,2997.96,318.52,309.10 +-18594.60,-18187.50,-407.10,-19585.28,-19906.25,320.97,4601.44,318.52,304.02 +-18274.60,-23968.75,5694.15,-19265.28,-14687.50,-4577.78,4297.06,318.52,305.00 +-17954.60,-25312.50,7357.90,-18945.28,-11250.00,-7695.28,0.00,318.52,317.58 +-17634.60,-22093.75,4459.15,-18625.28,-12250.00,-6375.28,0.00,318.52,317.88 +-17314.60,-14187.50,-3127.10,-18305.28,-18000.00,-305.28,1156.90,318.52,314.97 +-16994.60,-11750.00,-5244.60,-17985.28,-21562.50,3577.22,3221.18,318.52,308.42 +-16664.60,-16090.91,-573.69,-17655.28,-18515.15,859.87,3543.33,318.52,307.41 +-16334.60,-22000.00,5665.40,-17325.28,-11272.73,-6052.56,1428.04,318.52,314.12 +-16014.60,-22375.00,6360.40,-17005.28,-9531.25,-7474.03,-699.91,318.52,320.88 +-15694.60,-15625.00,-69.60,-16685.28,-14312.50,-2372.78,-612.05,318.52,320.47 +-15364.60,-9151.52,-6213.09,-16355.28,-19454.55,3099.26,1287.08,318.52,314.44 +-15044.60,-11187.50,-3857.10,-16035.28,-19531.25,3495.97,4283.22,318.52,304.93 +-14714.60,-18636.36,3921.76,-15705.28,-13727.27,-1978.01,5775.37,318.52,300.21 +-14384.60,-22121.21,7736.61,-15375.28,-5939.39,-9435.89,0.00,318.52,319.20 +-14074.60,-20451.61,6377.01,-15065.28,-6354.84,-8710.44,328.31,318.52,317.50 +-13744.60,-11151.52,-2593.09,-14735.28,-12939.39,-1795.89,1118.85,318.52,315.00 +-13434.60,-7903.23,-5531.38,-14425.28,-18000.00,3574.72,2913.73,318.52,309.30 +-13114.60,-13125.00,10.40,-14105.28,-15750.00,1644.72,5778.40,318.52,300.22 +-12794.60,-18781.25,5986.65,-13785.28,-7937.50,-5847.78,4635.34,318.52,303.86 +-12484.60,-20774.19,8289.59,-13475.28,-1548.39,-11926.90,3083.53,318.52,308.79 +-12164.60,-18343.75,6179.15,-13155.28,-4125.00,-9030.28,-1425.20,318.52,323.10 +-11854.60,-12741.94,887.33,-12845.28,-11903.23,-942.06,341.65,318.52,317.44 +-11524.60,-6090.91,-5433.69,-12515.28,-17181.82,4666.54,3022.53,318.52,308.93 +-11214.60,-7774.19,-3440.41,-12205.28,-14838.71,2633.43,6031.79,318.52,299.39 +-10884.60,-14363.64,3479.03,-11875.28,-6000.00,-5875.28,5999.73,318.52,299.51 +-10564.60,-18781.25,8216.65,-11555.28,187.50,-11742.78,-951.69,318.52,321.57 +-10254.60,-17064.52,6809.91,-11245.28,-1967.74,-9277.54,0.00,318.52,318.94 +-9924.60,-8333.33,-1591.27,-10915.28,-9393.94,-1521.34,1546.02,318.52,313.62 +-9614.60,-4290.32,-5324.28,-10605.28,-14419.35,3814.07,2350.93,318.52,311.06 +-9304.60,-8741.94,-562.67,-10295.28,-12225.81,1930.52,4535.27,318.52,304.14 +-8994.60,-14000.00,5005.40,-9985.28,-5096.77,-4888.51,4609.02,318.52,303.91 +-8684.60,-16516.13,7831.53,-9675.28,290.32,-9965.61,1258.34,318.52,314.55 +-8384.60,-13633.33,5248.73,-9375.28,-1666.67,-7708.62,-358.29,318.52,319.69 +-8074.60,-6870.97,-1203.64,-9065.28,-8774.19,-291.09,0.00,318.52,319.47 +-7774.60,-2700.00,-5074.60,-8765.28,-13500.00,4734.72,2468.26,318.52,310.69 +-7464.60,-5387.10,-2077.51,-8455.28,-11258.06,2802.78,1665.15,318.52,313.24 +-7144.60,-10687.50,3542.90,-8135.28,-3718.75,-4416.53,2116.57,318.52,311.81 +-6834.60,-11580.65,4746.04,-7825.28,-1193.55,-6631.73,-514.52,318.52,320.16 +-6524.60,-8354.84,1830.24,-7515.28,-4064.52,-3450.77,-1230.64,318.52,322.43 +-6214.60,-3451.61,-2762.99,-7205.28,-9967.74,2762.46,708.74,318.52,316.27 +-5904.60,-3129.03,-2775.57,-6895.28,-11741.94,4846.65,2706.71,318.52,309.94 +-5544.60,-6833.33,1288.73,-6535.28,-7194.44,659.16,5804.75,318.52,300.11 +-5234.60,-11290.32,6055.72,-6225.28,2000.00,-8225.28,2721.40,318.52,309.91 +-4924.60,-12935.48,8010.88,-5915.28,4258.06,-10173.35,-1476.65,318.52,323.23 +-4624.60,-8833.33,4208.73,-5615.28,-2633.33,-2981.95,1354.13,318.52,314.23 +-4294.60,-1454.55,-2840.06,-5285.28,-8848.48,3563.20,2627.30,318.52,310.19 +-3994.60,-900.00,-3094.60,-4985.28,-7733.33,2748.05,4412.06,318.52,304.53 +-3684.60,-6548.39,2863.78,-4675.28,-612.90,-4062.38,4971.44,318.52,302.76 +-3374.60,-11322.58,7947.98,-4365.28,3838.71,-8203.99,-727.16,318.52,320.85 +-3064.60,-9838.71,6774.11,-4055.28,1870.97,-5926.25,0.00,318.52,317.91 +-2744.60,-906.25,-1838.35,-3735.28,-4781.25,1045.97,1803.19,318.52,312.80 +-2434.60,2548.39,-4982.99,-3425.28,-7451.61,4026.33,3811.36,318.52,306.43 +-2124.60,-3774.19,1649.59,-3115.28,-3064.52,-50.77,5347.55,318.52,301.57 +-1804.60,-9718.75,7914.15,-2795.28,3812.50,-6607.78,2241.46,318.52,311.43 +-1494.60,-8838.71,7344.11,-2485.28,5483.87,-7969.15,817.21,318.52,315.95 +-1184.60,-1290.32,105.72,-2175.28,-645.16,-1530.12,1667.23,318.52,313.26 +-874.60,2677.42,-3552.02,-1865.28,-5709.68,3844.39,526.21,318.52,316.88 +-564.60,-1096.77,532.17,-1555.28,-4032.26,2476.98,4302.85,318.52,304.90 +-254.60,-3903.23,3648.62,-1245.28,774.19,-2019.48,5391.15,318.52,301.46 +0.00,-6161.29,6161.29,-935.28,6354.84,-7290.12,0.00,318.52,317.62 +0.00,-5096.77,5096.77,-625.28,5677.42,-6302.70,463.77,318.52,317.10 +0.00,1800.00,-1800.00,-325.28,-2300.00,1974.72,1432.74,318.52,314.03 +0.00,2677.42,-2677.42,-15.28,-4870.97,4855.68,2685.94,318.52,310.05 +0.00,-866.67,866.67,0.00,500.00,-500.00,7010.80,318.52,296.34 +0.00,-5580.65,5580.65,0.00,7193.55,-7193.55,3765.65,318.52,306.65 +0.00,-9093.75,9093.75,0.00,9906.25,-9906.25,1279.73,318.52,314.54 +0.00,-5677.42,5677.42,0.00,4483.87,-4483.87,0.00,318.52,317.96 +0.00,2161.29,-2161.29,0.00,-3000.00,3000.00,1092.16,318.52,315.14 +0.00,3900.00,-3900.00,0.00,-3700.00,3700.00,5013.43,318.52,302.70 +0.00,-1433.33,1433.33,0.00,1300.00,-1300.00,1718.43,318.52,313.16 +0.00,-6843.75,6843.75,0.00,6187.50,-6187.50,-1208.09,318.52,322.45 +0.00,-3354.84,3354.84,0.00,4096.77,-4096.77,651.70,318.52,316.46 +0.00,2677.42,-2677.42,0.00,-1516.13,1516.13,1900.03,318.52,312.50 +0.00,1500.00,-1500.00,0.00,-1633.33,1633.33,2341.12,318.52,311.10 +0.00,-2866.67,2866.67,0.00,1500.00,-1500.00,4229.43,318.52,305.11 +0.00,-4466.67,4466.67,0.00,4333.33,-4333.33,1134.48,318.52,314.94 +0.00,-3838.71,3838.71,0.00,4419.35,-4419.35,-1237.19,318.52,322.47 +0.00,600.00,-600.00,0.00,200.00,-200.00,-574.52,318.52,320.35 +0.00,3766.67,-3766.67,0.00,-3866.67,3866.67,1766.42,318.52,312.92 +0.00,1866.67,-1866.67,0.00,-2033.33,2033.33,5192.97,318.52,302.05 +0.00,-3838.71,3838.71,0.00,4290.32,-4290.32,6091.93,318.52,299.21 +0.00,-8387.10,8387.10,0.00,9032.26,-9032.26,0.00,318.52,318.18 +0.00,-6866.67,6866.67,0.00,7033.33,-7033.33,-866.13,318.52,321.29 +0.00,1969.70,-1969.70,0.00,-1484.85,1484.85,872.54,318.52,315.76 +0.00,5451.61,-5451.61,0.00,-5516.13,5516.13,3046.05,318.52,308.86 +0.00,-133.33,133.33,0.00,-1266.67,1266.67,6150.64,318.52,299.02 +0.00,-6875.00,6875.00,0.00,5437.50,-5437.50,3849.92,318.52,306.33 +0.00,-8580.65,8580.65,0.00,9806.45,-9806.45,-1235.30,318.52,322.47 +0.00,-3064.52,3064.52,0.00,6451.61,-6451.61,-344.71,318.52,319.62 +0.00,3406.25,-3406.25,0.00,-2812.50,2812.50,2129.13,318.52,311.77 +0.00,2433.33,-2433.33,0.00,-5366.67,5366.67,5786.26,318.52,300.17 +0.00,-4433.33,4433.33,0.00,1366.67,-1366.67,5252.09,318.52,301.87 +0.00,-6937.50,6937.50,0.00,8437.50,-8437.50,453.94,318.52,317.10 +0.00,-5483.87,5483.87,0.00,8129.03,-8129.03,1641.45,318.52,313.34 +0.00,96.77,-96.77,0.00,-322.58,322.58,1040.76,318.52,315.25 +0.00,1766.67,-1766.67,0.00,-4533.33,4533.33,1805.35,318.52,312.82 +0.00,166.67,-166.67,0.00,-2600.00,2600.00,6049.24,318.52,299.36 +0.00,-3366.67,3366.67,0.00,4800.00,-4800.00,4221.69,318.52,305.17 +0.00,-6838.71,6838.71,0.00,9548.39,-9548.39,-1859.27,318.52,324.47 +0.00,-4033.33,4033.33,0.00,5933.33,-5933.33,0.00,318.52,318.27 +0.00,2687.50,-2687.50,0.00,-2437.50,2437.50,2088.91,318.52,311.90 +0.00,2451.61,-2451.61,0.00,-4387.10,4387.10,4450.55,318.52,304.40 +0.00,-3366.67,3366.67,0.00,1866.67,-1866.67,6673.48,318.52,297.36 +0.00,-6812.50,6812.50,0.00,8500.00,-8500.00,2123.48,318.52,311.81 +0.00,-7032.26,7032.26,0.00,9161.29,-9161.29,977.43,318.52,315.45 +0.00,-733.33,733.33,0.00,1400.00,-1400.00,503.29,318.52,316.95 +0.00,3085.71,-3085.71,0.00,-3942.86,3942.86,2252.61,318.52,311.41 +0.00,933.33,-933.33,0.00,-2033.33,2033.33,6434.64,318.52,298.14 +0.00,-4451.61,4451.61,0.00,5193.55,-5193.55,5044.27,318.52,302.57 +0.00,-8093.75,8093.75,0.00,9687.50,-9687.50,489.42,318.52,317.03 +0.00,-4935.48,4935.48,0.00,6322.58,-6322.58,0.00,318.52,317.60 +0.00,2266.67,-2266.67,0.00,-2000.00,2000.00,0.00,318.52,318.68 +0.00,3733.33,-3733.33,0.00,-5033.33,5033.33,2419.71,318.52,310.90 +0.00,-666.67,666.67,0.00,-1200.00,1200.00,5321.69,318.52,301.70 +0.00,-5866.67,5866.67,0.00,5900.00,-5900.00,4289.62,318.52,304.99 +0.00,-7366.67,7366.67,0.00,9600.00,-9600.00,1436.52,318.52,314.05 +0.00,-4741.94,4741.94,0.00,6129.03,-6129.03,-887.32,318.52,321.42 +0.00,1966.67,-1966.67,0.00,-2033.33,2033.33,0.00,318.52,318.92 +0.00,5000.00,-5000.00,0.00,-5580.65,5580.65,2152.85,318.52,311.69 +0.00,2466.67,-2466.67,0.00,-1866.67,1866.67,2472.83,318.52,310.68 +0.00,-3935.48,3935.48,0.00,4483.87,-4483.87,1579.15,318.52,313.52 +0.00,-5677.42,5677.42,0.00,5741.94,-5741.94,-651.63,318.52,320.60 +0.00,-3548.39,3548.39,0.00,1516.13,-1516.13,-1252.18,318.52,322.50 +0.00,2967.74,-2967.74,0.00,-2967.74,2967.74,1226.44,318.52,314.63 +0.00,4322.58,-4322.58,0.00,-2645.16,2645.16,4884.18,318.52,303.03 +0.00,-1866.67,1866.67,0.00,1566.67,-1566.67,5171.39,318.52,302.13 +0.00,-8218.75,8218.75,0.00,6593.75,-6593.75,2993.76,318.52,309.04 +0.00,-7935.48,7935.48,0.00,7225.81,-7225.81,-739.33,318.52,320.89 +0.00,-1033.33,1033.33,0.00,2133.33,-2133.33,0.00,318.52,318.78 +0.00,4593.75,-4593.75,0.00,-3531.25,3531.25,1357.19,318.52,314.22 +0.00,2233.33,-2233.33,0.00,-2733.33,2733.33,1369.50,318.52,314.18 +0.00,-3633.33,3633.33,0.00,2533.33,-2533.33,1104.20,318.52,315.02 +0.00,-3766.67,3766.67,0.00,4733.33,-4733.33,1998.36,318.52,312.19 +0.00,-1733.33,1733.33,0.00,3466.67,-3466.67,-469.81,318.52,320.02 +0.00,-966.67,966.67,0.00,633.33,-633.33,0.00,318.52,317.62 +0.00,266.67,-266.67,0.00,-1466.67,1466.67,1564.61,318.52,313.56 +0.00,-333.33,333.33,0.00,-300.00,300.00,1428.18,318.52,313.99 +0.00,-166.67,166.67,0.00,1666.67,-1666.67,0.00,318.52,318.57 +0.00,433.33,-433.33,0.00,2000.00,-2000.00,0.00,318.52,319.37 +0.00,-133.33,133.33,0.00,1300.00,-1300.00,-384.48,318.52,319.75 +0.00,-34.48,34.48,0.00,-172.41,172.41,0.00,318.52,318.00 +0.00,0.00,0.00,0.00,-103.45,103.45,670.01,318.52,316.40 +0.00,0.00,0.00,0.00,0.00,0.00,681.09,318.52,316.36 +0.00,0.00,0.00,0.00,0.00,0.00,658.65,318.52,316.43 +0.00,0.00,0.00,0.00,0.00,0.00,579.80,318.52,316.69 +0.00,0.00,0.00,0.00,0.00,0.00,570.41,318.52,316.72 +0.00,0.00,0.00,0.00,0.00,0.00,549.17,318.52,316.79 +0.00,0.00,0.00,0.00,0.00,0.00,606.37,318.52,316.61 +0.00,0.00,0.00,0.00,0.00,0.00,550.34,318.52,316.78 +0.00,0.00,0.00,0.00,0.00,0.00,550.43,318.52,316.78 +0.00,0.00,0.00,0.00,0.00,0.00,559.23,318.52,316.76 +0.00,0.00,0.00,0.00,0.00,0.00,545.86,318.52,316.80 +0.00,0.00,0.00,0.00,0.00,0.00,632.08,318.52,316.53 +0.00,0.00,0.00,0.00,0.00,0.00,590.14,318.52,316.66 +0.00,0.00,0.00,0.00,0.00,0.00,586.10,318.52,316.68 +0.00,0.00,0.00,0.00,0.00,0.00,566.37,318.52,316.74 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,347.66 +0.00,0.00,0.00,0.00,0.00,0.00,-476.63,346.67,348.19 +0.00,0.00,0.00,0.00,0.00,0.00,-401.23,346.67,347.95 +0.00,0.00,0.00,0.00,0.00,0.00,-401.47,346.67,347.95 +0.00,0.00,0.00,0.00,0.00,0.00,-442.76,346.67,348.08 +0.00,0.00,0.00,0.00,0.00,0.00,-472.73,346.67,348.17 +0.00,0.00,0.00,0.00,0.00,0.00,-409.37,346.67,347.97 +0.00,0.00,0.00,0.00,0.00,0.00,-409.60,346.67,347.97 +0.00,0.00,0.00,0.00,0.00,0.00,-341.87,346.67,347.75 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,347.32 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,347.32 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,346.69 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,346.53 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,346.30 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,346.30 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,346.34 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,346.07 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,346.04 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,346.04 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,346.30 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,346.21 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,346.26 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,346.26 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,346.23 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,346.24 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,346.24 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,345.89 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,346.29 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,346.57 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,346.57 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,346.55 +310.00,0.00,310.00,310.00,0.00,310.00,0.00,346.87,346.87 +610.00,0.00,610.00,610.00,0.00,610.00,0.00,346.87,346.51 +900.00,0.00,900.00,900.00,0.00,900.00,0.00,346.87,346.51 +1190.00,0.00,1190.00,1190.00,0.00,1190.00,0.00,346.87,346.81 +1480.00,0.00,1480.00,1480.00,0.00,1480.00,0.00,346.87,347.02 +1770.00,0.00,1770.00,1770.00,0.00,1770.00,0.00,346.87,346.81 +2060.00,68.97,1991.03,2060.00,172.41,1887.59,0.00,346.87,346.81 +2360.00,266.67,2093.33,2360.00,300.00,2060.00,1039.51,346.87,343.56 +2660.00,66.67,2593.33,2660.00,200.00,2460.00,2054.92,346.87,340.35 +2960.00,-300.00,3260.00,2960.00,1166.67,1793.33,2056.16,346.87,340.35 +3260.00,0.00,3260.00,3260.00,2266.67,993.33,5329.74,346.87,329.96 +3560.00,-133.33,3693.33,3560.00,3533.33,26.67,3920.59,346.87,334.45 +3860.00,-66.67,3926.67,3860.00,4900.00,-1040.00,6409.43,346.87,326.56 +4160.00,-133.33,4293.33,4160.00,6133.33,-1973.33,6413.27,346.87,326.56 +4470.00,-129.03,4599.03,4470.00,7387.10,-2917.10,6874.31,346.87,325.11 +4770.00,-200.00,4970.00,4770.00,8500.00,-3730.00,4711.33,346.87,331.98 +5080.00,193.55,4886.45,5080.00,8580.65,-3500.65,2803.05,346.87,338.05 +5430.00,742.86,4687.14,5430.00,7714.29,-2284.29,0.00,346.87,345.97 +5730.00,2300.00,3430.00,5730.00,6533.33,-803.33,0.00,346.87,345.97 +6030.00,5733.33,296.67,6030.00,5700.00,330.00,583.29,346.87,345.09 +6330.00,5666.67,663.33,6330.00,4900.00,1430.00,540.30,346.87,345.23 +6630.00,2833.33,3796.67,6630.00,4066.67,2563.33,1673.22,346.87,341.64 +6930.00,2600.00,4330.00,6930.00,4233.33,2696.67,1674.21,346.87,341.64 +7220.00,3931.03,3288.97,7220.00,5344.83,1875.17,5014.56,346.87,331.04 +7520.00,2666.67,4853.33,7520.00,6833.33,686.67,5647.70,346.87,329.04 +7820.00,1766.67,6053.33,7820.00,9033.33,-1213.33,9432.67,346.87,317.05 +8130.00,838.71,7291.29,8130.00,11161.29,-3031.29,9438.50,346.87,317.05 +8440.00,-322.58,8762.58,8440.00,14193.55,-5753.55,10618.43,346.87,313.32 +8750.00,-193.55,8943.55,8750.00,15838.71,-7088.71,7808.72,346.87,322.26 +9050.00,-100.00,9150.00,9050.00,16166.67,-7116.67,2552.07,346.87,338.95 +9360.00,1548.39,7811.61,9360.00,14709.68,-5349.68,2553.61,346.87,338.95 +9670.00,5741.94,3928.06,9670.00,12419.35,-2749.35,-452.21,346.87,348.49 +9980.00,6419.35,3560.65,9980.00,10806.45,-826.45,-719.81,346.87,349.15 +10280.00,7400.00,2880.00,10280.00,8900.00,1380.00,-1292.98,346.87,350.97 +10590.00,9064.52,1525.48,10590.00,8000.00,2590.00,-555.13,346.87,348.62 +10900.00,9935.48,964.52,10900.00,8225.81,2674.19,-555.47,346.87,348.62 +11210.00,9741.94,1468.06,11210.00,7419.35,3790.65,380.22,346.87,345.65 +11520.00,9419.35,2100.65,11520.00,8290.32,3229.68,1737.31,346.87,341.35 +11830.00,9193.55,2636.45,11830.00,9838.71,1991.29,5383.55,346.87,329.79 +12140.00,8193.55,3946.45,12140.00,11935.48,204.52,5386.88,346.87,329.79 +12450.00,6806.45,5643.55,12450.00,14064.52,-1614.52,10768.76,346.87,312.73 +12760.00,4870.97,7889.03,12760.00,15935.48,-3175.48,6572.74,346.87,326.06 +13080.00,1625.00,11455.00,13080.00,17812.50,-4732.50,8380.62,346.87,320.34 +13390.00,3709.68,9680.32,13390.00,18774.19,-5384.19,3938.22,346.87,334.45 +13710.00,6718.75,6991.25,13710.00,18562.50,-4852.50,3940.72,346.87,334.45 +14030.00,8562.50,5467.50,14030.00,16281.25,-2251.25,1239.75,346.87,343.02 +14340.00,8096.77,6243.23,14340.00,15774.19,-1434.19,1641.76,346.87,341.75 +14650.00,10354.84,4295.16,14650.00,14483.87,166.13,2778.81,346.87,338.15 +14960.00,11064.52,3895.48,14960.00,12870.97,2089.03,6984.78,346.87,324.81 +15270.00,10032.26,5237.74,15270.00,13032.26,2237.74,6989.08,346.87,324.81 +15590.00,7750.00,7840.00,15590.00,11812.50,3777.50,17414.24,346.87,291.75 +15910.00,4750.00,11160.00,15910.00,10687.50,5222.50,18222.74,346.87,289.22 +16230.00,-2187.50,18417.50,16230.00,9656.25,6573.75,17266.91,346.87,292.29 +16550.00,-4343.75,20893.75,16550.00,9062.50,7487.50,17277.91,346.87,292.29 +16860.00,-3322.58,20182.58,16860.00,8354.84,8505.16,18900.00,346.87,283.90 +17170.00,-161.29,17331.29,17170.00,6290.32,10879.68,18900.00,346.87,285.17 +17490.00,687.50,16802.50,17490.00,3656.25,13833.75,18900.00,346.87,279.32 +17800.00,-677.42,18477.42,17800.00,1129.03,16670.97,18900.00,346.87,269.42 +18100.00,266.67,17833.33,18100.00,566.67,17533.33,18900.00,346.87,269.42 +18400.00,533.33,17866.67,18400.00,0.00,18400.00,16834.00,346.87,293.94 +18700.00,-233.33,18933.33,18700.00,-33.33,18733.33,17070.97,346.87,293.22 +19000.00,-133.33,19133.33,19000.00,0.00,19000.00,16430.02,346.87,295.29 +19300.00,133.33,19166.67,19300.00,33.33,19266.67,16439.77,346.87,295.29 +19590.00,448.28,19141.72,19590.00,206.90,19383.10,15087.70,346.87,299.61 +19742.81,1333.33,18409.48,19890.00,133.33,19756.67,18106.89,346.87,290.06 +19442.81,1500.00,17942.81,20190.00,466.67,19723.33,18900.00,346.87,272.38 +19142.81,766.67,18376.15,20490.00,3366.67,17123.33,18900.00,346.87,272.38 +18832.81,161.29,18671.52,20800.00,5741.94,15058.06,18319.56,346.87,289.51 +18532.81,-133.33,18666.15,21100.00,8166.67,12933.33,18900.00,346.87,284.66 +18222.81,32.26,18190.56,21410.00,11419.35,9990.65,18900.00,346.87,287.01 +17912.81,-32.26,17945.07,21720.00,13225.81,8494.19,18900.00,346.87,287.01 +17602.81,0.00,17602.81,22030.00,10451.61,11578.39,18900.00,346.87,285.19 +17302.81,266.67,17036.15,22330.00,7300.00,15030.00,18900.00,346.87,282.40 +17002.81,300.00,16702.81,22630.00,8000.00,14630.00,18900.00,346.87,280.65 +16702.81,-866.67,17569.48,22455.46,11066.67,11388.79,18900.00,346.87,280.65 +16392.81,-612.90,17005.72,22145.46,14935.48,7209.98,18063.88,346.87,290.62 +16082.81,-64.52,16147.33,21835.46,19806.45,2029.01,15958.60,346.87,297.34 +15772.81,96.77,15676.04,21525.46,23354.84,-1829.38,14259.03,346.87,302.76 +15462.81,322.58,15140.23,21215.46,25516.13,-4300.67,12875.64,346.87,307.18 +15152.81,1000.00,14152.81,20905.46,26129.03,-5223.57,12883.39,346.87,307.18 +14842.81,1000.00,13842.81,20595.46,25322.58,-4727.12,11267.04,346.87,312.33 +14532.81,1548.39,12984.43,20285.46,26258.06,-5972.60,11103.66,346.87,312.87 +14172.81,2555.56,11617.26,19925.46,28694.44,-8768.98,8964.33,346.87,319.68 +13852.81,3687.50,10165.31,19605.46,30937.50,-11332.04,4515.82,346.87,333.81 +13542.81,5741.94,7800.88,19295.46,27322.58,-8027.12,4518.37,346.87,333.81 +13222.81,10687.50,2535.31,18975.46,20375.00,-1399.54,3461.87,346.87,337.17 +12912.81,11225.81,1687.01,18665.46,15580.65,3084.82,6125.94,346.87,328.72 +12602.81,7645.16,4957.65,18355.46,16516.13,1839.33,13956.65,346.87,303.89 +12292.81,2064.52,10228.30,18045.46,20580.65,-2535.18,13965.04,346.87,303.89 +11972.81,-4656.25,16629.06,17725.46,23875.00,-6149.54,14654.90,346.87,301.73 +11652.81,-4218.75,15871.56,17405.46,27625.00,-10219.54,12112.44,346.87,309.83 +11332.81,-2718.75,14051.56,17085.46,30531.25,-13445.79,8620.89,346.87,320.93 +11012.81,1875.00,9137.81,16765.46,28093.75,-11328.29,0.00,346.87,346.93 +10692.81,7093.75,3599.06,16445.46,17656.25,-1210.79,0.00,346.87,346.93 +10372.81,12125.00,-1752.19,16125.46,5843.75,10281.71,2213.99,346.87,341.27 +10062.81,12935.48,-2872.67,15815.46,4161.29,11654.17,5764.01,346.87,330.01 +9742.81,9062.50,680.31,15495.46,11000.00,4495.46,12438.57,346.87,308.85 +9432.81,1516.13,7916.69,15185.46,14193.55,991.91,10181.64,346.87,316.03 +9122.81,-4193.55,13316.36,14875.46,17290.32,-2414.86,10187.66,346.87,316.03 +8802.81,-3906.25,12709.06,14555.46,22000.00,-7444.54,9628.97,346.87,317.82 +8482.81,-281.25,8764.06,14235.46,26125.00,-11889.54,5775.42,346.87,330.07 +8162.81,2000.00,6162.81,13915.46,25093.75,-11178.29,-3756.55,346.87,0.32 +7842.81,4875.00,2967.81,13595.46,16750.00,-3154.54,-5256.87,346.87,3.54 +7522.81,10562.50,-3039.69,13275.46,4781.25,8494.21,-5260.23,346.87,3.54 +7222.81,15400.00,-8177.19,12975.46,-333.33,13308.79,-1184.25,346.87,350.60 +6912.81,13064.52,-6151.70,12665.46,4548.39,8117.07,8785.12,346.87,318.97 +6592.81,3968.75,2624.06,12345.46,12343.75,1.71,10359.59,346.87,314.00 +6282.81,-5032.26,11315.07,12035.46,16903.23,-4867.77,10366.01,346.87,314.00 +5962.81,-7687.50,13650.31,11715.46,22062.50,-10347.04,12322.93,346.87,307.81 +5642.81,-5500.00,11142.81,11395.46,25031.25,-13635.79,6959.53,346.87,324.85 +5322.81,-3156.25,8479.06,11075.46,23781.25,-12705.79,395.72,346.87,345.69 +5012.81,2516.13,2496.69,10765.46,16387.10,-5621.64,-1812.08,346.87,352.70 +4692.81,7562.50,-2869.69,10445.46,5062.50,5382.96,-1837.71,346.87,352.70 +4382.81,8870.97,-4488.15,10135.46,483.87,9651.59,912.35,346.87,343.97 +4082.81,5766.67,-1683.85,9835.46,5700.00,4135.46,7903.76,346.87,321.79 +3772.81,-129.03,3901.85,9525.46,13225.81,-3700.35,12851.20,346.87,306.11 +3462.81,-6806.45,10269.27,9215.46,18516.13,-9300.67,11288.59,346.87,311.09 +3142.81,-10937.50,14080.31,8895.46,21812.50,-12917.04,11295.80,346.87,311.09 +2822.81,-8937.50,11760.31,8575.46,21625.00,-13049.54,-5270.76,346.87,3.67 +2502.81,-5250.00,7752.81,8255.46,17187.50,-8932.04,-7089.71,346.87,9.36 +2202.81,2866.67,-663.85,7955.46,5933.33,2022.13,-548.90,346.87,348.59 +1892.81,7709.68,-5816.86,7645.46,-1193.55,8839.01,-549.24,346.87,348.59 +1582.81,4806.45,-3223.64,7335.46,2354.84,4980.62,12001.35,346.87,308.77 +1272.81,-2193.55,3466.36,7025.46,9516.13,-2490.67,15561.20,346.87,297.50 +952.81,-9187.50,10140.31,6705.46,14531.25,-7825.79,12811.44,346.87,306.25 +632.81,-13000.00,13632.81,6385.46,18875.00,-12489.54,9851.03,346.87,315.67 +312.81,-13031.25,13344.06,6065.46,20187.50,-14122.04,9857.32,346.87,315.67 +0.00,-9656.25,9656.25,5745.46,15312.50,-9567.04,-1749.17,346.87,352.51 +0.00,-5548.39,5548.39,5435.46,9548.39,-4112.93,0.00,346.87,346.67 +0.00,2406.25,-2406.25,5115.46,1000.00,4115.46,6051.16,346.87,327.67 +0.00,3300.00,-3300.00,4815.46,800.00,4015.46,13274.83,346.87,304.75 +0.00,-3354.84,3354.84,4505.46,7225.81,-2720.35,13283.05,346.87,304.75 +0.00,-9718.75,9718.75,4185.46,12906.25,-8720.79,11399.05,346.87,310.75 +0.00,-13125.00,13125.00,3865.46,17093.75,-13228.29,9809.91,346.87,315.82 +0.00,-12312.50,12312.50,3545.46,16875.00,-13329.54,-1510.76,346.87,351.75 +0.00,-7281.25,7281.25,3225.46,11281.25,-8055.79,-1889.24,346.87,352.86 +0.00,1533.33,-1533.33,2925.46,1166.67,1758.79,-1890.37,346.87,352.86 +0.00,5903.23,-5903.23,2615.46,-4322.58,6938.04,1651.64,346.87,341.62 +0.00,3709.68,-3709.68,2305.46,-2193.55,4499.01,4000.51,346.87,334.17 +0.00,-2483.87,2483.87,1995.46,5032.26,-3036.80,6874.77,346.87,325.06 +0.00,-7166.67,7166.67,1695.46,10133.33,-8437.87,6878.89,346.87,325.06 +0.00,-8709.68,8709.68,1385.46,11225.81,-9840.35,-545.04,346.87,348.63 +0.00,-5000.00,5000.00,1075.46,7096.77,-6021.31,-5429.58,346.87,4.09 +0.00,2612.90,-2612.90,765.46,-1419.35,2184.82,-2140.81,346.87,353.65 +0.00,7806.45,-7806.45,455.46,-6451.61,6907.07,-2142.14,346.87,353.65 +0.00,4766.67,-4766.67,155.46,-4733.33,4888.79,-1181.07,346.87,350.59 +0.00,-1657.14,1657.14,0.00,485.71,-485.71,480.89,346.87,345.32 +0.00,-2733.33,2733.33,0.00,2300.00,-2300.00,-6144.09,346.87,6.36 +0.00,322.58,-322.58,0.00,-64.52,64.52,-6317.44,346.87,6.91 +0.00,7843.75,-7843.75,0.00,-6000.00,6000.00,-6321.48,346.87,6.91 +0.00,10593.75,-10593.75,0.00,-9343.75,9343.75,-5295.45,346.87,3.64 +0.00,6419.35,-6419.35,0.00,-7000.00,7000.00,-6393.61,346.87,7.12 +0.00,612.90,-612.90,0.00,-3483.87,3483.87,-8217.73,346.87,12.89 +0.00,1612.90,-1612.90,0.00,-3483.87,3483.87,-7803.09,346.87,11.56 +0.00,9193.55,-9193.55,0.00,-6838.71,6838.71,-7807.91,346.87,11.56 +0.00,11806.45,-11806.45,0.00,-9258.06,9258.06,-6828.83,346.87,8.44 +0.00,7354.84,-7354.84,0.00,-8806.45,8806.45,-6328.92,346.87,6.84 +0.00,2935.48,-2935.48,0.00,-6967.74,6967.74,-6630.81,346.87,7.78 +0.00,3161.29,-3161.29,0.00,-5645.16,5645.16,-6634.89,346.87,7.78 +0.00,6000.00,-6000.00,0.00,-4838.71,4838.71,-6942.16,346.87,8.74 +0.00,7774.19,-7774.19,0.00,-5064.52,5064.52,-6527.13,346.87,7.41 +0.00,7451.61,-7451.61,0.00,-5741.94,5741.94,-6550.80,346.87,7.48 +0.00,6064.52,-6064.52,0.00,-5967.74,5967.74,-6646.25,346.87,7.77 +0.00,5322.58,-5322.58,0.00,-6032.26,6032.26,-6650.33,346.87,7.77 +0.00,5193.55,-5193.55,0.00,-5935.48,5935.48,-6394.52,346.87,6.94 +0.00,5516.13,-5516.13,0.00,-5838.71,5838.71,-6331.71,346.87,6.73 +0.00,5709.68,-5709.68,0.00,-5677.42,5677.42,-6142.09,346.87,6.12 +0.00,5733.33,-5733.33,0.00,-5566.67,5566.67,-6145.73,346.87,6.12 +0.00,5580.65,-5580.65,0.00,-5354.84,5354.84,-6073.29,346.87,5.87 +0.00,5354.84,-5354.84,0.00,-5258.06,5258.06,-5701.28,346.87,4.68 +0.00,5064.52,-5064.52,0.00,-5064.52,5064.52,-5369.18,346.87,3.62 +0.00,4225.81,-4225.81,0.00,-4193.55,4193.55,-5372.45,346.87,3.62 +0.00,3766.67,-3766.67,0.00,-3766.67,3766.67,-5483.80,346.87,3.96 +0.00,4100.00,-4100.00,0.00,-4366.67,4366.67,-5194.46,346.87,3.03 +0.00,4633.33,-4633.33,0.00,-4600.00,4600.00,-5134.36,346.87,2.83 +0.00,4612.90,-4612.90,0.00,-4419.35,4419.35,-5137.48,346.87,2.83 +0.00,3866.67,-3866.67,0.00,-4033.33,4033.33,-4687.59,346.87,1.40 +0.00,3266.67,-3266.67,0.00,-4000.00,4000.00,-4572.17,346.87,1.02 +0.00,3387.10,-3387.10,0.00,-3258.06,3258.06,-4222.70,346.87,359.90 +0.00,3451.61,-3451.61,0.00,-2806.45,2806.45,-4026.19,346.87,359.27 +0.00,2866.67,-2866.67,0.00,-3000.00,3000.00,-4028.54,346.87,359.27 +0.00,2300.00,-2300.00,0.00,-3200.00,3200.00,-3763.22,346.87,358.42 +0.00,2483.87,-2483.87,0.00,-3161.29,3161.29,-3434.25,346.87,357.37 +0.00,2709.68,-2709.68,0.00,-2516.13,2516.13,-3080.56,346.87,356.24 +0.00,2033.33,-2033.33,0.00,-1900.00,1900.00,-3082.33,346.87,356.24 +0.00,1433.33,-1433.33,0.00,-1166.67,1166.67,-3119.91,346.87,356.36 +0.00,266.67,-266.67,0.00,-1366.67,1366.67,-2903.08,346.87,355.66 +0.00,1533.33,-1533.33,0.00,-1900.00,1900.00,-3034.68,346.87,356.08 +0.00,2645.16,-2645.16,0.00,-2064.52,2064.52,-3036.48,346.87,356.08 +0.00,2833.33,-2833.33,0.00,-1266.67,1266.67,-1936.01,346.87,352.58 +0.00,2233.33,-2233.33,0.00,-1033.33,1033.33,-2421.88,346.87,354.12 +0.00,1700.00,-1700.00,0.00,0.00,0.00,-2947.13,346.87,355.78 +0.00,966.67,-966.67,0.00,-600.00,600.00,-2948.81,346.87,355.78 +0.00,1533.33,-1533.33,0.00,-2433.33,2433.33,-3533.10,346.87,357.63 +0.00,2133.33,-2133.33,0.00,-3333.33,3333.33,-2582.39,346.87,354.60 +0.00,2500.00,-2500.00,0.00,-3333.33,3333.33,-1634.78,346.87,351.59 +0.00,1800.00,-1800.00,0.00,-2800.00,2800.00,-1635.68,346.87,351.59 +0.00,666.67,-666.67,0.00,-2333.33,2333.33,-1846.62,346.87,352.26 +0.00,774.19,-774.19,0.00,-1677.42,1677.42,-1595.89,346.87,351.46 +0.00,-66.67,66.67,0.00,-1200.00,1200.00,-1178.15,346.87,350.13 +0.00,-172.41,172.41,0.00,68.97,-68.97,-1178.75,346.87,350.13 +0.00,66.67,-66.67,0.00,700.00,-700.00,-1236.46,346.87,350.31 +0.00,0.00,0.00,0.00,-100.00,100.00,-1312.45,346.87,350.55 +0.00,0.00,0.00,0.00,-482.76,482.76,-638.50,346.87,348.41 +0.00,0.00,0.00,0.00,586.21,-586.21,-638.78,346.87,348.41 +0.00,0.00,0.00,0.00,68.97,-68.97,-559.84,346.87,348.16 +0.00,0.00,0.00,0.00,-133.33,133.33,0.00,346.87,347.43 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.87,346.94 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.87,346.94 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.87,346.80 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.87,346.60 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.87,346.60 \ No newline at end of file diff --git a/src/calibrate.cpp b/src/calibrate.cpp new file mode 100644 index 0000000..c42fae7 --- /dev/null +++ b/src/calibrate.cpp @@ -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); +} From df62e3f1008287d0c80a1687d012434bdf801fd6 Mon Sep 17 00:00:00 2001 From: Mason Thomas Date: Mon, 20 Oct 2025 23:30:50 -0500 Subject: [PATCH 41/47] fix calibration cpp --- src/{calibrate.cpp => calibrate.cpp.bak} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename src/{calibrate.cpp => calibrate.cpp.bak} (100%) diff --git a/src/calibrate.cpp b/src/calibrate.cpp.bak similarity index 100% rename from src/calibrate.cpp rename to src/calibrate.cpp.bak From 9959cf7e512f2edf7e6fe392a22c93075bc52b71 Mon Sep 17 00:00:00 2001 From: Mason Thomas Date: Mon, 20 Oct 2025 23:37:18 -0500 Subject: [PATCH 42/47] update pid consts --- pid_test.csv | 1046 ++++++++++++++--------------------------- src/robot/control.cpp | 6 +- 2 files changed, 366 insertions(+), 686 deletions(-) diff --git a/pid_test.csv b/pid_test.csv index 52be84a..f517b2f 100644 --- a/pid_test.csv +++ b/pid_test.csv @@ -1,684 +1,364 @@ LeftSetpoint,LeftVelocity,LeftError,RightSetpoint,RightVelocity,RightError,HeadingVelocityCorrection,HeadingSetpoint,Heading -6699.79,7193.55,-493.75,6699.79,5741.94,957.86,631.69,317.59,315.58 -6389.79,6129.03,260.76,6389.79,6064.52,325.28,640.91,317.59,315.55 -6079.79,5290.32,789.47,6079.79,6645.16,-565.37,370.10,317.59,316.41 -5779.79,4500.00,1279.79,5779.79,6466.67,-686.87,-396.70,317.59,318.85 -5479.79,4300.00,1179.79,5479.79,5400.00,79.79,0.00,317.59,318.53 -5179.79,4833.33,346.46,5179.79,4633.33,546.46,0.00,317.59,318.11 -4879.79,4966.67,-86.87,4879.79,3933.33,946.46,0.00,317.59,317.18 -4579.79,4366.67,213.13,4579.79,3300.00,1279.79,0.00,317.59,316.78 -4279.79,3733.33,546.46,4279.79,3633.33,646.46,596.54,317.59,315.69 -3979.79,3133.33,846.46,3979.79,3766.67,213.13,0.00,317.59,317.42 -3679.79,2600.00,1079.79,3679.79,3733.33,-53.54,-892.31,317.59,320.42 -3369.79,2483.87,885.92,3369.79,3129.03,240.76,0.00,317.59,318.31 -3069.79,3000.00,69.79,3069.79,2366.67,703.13,-387.66,317.59,318.81 -2769.79,2400.00,369.79,2769.79,1733.33,1036.46,0.00,317.59,318.54 -2469.79,2033.33,436.46,2469.79,800.00,1669.79,0.00,317.59,317.71 -2179.79,1379.31,800.48,2179.79,413.79,1766.00,945.10,317.59,314.59 -1879.79,900.00,979.79,1879.79,1733.33,146.46,400.61,317.59,316.31 -1579.79,-633.33,2213.13,1579.79,2600.00,-1020.21,-469.35,317.59,319.07 -1279.79,133.33,1146.46,1279.79,1966.67,-686.87,-1230.05,317.59,321.49 -979.79,1533.33,-553.54,979.79,1666.67,-686.87,-445.67,317.59,319.00 -679.79,2366.67,-1686.87,679.79,500.00,179.79,0.00,317.59,316.89 -379.79,1833.33,-1453.54,379.79,-166.67,546.46,0.00,317.59,317.28 -89.79,1482.76,-1392.96,89.79,-586.21,676.00,0.00,317.59,316.87 -0.00,517.24,-517.24,0.00,-517.24,517.24,0.00,317.59,316.92 -0.00,310.34,-310.34,0.00,241.38,-241.38,0.00,317.59,317.41 -0.00,833.33,-833.33,0.00,66.67,-66.67,0.00,317.59,318.38 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.43 -0.00,-137.93,137.93,0.00,0.00,0.00,-338.72,317.59,318.66 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.57 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.33 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.36 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.56 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.54 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.14 -0.00,0.00,0.00,0.00,0.00,0.00,-392.92,317.59,318.83 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.54 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.25 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.29 -0.00,0.00,0.00,0.00,0.00,0.00,-367.88,317.59,318.75 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.39 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.44 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.53 -0.00,0.00,0.00,0.00,0.00,0.00,-323.02,317.59,318.60 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.46 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.36 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.28 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.34 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.47 -0.00,0.00,0.00,0.00,0.00,0.00,-327.57,317.59,318.62 -0.00,0.00,0.00,0.00,0.00,0.00,-405.40,317.59,318.86 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.40 -0.00,0.00,0.00,0.00,0.00,0.00,-383.01,317.59,318.79 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.52 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.30 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.50 -0.00,0.00,0.00,0.00,0.00,0.00,-324.44,317.59,318.61 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.45 -0.00,0.00,0.00,0.00,0.00,0.00,-318.22,317.59,318.59 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.38 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.24 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.47 -0.00,0.00,0.00,0.00,0.00,0.00,-415.92,317.59,318.90 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.21 -0.00,0.00,0.00,0.00,0.00,0.00,-353.33,317.59,318.70 -0.00,0.00,0.00,0.00,0.00,0.00,-407.62,317.59,318.87 -0.00,0.00,0.00,0.00,0.00,0.00,-326.32,317.59,318.61 -0.00,0.00,0.00,0.00,0.00,0.00,-418.74,317.59,318.90 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.51 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.54 -0.00,0.00,0.00,0.00,0.00,0.00,-348.75,317.59,318.68 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.53 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.33 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.36 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.07 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.36 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.41 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.37 -0.00,0.00,0.00,0.00,0.00,0.00,-368.21,317.59,318.74 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.43 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.27 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.57 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.08 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.12 -0.00,0.00,0.00,0.00,0.00,0.00,-322.22,317.59,318.59 -0.00,0.00,0.00,0.00,0.00,0.00,-394.72,317.59,318.82 -0.00,0.00,0.00,0.00,0.00,0.00,-336.49,317.59,318.64 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.41 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.46 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.56 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.23 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.48 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.37 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.57 -0.00,0.00,0.00,0.00,0.00,0.00,-400.65,317.59,318.84 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.26 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.39 -0.00,0.00,0.00,0.00,0.00,0.00,-335.81,317.59,318.63 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.29 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.52 -0.00,0.00,0.00,0.00,0.00,0.00,-402.21,317.59,318.84 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.48 -0.00,0.00,0.00,0.00,0.00,0.00,-421.24,317.59,318.90 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.52 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.12 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.56 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.21 -0.00,0.00,0.00,0.00,0.00,0.00,-342.48,317.59,318.65 -0.00,0.00,0.00,0.00,0.00,0.00,-372.57,317.59,318.75 -0.00,0.00,0.00,0.00,0.00,0.00,-374.67,317.59,318.75 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.22 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.30 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.37 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.47 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.42 -0.00,0.00,0.00,0.00,0.00,0.00,-324.18,317.59,318.59 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.55 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.39 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.39 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.33 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.48 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.58 -0.00,0.00,0.00,0.00,0.00,0.00,-342.60,317.59,318.65 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.31 -0.00,0.00,0.00,0.00,0.00,0.00,-364.77,317.59,318.72 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.48 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.52 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.43 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.18 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.27 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.46 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.47 -0.00,0.00,0.00,0.00,0.00,0.00,-387.89,317.59,318.79 -0.00,0.00,0.00,0.00,0.00,0.00,-333.81,317.59,318.62 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.52 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.54 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.16 -0.00,0.00,0.00,0.00,0.00,0.00,-402.17,317.59,318.84 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.45 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.47 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.57 -0.00,0.00,0.00,0.00,0.00,0.00,-389.54,317.59,318.80 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.57 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.48 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.45 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.40 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.45 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.58 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.55 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.54 -0.00,0.00,0.00,0.00,0.00,0.00,-325.94,317.59,318.59 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.46 -0.00,0.00,0.00,0.00,0.00,0.00,-347.99,317.59,318.66 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.54 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.15 -0.00,0.00,0.00,0.00,0.00,0.00,-354.28,317.59,318.68 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.45 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.58 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.35 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.41 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.57 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.57 -0.00,0.00,0.00,0.00,0.00,0.00,-358.56,317.59,318.70 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.31 -0.00,0.00,0.00,0.00,0.00,0.00,-404.60,317.59,318.84 -0.00,0.00,0.00,0.00,0.00,0.00,-335.34,317.59,318.62 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.32 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.52 -0.00,0.00,0.00,0.00,0.00,0.00,-341.15,317.59,318.64 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.40 -0.00,0.00,0.00,0.00,0.00,0.00,-381.33,317.59,318.77 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.55 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.26 -0.00,0.00,0.00,0.00,0.00,0.00,-337.87,317.59,318.63 -0.00,0.00,0.00,0.00,0.00,0.00,-350.78,317.59,318.67 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.44 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.47 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.48 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.43 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.45 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.54 -0.00,0.00,0.00,0.00,0.00,0.00,-344.93,317.59,318.65 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.37 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.07 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.46 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.14 -0.00,0.00,0.00,0.00,0.00,0.00,-415.19,317.59,318.87 -0.00,0.00,0.00,0.00,0.00,0.00,-331.89,317.59,318.60 -0.00,0.00,0.00,0.00,0.00,0.00,-352.15,317.59,318.67 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.48 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.40 -0.00,0.00,0.00,0.00,0.00,0.00,-366.91,317.59,318.71 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.57 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.30 -0.00,0.00,0.00,0.00,0.00,0.00,-351.67,317.59,318.67 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.13 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.51 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,317.59,318.48 --320.00,0.00,-320.00,-320.00,0.00,-320.00,0.00,318.52,318.52 --610.00,0.00,-610.00,-610.00,0.00,-610.00,0.00,318.52,318.32 --960.00,0.00,-960.00,-960.00,0.00,-960.00,0.00,318.52,318.47 --1260.00,0.00,-1260.00,-1260.00,0.00,-1260.00,0.00,318.52,318.29 --1550.00,0.00,-1550.00,-1550.00,0.00,-1550.00,0.00,318.52,318.46 --1850.00,0.00,-1850.00,-1850.00,0.00,-1850.00,0.00,318.52,318.55 --2140.00,-137.93,-2002.07,-2140.00,-206.90,-1933.10,0.00,318.52,318.40 --2440.00,-333.33,-2106.67,-2440.00,-600.00,-1840.00,0.00,318.52,318.18 --2740.00,-400.00,-2340.00,-2740.00,-566.67,-2173.33,377.07,318.52,317.29 --3050.00,-1516.13,-1533.87,-3050.00,-1483.87,-1566.13,708.54,318.52,316.28 --3360.00,-2967.74,-392.26,-3360.00,-1580.65,-1779.35,1209.31,318.52,314.69 --3670.00,-3903.23,233.23,-3670.00,-580.65,-3089.35,1073.21,318.52,315.12 --3980.00,-4193.55,213.55,-3980.00,129.03,-4109.03,-526.79,318.52,320.20 --4290.00,-4129.03,-160.97,-4290.00,-1161.29,-3128.71,-737.32,318.52,320.86 --4590.00,-3366.67,-1223.33,-4590.00,-4800.00,210.00,0.00,318.52,317.88 --4890.00,-3033.33,-1856.67,-4890.00,-6533.33,1643.33,1817.96,318.52,312.75 --5190.00,-3866.67,-1323.33,-5190.00,-4900.00,-290.00,3548.73,318.52,307.26 --5490.00,-6800.00,1310.00,-5490.00,-1633.33,-3856.67,1241.66,318.52,314.59 --5790.00,-9466.67,3676.67,-5790.00,-733.33,-5056.67,-1317.25,318.52,322.71 --6100.00,-7129.03,1029.03,-6100.00,-3419.35,-2680.65,-586.18,318.52,320.38 --6410.00,-2451.61,-3958.39,-6410.00,-8451.61,2041.61,328.84,318.52,317.48 --6720.00,-2483.87,-4236.13,-6720.00,-9161.29,2441.29,2307.88,318.52,311.20 --7020.00,-6766.67,-253.33,-7020.00,-6666.67,-353.33,4478.34,318.52,304.32 --7330.00,-12258.06,4928.06,-7330.00,-1548.39,-5781.61,1410.36,318.52,314.06 --7630.00,-13866.67,6236.67,-7630.00,-366.67,-7263.33,385.10,318.52,317.32 --7940.00,-10161.29,2221.29,-7940.00,-5032.26,-2907.74,0.00,318.52,318.53 --8250.00,-4612.90,-3637.10,-8250.00,-10193.55,1943.55,0.00,318.52,318.80 --8560.00,-4096.77,-4463.23,-8560.00,-10645.16,2085.16,3304.65,318.52,308.06 --8870.00,-8161.29,-708.71,-8870.00,-7516.13,-1353.87,4803.27,318.52,303.31 --9200.00,-14696.97,5496.97,-9200.00,-1939.39,-7260.61,1808.23,318.52,312.82 --9510.00,-16967.74,7457.74,-9510.00,-645.16,-8864.84,-1128.71,318.52,322.14 --9810.00,-11966.67,2156.67,-9810.00,-6466.67,-3343.33,-1733.74,318.52,324.02 --10180.00,-3810.81,-6369.19,-10180.00,-13243.24,3063.24,1595.92,318.52,313.46 --10490.00,-3838.71,-6651.29,-10490.00,-14612.90,4122.90,5037.82,318.52,302.54 --10830.00,-11764.71,934.71,-10830.00,-8176.47,-2653.53,5692.86,318.52,300.47 --11180.00,-18514.29,7334.29,-11180.00,-257.14,-10922.86,0.00,318.52,317.69 --11490.00,-18322.58,6832.58,-11490.00,-1935.48,-9554.52,-340.21,318.52,319.62 --11840.00,-9685.71,-2154.29,-11840.00,-10200.00,-1640.00,1078.23,318.52,315.10 --12170.00,-4424.24,-7745.76,-12170.00,-15939.39,3769.39,3429.17,318.52,307.64 --12480.00,-10129.03,-2350.97,-12480.00,-13967.74,1487.74,5723.53,318.52,300.37 --12820.00,-16882.35,4062.35,-12820.00,-6058.82,-6761.18,5914.35,318.52,299.78 --13140.00,-20781.25,7641.25,-13140.00,-687.50,-12452.50,-952.12,318.52,321.58 --13460.00,-19062.50,5602.50,-13460.00,-2843.75,-10616.25,-789.41,318.52,321.03 --13810.00,-10400.00,-3410.00,-13810.00,-11171.43,-2638.57,344.14,318.52,317.43 --14140.00,-6333.33,-7806.67,-14140.00,-17545.45,3405.45,2985.37,318.52,309.05 --14460.00,-10937.50,-3522.50,-14460.00,-16531.25,2071.25,5309.11,318.52,301.69 --14790.00,-18121.21,3331.21,-14790.00,-9090.91,-5699.09,4944.67,318.52,302.85 --15110.00,-23031.25,7921.25,-15110.00,-3000.00,-12110.00,0.00,318.52,319.00 --15420.00,-20838.71,5418.71,-15420.00,-5064.52,-10355.48,0.00,318.52,319.02 --15770.00,-12914.29,-2855.71,-15770.00,-13057.14,-2712.86,1208.60,318.52,314.72 --16090.00,-10781.25,-5308.75,-16090.00,-19250.00,3160.00,2826.53,318.52,309.59 --16410.00,-14937.50,-1472.50,-16410.00,-17906.25,1496.25,4807.93,318.52,303.31 --16740.00,-20848.48,4108.48,-16740.00,-10606.06,-6133.94,4106.84,318.52,305.54 --17060.00,-24125.00,7065.00,-17060.00,-5531.25,-11528.75,0.00,318.52,319.26 --17370.00,-20483.87,3113.87,-17370.00,-8451.61,-8918.39,-1635.20,318.52,323.77 --17710.00,-13647.06,-4062.94,-17710.00,-16176.47,-1533.53,0.00,318.52,318.01 --18030.00,-11593.75,-6436.25,-18030.00,-22093.75,4063.75,1132.94,318.52,314.93 --18350.00,-15656.25,-2693.75,-18350.00,-20781.25,2431.25,4840.90,318.52,303.17 --18670.00,-21812.50,3142.50,-18670.00,-14781.25,-3888.75,4996.32,318.52,302.68 --18990.00,-25875.00,6885.00,-18990.00,-7875.00,-11115.00,0.00,318.52,318.62 --19310.00,-23625.00,4315.00,-19310.00,-8843.75,-10466.25,-706.66,318.52,320.79 --19630.00,-17781.25,-1848.75,-19630.00,-16656.25,-2973.75,-460.53,318.52,319.98 --19960.00,-14151.52,-5808.48,-19960.00,-22757.58,2797.58,1785.45,318.52,312.86 --20280.00,-16093.75,-4186.25,-20280.00,-22343.75,2063.75,4579.69,318.52,303.99 --20610.00,-22303.03,1693.03,-20610.00,-16151.52,-4458.48,5390.62,318.52,301.43 --20990.00,-27578.95,6588.95,-20990.00,-9894.74,-11095.26,1009.04,318.52,315.34 --21320.00,-27000.00,5680.00,-21320.00,-10727.27,-10592.73,0.00,318.52,317.83 --21650.00,-19909.09,-1740.91,-21650.00,-18151.52,-3498.48,500.17,318.52,316.96 --21970.00,-15500.00,-6470.00,-21970.00,-23968.75,1998.75,2468.80,318.52,310.71 --22300.00,-18757.58,-3542.42,-22300.00,-23333.33,1033.33,5187.84,318.52,302.09 --22630.00,-25424.24,2794.24,-22630.00,-17333.33,-5296.67,4584.06,318.52,304.02 --22950.00,-29593.75,6643.75,-22950.00,-13312.50,-9637.50,484.10,318.52,317.04 --23270.00,-28031.25,4761.25,-23270.00,-14812.50,-8457.50,0.00,318.52,319.41 --23104.60,-20727.27,-2377.33,-23600.00,-21303.03,-2296.97,0.00,318.52,317.72 --22784.60,-16187.50,-6597.10,-23775.28,-26218.75,2443.47,1902.96,318.52,312.54 --22464.60,-19000.00,-3464.60,-23455.28,-25093.75,1638.47,1934.45,318.52,312.44 --22134.60,-24787.88,2653.28,-23125.28,-19060.61,-4064.68,2422.45,318.52,310.90 --21814.60,-27125.00,5310.40,-22805.28,-16562.50,-6242.78,0.00,318.52,318.23 --21484.60,-24636.36,3151.76,-22475.28,-18181.82,-4293.46,413.39,318.52,317.28 --21164.60,-18531.25,-2633.35,-22155.28,-22562.50,407.22,868.37,318.52,315.83 --20844.60,-17531.25,-3313.35,-21835.28,-23656.25,1820.97,2463.15,318.52,310.77 --20524.60,-20437.50,-87.10,-21515.28,-20906.25,-609.03,4784.52,318.52,303.41 --20204.60,-24562.50,4357.90,-21195.28,-15312.50,-5882.78,2725.88,318.52,309.96 --19884.60,-26562.50,6677.90,-20875.28,-12437.50,-8437.78,1268.69,318.52,314.58 --19554.60,-23060.61,3506.00,-20545.28,-15515.15,-5030.13,0.00,318.52,318.97 --19234.60,-16812.50,-2422.10,-20225.28,-20968.75,743.47,973.03,318.52,315.52 --18914.60,-14000.00,-4914.60,-19905.28,-22875.00,2969.72,2997.96,318.52,309.10 --18594.60,-18187.50,-407.10,-19585.28,-19906.25,320.97,4601.44,318.52,304.02 --18274.60,-23968.75,5694.15,-19265.28,-14687.50,-4577.78,4297.06,318.52,305.00 --17954.60,-25312.50,7357.90,-18945.28,-11250.00,-7695.28,0.00,318.52,317.58 --17634.60,-22093.75,4459.15,-18625.28,-12250.00,-6375.28,0.00,318.52,317.88 --17314.60,-14187.50,-3127.10,-18305.28,-18000.00,-305.28,1156.90,318.52,314.97 --16994.60,-11750.00,-5244.60,-17985.28,-21562.50,3577.22,3221.18,318.52,308.42 --16664.60,-16090.91,-573.69,-17655.28,-18515.15,859.87,3543.33,318.52,307.41 --16334.60,-22000.00,5665.40,-17325.28,-11272.73,-6052.56,1428.04,318.52,314.12 --16014.60,-22375.00,6360.40,-17005.28,-9531.25,-7474.03,-699.91,318.52,320.88 --15694.60,-15625.00,-69.60,-16685.28,-14312.50,-2372.78,-612.05,318.52,320.47 --15364.60,-9151.52,-6213.09,-16355.28,-19454.55,3099.26,1287.08,318.52,314.44 --15044.60,-11187.50,-3857.10,-16035.28,-19531.25,3495.97,4283.22,318.52,304.93 --14714.60,-18636.36,3921.76,-15705.28,-13727.27,-1978.01,5775.37,318.52,300.21 --14384.60,-22121.21,7736.61,-15375.28,-5939.39,-9435.89,0.00,318.52,319.20 --14074.60,-20451.61,6377.01,-15065.28,-6354.84,-8710.44,328.31,318.52,317.50 --13744.60,-11151.52,-2593.09,-14735.28,-12939.39,-1795.89,1118.85,318.52,315.00 --13434.60,-7903.23,-5531.38,-14425.28,-18000.00,3574.72,2913.73,318.52,309.30 --13114.60,-13125.00,10.40,-14105.28,-15750.00,1644.72,5778.40,318.52,300.22 --12794.60,-18781.25,5986.65,-13785.28,-7937.50,-5847.78,4635.34,318.52,303.86 --12484.60,-20774.19,8289.59,-13475.28,-1548.39,-11926.90,3083.53,318.52,308.79 --12164.60,-18343.75,6179.15,-13155.28,-4125.00,-9030.28,-1425.20,318.52,323.10 --11854.60,-12741.94,887.33,-12845.28,-11903.23,-942.06,341.65,318.52,317.44 --11524.60,-6090.91,-5433.69,-12515.28,-17181.82,4666.54,3022.53,318.52,308.93 --11214.60,-7774.19,-3440.41,-12205.28,-14838.71,2633.43,6031.79,318.52,299.39 --10884.60,-14363.64,3479.03,-11875.28,-6000.00,-5875.28,5999.73,318.52,299.51 --10564.60,-18781.25,8216.65,-11555.28,187.50,-11742.78,-951.69,318.52,321.57 --10254.60,-17064.52,6809.91,-11245.28,-1967.74,-9277.54,0.00,318.52,318.94 --9924.60,-8333.33,-1591.27,-10915.28,-9393.94,-1521.34,1546.02,318.52,313.62 --9614.60,-4290.32,-5324.28,-10605.28,-14419.35,3814.07,2350.93,318.52,311.06 --9304.60,-8741.94,-562.67,-10295.28,-12225.81,1930.52,4535.27,318.52,304.14 --8994.60,-14000.00,5005.40,-9985.28,-5096.77,-4888.51,4609.02,318.52,303.91 --8684.60,-16516.13,7831.53,-9675.28,290.32,-9965.61,1258.34,318.52,314.55 --8384.60,-13633.33,5248.73,-9375.28,-1666.67,-7708.62,-358.29,318.52,319.69 --8074.60,-6870.97,-1203.64,-9065.28,-8774.19,-291.09,0.00,318.52,319.47 --7774.60,-2700.00,-5074.60,-8765.28,-13500.00,4734.72,2468.26,318.52,310.69 --7464.60,-5387.10,-2077.51,-8455.28,-11258.06,2802.78,1665.15,318.52,313.24 --7144.60,-10687.50,3542.90,-8135.28,-3718.75,-4416.53,2116.57,318.52,311.81 --6834.60,-11580.65,4746.04,-7825.28,-1193.55,-6631.73,-514.52,318.52,320.16 --6524.60,-8354.84,1830.24,-7515.28,-4064.52,-3450.77,-1230.64,318.52,322.43 --6214.60,-3451.61,-2762.99,-7205.28,-9967.74,2762.46,708.74,318.52,316.27 --5904.60,-3129.03,-2775.57,-6895.28,-11741.94,4846.65,2706.71,318.52,309.94 --5544.60,-6833.33,1288.73,-6535.28,-7194.44,659.16,5804.75,318.52,300.11 --5234.60,-11290.32,6055.72,-6225.28,2000.00,-8225.28,2721.40,318.52,309.91 --4924.60,-12935.48,8010.88,-5915.28,4258.06,-10173.35,-1476.65,318.52,323.23 --4624.60,-8833.33,4208.73,-5615.28,-2633.33,-2981.95,1354.13,318.52,314.23 --4294.60,-1454.55,-2840.06,-5285.28,-8848.48,3563.20,2627.30,318.52,310.19 --3994.60,-900.00,-3094.60,-4985.28,-7733.33,2748.05,4412.06,318.52,304.53 --3684.60,-6548.39,2863.78,-4675.28,-612.90,-4062.38,4971.44,318.52,302.76 --3374.60,-11322.58,7947.98,-4365.28,3838.71,-8203.99,-727.16,318.52,320.85 --3064.60,-9838.71,6774.11,-4055.28,1870.97,-5926.25,0.00,318.52,317.91 --2744.60,-906.25,-1838.35,-3735.28,-4781.25,1045.97,1803.19,318.52,312.80 --2434.60,2548.39,-4982.99,-3425.28,-7451.61,4026.33,3811.36,318.52,306.43 --2124.60,-3774.19,1649.59,-3115.28,-3064.52,-50.77,5347.55,318.52,301.57 --1804.60,-9718.75,7914.15,-2795.28,3812.50,-6607.78,2241.46,318.52,311.43 --1494.60,-8838.71,7344.11,-2485.28,5483.87,-7969.15,817.21,318.52,315.95 --1184.60,-1290.32,105.72,-2175.28,-645.16,-1530.12,1667.23,318.52,313.26 --874.60,2677.42,-3552.02,-1865.28,-5709.68,3844.39,526.21,318.52,316.88 --564.60,-1096.77,532.17,-1555.28,-4032.26,2476.98,4302.85,318.52,304.90 --254.60,-3903.23,3648.62,-1245.28,774.19,-2019.48,5391.15,318.52,301.46 -0.00,-6161.29,6161.29,-935.28,6354.84,-7290.12,0.00,318.52,317.62 -0.00,-5096.77,5096.77,-625.28,5677.42,-6302.70,463.77,318.52,317.10 -0.00,1800.00,-1800.00,-325.28,-2300.00,1974.72,1432.74,318.52,314.03 -0.00,2677.42,-2677.42,-15.28,-4870.97,4855.68,2685.94,318.52,310.05 -0.00,-866.67,866.67,0.00,500.00,-500.00,7010.80,318.52,296.34 -0.00,-5580.65,5580.65,0.00,7193.55,-7193.55,3765.65,318.52,306.65 -0.00,-9093.75,9093.75,0.00,9906.25,-9906.25,1279.73,318.52,314.54 -0.00,-5677.42,5677.42,0.00,4483.87,-4483.87,0.00,318.52,317.96 -0.00,2161.29,-2161.29,0.00,-3000.00,3000.00,1092.16,318.52,315.14 -0.00,3900.00,-3900.00,0.00,-3700.00,3700.00,5013.43,318.52,302.70 -0.00,-1433.33,1433.33,0.00,1300.00,-1300.00,1718.43,318.52,313.16 -0.00,-6843.75,6843.75,0.00,6187.50,-6187.50,-1208.09,318.52,322.45 -0.00,-3354.84,3354.84,0.00,4096.77,-4096.77,651.70,318.52,316.46 -0.00,2677.42,-2677.42,0.00,-1516.13,1516.13,1900.03,318.52,312.50 -0.00,1500.00,-1500.00,0.00,-1633.33,1633.33,2341.12,318.52,311.10 -0.00,-2866.67,2866.67,0.00,1500.00,-1500.00,4229.43,318.52,305.11 -0.00,-4466.67,4466.67,0.00,4333.33,-4333.33,1134.48,318.52,314.94 -0.00,-3838.71,3838.71,0.00,4419.35,-4419.35,-1237.19,318.52,322.47 -0.00,600.00,-600.00,0.00,200.00,-200.00,-574.52,318.52,320.35 -0.00,3766.67,-3766.67,0.00,-3866.67,3866.67,1766.42,318.52,312.92 -0.00,1866.67,-1866.67,0.00,-2033.33,2033.33,5192.97,318.52,302.05 -0.00,-3838.71,3838.71,0.00,4290.32,-4290.32,6091.93,318.52,299.21 -0.00,-8387.10,8387.10,0.00,9032.26,-9032.26,0.00,318.52,318.18 -0.00,-6866.67,6866.67,0.00,7033.33,-7033.33,-866.13,318.52,321.29 -0.00,1969.70,-1969.70,0.00,-1484.85,1484.85,872.54,318.52,315.76 -0.00,5451.61,-5451.61,0.00,-5516.13,5516.13,3046.05,318.52,308.86 -0.00,-133.33,133.33,0.00,-1266.67,1266.67,6150.64,318.52,299.02 -0.00,-6875.00,6875.00,0.00,5437.50,-5437.50,3849.92,318.52,306.33 -0.00,-8580.65,8580.65,0.00,9806.45,-9806.45,-1235.30,318.52,322.47 -0.00,-3064.52,3064.52,0.00,6451.61,-6451.61,-344.71,318.52,319.62 -0.00,3406.25,-3406.25,0.00,-2812.50,2812.50,2129.13,318.52,311.77 -0.00,2433.33,-2433.33,0.00,-5366.67,5366.67,5786.26,318.52,300.17 -0.00,-4433.33,4433.33,0.00,1366.67,-1366.67,5252.09,318.52,301.87 -0.00,-6937.50,6937.50,0.00,8437.50,-8437.50,453.94,318.52,317.10 -0.00,-5483.87,5483.87,0.00,8129.03,-8129.03,1641.45,318.52,313.34 -0.00,96.77,-96.77,0.00,-322.58,322.58,1040.76,318.52,315.25 -0.00,1766.67,-1766.67,0.00,-4533.33,4533.33,1805.35,318.52,312.82 -0.00,166.67,-166.67,0.00,-2600.00,2600.00,6049.24,318.52,299.36 -0.00,-3366.67,3366.67,0.00,4800.00,-4800.00,4221.69,318.52,305.17 -0.00,-6838.71,6838.71,0.00,9548.39,-9548.39,-1859.27,318.52,324.47 -0.00,-4033.33,4033.33,0.00,5933.33,-5933.33,0.00,318.52,318.27 -0.00,2687.50,-2687.50,0.00,-2437.50,2437.50,2088.91,318.52,311.90 -0.00,2451.61,-2451.61,0.00,-4387.10,4387.10,4450.55,318.52,304.40 -0.00,-3366.67,3366.67,0.00,1866.67,-1866.67,6673.48,318.52,297.36 -0.00,-6812.50,6812.50,0.00,8500.00,-8500.00,2123.48,318.52,311.81 -0.00,-7032.26,7032.26,0.00,9161.29,-9161.29,977.43,318.52,315.45 -0.00,-733.33,733.33,0.00,1400.00,-1400.00,503.29,318.52,316.95 -0.00,3085.71,-3085.71,0.00,-3942.86,3942.86,2252.61,318.52,311.41 -0.00,933.33,-933.33,0.00,-2033.33,2033.33,6434.64,318.52,298.14 -0.00,-4451.61,4451.61,0.00,5193.55,-5193.55,5044.27,318.52,302.57 -0.00,-8093.75,8093.75,0.00,9687.50,-9687.50,489.42,318.52,317.03 -0.00,-4935.48,4935.48,0.00,6322.58,-6322.58,0.00,318.52,317.60 -0.00,2266.67,-2266.67,0.00,-2000.00,2000.00,0.00,318.52,318.68 -0.00,3733.33,-3733.33,0.00,-5033.33,5033.33,2419.71,318.52,310.90 -0.00,-666.67,666.67,0.00,-1200.00,1200.00,5321.69,318.52,301.70 -0.00,-5866.67,5866.67,0.00,5900.00,-5900.00,4289.62,318.52,304.99 -0.00,-7366.67,7366.67,0.00,9600.00,-9600.00,1436.52,318.52,314.05 -0.00,-4741.94,4741.94,0.00,6129.03,-6129.03,-887.32,318.52,321.42 -0.00,1966.67,-1966.67,0.00,-2033.33,2033.33,0.00,318.52,318.92 -0.00,5000.00,-5000.00,0.00,-5580.65,5580.65,2152.85,318.52,311.69 -0.00,2466.67,-2466.67,0.00,-1866.67,1866.67,2472.83,318.52,310.68 -0.00,-3935.48,3935.48,0.00,4483.87,-4483.87,1579.15,318.52,313.52 -0.00,-5677.42,5677.42,0.00,5741.94,-5741.94,-651.63,318.52,320.60 -0.00,-3548.39,3548.39,0.00,1516.13,-1516.13,-1252.18,318.52,322.50 -0.00,2967.74,-2967.74,0.00,-2967.74,2967.74,1226.44,318.52,314.63 -0.00,4322.58,-4322.58,0.00,-2645.16,2645.16,4884.18,318.52,303.03 -0.00,-1866.67,1866.67,0.00,1566.67,-1566.67,5171.39,318.52,302.13 -0.00,-8218.75,8218.75,0.00,6593.75,-6593.75,2993.76,318.52,309.04 -0.00,-7935.48,7935.48,0.00,7225.81,-7225.81,-739.33,318.52,320.89 -0.00,-1033.33,1033.33,0.00,2133.33,-2133.33,0.00,318.52,318.78 -0.00,4593.75,-4593.75,0.00,-3531.25,3531.25,1357.19,318.52,314.22 -0.00,2233.33,-2233.33,0.00,-2733.33,2733.33,1369.50,318.52,314.18 -0.00,-3633.33,3633.33,0.00,2533.33,-2533.33,1104.20,318.52,315.02 -0.00,-3766.67,3766.67,0.00,4733.33,-4733.33,1998.36,318.52,312.19 -0.00,-1733.33,1733.33,0.00,3466.67,-3466.67,-469.81,318.52,320.02 -0.00,-966.67,966.67,0.00,633.33,-633.33,0.00,318.52,317.62 -0.00,266.67,-266.67,0.00,-1466.67,1466.67,1564.61,318.52,313.56 -0.00,-333.33,333.33,0.00,-300.00,300.00,1428.18,318.52,313.99 -0.00,-166.67,166.67,0.00,1666.67,-1666.67,0.00,318.52,318.57 -0.00,433.33,-433.33,0.00,2000.00,-2000.00,0.00,318.52,319.37 -0.00,-133.33,133.33,0.00,1300.00,-1300.00,-384.48,318.52,319.75 -0.00,-34.48,34.48,0.00,-172.41,172.41,0.00,318.52,318.00 -0.00,0.00,0.00,0.00,-103.45,103.45,670.01,318.52,316.40 -0.00,0.00,0.00,0.00,0.00,0.00,681.09,318.52,316.36 -0.00,0.00,0.00,0.00,0.00,0.00,658.65,318.52,316.43 -0.00,0.00,0.00,0.00,0.00,0.00,579.80,318.52,316.69 -0.00,0.00,0.00,0.00,0.00,0.00,570.41,318.52,316.72 -0.00,0.00,0.00,0.00,0.00,0.00,549.17,318.52,316.79 -0.00,0.00,0.00,0.00,0.00,0.00,606.37,318.52,316.61 -0.00,0.00,0.00,0.00,0.00,0.00,550.34,318.52,316.78 -0.00,0.00,0.00,0.00,0.00,0.00,550.43,318.52,316.78 -0.00,0.00,0.00,0.00,0.00,0.00,559.23,318.52,316.76 -0.00,0.00,0.00,0.00,0.00,0.00,545.86,318.52,316.80 -0.00,0.00,0.00,0.00,0.00,0.00,632.08,318.52,316.53 -0.00,0.00,0.00,0.00,0.00,0.00,590.14,318.52,316.66 -0.00,0.00,0.00,0.00,0.00,0.00,586.10,318.52,316.68 -0.00,0.00,0.00,0.00,0.00,0.00,566.37,318.52,316.74 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,347.66 -0.00,0.00,0.00,0.00,0.00,0.00,-476.63,346.67,348.19 -0.00,0.00,0.00,0.00,0.00,0.00,-401.23,346.67,347.95 -0.00,0.00,0.00,0.00,0.00,0.00,-401.47,346.67,347.95 -0.00,0.00,0.00,0.00,0.00,0.00,-442.76,346.67,348.08 -0.00,0.00,0.00,0.00,0.00,0.00,-472.73,346.67,348.17 -0.00,0.00,0.00,0.00,0.00,0.00,-409.37,346.67,347.97 -0.00,0.00,0.00,0.00,0.00,0.00,-409.60,346.67,347.97 -0.00,0.00,0.00,0.00,0.00,0.00,-341.87,346.67,347.75 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,347.32 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,347.32 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,346.69 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,346.53 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,346.30 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,346.30 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,346.34 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,346.07 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,346.04 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,346.04 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,346.30 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,346.21 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,346.26 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,346.26 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,346.23 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,346.24 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,346.24 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,345.89 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,346.29 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,346.57 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,346.57 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.67,346.55 -310.00,0.00,310.00,310.00,0.00,310.00,0.00,346.87,346.87 -610.00,0.00,610.00,610.00,0.00,610.00,0.00,346.87,346.51 -900.00,0.00,900.00,900.00,0.00,900.00,0.00,346.87,346.51 -1190.00,0.00,1190.00,1190.00,0.00,1190.00,0.00,346.87,346.81 -1480.00,0.00,1480.00,1480.00,0.00,1480.00,0.00,346.87,347.02 -1770.00,0.00,1770.00,1770.00,0.00,1770.00,0.00,346.87,346.81 -2060.00,68.97,1991.03,2060.00,172.41,1887.59,0.00,346.87,346.81 -2360.00,266.67,2093.33,2360.00,300.00,2060.00,1039.51,346.87,343.56 -2660.00,66.67,2593.33,2660.00,200.00,2460.00,2054.92,346.87,340.35 -2960.00,-300.00,3260.00,2960.00,1166.67,1793.33,2056.16,346.87,340.35 -3260.00,0.00,3260.00,3260.00,2266.67,993.33,5329.74,346.87,329.96 -3560.00,-133.33,3693.33,3560.00,3533.33,26.67,3920.59,346.87,334.45 -3860.00,-66.67,3926.67,3860.00,4900.00,-1040.00,6409.43,346.87,326.56 -4160.00,-133.33,4293.33,4160.00,6133.33,-1973.33,6413.27,346.87,326.56 -4470.00,-129.03,4599.03,4470.00,7387.10,-2917.10,6874.31,346.87,325.11 -4770.00,-200.00,4970.00,4770.00,8500.00,-3730.00,4711.33,346.87,331.98 -5080.00,193.55,4886.45,5080.00,8580.65,-3500.65,2803.05,346.87,338.05 -5430.00,742.86,4687.14,5430.00,7714.29,-2284.29,0.00,346.87,345.97 -5730.00,2300.00,3430.00,5730.00,6533.33,-803.33,0.00,346.87,345.97 -6030.00,5733.33,296.67,6030.00,5700.00,330.00,583.29,346.87,345.09 -6330.00,5666.67,663.33,6330.00,4900.00,1430.00,540.30,346.87,345.23 -6630.00,2833.33,3796.67,6630.00,4066.67,2563.33,1673.22,346.87,341.64 -6930.00,2600.00,4330.00,6930.00,4233.33,2696.67,1674.21,346.87,341.64 -7220.00,3931.03,3288.97,7220.00,5344.83,1875.17,5014.56,346.87,331.04 -7520.00,2666.67,4853.33,7520.00,6833.33,686.67,5647.70,346.87,329.04 -7820.00,1766.67,6053.33,7820.00,9033.33,-1213.33,9432.67,346.87,317.05 -8130.00,838.71,7291.29,8130.00,11161.29,-3031.29,9438.50,346.87,317.05 -8440.00,-322.58,8762.58,8440.00,14193.55,-5753.55,10618.43,346.87,313.32 -8750.00,-193.55,8943.55,8750.00,15838.71,-7088.71,7808.72,346.87,322.26 -9050.00,-100.00,9150.00,9050.00,16166.67,-7116.67,2552.07,346.87,338.95 -9360.00,1548.39,7811.61,9360.00,14709.68,-5349.68,2553.61,346.87,338.95 -9670.00,5741.94,3928.06,9670.00,12419.35,-2749.35,-452.21,346.87,348.49 -9980.00,6419.35,3560.65,9980.00,10806.45,-826.45,-719.81,346.87,349.15 -10280.00,7400.00,2880.00,10280.00,8900.00,1380.00,-1292.98,346.87,350.97 -10590.00,9064.52,1525.48,10590.00,8000.00,2590.00,-555.13,346.87,348.62 -10900.00,9935.48,964.52,10900.00,8225.81,2674.19,-555.47,346.87,348.62 -11210.00,9741.94,1468.06,11210.00,7419.35,3790.65,380.22,346.87,345.65 -11520.00,9419.35,2100.65,11520.00,8290.32,3229.68,1737.31,346.87,341.35 -11830.00,9193.55,2636.45,11830.00,9838.71,1991.29,5383.55,346.87,329.79 -12140.00,8193.55,3946.45,12140.00,11935.48,204.52,5386.88,346.87,329.79 -12450.00,6806.45,5643.55,12450.00,14064.52,-1614.52,10768.76,346.87,312.73 -12760.00,4870.97,7889.03,12760.00,15935.48,-3175.48,6572.74,346.87,326.06 -13080.00,1625.00,11455.00,13080.00,17812.50,-4732.50,8380.62,346.87,320.34 -13390.00,3709.68,9680.32,13390.00,18774.19,-5384.19,3938.22,346.87,334.45 -13710.00,6718.75,6991.25,13710.00,18562.50,-4852.50,3940.72,346.87,334.45 -14030.00,8562.50,5467.50,14030.00,16281.25,-2251.25,1239.75,346.87,343.02 -14340.00,8096.77,6243.23,14340.00,15774.19,-1434.19,1641.76,346.87,341.75 -14650.00,10354.84,4295.16,14650.00,14483.87,166.13,2778.81,346.87,338.15 -14960.00,11064.52,3895.48,14960.00,12870.97,2089.03,6984.78,346.87,324.81 -15270.00,10032.26,5237.74,15270.00,13032.26,2237.74,6989.08,346.87,324.81 -15590.00,7750.00,7840.00,15590.00,11812.50,3777.50,17414.24,346.87,291.75 -15910.00,4750.00,11160.00,15910.00,10687.50,5222.50,18222.74,346.87,289.22 -16230.00,-2187.50,18417.50,16230.00,9656.25,6573.75,17266.91,346.87,292.29 -16550.00,-4343.75,20893.75,16550.00,9062.50,7487.50,17277.91,346.87,292.29 -16860.00,-3322.58,20182.58,16860.00,8354.84,8505.16,18900.00,346.87,283.90 -17170.00,-161.29,17331.29,17170.00,6290.32,10879.68,18900.00,346.87,285.17 -17490.00,687.50,16802.50,17490.00,3656.25,13833.75,18900.00,346.87,279.32 -17800.00,-677.42,18477.42,17800.00,1129.03,16670.97,18900.00,346.87,269.42 -18100.00,266.67,17833.33,18100.00,566.67,17533.33,18900.00,346.87,269.42 -18400.00,533.33,17866.67,18400.00,0.00,18400.00,16834.00,346.87,293.94 -18700.00,-233.33,18933.33,18700.00,-33.33,18733.33,17070.97,346.87,293.22 -19000.00,-133.33,19133.33,19000.00,0.00,19000.00,16430.02,346.87,295.29 -19300.00,133.33,19166.67,19300.00,33.33,19266.67,16439.77,346.87,295.29 -19590.00,448.28,19141.72,19590.00,206.90,19383.10,15087.70,346.87,299.61 -19742.81,1333.33,18409.48,19890.00,133.33,19756.67,18106.89,346.87,290.06 -19442.81,1500.00,17942.81,20190.00,466.67,19723.33,18900.00,346.87,272.38 -19142.81,766.67,18376.15,20490.00,3366.67,17123.33,18900.00,346.87,272.38 -18832.81,161.29,18671.52,20800.00,5741.94,15058.06,18319.56,346.87,289.51 -18532.81,-133.33,18666.15,21100.00,8166.67,12933.33,18900.00,346.87,284.66 -18222.81,32.26,18190.56,21410.00,11419.35,9990.65,18900.00,346.87,287.01 -17912.81,-32.26,17945.07,21720.00,13225.81,8494.19,18900.00,346.87,287.01 -17602.81,0.00,17602.81,22030.00,10451.61,11578.39,18900.00,346.87,285.19 -17302.81,266.67,17036.15,22330.00,7300.00,15030.00,18900.00,346.87,282.40 -17002.81,300.00,16702.81,22630.00,8000.00,14630.00,18900.00,346.87,280.65 -16702.81,-866.67,17569.48,22455.46,11066.67,11388.79,18900.00,346.87,280.65 -16392.81,-612.90,17005.72,22145.46,14935.48,7209.98,18063.88,346.87,290.62 -16082.81,-64.52,16147.33,21835.46,19806.45,2029.01,15958.60,346.87,297.34 -15772.81,96.77,15676.04,21525.46,23354.84,-1829.38,14259.03,346.87,302.76 -15462.81,322.58,15140.23,21215.46,25516.13,-4300.67,12875.64,346.87,307.18 -15152.81,1000.00,14152.81,20905.46,26129.03,-5223.57,12883.39,346.87,307.18 -14842.81,1000.00,13842.81,20595.46,25322.58,-4727.12,11267.04,346.87,312.33 -14532.81,1548.39,12984.43,20285.46,26258.06,-5972.60,11103.66,346.87,312.87 -14172.81,2555.56,11617.26,19925.46,28694.44,-8768.98,8964.33,346.87,319.68 -13852.81,3687.50,10165.31,19605.46,30937.50,-11332.04,4515.82,346.87,333.81 -13542.81,5741.94,7800.88,19295.46,27322.58,-8027.12,4518.37,346.87,333.81 -13222.81,10687.50,2535.31,18975.46,20375.00,-1399.54,3461.87,346.87,337.17 -12912.81,11225.81,1687.01,18665.46,15580.65,3084.82,6125.94,346.87,328.72 -12602.81,7645.16,4957.65,18355.46,16516.13,1839.33,13956.65,346.87,303.89 -12292.81,2064.52,10228.30,18045.46,20580.65,-2535.18,13965.04,346.87,303.89 -11972.81,-4656.25,16629.06,17725.46,23875.00,-6149.54,14654.90,346.87,301.73 -11652.81,-4218.75,15871.56,17405.46,27625.00,-10219.54,12112.44,346.87,309.83 -11332.81,-2718.75,14051.56,17085.46,30531.25,-13445.79,8620.89,346.87,320.93 -11012.81,1875.00,9137.81,16765.46,28093.75,-11328.29,0.00,346.87,346.93 -10692.81,7093.75,3599.06,16445.46,17656.25,-1210.79,0.00,346.87,346.93 -10372.81,12125.00,-1752.19,16125.46,5843.75,10281.71,2213.99,346.87,341.27 -10062.81,12935.48,-2872.67,15815.46,4161.29,11654.17,5764.01,346.87,330.01 -9742.81,9062.50,680.31,15495.46,11000.00,4495.46,12438.57,346.87,308.85 -9432.81,1516.13,7916.69,15185.46,14193.55,991.91,10181.64,346.87,316.03 -9122.81,-4193.55,13316.36,14875.46,17290.32,-2414.86,10187.66,346.87,316.03 -8802.81,-3906.25,12709.06,14555.46,22000.00,-7444.54,9628.97,346.87,317.82 -8482.81,-281.25,8764.06,14235.46,26125.00,-11889.54,5775.42,346.87,330.07 -8162.81,2000.00,6162.81,13915.46,25093.75,-11178.29,-3756.55,346.87,0.32 -7842.81,4875.00,2967.81,13595.46,16750.00,-3154.54,-5256.87,346.87,3.54 -7522.81,10562.50,-3039.69,13275.46,4781.25,8494.21,-5260.23,346.87,3.54 -7222.81,15400.00,-8177.19,12975.46,-333.33,13308.79,-1184.25,346.87,350.60 -6912.81,13064.52,-6151.70,12665.46,4548.39,8117.07,8785.12,346.87,318.97 -6592.81,3968.75,2624.06,12345.46,12343.75,1.71,10359.59,346.87,314.00 -6282.81,-5032.26,11315.07,12035.46,16903.23,-4867.77,10366.01,346.87,314.00 -5962.81,-7687.50,13650.31,11715.46,22062.50,-10347.04,12322.93,346.87,307.81 -5642.81,-5500.00,11142.81,11395.46,25031.25,-13635.79,6959.53,346.87,324.85 -5322.81,-3156.25,8479.06,11075.46,23781.25,-12705.79,395.72,346.87,345.69 -5012.81,2516.13,2496.69,10765.46,16387.10,-5621.64,-1812.08,346.87,352.70 -4692.81,7562.50,-2869.69,10445.46,5062.50,5382.96,-1837.71,346.87,352.70 -4382.81,8870.97,-4488.15,10135.46,483.87,9651.59,912.35,346.87,343.97 -4082.81,5766.67,-1683.85,9835.46,5700.00,4135.46,7903.76,346.87,321.79 -3772.81,-129.03,3901.85,9525.46,13225.81,-3700.35,12851.20,346.87,306.11 -3462.81,-6806.45,10269.27,9215.46,18516.13,-9300.67,11288.59,346.87,311.09 -3142.81,-10937.50,14080.31,8895.46,21812.50,-12917.04,11295.80,346.87,311.09 -2822.81,-8937.50,11760.31,8575.46,21625.00,-13049.54,-5270.76,346.87,3.67 -2502.81,-5250.00,7752.81,8255.46,17187.50,-8932.04,-7089.71,346.87,9.36 -2202.81,2866.67,-663.85,7955.46,5933.33,2022.13,-548.90,346.87,348.59 -1892.81,7709.68,-5816.86,7645.46,-1193.55,8839.01,-549.24,346.87,348.59 -1582.81,4806.45,-3223.64,7335.46,2354.84,4980.62,12001.35,346.87,308.77 -1272.81,-2193.55,3466.36,7025.46,9516.13,-2490.67,15561.20,346.87,297.50 -952.81,-9187.50,10140.31,6705.46,14531.25,-7825.79,12811.44,346.87,306.25 -632.81,-13000.00,13632.81,6385.46,18875.00,-12489.54,9851.03,346.87,315.67 -312.81,-13031.25,13344.06,6065.46,20187.50,-14122.04,9857.32,346.87,315.67 -0.00,-9656.25,9656.25,5745.46,15312.50,-9567.04,-1749.17,346.87,352.51 -0.00,-5548.39,5548.39,5435.46,9548.39,-4112.93,0.00,346.87,346.67 -0.00,2406.25,-2406.25,5115.46,1000.00,4115.46,6051.16,346.87,327.67 -0.00,3300.00,-3300.00,4815.46,800.00,4015.46,13274.83,346.87,304.75 -0.00,-3354.84,3354.84,4505.46,7225.81,-2720.35,13283.05,346.87,304.75 -0.00,-9718.75,9718.75,4185.46,12906.25,-8720.79,11399.05,346.87,310.75 -0.00,-13125.00,13125.00,3865.46,17093.75,-13228.29,9809.91,346.87,315.82 -0.00,-12312.50,12312.50,3545.46,16875.00,-13329.54,-1510.76,346.87,351.75 -0.00,-7281.25,7281.25,3225.46,11281.25,-8055.79,-1889.24,346.87,352.86 -0.00,1533.33,-1533.33,2925.46,1166.67,1758.79,-1890.37,346.87,352.86 -0.00,5903.23,-5903.23,2615.46,-4322.58,6938.04,1651.64,346.87,341.62 -0.00,3709.68,-3709.68,2305.46,-2193.55,4499.01,4000.51,346.87,334.17 -0.00,-2483.87,2483.87,1995.46,5032.26,-3036.80,6874.77,346.87,325.06 -0.00,-7166.67,7166.67,1695.46,10133.33,-8437.87,6878.89,346.87,325.06 -0.00,-8709.68,8709.68,1385.46,11225.81,-9840.35,-545.04,346.87,348.63 -0.00,-5000.00,5000.00,1075.46,7096.77,-6021.31,-5429.58,346.87,4.09 -0.00,2612.90,-2612.90,765.46,-1419.35,2184.82,-2140.81,346.87,353.65 -0.00,7806.45,-7806.45,455.46,-6451.61,6907.07,-2142.14,346.87,353.65 -0.00,4766.67,-4766.67,155.46,-4733.33,4888.79,-1181.07,346.87,350.59 -0.00,-1657.14,1657.14,0.00,485.71,-485.71,480.89,346.87,345.32 -0.00,-2733.33,2733.33,0.00,2300.00,-2300.00,-6144.09,346.87,6.36 -0.00,322.58,-322.58,0.00,-64.52,64.52,-6317.44,346.87,6.91 -0.00,7843.75,-7843.75,0.00,-6000.00,6000.00,-6321.48,346.87,6.91 -0.00,10593.75,-10593.75,0.00,-9343.75,9343.75,-5295.45,346.87,3.64 -0.00,6419.35,-6419.35,0.00,-7000.00,7000.00,-6393.61,346.87,7.12 -0.00,612.90,-612.90,0.00,-3483.87,3483.87,-8217.73,346.87,12.89 -0.00,1612.90,-1612.90,0.00,-3483.87,3483.87,-7803.09,346.87,11.56 -0.00,9193.55,-9193.55,0.00,-6838.71,6838.71,-7807.91,346.87,11.56 -0.00,11806.45,-11806.45,0.00,-9258.06,9258.06,-6828.83,346.87,8.44 -0.00,7354.84,-7354.84,0.00,-8806.45,8806.45,-6328.92,346.87,6.84 -0.00,2935.48,-2935.48,0.00,-6967.74,6967.74,-6630.81,346.87,7.78 -0.00,3161.29,-3161.29,0.00,-5645.16,5645.16,-6634.89,346.87,7.78 -0.00,6000.00,-6000.00,0.00,-4838.71,4838.71,-6942.16,346.87,8.74 -0.00,7774.19,-7774.19,0.00,-5064.52,5064.52,-6527.13,346.87,7.41 -0.00,7451.61,-7451.61,0.00,-5741.94,5741.94,-6550.80,346.87,7.48 -0.00,6064.52,-6064.52,0.00,-5967.74,5967.74,-6646.25,346.87,7.77 -0.00,5322.58,-5322.58,0.00,-6032.26,6032.26,-6650.33,346.87,7.77 -0.00,5193.55,-5193.55,0.00,-5935.48,5935.48,-6394.52,346.87,6.94 -0.00,5516.13,-5516.13,0.00,-5838.71,5838.71,-6331.71,346.87,6.73 -0.00,5709.68,-5709.68,0.00,-5677.42,5677.42,-6142.09,346.87,6.12 -0.00,5733.33,-5733.33,0.00,-5566.67,5566.67,-6145.73,346.87,6.12 -0.00,5580.65,-5580.65,0.00,-5354.84,5354.84,-6073.29,346.87,5.87 -0.00,5354.84,-5354.84,0.00,-5258.06,5258.06,-5701.28,346.87,4.68 -0.00,5064.52,-5064.52,0.00,-5064.52,5064.52,-5369.18,346.87,3.62 -0.00,4225.81,-4225.81,0.00,-4193.55,4193.55,-5372.45,346.87,3.62 -0.00,3766.67,-3766.67,0.00,-3766.67,3766.67,-5483.80,346.87,3.96 -0.00,4100.00,-4100.00,0.00,-4366.67,4366.67,-5194.46,346.87,3.03 -0.00,4633.33,-4633.33,0.00,-4600.00,4600.00,-5134.36,346.87,2.83 -0.00,4612.90,-4612.90,0.00,-4419.35,4419.35,-5137.48,346.87,2.83 -0.00,3866.67,-3866.67,0.00,-4033.33,4033.33,-4687.59,346.87,1.40 -0.00,3266.67,-3266.67,0.00,-4000.00,4000.00,-4572.17,346.87,1.02 -0.00,3387.10,-3387.10,0.00,-3258.06,3258.06,-4222.70,346.87,359.90 -0.00,3451.61,-3451.61,0.00,-2806.45,2806.45,-4026.19,346.87,359.27 -0.00,2866.67,-2866.67,0.00,-3000.00,3000.00,-4028.54,346.87,359.27 -0.00,2300.00,-2300.00,0.00,-3200.00,3200.00,-3763.22,346.87,358.42 -0.00,2483.87,-2483.87,0.00,-3161.29,3161.29,-3434.25,346.87,357.37 -0.00,2709.68,-2709.68,0.00,-2516.13,2516.13,-3080.56,346.87,356.24 -0.00,2033.33,-2033.33,0.00,-1900.00,1900.00,-3082.33,346.87,356.24 -0.00,1433.33,-1433.33,0.00,-1166.67,1166.67,-3119.91,346.87,356.36 -0.00,266.67,-266.67,0.00,-1366.67,1366.67,-2903.08,346.87,355.66 -0.00,1533.33,-1533.33,0.00,-1900.00,1900.00,-3034.68,346.87,356.08 -0.00,2645.16,-2645.16,0.00,-2064.52,2064.52,-3036.48,346.87,356.08 -0.00,2833.33,-2833.33,0.00,-1266.67,1266.67,-1936.01,346.87,352.58 -0.00,2233.33,-2233.33,0.00,-1033.33,1033.33,-2421.88,346.87,354.12 -0.00,1700.00,-1700.00,0.00,0.00,0.00,-2947.13,346.87,355.78 -0.00,966.67,-966.67,0.00,-600.00,600.00,-2948.81,346.87,355.78 -0.00,1533.33,-1533.33,0.00,-2433.33,2433.33,-3533.10,346.87,357.63 -0.00,2133.33,-2133.33,0.00,-3333.33,3333.33,-2582.39,346.87,354.60 -0.00,2500.00,-2500.00,0.00,-3333.33,3333.33,-1634.78,346.87,351.59 -0.00,1800.00,-1800.00,0.00,-2800.00,2800.00,-1635.68,346.87,351.59 -0.00,666.67,-666.67,0.00,-2333.33,2333.33,-1846.62,346.87,352.26 -0.00,774.19,-774.19,0.00,-1677.42,1677.42,-1595.89,346.87,351.46 -0.00,-66.67,66.67,0.00,-1200.00,1200.00,-1178.15,346.87,350.13 -0.00,-172.41,172.41,0.00,68.97,-68.97,-1178.75,346.87,350.13 -0.00,66.67,-66.67,0.00,700.00,-700.00,-1236.46,346.87,350.31 -0.00,0.00,0.00,0.00,-100.00,100.00,-1312.45,346.87,350.55 -0.00,0.00,0.00,0.00,-482.76,482.76,-638.50,346.87,348.41 -0.00,0.00,0.00,0.00,586.21,-586.21,-638.78,346.87,348.41 -0.00,0.00,0.00,0.00,68.97,-68.97,-559.84,346.87,348.16 -0.00,0.00,0.00,0.00,-133.33,133.33,0.00,346.87,347.43 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.87,346.94 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.87,346.94 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.87,346.80 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.87,346.60 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,346.87,346.60 \ No newline at end of file +0.00,0.00,0.00,0.00,0.00,0.00,-177.80,278.92,281.74 +0.00,0.00,0.00,0.00,0.00,0.00,-177.80,278.92,281.74 +0.00,0.00,0.00,0.00,0.00,0.00,-147.55,278.92,281.26 +0.00,0.00,0.00,0.00,0.00,0.00,-150.32,278.92,281.31 +0.00,0.00,0.00,0.00,0.00,0.00,-131.82,278.92,281.01 +0.00,0.00,0.00,0.00,0.00,0.00,-131.82,278.92,281.01 +0.00,0.00,0.00,0.00,0.00,0.00,-153.37,278.92,281.36 +0.00,0.00,0.00,0.00,0.00,0.00,-162.51,278.92,281.50 +0.00,0.00,0.00,0.00,0.00,0.00,-162.51,278.92,281.50 +0.00,0.00,0.00,0.00,0.00,0.00,-178.14,278.92,281.75 +0.00,0.00,0.00,0.00,0.00,0.00,-173.78,278.92,281.68 +0.00,0.00,0.00,0.00,0.00,0.00,-159.61,278.92,281.45 +0.00,0.00,0.00,0.00,0.00,0.00,-159.61,278.92,281.45 +0.00,0.00,0.00,0.00,0.00,0.00,-158.89,278.92,281.44 +0.00,0.00,0.00,0.00,0.00,0.00,-177.80,278.92,281.74 +0.00,0.00,0.00,0.00,0.00,0.00,-177.80,278.92,281.74 +0.00,0.00,0.00,0.00,0.00,0.00,-171.07,278.92,281.64 +0.00,0.00,0.00,0.00,0.00,0.00,-172.86,278.92,281.66 +0.00,0.00,0.00,0.00,0.00,0.00,-175.11,278.92,281.70 +0.00,0.00,0.00,0.00,0.00,0.00,-175.11,278.92,281.70 +0.00,0.00,0.00,0.00,0.00,0.00,-163.92,278.92,281.52 +0.00,0.00,0.00,0.00,0.00,0.00,-161.52,278.92,281.48 +0.00,0.00,0.00,0.00,0.00,0.00,-177.62,278.92,281.74 +0.00,0.00,0.00,0.00,0.00,0.00,-177.62,278.92,281.74 +0.00,0.00,0.00,0.00,0.00,0.00,-159.70,278.92,281.46 +0.00,0.00,0.00,0.00,0.00,0.00,-159.99,278.92,281.46 +0.00,0.00,0.00,0.00,0.00,0.00,-166.76,278.92,281.57 +0.00,0.00,0.00,0.00,0.00,0.00,-166.76,278.92,281.57 +0.00,0.00,0.00,0.00,0.00,0.00,-170.81,278.92,281.63 +0.00,0.00,0.00,0.00,0.00,0.00,-183.08,278.92,281.83 +0.00,0.00,0.00,0.00,0.00,0.00,-183.08,278.92,281.83 +0.00,0.00,0.00,0.00,0.00,0.00,-166.22,278.92,281.56 +0.00,0.00,0.00,0.00,0.00,0.00,-154.34,278.92,281.37 +0.00,0.00,0.00,0.00,0.00,0.00,-147.94,278.92,281.27 +0.00,0.00,0.00,0.00,0.00,0.00,-147.94,278.92,281.27 +0.00,0.00,0.00,0.00,0.00,0.00,-170.56,278.92,281.63 +0.00,0.00,0.00,0.00,0.00,0.00,-166.36,278.92,281.56 +0.00,0.00,0.00,0.00,0.00,0.00,-186.38,278.92,281.88 +0.00,0.00,0.00,0.00,0.00,0.00,-186.38,278.92,281.88 +0.00,0.00,0.00,0.00,0.00,0.00,-182.31,278.92,281.81 +0.00,0.00,0.00,0.00,0.00,0.00,-208.67,278.92,282.23 +0.00,0.00,0.00,0.00,0.00,0.00,-208.67,278.92,282.23 +0.00,0.00,0.00,0.00,0.00,0.00,-187.24,278.92,281.89 +0.00,0.00,0.00,0.00,0.00,0.00,-173.45,278.92,281.67 +0.00,0.00,0.00,0.00,0.00,0.00,-190.57,278.92,281.95 +0.00,0.00,0.00,0.00,0.00,0.00,-190.57,278.92,281.95 +0.00,0.00,0.00,0.00,0.00,0.00,-185.93,278.92,281.87 +0.00,0.00,0.00,0.00,0.00,0.00,-173.88,278.92,281.68 +0.00,0.00,0.00,0.00,0.00,0.00,-151.67,278.92,281.33 +0.00,0.00,0.00,0.00,0.00,0.00,-151.67,278.92,281.33 +0.00,0.00,0.00,0.00,0.00,0.00,-157.38,278.92,281.42 +0.00,0.00,0.00,0.00,0.00,0.00,-160.64,278.92,281.47 +0.00,0.00,0.00,0.00,0.00,0.00,-160.64,278.92,281.47 +0.00,0.00,0.00,0.00,0.00,0.00,-170.85,278.92,281.63 +0.00,0.00,0.00,0.00,0.00,0.00,-172.86,278.92,281.66 +0.00,0.00,0.00,0.00,0.00,0.00,-176.01,278.92,281.71 +0.00,0.00,0.00,0.00,0.00,0.00,-176.01,278.92,281.71 +0.00,0.00,0.00,0.00,0.00,0.00,-177.85,278.92,281.74 +0.00,0.00,0.00,0.00,0.00,0.00,-197.79,278.92,282.06 +0.00,0.00,0.00,0.00,0.00,0.00,-197.79,278.92,282.06 +0.00,0.00,0.00,0.00,0.00,0.00,-180.39,278.92,281.78 +0.00,0.00,0.00,0.00,0.00,0.00,-175.95,278.92,281.71 +0.00,0.00,0.00,0.00,0.00,0.00,-181.86,278.92,281.81 +0.00,0.00,0.00,0.00,0.00,0.00,-181.86,278.92,281.81 +0.00,0.00,0.00,0.00,0.00,0.00,-208.99,278.92,282.24 +0.00,0.00,0.00,0.00,0.00,0.00,-185.02,278.92,281.86 +0.00,0.00,0.00,0.00,0.00,0.00,-185.02,278.92,281.86 +0.00,0.00,0.00,0.00,0.00,0.00,-192.19,278.92,281.97 +0.00,0.00,0.00,0.00,0.00,0.00,-217.43,278.92,282.37 +0.00,0.00,0.00,0.00,0.00,0.00,-211.82,278.92,282.28 +0.00,0.00,0.00,0.00,0.00,0.00,-211.82,278.92,282.28 +0.00,0.00,0.00,0.00,0.00,0.00,-244.92,278.92,282.81 +0.00,0.00,0.00,0.00,0.00,0.00,-250.41,278.92,282.90 +0.00,0.00,0.00,0.00,0.00,0.00,-232.31,278.92,282.61 +0.00,0.00,0.00,0.00,0.00,0.00,-232.31,278.92,282.61 +0.00,0.00,0.00,0.00,0.00,0.00,-228.85,278.92,282.55 +0.00,0.00,0.00,0.00,0.00,0.00,-190.92,278.92,281.95 +0.00,0.00,0.00,0.00,0.00,0.00,-190.92,278.92,281.95 +0.00,0.00,0.00,0.00,0.00,0.00,-173.38,278.92,281.67 +0.00,0.00,0.00,0.00,0.00,0.00,-153.91,278.92,281.36 +0.00,0.00,0.00,0.00,0.00,0.00,-149.66,278.92,281.30 +0.00,0.00,0.00,0.00,0.00,0.00,-149.66,278.92,281.30 +0.00,0.00,0.00,0.00,0.00,0.00,-157.86,278.92,281.43 +0.00,0.00,0.00,0.00,0.00,0.00,-141.89,278.92,281.17 +0.00,0.00,0.00,0.00,0.00,0.00,-141.89,278.92,281.17 +0.00,0.00,0.00,0.00,0.00,0.00,-136.59,278.92,281.09 +-320.00,0.00,-320.00,-320.00,0.00,-320.00,0.00,281.20,281.20 +-610.00,0.00,-610.00,-610.00,0.00,-610.00,0.00,281.20,281.53 +-900.00,0.00,-900.00,-900.00,0.00,-900.00,0.00,281.20,281.53 +-1240.00,0.00,-1240.00,-1240.00,0.00,-1240.00,0.00,281.20,281.49 +-1530.00,0.00,-1530.00,-1530.00,0.00,-1530.00,0.00,281.20,281.25 +-1820.00,0.00,-1820.00,-1820.00,0.00,-1820.00,0.00,281.20,281.30 +-2110.00,-137.93,-1972.07,-2110.00,-137.93,-1972.07,0.00,281.20,281.30 +-2410.00,-366.67,-2043.33,-2410.00,-266.67,-2143.33,0.00,281.20,281.67 +-2710.00,-266.67,-2443.33,-2710.00,-133.33,-2576.67,0.00,281.20,280.68 +-3010.00,-866.67,-2143.33,-3010.00,-400.00,-2610.00,140.21,281.20,278.98 +-3320.00,-2225.81,-1094.19,-3320.00,-1612.90,-1707.10,215.79,281.20,277.78 +-3630.00,-2935.48,-694.52,-3630.00,-2580.65,-1049.35,215.79,281.20,277.78 +-3940.00,-2903.23,-1036.77,-3940.00,-2677.42,-1262.58,298.93,281.20,276.46 +-4250.00,-2451.61,-1798.39,-4250.00,-2096.77,-2153.23,365.82,281.20,275.40 +-4560.00,-3064.52,-1495.48,-4560.00,-1806.45,-2753.55,190.68,281.20,278.18 +-4870.00,-3741.94,-1128.06,-4870.00,-2516.13,-2353.87,190.68,281.20,278.18 +-5180.00,-4322.58,-857.42,-5180.00,-3645.16,-1534.84,169.33,281.20,278.51 +-5490.00,-4580.65,-909.35,-5490.00,-4225.81,-1264.19,272.61,281.20,276.88 +-5800.00,-4741.94,-1058.06,-5800.00,-4451.61,-1348.39,246.25,281.20,277.29 +-6110.00,-4967.74,-1142.26,-6110.00,-4580.65,-1529.35,246.25,281.20,277.29 +-6420.00,-5322.58,-1097.42,-6420.00,-4612.90,-1807.10,256.26,281.20,277.13 +-6730.00,-5709.68,-1020.32,-6730.00,-4870.97,-1859.03,255.89,281.20,277.14 +-7040.00,-6064.52,-975.48,-7040.00,-5354.84,-1685.16,277.12,281.20,276.80 +-7350.00,-6419.35,-930.65,-7350.00,-5806.45,-1543.55,296.24,281.20,276.50 +-7660.00,-6838.71,-821.29,-7660.00,-6129.03,-1530.97,296.24,281.20,276.50 +-7970.00,-7129.03,-840.97,-7970.00,-6387.10,-1582.90,292.58,281.20,276.56 +-8280.00,-7419.35,-860.65,-8280.00,-6645.16,-1634.84,337.49,281.20,275.85 +-8580.00,-7666.67,-913.33,-8580.00,-6933.33,-1646.67,318.73,281.20,276.14 +-8890.00,-8032.26,-857.74,-8890.00,-7290.32,-1599.68,318.73,281.20,276.14 +-9200.00,-8354.84,-845.16,-9200.00,-7548.39,-1651.61,354.84,281.20,275.57 +-9500.00,-8666.67,-833.33,-9500.00,-7900.00,-1600.00,346.75,281.20,275.70 +-9810.00,-9000.00,-810.00,-9810.00,-8225.81,-1584.19,388.26,281.20,275.04 +-10120.00,-9322.58,-797.42,-10120.00,-8483.87,-1636.13,430.98,281.20,274.36 +-10430.00,-9612.90,-817.10,-10430.00,-8838.71,-1591.29,430.98,281.20,274.36 +-10740.00,-9935.48,-804.52,-10740.00,-9096.77,-1643.23,432.14,281.20,274.34 +-11050.00,-10290.32,-759.68,-11050.00,-9354.84,-1695.16,452.42,281.20,274.02 +-11360.00,-10612.90,-747.10,-11360.00,-9645.16,-1714.84,526.77,281.20,272.84 +-11670.00,-10870.97,-799.03,-11670.00,-9935.48,-1734.52,526.77,281.20,272.84 +-11980.00,-11258.06,-721.94,-11980.00,-10161.29,-1818.71,539.96,281.20,272.63 +-12290.00,-11548.39,-741.61,-12290.00,-10419.35,-1870.65,553.51,281.20,272.42 +-12600.00,-11967.74,-632.26,-12600.00,-10741.94,-1858.06,554.39,281.20,272.40 +-12920.00,-12218.75,-701.25,-12920.00,-11031.25,-1888.75,622.34,281.20,271.32 +-13240.00,-12437.50,-802.50,-13240.00,-11312.50,-1927.50,622.34,281.20,271.32 +-13550.00,-12774.19,-775.81,-13550.00,-11548.39,-2001.61,620.68,281.20,271.35 +-13850.00,-13133.33,-716.67,-13850.00,-11800.00,-2050.00,635.94,281.20,271.11 +-14170.00,-13437.50,-732.50,-14170.00,-12125.00,-2045.00,642.39,281.20,271.01 +-14480.00,-13838.71,-641.29,-14480.00,-12354.84,-2125.16,642.39,281.20,271.01 +-14790.00,-14064.52,-725.48,-14790.00,-12677.42,-2112.58,656.82,281.20,270.78 +-15100.00,-14419.35,-680.65,-15100.00,-13000.00,-2100.00,640.36,281.20,271.04 +-15420.00,-14625.00,-795.00,-15420.00,-13250.00,-2170.00,654.50,281.20,270.81 +-15730.00,-15000.00,-730.00,-15730.00,-13580.65,-2149.35,684.69,281.20,270.33 +-16040.00,-15322.58,-717.42,-16040.00,-13935.48,-2104.52,684.69,281.20,270.33 +-16360.00,-15718.75,-641.25,-16360.00,-14218.75,-2141.25,759.03,281.20,269.15 +-16680.00,-16031.25,-648.75,-16680.00,-14468.75,-2211.25,758.07,281.20,269.17 +-16990.00,-16354.84,-635.16,-16990.00,-14774.19,-2215.81,796.32,281.20,268.56 +-17300.00,-16645.16,-654.84,-17300.00,-15000.00,-2300.00,796.32,281.20,268.56 +-17620.00,-17000.00,-620.00,-17620.00,-15343.75,-2276.25,809.10,281.20,268.36 +-17940.00,-17312.50,-627.50,-17940.00,-15718.75,-2221.25,874.11,281.20,267.33 +-18260.00,-17718.75,-541.25,-18260.00,-16031.25,-2228.75,896.67,281.20,266.97 +-18570.00,-18000.00,-570.00,-18570.00,-16290.32,-2279.68,973.13,281.20,265.76 +-18880.00,-18354.84,-525.16,-18880.00,-16548.39,-2331.61,973.13,281.20,265.76 +-19200.00,-18812.50,-387.50,-19200.00,-16781.25,-2418.75,1029.92,281.20,264.85 +-19520.00,-19218.75,-301.25,-19520.00,-17031.25,-2488.75,1062.06,281.20,264.34 +-19840.00,-19468.75,-371.25,-19840.00,-17250.00,-2590.00,1069.36,281.20,264.23 +-20160.00,-19812.50,-347.50,-20160.00,-17562.50,-2597.50,1072.58,281.20,264.18 +-20480.00,-20031.25,-448.75,-20480.00,-17812.50,-2667.50,1072.58,281.20,264.18 +-20800.00,-20156.25,-643.75,-20800.00,-18250.00,-2550.00,1095.88,281.20,263.81 +-21120.00,-20562.50,-557.50,-21120.00,-18500.00,-2620.00,1120.44,281.20,263.42 +-21490.00,-20945.95,-544.05,-21490.00,-18783.78,-2706.22,1140.44,281.20,263.10 +-21800.00,-21322.58,-477.42,-21800.00,-19161.29,-2638.71,1161.85,281.20,262.76 +-22110.00,-21838.71,-271.29,-22110.00,-19419.35,-2690.65,1161.85,281.20,262.76 +-22430.00,-22000.00,-430.00,-22430.00,-19593.75,-2836.25,1229.28,281.20,261.69 +-22760.00,-22363.64,-396.36,-22760.00,-19909.09,-2850.91,1208.37,281.20,262.02 +-23080.00,-22656.25,-423.75,-23080.00,-20218.75,-2861.25,1249.77,281.20,261.36 +-23400.00,-23125.00,-275.00,-23400.00,-20468.75,-2931.25,1242.71,281.20,261.48 +-23720.00,-23500.00,-220.00,-23720.00,-20843.75,-2876.25,1246.61,281.20,261.41 +-24040.00,-23750.00,-290.00,-24040.00,-21187.50,-2852.50,1246.61,281.20,261.41 +-24360.00,-23968.75,-391.25,-24360.00,-21500.00,-2860.00,1246.02,281.20,261.42 +-24680.00,-24406.25,-273.75,-24680.00,-21843.75,-2836.25,1198.51,281.20,262.18 +-25000.00,-24625.00,-375.00,-25000.00,-22125.00,-2875.00,1197.51,281.20,262.19 +-25320.00,-24781.25,-538.75,-25320.00,-22375.00,-2945.00,1165.38,281.20,262.70 +-25640.00,-24968.75,-671.25,-25640.00,-22750.00,-2890.00,1165.38,281.20,262.70 +-25960.00,-25218.75,-741.25,-25960.00,-23312.50,-2647.50,1120.43,281.20,263.42 +-26280.00,-25593.75,-686.25,-26280.00,-23531.25,-2748.75,1107.39,281.20,263.62 +-26600.00,-25781.25,-818.75,-26600.00,-23906.25,-2693.75,1095.39,281.20,263.82 +-26920.00,-26281.25,-638.75,-26920.00,-24000.00,-2920.00,1079.97,281.20,264.06 +-27240.00,-26562.50,-677.50,-27240.00,-24406.25,-2833.75,1079.97,281.20,264.06 +-27560.00,-27062.50,-497.50,-27560.00,-24812.50,-2747.50,1052.45,281.20,264.50 +-27880.00,-27156.25,-723.75,-27880.00,-25093.75,-2786.25,1051.00,281.20,264.52 +-28200.00,-27468.75,-731.25,-28200.00,-25406.25,-2793.75,1057.11,281.20,264.42 +-28520.00,-27875.00,-645.00,-28520.00,-25656.25,-2863.75,1025.26,281.20,264.93 +-28840.00,-27781.25,-1058.75,-28840.00,-25937.50,-2902.50,1025.26,281.20,264.93 +-29160.00,-28250.00,-910.00,-29160.00,-26125.00,-3035.00,1007.88,281.20,265.20 +-29480.00,-28500.00,-980.00,-29480.00,-26656.25,-2823.75,968.39,281.20,265.83 +-29810.00,-29000.00,-810.00,-29810.00,-27181.82,-2628.18,957.23,281.20,266.01 +-30130.00,-29156.25,-973.75,-30130.00,-27531.25,-2598.75,941.39,281.20,266.26 +-30450.00,-29375.00,-1075.00,-30450.00,-27593.75,-2856.25,941.39,281.20,266.26 +-30780.00,-29818.18,-961.82,-30780.00,-28000.00,-2780.00,918.42,281.20,266.62 +-31110.00,-30212.12,-897.88,-31110.00,-28151.52,-2958.48,871.54,281.20,267.37 +-31430.00,-30375.00,-1055.00,-31430.00,-28562.50,-2867.50,850.76,281.20,267.70 +-31760.00,-30515.15,-1244.85,-31760.00,-29090.91,-2669.09,816.56,281.20,268.24 +-32090.00,-30909.09,-1180.91,-32090.00,-29393.94,-2696.06,816.56,281.20,268.24 +-32410.00,-31281.25,-1128.75,-32410.00,-29500.00,-2910.00,816.69,281.20,268.24 +-32740.00,-31242.42,-1497.58,-32740.00,-29696.97,-3043.03,777.47,281.20,268.86 +-33070.00,-31787.88,-1282.12,-33070.00,-29666.67,-3403.33,709.53,281.20,269.94 +-33400.00,-32121.21,-1278.79,-33400.00,-30696.97,-2703.03,658.10,281.20,270.76 +-33451.12,-32593.75,-857.37,-33589.43,-31343.75,-2245.68,629.95,281.20,271.20 +-33121.12,-32545.45,-575.67,-33259.43,-31696.97,-1562.47,629.95,281.20,271.20 +-32791.12,-32484.85,-306.28,-32929.43,-31545.45,-1383.98,678.70,281.20,270.43 +-32461.12,-32090.91,-370.22,-32599.43,-30787.88,-1811.56,656.99,281.20,270.77 +-32131.12,-31666.67,-464.46,-32269.43,-30575.76,-1693.68,610.54,281.20,271.51 +-31801.12,-31454.55,-346.58,-31939.43,-30454.55,-1484.89,574.48,281.20,272.08 +-31471.12,-31030.30,-440.82,-31609.43,-30181.82,-1427.62,574.48,281.20,272.08 +-31141.12,-30242.42,-898.70,-31279.43,-29454.55,-1824.89,555.95,281.20,272.38 +-30821.12,-30500.00,-321.12,-30959.43,-29375.00,-1584.43,556.03,281.20,272.38 +-30501.12,-30281.25,-219.87,-30639.43,-28937.50,-1701.93,484.60,281.20,273.51 +-30181.12,-30000.00,-181.12,-30319.43,-28687.50,-1631.93,442.66,281.20,274.18 +-29851.12,-29393.94,-457.19,-29989.43,-28545.45,-1443.98,452.53,281.20,274.02 +-29531.12,-28718.75,-812.37,-29669.43,-28343.75,-1325.68,452.53,281.20,274.02 +-29211.12,-28687.50,-523.62,-29349.43,-28218.75,-1130.68,399.77,281.20,274.86 +-28891.12,-28468.75,-422.37,-29029.43,-27593.75,-1435.68,331.46,281.20,275.94 +-28561.12,-28000.00,-561.12,-28699.43,-27515.15,-1184.28,305.92,281.20,276.35 +-28241.12,-27562.50,-678.62,-28379.43,-27343.75,-1035.68,250.97,281.20,277.22 +-27911.12,-27515.15,-395.97,-28049.43,-27000.00,-1049.43,250.97,281.20,277.22 +-27581.12,-26909.09,-672.03,-27719.43,-26636.36,-1083.07,274.58,281.20,276.84 +-27261.12,-26593.75,-667.37,-27399.43,-26375.00,-1024.43,238.21,281.20,277.42 +-26931.12,-26393.94,-537.19,-27069.43,-25939.39,-1130.04,212.66,281.20,277.83 +-26601.12,-26030.30,-570.82,-26739.43,-25515.15,-1224.28,233.82,281.20,277.49 +-26281.12,-25718.75,-562.37,-26419.43,-25156.25,-1263.18,233.82,281.20,277.49 +-25961.12,-25468.75,-492.37,-26099.43,-24968.75,-1130.68,179.67,281.20,278.35 +-25581.12,-25078.95,-502.18,-25719.43,-24657.89,-1061.54,144.80,281.20,278.90 +-25261.12,-24718.75,-542.37,-25399.43,-24562.50,-836.93,155.96,281.20,278.73 +-24941.12,-24281.25,-659.87,-25079.43,-24218.75,-860.68,134.42,281.20,279.07 +-24621.12,-24125.00,-496.12,-24759.43,-23937.50,-821.93,154.01,281.20,278.76 +-24291.12,-23696.97,-594.16,-24429.43,-23666.67,-762.77,154.01,281.20,278.76 +-23971.12,-23375.00,-596.12,-24109.43,-23250.00,-859.43,130.26,281.20,279.13 +-23651.12,-23093.75,-557.37,-23789.43,-22937.50,-851.93,96.75,281.20,279.67 +-23331.12,-22812.50,-518.62,-23469.43,-22656.25,-813.18,0.00,281.20,280.59 +-23011.12,-22218.75,-792.37,-23149.43,-22406.25,-743.18,70.41,281.20,280.08 +-22691.12,-22062.50,-628.62,-22829.43,-21968.75,-860.68,70.41,281.20,280.08 +-22371.12,-21875.00,-496.12,-22509.43,-21750.00,-759.43,76.66,281.20,279.99 +-22051.12,-21750.00,-301.12,-22189.43,-21437.50,-751.93,0.00,281.20,280.43 +-21731.12,-21312.50,-418.62,-21869.43,-21062.50,-806.93,0.00,281.20,280.93 +-21411.12,-20812.50,-598.62,-21549.43,-20875.00,-674.43,0.00,281.20,280.97 +-21091.12,-20562.50,-528.62,-21229.43,-20593.75,-635.68,0.00,281.20,280.97 +-20771.12,-20250.00,-521.12,-20909.43,-20250.00,-659.43,0.00,281.20,280.49 +-20451.12,-19718.75,-732.37,-20589.43,-19875.00,-714.43,0.00,281.20,280.75 +-20131.12,-19625.00,-506.12,-20269.43,-19500.00,-769.43,0.00,281.20,280.89 +-19811.12,-19343.75,-467.37,-19949.43,-19218.75,-730.68,0.00,281.20,281.07 +-19491.12,-18843.75,-647.37,-19629.43,-18937.50,-691.93,0.00,281.20,281.07 +-19181.12,-18612.90,-568.22,-19319.43,-18774.19,-545.24,0.00,281.20,280.90 +-18861.12,-18343.75,-517.37,-18999.43,-18562.50,-436.93,0.00,281.20,280.79 +-18541.12,-18062.50,-478.62,-18679.43,-18218.75,-460.68,0.00,281.20,281.06 +-18231.12,-17677.42,-553.71,-18369.43,-17967.74,-401.69,0.00,281.20,281.02 +-17911.12,-17437.50,-473.62,-18049.43,-17718.75,-330.68,0.00,281.20,281.02 +-17601.12,-17193.55,-407.58,-17739.43,-17161.29,-578.14,0.00,281.20,280.96 +-17281.12,-16750.00,-531.12,-17419.43,-16906.25,-513.18,0.00,281.20,281.61 +-16961.12,-16531.25,-429.87,-17099.43,-16656.25,-443.18,0.00,281.20,281.52 +-16651.12,-16354.84,-296.29,-16789.43,-16419.35,-370.08,0.00,281.20,281.74 +-16331.12,-16000.00,-331.12,-16469.43,-15937.50,-531.93,0.00,281.20,281.74 +-16021.12,-15645.16,-375.96,-16159.43,-15677.42,-482.02,0.00,281.20,281.03 +-15701.12,-15343.75,-357.37,-15839.43,-15375.00,-464.43,0.00,281.20,281.55 +-15381.12,-15031.25,-349.87,-15519.43,-15062.50,-456.93,0.00,281.20,281.97 +-15061.12,-14812.50,-248.62,-15199.43,-14750.00,-449.43,0.00,281.20,281.97 +-14751.12,-14419.35,-331.77,-14889.43,-14322.58,-566.85,0.00,281.20,281.96 +-14441.12,-14129.03,-312.09,-14579.43,-13935.48,-643.95,-78.90,281.20,282.45 +-14131.12,-13838.71,-292.42,-14269.43,-13709.68,-559.76,-115.54,281.20,283.04 +-13811.12,-13468.75,-342.37,-13949.43,-13531.25,-418.18,-116.18,281.20,283.05 +-13501.12,-13129.03,-372.09,-13639.43,-13387.10,-252.34,-116.18,281.20,283.05 +-13181.12,-12812.50,-368.62,-13319.43,-13093.75,-225.68,-136.08,281.20,283.36 +-12861.12,-12468.75,-392.37,-12999.43,-12687.50,-311.93,-166.95,281.20,283.85 +-12541.12,-12156.25,-384.87,-12679.43,-12375.00,-304.43,-177.70,281.20,284.02 +-12221.12,-11750.00,-471.12,-12359.43,-12125.00,-234.43,-214.41,281.20,284.61 +-11911.12,-11451.61,-459.51,-12049.43,-11870.97,-178.47,-214.41,281.20,284.61 +-11591.12,-11062.50,-528.62,-11729.43,-11687.50,-41.93,-178.45,281.20,284.03 +-11281.12,-10806.45,-474.67,-11419.43,-11354.84,-64.60,-222.52,281.20,284.73 +-10971.12,-10580.65,-390.48,-11109.43,-11000.00,-109.43,-207.54,281.20,284.50 +-10661.12,-10290.32,-370.80,-10799.43,-10741.94,-57.50,-207.54,281.20,284.50 +-10351.12,-9903.23,-447.90,-10489.43,-10516.13,26.69,-233.66,281.20,284.91 +-10041.12,-9483.87,-557.25,-10179.43,-10225.81,46.37,-249.91,281.20,285.17 +-9731.12,-9161.29,-569.83,-9869.43,-9806.45,-62.98,-271.57,281.20,285.51 +-9421.12,-8935.48,-485.64,-9559.43,-9516.13,-43.31,-255.03,281.20,285.25 +-9101.12,-8656.25,-444.87,-9239.43,-9312.50,73.07,-255.03,281.20,285.25 +-8791.12,-8354.84,-436.29,-8929.43,-9032.26,102.82,-226.19,281.20,284.79 +-8471.12,-8000.00,-471.12,-8609.43,-8687.50,78.07,-219.05,281.20,284.68 +-8161.12,-7741.94,-419.19,-8299.43,-8354.84,55.40,-259.29,281.20,285.32 +-7851.12,-7483.87,-367.25,-7989.43,-8000.00,10.57,-234.85,281.20,284.93 +-7541.12,-7161.29,-379.83,-7679.43,-7774.19,94.76,-234.85,281.20,284.93 +-7231.12,-6741.94,-489.19,-7369.43,-7548.39,178.95,-249.50,281.20,285.16 +-6921.12,-6419.35,-501.77,-7059.43,-7225.81,166.37,-262.69,281.20,285.37 +-6611.12,-6193.55,-417.58,-6749.43,-6645.16,-104.27,-211.40,281.20,284.56 +-6301.12,-5741.94,-559.19,-6439.43,-5612.90,-826.53,-211.40,281.20,284.56 +-5981.12,-4781.25,-1199.87,-6119.43,-5625.00,-494.43,-229.89,281.20,284.85 +-5671.12,-4290.32,-1380.80,-5809.43,-5935.48,126.05,-282.05,281.20,285.68 +-5311.12,-4638.89,-672.24,-5449.43,-5388.89,-60.55,-149.26,281.20,283.57 +-5001.12,-4516.13,-485.00,-5139.43,-4451.61,-687.82,-214.87,281.20,284.61 +-4691.12,-3870.97,-820.16,-4829.43,-4032.26,-797.18,-214.87,281.20,284.61 +-4381.12,-3161.29,-1219.83,-4519.43,-4161.29,-358.14,-227.55,281.20,284.81 +-4071.12,-2709.68,-1361.45,-4209.43,-3870.97,-338.47,-221.45,281.20,284.72 +-3761.12,-3000.00,-761.12,-3899.43,-3225.81,-673.63,-240.14,281.20,285.01 +-3451.12,-2935.48,-515.64,-3589.43,-2806.45,-782.98,-229.80,281.20,284.85 +-3141.12,-2322.58,-818.54,-3279.43,-2967.74,-311.69,-229.80,281.20,284.85 +-2831.12,-1645.16,-1185.96,-2969.43,-2612.90,-356.53,-154.08,281.20,283.65 +-2531.12,-833.33,-1697.79,-2669.43,-2100.00,-569.43,-162.90,281.20,283.79 +-2231.12,-33.33,-2197.79,-2369.43,-1300.00,-1069.43,-112.89,281.20,282.99 +-1931.12,-1066.67,-864.46,-2069.43,-866.67,-1202.77,-112.89,281.20,282.99 +-1631.12,-1466.67,-164.46,-1769.43,433.33,-2202.77,-162.94,281.20,283.79 +-1331.12,-1300.00,-31.12,-1469.43,-133.33,-1336.10,-389.28,281.20,287.38 +-1031.12,-100.00,-931.12,-1169.43,-833.33,-336.10,-227.80,281.20,284.82 +-741.12,655.17,-1396.30,-879.43,-1241.38,361.94,-227.80,281.20,284.82 +-451.12,-103.45,-347.68,-589.43,-241.38,-348.06,-173.97,281.20,283.96 +-151.12,-100.00,-51.12,-289.43,366.67,-656.10,-179.19,281.20,284.05 +0.00,33.33,-33.33,0.00,66.67,-66.67,-218.19,281.20,284.67 +0.00,0.00,0.00,0.00,0.00,0.00,-218.19,281.20,284.67 +0.00,0.00,0.00,0.00,0.00,0.00,-226.73,281.20,284.80 +0.00,0.00,0.00,0.00,0.00,0.00,-217.38,281.20,284.65 +0.00,0.00,0.00,0.00,0.00,0.00,-217.38,281.20,284.65 +0.00,0.00,0.00,0.00,0.00,0.00,-207.81,281.20,284.50 +0.00,0.00,0.00,0.00,0.00,0.00,-186.34,281.20,284.16 +0.00,0.00,0.00,0.00,0.00,0.00,-168.65,281.20,283.88 +0.00,0.00,0.00,0.00,0.00,0.00,-168.65,281.20,283.88 +0.00,0.00,0.00,0.00,0.00,0.00,-139.25,281.20,283.41 +0.00,0.00,0.00,0.00,0.00,0.00,-137.75,281.20,283.39 +0.00,0.00,0.00,0.00,0.00,0.00,-137.75,281.20,283.39 +0.00,0.00,0.00,0.00,0.00,0.00,-111.84,281.20,282.98 +0.00,0.00,0.00,0.00,0.00,0.00,-103.14,281.20,282.84 +0.00,0.00,0.00,0.00,0.00,0.00,-90.86,281.20,282.64 +0.00,0.00,0.00,0.00,0.00,0.00,-90.86,281.20,282.64 +0.00,0.00,0.00,0.00,0.00,0.00,-80.58,281.20,282.48 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,282.09 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.87 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.87 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,282.07 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.82 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.82 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.61 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.69 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.80 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.80 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.54 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.66 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.66 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.76 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.89 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.82 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.82 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,282.04 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.55 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.76 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.76 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.88 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.90 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.90 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.85 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.64 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.84 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.84 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.65 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.63 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.63 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.69 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.74 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,282.05 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,282.05 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.83 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.67 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.55 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.55 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.54 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.72 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.72 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.89 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.49 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.82 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.82 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.53 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.83 \ No newline at end of file diff --git a/src/robot/control.cpp b/src/robot/control.cpp index 118c0ab..db90cea 100644 --- a/src/robot/control.cpp +++ b/src/robot/control.cpp @@ -37,7 +37,7 @@ TrapezoidProfile rightProfile(profileConstraints); TrapezoidProfile::State leftSetpoint, rightSetpoint; PIDController encoderAVelocityController(0.00006, 0.000000, 0.00000, -1, +1, 100); // blue on graph // input ticks per second, output duty cycle PIDController encoderBVelocityController(0.00006, 0.000000, 0.00000, -1, +1, 100); // red on graph // input ticks per second, output duty cycle -ContinuousPIDController headingController(0.005, 0.0001, 0.0000, -0.3, +0.3, 1.0, 0, 360); // input degrees, output duty cycle +ContinuousPIDController headingController(0.001, 0.0000, 0.0000, -0.3, +0.3, 1.0, 0, 360); // 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; @@ -124,8 +124,8 @@ void testEncoderPID() if (!testEncoderPID_value) { testEncoderPID_value = true; - setLeftMotorControl({POSITION, (float)TICKS_PER_ROTATION * 5}); - setRightMotorControl({POSITION, (float)TICKS_PER_ROTATION * 5}); + setLeftMotorControl({POSITION, (float)TICKS_PER_ROTATION * 10}); + setRightMotorControl({POSITION, (float)TICKS_PER_ROTATION * 10}); setHeadingTarget(magnet->readDegrees()); } else From 692f7d664bcbefa91ac47a9f4cb368f705053067 Mon Sep 17 00:00:00 2001 From: democat Date: Wed, 22 Oct 2025 01:32:19 -0500 Subject: [PATCH 43/47] Update drive test to track elapsed time, calculate accel theoretically correct --- include/robot/driveTest.h | 1 + src/robot/driveTest.cpp | 11 +++++++---- src/robot/trapezoidalProfileNew.cpp | 14 +++++++++----- 3 files changed, 17 insertions(+), 9 deletions(-) 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/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/trapezoidalProfileNew.cpp b/src/robot/trapezoidalProfileNew.cpp index 962fe6f..da3a20f 100644 --- a/src/robot/trapezoidalProfileNew.cpp +++ b/src/robot/trapezoidalProfileNew.cpp @@ -6,9 +6,13 @@ TrapezoidProfile::State TrapezoidProfile::calculate(double t, const State &curre State m_current = direct(current, m_direction); State goalDir = direct(goal, m_direction); - if (std::abs(m_current.velocity) > m_constraints.maxVelocity) + if (m_current.velocity > m_constraints.maxVelocity) { - m_current.velocity = std::copysign(m_constraints.maxVelocity, m_current.velocity); + 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; @@ -47,10 +51,10 @@ TrapezoidProfile::State TrapezoidProfile::calculate(double t, const State &curre } else if (t <= m_endDecel) { - result.velocity = goalDir.velocity + (m_endDecel - t) * m_constraints.maxAcceleration; double timeLeft = m_endDecel - t; - result.position = - goalDir.position - (goalDir.velocity + timeLeft * m_constraints.maxAcceleration / 2.0) * timeLeft; + result.velocity = goalDir.velocity + timeLeft * m_constraints.maxAcceleration; + result.position = goalDir.position - goalDir.velocity * timeLeft + + timeLeft * timeLeft * m_constraints.maxAcceleration / 2.0; } else { From fd78d9543e7db10ec9b172d6b25ce445f526c97e Mon Sep 17 00:00:00 2001 From: democat Date: Wed, 22 Oct 2025 01:38:59 -0500 Subject: [PATCH 44/47] whoops sign error --- src/robot/trapezoidalProfileNew.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/src/robot/trapezoidalProfileNew.cpp b/src/robot/trapezoidalProfileNew.cpp index da3a20f..f50b75d 100644 --- a/src/robot/trapezoidalProfileNew.cpp +++ b/src/robot/trapezoidalProfileNew.cpp @@ -53,8 +53,7 @@ TrapezoidProfile::State TrapezoidProfile::calculate(double t, const State &curre { 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; + result.position = goalDir.position - (goalDir.velocity * timeLeft) - (timeLeft * timeLeft * m_constraints.maxAcceleration / 2.0); } else { From 71865102be03e44256d3ac7ce73db1a7bf2e1b7d Mon Sep 17 00:00:00 2001 From: democat Date: Wed, 22 Oct 2025 01:56:10 -0500 Subject: [PATCH 45/47] new tuning --- pid_test.csv | 1089 +++++++++++++++++++++++++++-------------- pid_vis.py | 2 + src/robot/control.cpp | 19 +- src/utils/config.cpp | 10 +- 4 files changed, 742 insertions(+), 378 deletions(-) diff --git a/pid_test.csv b/pid_test.csv index f517b2f..987d7bd 100644 --- a/pid_test.csv +++ b/pid_test.csv @@ -1,364 +1,727 @@ LeftSetpoint,LeftVelocity,LeftError,RightSetpoint,RightVelocity,RightError,HeadingVelocityCorrection,HeadingSetpoint,Heading -0.00,0.00,0.00,0.00,0.00,0.00,-177.80,278.92,281.74 -0.00,0.00,0.00,0.00,0.00,0.00,-177.80,278.92,281.74 -0.00,0.00,0.00,0.00,0.00,0.00,-147.55,278.92,281.26 -0.00,0.00,0.00,0.00,0.00,0.00,-150.32,278.92,281.31 -0.00,0.00,0.00,0.00,0.00,0.00,-131.82,278.92,281.01 -0.00,0.00,0.00,0.00,0.00,0.00,-131.82,278.92,281.01 -0.00,0.00,0.00,0.00,0.00,0.00,-153.37,278.92,281.36 -0.00,0.00,0.00,0.00,0.00,0.00,-162.51,278.92,281.50 -0.00,0.00,0.00,0.00,0.00,0.00,-162.51,278.92,281.50 -0.00,0.00,0.00,0.00,0.00,0.00,-178.14,278.92,281.75 -0.00,0.00,0.00,0.00,0.00,0.00,-173.78,278.92,281.68 -0.00,0.00,0.00,0.00,0.00,0.00,-159.61,278.92,281.45 -0.00,0.00,0.00,0.00,0.00,0.00,-159.61,278.92,281.45 -0.00,0.00,0.00,0.00,0.00,0.00,-158.89,278.92,281.44 -0.00,0.00,0.00,0.00,0.00,0.00,-177.80,278.92,281.74 -0.00,0.00,0.00,0.00,0.00,0.00,-177.80,278.92,281.74 -0.00,0.00,0.00,0.00,0.00,0.00,-171.07,278.92,281.64 -0.00,0.00,0.00,0.00,0.00,0.00,-172.86,278.92,281.66 -0.00,0.00,0.00,0.00,0.00,0.00,-175.11,278.92,281.70 -0.00,0.00,0.00,0.00,0.00,0.00,-175.11,278.92,281.70 -0.00,0.00,0.00,0.00,0.00,0.00,-163.92,278.92,281.52 -0.00,0.00,0.00,0.00,0.00,0.00,-161.52,278.92,281.48 -0.00,0.00,0.00,0.00,0.00,0.00,-177.62,278.92,281.74 -0.00,0.00,0.00,0.00,0.00,0.00,-177.62,278.92,281.74 -0.00,0.00,0.00,0.00,0.00,0.00,-159.70,278.92,281.46 -0.00,0.00,0.00,0.00,0.00,0.00,-159.99,278.92,281.46 -0.00,0.00,0.00,0.00,0.00,0.00,-166.76,278.92,281.57 -0.00,0.00,0.00,0.00,0.00,0.00,-166.76,278.92,281.57 -0.00,0.00,0.00,0.00,0.00,0.00,-170.81,278.92,281.63 -0.00,0.00,0.00,0.00,0.00,0.00,-183.08,278.92,281.83 -0.00,0.00,0.00,0.00,0.00,0.00,-183.08,278.92,281.83 -0.00,0.00,0.00,0.00,0.00,0.00,-166.22,278.92,281.56 -0.00,0.00,0.00,0.00,0.00,0.00,-154.34,278.92,281.37 -0.00,0.00,0.00,0.00,0.00,0.00,-147.94,278.92,281.27 -0.00,0.00,0.00,0.00,0.00,0.00,-147.94,278.92,281.27 -0.00,0.00,0.00,0.00,0.00,0.00,-170.56,278.92,281.63 -0.00,0.00,0.00,0.00,0.00,0.00,-166.36,278.92,281.56 -0.00,0.00,0.00,0.00,0.00,0.00,-186.38,278.92,281.88 -0.00,0.00,0.00,0.00,0.00,0.00,-186.38,278.92,281.88 -0.00,0.00,0.00,0.00,0.00,0.00,-182.31,278.92,281.81 -0.00,0.00,0.00,0.00,0.00,0.00,-208.67,278.92,282.23 -0.00,0.00,0.00,0.00,0.00,0.00,-208.67,278.92,282.23 -0.00,0.00,0.00,0.00,0.00,0.00,-187.24,278.92,281.89 -0.00,0.00,0.00,0.00,0.00,0.00,-173.45,278.92,281.67 -0.00,0.00,0.00,0.00,0.00,0.00,-190.57,278.92,281.95 -0.00,0.00,0.00,0.00,0.00,0.00,-190.57,278.92,281.95 -0.00,0.00,0.00,0.00,0.00,0.00,-185.93,278.92,281.87 -0.00,0.00,0.00,0.00,0.00,0.00,-173.88,278.92,281.68 -0.00,0.00,0.00,0.00,0.00,0.00,-151.67,278.92,281.33 -0.00,0.00,0.00,0.00,0.00,0.00,-151.67,278.92,281.33 -0.00,0.00,0.00,0.00,0.00,0.00,-157.38,278.92,281.42 -0.00,0.00,0.00,0.00,0.00,0.00,-160.64,278.92,281.47 -0.00,0.00,0.00,0.00,0.00,0.00,-160.64,278.92,281.47 -0.00,0.00,0.00,0.00,0.00,0.00,-170.85,278.92,281.63 -0.00,0.00,0.00,0.00,0.00,0.00,-172.86,278.92,281.66 -0.00,0.00,0.00,0.00,0.00,0.00,-176.01,278.92,281.71 -0.00,0.00,0.00,0.00,0.00,0.00,-176.01,278.92,281.71 -0.00,0.00,0.00,0.00,0.00,0.00,-177.85,278.92,281.74 -0.00,0.00,0.00,0.00,0.00,0.00,-197.79,278.92,282.06 -0.00,0.00,0.00,0.00,0.00,0.00,-197.79,278.92,282.06 -0.00,0.00,0.00,0.00,0.00,0.00,-180.39,278.92,281.78 -0.00,0.00,0.00,0.00,0.00,0.00,-175.95,278.92,281.71 -0.00,0.00,0.00,0.00,0.00,0.00,-181.86,278.92,281.81 -0.00,0.00,0.00,0.00,0.00,0.00,-181.86,278.92,281.81 -0.00,0.00,0.00,0.00,0.00,0.00,-208.99,278.92,282.24 -0.00,0.00,0.00,0.00,0.00,0.00,-185.02,278.92,281.86 -0.00,0.00,0.00,0.00,0.00,0.00,-185.02,278.92,281.86 -0.00,0.00,0.00,0.00,0.00,0.00,-192.19,278.92,281.97 -0.00,0.00,0.00,0.00,0.00,0.00,-217.43,278.92,282.37 -0.00,0.00,0.00,0.00,0.00,0.00,-211.82,278.92,282.28 -0.00,0.00,0.00,0.00,0.00,0.00,-211.82,278.92,282.28 -0.00,0.00,0.00,0.00,0.00,0.00,-244.92,278.92,282.81 -0.00,0.00,0.00,0.00,0.00,0.00,-250.41,278.92,282.90 -0.00,0.00,0.00,0.00,0.00,0.00,-232.31,278.92,282.61 -0.00,0.00,0.00,0.00,0.00,0.00,-232.31,278.92,282.61 -0.00,0.00,0.00,0.00,0.00,0.00,-228.85,278.92,282.55 -0.00,0.00,0.00,0.00,0.00,0.00,-190.92,278.92,281.95 -0.00,0.00,0.00,0.00,0.00,0.00,-190.92,278.92,281.95 -0.00,0.00,0.00,0.00,0.00,0.00,-173.38,278.92,281.67 -0.00,0.00,0.00,0.00,0.00,0.00,-153.91,278.92,281.36 -0.00,0.00,0.00,0.00,0.00,0.00,-149.66,278.92,281.30 -0.00,0.00,0.00,0.00,0.00,0.00,-149.66,278.92,281.30 -0.00,0.00,0.00,0.00,0.00,0.00,-157.86,278.92,281.43 -0.00,0.00,0.00,0.00,0.00,0.00,-141.89,278.92,281.17 -0.00,0.00,0.00,0.00,0.00,0.00,-141.89,278.92,281.17 -0.00,0.00,0.00,0.00,0.00,0.00,-136.59,278.92,281.09 --320.00,0.00,-320.00,-320.00,0.00,-320.00,0.00,281.20,281.20 --610.00,0.00,-610.00,-610.00,0.00,-610.00,0.00,281.20,281.53 --900.00,0.00,-900.00,-900.00,0.00,-900.00,0.00,281.20,281.53 --1240.00,0.00,-1240.00,-1240.00,0.00,-1240.00,0.00,281.20,281.49 --1530.00,0.00,-1530.00,-1530.00,0.00,-1530.00,0.00,281.20,281.25 --1820.00,0.00,-1820.00,-1820.00,0.00,-1820.00,0.00,281.20,281.30 --2110.00,-137.93,-1972.07,-2110.00,-137.93,-1972.07,0.00,281.20,281.30 --2410.00,-366.67,-2043.33,-2410.00,-266.67,-2143.33,0.00,281.20,281.67 --2710.00,-266.67,-2443.33,-2710.00,-133.33,-2576.67,0.00,281.20,280.68 --3010.00,-866.67,-2143.33,-3010.00,-400.00,-2610.00,140.21,281.20,278.98 --3320.00,-2225.81,-1094.19,-3320.00,-1612.90,-1707.10,215.79,281.20,277.78 --3630.00,-2935.48,-694.52,-3630.00,-2580.65,-1049.35,215.79,281.20,277.78 --3940.00,-2903.23,-1036.77,-3940.00,-2677.42,-1262.58,298.93,281.20,276.46 --4250.00,-2451.61,-1798.39,-4250.00,-2096.77,-2153.23,365.82,281.20,275.40 --4560.00,-3064.52,-1495.48,-4560.00,-1806.45,-2753.55,190.68,281.20,278.18 --4870.00,-3741.94,-1128.06,-4870.00,-2516.13,-2353.87,190.68,281.20,278.18 --5180.00,-4322.58,-857.42,-5180.00,-3645.16,-1534.84,169.33,281.20,278.51 --5490.00,-4580.65,-909.35,-5490.00,-4225.81,-1264.19,272.61,281.20,276.88 --5800.00,-4741.94,-1058.06,-5800.00,-4451.61,-1348.39,246.25,281.20,277.29 --6110.00,-4967.74,-1142.26,-6110.00,-4580.65,-1529.35,246.25,281.20,277.29 --6420.00,-5322.58,-1097.42,-6420.00,-4612.90,-1807.10,256.26,281.20,277.13 --6730.00,-5709.68,-1020.32,-6730.00,-4870.97,-1859.03,255.89,281.20,277.14 --7040.00,-6064.52,-975.48,-7040.00,-5354.84,-1685.16,277.12,281.20,276.80 --7350.00,-6419.35,-930.65,-7350.00,-5806.45,-1543.55,296.24,281.20,276.50 --7660.00,-6838.71,-821.29,-7660.00,-6129.03,-1530.97,296.24,281.20,276.50 --7970.00,-7129.03,-840.97,-7970.00,-6387.10,-1582.90,292.58,281.20,276.56 --8280.00,-7419.35,-860.65,-8280.00,-6645.16,-1634.84,337.49,281.20,275.85 --8580.00,-7666.67,-913.33,-8580.00,-6933.33,-1646.67,318.73,281.20,276.14 --8890.00,-8032.26,-857.74,-8890.00,-7290.32,-1599.68,318.73,281.20,276.14 --9200.00,-8354.84,-845.16,-9200.00,-7548.39,-1651.61,354.84,281.20,275.57 --9500.00,-8666.67,-833.33,-9500.00,-7900.00,-1600.00,346.75,281.20,275.70 --9810.00,-9000.00,-810.00,-9810.00,-8225.81,-1584.19,388.26,281.20,275.04 --10120.00,-9322.58,-797.42,-10120.00,-8483.87,-1636.13,430.98,281.20,274.36 --10430.00,-9612.90,-817.10,-10430.00,-8838.71,-1591.29,430.98,281.20,274.36 --10740.00,-9935.48,-804.52,-10740.00,-9096.77,-1643.23,432.14,281.20,274.34 --11050.00,-10290.32,-759.68,-11050.00,-9354.84,-1695.16,452.42,281.20,274.02 --11360.00,-10612.90,-747.10,-11360.00,-9645.16,-1714.84,526.77,281.20,272.84 --11670.00,-10870.97,-799.03,-11670.00,-9935.48,-1734.52,526.77,281.20,272.84 --11980.00,-11258.06,-721.94,-11980.00,-10161.29,-1818.71,539.96,281.20,272.63 --12290.00,-11548.39,-741.61,-12290.00,-10419.35,-1870.65,553.51,281.20,272.42 --12600.00,-11967.74,-632.26,-12600.00,-10741.94,-1858.06,554.39,281.20,272.40 --12920.00,-12218.75,-701.25,-12920.00,-11031.25,-1888.75,622.34,281.20,271.32 --13240.00,-12437.50,-802.50,-13240.00,-11312.50,-1927.50,622.34,281.20,271.32 --13550.00,-12774.19,-775.81,-13550.00,-11548.39,-2001.61,620.68,281.20,271.35 --13850.00,-13133.33,-716.67,-13850.00,-11800.00,-2050.00,635.94,281.20,271.11 --14170.00,-13437.50,-732.50,-14170.00,-12125.00,-2045.00,642.39,281.20,271.01 --14480.00,-13838.71,-641.29,-14480.00,-12354.84,-2125.16,642.39,281.20,271.01 --14790.00,-14064.52,-725.48,-14790.00,-12677.42,-2112.58,656.82,281.20,270.78 --15100.00,-14419.35,-680.65,-15100.00,-13000.00,-2100.00,640.36,281.20,271.04 --15420.00,-14625.00,-795.00,-15420.00,-13250.00,-2170.00,654.50,281.20,270.81 --15730.00,-15000.00,-730.00,-15730.00,-13580.65,-2149.35,684.69,281.20,270.33 --16040.00,-15322.58,-717.42,-16040.00,-13935.48,-2104.52,684.69,281.20,270.33 --16360.00,-15718.75,-641.25,-16360.00,-14218.75,-2141.25,759.03,281.20,269.15 --16680.00,-16031.25,-648.75,-16680.00,-14468.75,-2211.25,758.07,281.20,269.17 --16990.00,-16354.84,-635.16,-16990.00,-14774.19,-2215.81,796.32,281.20,268.56 --17300.00,-16645.16,-654.84,-17300.00,-15000.00,-2300.00,796.32,281.20,268.56 --17620.00,-17000.00,-620.00,-17620.00,-15343.75,-2276.25,809.10,281.20,268.36 --17940.00,-17312.50,-627.50,-17940.00,-15718.75,-2221.25,874.11,281.20,267.33 --18260.00,-17718.75,-541.25,-18260.00,-16031.25,-2228.75,896.67,281.20,266.97 --18570.00,-18000.00,-570.00,-18570.00,-16290.32,-2279.68,973.13,281.20,265.76 --18880.00,-18354.84,-525.16,-18880.00,-16548.39,-2331.61,973.13,281.20,265.76 --19200.00,-18812.50,-387.50,-19200.00,-16781.25,-2418.75,1029.92,281.20,264.85 --19520.00,-19218.75,-301.25,-19520.00,-17031.25,-2488.75,1062.06,281.20,264.34 --19840.00,-19468.75,-371.25,-19840.00,-17250.00,-2590.00,1069.36,281.20,264.23 --20160.00,-19812.50,-347.50,-20160.00,-17562.50,-2597.50,1072.58,281.20,264.18 --20480.00,-20031.25,-448.75,-20480.00,-17812.50,-2667.50,1072.58,281.20,264.18 --20800.00,-20156.25,-643.75,-20800.00,-18250.00,-2550.00,1095.88,281.20,263.81 --21120.00,-20562.50,-557.50,-21120.00,-18500.00,-2620.00,1120.44,281.20,263.42 --21490.00,-20945.95,-544.05,-21490.00,-18783.78,-2706.22,1140.44,281.20,263.10 --21800.00,-21322.58,-477.42,-21800.00,-19161.29,-2638.71,1161.85,281.20,262.76 --22110.00,-21838.71,-271.29,-22110.00,-19419.35,-2690.65,1161.85,281.20,262.76 --22430.00,-22000.00,-430.00,-22430.00,-19593.75,-2836.25,1229.28,281.20,261.69 --22760.00,-22363.64,-396.36,-22760.00,-19909.09,-2850.91,1208.37,281.20,262.02 --23080.00,-22656.25,-423.75,-23080.00,-20218.75,-2861.25,1249.77,281.20,261.36 --23400.00,-23125.00,-275.00,-23400.00,-20468.75,-2931.25,1242.71,281.20,261.48 --23720.00,-23500.00,-220.00,-23720.00,-20843.75,-2876.25,1246.61,281.20,261.41 --24040.00,-23750.00,-290.00,-24040.00,-21187.50,-2852.50,1246.61,281.20,261.41 --24360.00,-23968.75,-391.25,-24360.00,-21500.00,-2860.00,1246.02,281.20,261.42 --24680.00,-24406.25,-273.75,-24680.00,-21843.75,-2836.25,1198.51,281.20,262.18 --25000.00,-24625.00,-375.00,-25000.00,-22125.00,-2875.00,1197.51,281.20,262.19 --25320.00,-24781.25,-538.75,-25320.00,-22375.00,-2945.00,1165.38,281.20,262.70 --25640.00,-24968.75,-671.25,-25640.00,-22750.00,-2890.00,1165.38,281.20,262.70 --25960.00,-25218.75,-741.25,-25960.00,-23312.50,-2647.50,1120.43,281.20,263.42 --26280.00,-25593.75,-686.25,-26280.00,-23531.25,-2748.75,1107.39,281.20,263.62 --26600.00,-25781.25,-818.75,-26600.00,-23906.25,-2693.75,1095.39,281.20,263.82 --26920.00,-26281.25,-638.75,-26920.00,-24000.00,-2920.00,1079.97,281.20,264.06 --27240.00,-26562.50,-677.50,-27240.00,-24406.25,-2833.75,1079.97,281.20,264.06 --27560.00,-27062.50,-497.50,-27560.00,-24812.50,-2747.50,1052.45,281.20,264.50 --27880.00,-27156.25,-723.75,-27880.00,-25093.75,-2786.25,1051.00,281.20,264.52 --28200.00,-27468.75,-731.25,-28200.00,-25406.25,-2793.75,1057.11,281.20,264.42 --28520.00,-27875.00,-645.00,-28520.00,-25656.25,-2863.75,1025.26,281.20,264.93 --28840.00,-27781.25,-1058.75,-28840.00,-25937.50,-2902.50,1025.26,281.20,264.93 --29160.00,-28250.00,-910.00,-29160.00,-26125.00,-3035.00,1007.88,281.20,265.20 --29480.00,-28500.00,-980.00,-29480.00,-26656.25,-2823.75,968.39,281.20,265.83 --29810.00,-29000.00,-810.00,-29810.00,-27181.82,-2628.18,957.23,281.20,266.01 --30130.00,-29156.25,-973.75,-30130.00,-27531.25,-2598.75,941.39,281.20,266.26 --30450.00,-29375.00,-1075.00,-30450.00,-27593.75,-2856.25,941.39,281.20,266.26 --30780.00,-29818.18,-961.82,-30780.00,-28000.00,-2780.00,918.42,281.20,266.62 --31110.00,-30212.12,-897.88,-31110.00,-28151.52,-2958.48,871.54,281.20,267.37 --31430.00,-30375.00,-1055.00,-31430.00,-28562.50,-2867.50,850.76,281.20,267.70 --31760.00,-30515.15,-1244.85,-31760.00,-29090.91,-2669.09,816.56,281.20,268.24 --32090.00,-30909.09,-1180.91,-32090.00,-29393.94,-2696.06,816.56,281.20,268.24 --32410.00,-31281.25,-1128.75,-32410.00,-29500.00,-2910.00,816.69,281.20,268.24 --32740.00,-31242.42,-1497.58,-32740.00,-29696.97,-3043.03,777.47,281.20,268.86 --33070.00,-31787.88,-1282.12,-33070.00,-29666.67,-3403.33,709.53,281.20,269.94 --33400.00,-32121.21,-1278.79,-33400.00,-30696.97,-2703.03,658.10,281.20,270.76 --33451.12,-32593.75,-857.37,-33589.43,-31343.75,-2245.68,629.95,281.20,271.20 --33121.12,-32545.45,-575.67,-33259.43,-31696.97,-1562.47,629.95,281.20,271.20 --32791.12,-32484.85,-306.28,-32929.43,-31545.45,-1383.98,678.70,281.20,270.43 --32461.12,-32090.91,-370.22,-32599.43,-30787.88,-1811.56,656.99,281.20,270.77 --32131.12,-31666.67,-464.46,-32269.43,-30575.76,-1693.68,610.54,281.20,271.51 --31801.12,-31454.55,-346.58,-31939.43,-30454.55,-1484.89,574.48,281.20,272.08 --31471.12,-31030.30,-440.82,-31609.43,-30181.82,-1427.62,574.48,281.20,272.08 --31141.12,-30242.42,-898.70,-31279.43,-29454.55,-1824.89,555.95,281.20,272.38 --30821.12,-30500.00,-321.12,-30959.43,-29375.00,-1584.43,556.03,281.20,272.38 --30501.12,-30281.25,-219.87,-30639.43,-28937.50,-1701.93,484.60,281.20,273.51 --30181.12,-30000.00,-181.12,-30319.43,-28687.50,-1631.93,442.66,281.20,274.18 --29851.12,-29393.94,-457.19,-29989.43,-28545.45,-1443.98,452.53,281.20,274.02 --29531.12,-28718.75,-812.37,-29669.43,-28343.75,-1325.68,452.53,281.20,274.02 --29211.12,-28687.50,-523.62,-29349.43,-28218.75,-1130.68,399.77,281.20,274.86 --28891.12,-28468.75,-422.37,-29029.43,-27593.75,-1435.68,331.46,281.20,275.94 --28561.12,-28000.00,-561.12,-28699.43,-27515.15,-1184.28,305.92,281.20,276.35 --28241.12,-27562.50,-678.62,-28379.43,-27343.75,-1035.68,250.97,281.20,277.22 --27911.12,-27515.15,-395.97,-28049.43,-27000.00,-1049.43,250.97,281.20,277.22 --27581.12,-26909.09,-672.03,-27719.43,-26636.36,-1083.07,274.58,281.20,276.84 --27261.12,-26593.75,-667.37,-27399.43,-26375.00,-1024.43,238.21,281.20,277.42 --26931.12,-26393.94,-537.19,-27069.43,-25939.39,-1130.04,212.66,281.20,277.83 --26601.12,-26030.30,-570.82,-26739.43,-25515.15,-1224.28,233.82,281.20,277.49 --26281.12,-25718.75,-562.37,-26419.43,-25156.25,-1263.18,233.82,281.20,277.49 --25961.12,-25468.75,-492.37,-26099.43,-24968.75,-1130.68,179.67,281.20,278.35 --25581.12,-25078.95,-502.18,-25719.43,-24657.89,-1061.54,144.80,281.20,278.90 --25261.12,-24718.75,-542.37,-25399.43,-24562.50,-836.93,155.96,281.20,278.73 --24941.12,-24281.25,-659.87,-25079.43,-24218.75,-860.68,134.42,281.20,279.07 --24621.12,-24125.00,-496.12,-24759.43,-23937.50,-821.93,154.01,281.20,278.76 --24291.12,-23696.97,-594.16,-24429.43,-23666.67,-762.77,154.01,281.20,278.76 --23971.12,-23375.00,-596.12,-24109.43,-23250.00,-859.43,130.26,281.20,279.13 --23651.12,-23093.75,-557.37,-23789.43,-22937.50,-851.93,96.75,281.20,279.67 --23331.12,-22812.50,-518.62,-23469.43,-22656.25,-813.18,0.00,281.20,280.59 --23011.12,-22218.75,-792.37,-23149.43,-22406.25,-743.18,70.41,281.20,280.08 --22691.12,-22062.50,-628.62,-22829.43,-21968.75,-860.68,70.41,281.20,280.08 --22371.12,-21875.00,-496.12,-22509.43,-21750.00,-759.43,76.66,281.20,279.99 --22051.12,-21750.00,-301.12,-22189.43,-21437.50,-751.93,0.00,281.20,280.43 --21731.12,-21312.50,-418.62,-21869.43,-21062.50,-806.93,0.00,281.20,280.93 --21411.12,-20812.50,-598.62,-21549.43,-20875.00,-674.43,0.00,281.20,280.97 --21091.12,-20562.50,-528.62,-21229.43,-20593.75,-635.68,0.00,281.20,280.97 --20771.12,-20250.00,-521.12,-20909.43,-20250.00,-659.43,0.00,281.20,280.49 --20451.12,-19718.75,-732.37,-20589.43,-19875.00,-714.43,0.00,281.20,280.75 --20131.12,-19625.00,-506.12,-20269.43,-19500.00,-769.43,0.00,281.20,280.89 --19811.12,-19343.75,-467.37,-19949.43,-19218.75,-730.68,0.00,281.20,281.07 --19491.12,-18843.75,-647.37,-19629.43,-18937.50,-691.93,0.00,281.20,281.07 --19181.12,-18612.90,-568.22,-19319.43,-18774.19,-545.24,0.00,281.20,280.90 --18861.12,-18343.75,-517.37,-18999.43,-18562.50,-436.93,0.00,281.20,280.79 --18541.12,-18062.50,-478.62,-18679.43,-18218.75,-460.68,0.00,281.20,281.06 --18231.12,-17677.42,-553.71,-18369.43,-17967.74,-401.69,0.00,281.20,281.02 --17911.12,-17437.50,-473.62,-18049.43,-17718.75,-330.68,0.00,281.20,281.02 --17601.12,-17193.55,-407.58,-17739.43,-17161.29,-578.14,0.00,281.20,280.96 --17281.12,-16750.00,-531.12,-17419.43,-16906.25,-513.18,0.00,281.20,281.61 --16961.12,-16531.25,-429.87,-17099.43,-16656.25,-443.18,0.00,281.20,281.52 --16651.12,-16354.84,-296.29,-16789.43,-16419.35,-370.08,0.00,281.20,281.74 --16331.12,-16000.00,-331.12,-16469.43,-15937.50,-531.93,0.00,281.20,281.74 --16021.12,-15645.16,-375.96,-16159.43,-15677.42,-482.02,0.00,281.20,281.03 --15701.12,-15343.75,-357.37,-15839.43,-15375.00,-464.43,0.00,281.20,281.55 --15381.12,-15031.25,-349.87,-15519.43,-15062.50,-456.93,0.00,281.20,281.97 --15061.12,-14812.50,-248.62,-15199.43,-14750.00,-449.43,0.00,281.20,281.97 --14751.12,-14419.35,-331.77,-14889.43,-14322.58,-566.85,0.00,281.20,281.96 --14441.12,-14129.03,-312.09,-14579.43,-13935.48,-643.95,-78.90,281.20,282.45 --14131.12,-13838.71,-292.42,-14269.43,-13709.68,-559.76,-115.54,281.20,283.04 --13811.12,-13468.75,-342.37,-13949.43,-13531.25,-418.18,-116.18,281.20,283.05 --13501.12,-13129.03,-372.09,-13639.43,-13387.10,-252.34,-116.18,281.20,283.05 --13181.12,-12812.50,-368.62,-13319.43,-13093.75,-225.68,-136.08,281.20,283.36 --12861.12,-12468.75,-392.37,-12999.43,-12687.50,-311.93,-166.95,281.20,283.85 --12541.12,-12156.25,-384.87,-12679.43,-12375.00,-304.43,-177.70,281.20,284.02 --12221.12,-11750.00,-471.12,-12359.43,-12125.00,-234.43,-214.41,281.20,284.61 --11911.12,-11451.61,-459.51,-12049.43,-11870.97,-178.47,-214.41,281.20,284.61 --11591.12,-11062.50,-528.62,-11729.43,-11687.50,-41.93,-178.45,281.20,284.03 --11281.12,-10806.45,-474.67,-11419.43,-11354.84,-64.60,-222.52,281.20,284.73 --10971.12,-10580.65,-390.48,-11109.43,-11000.00,-109.43,-207.54,281.20,284.50 --10661.12,-10290.32,-370.80,-10799.43,-10741.94,-57.50,-207.54,281.20,284.50 --10351.12,-9903.23,-447.90,-10489.43,-10516.13,26.69,-233.66,281.20,284.91 --10041.12,-9483.87,-557.25,-10179.43,-10225.81,46.37,-249.91,281.20,285.17 --9731.12,-9161.29,-569.83,-9869.43,-9806.45,-62.98,-271.57,281.20,285.51 --9421.12,-8935.48,-485.64,-9559.43,-9516.13,-43.31,-255.03,281.20,285.25 --9101.12,-8656.25,-444.87,-9239.43,-9312.50,73.07,-255.03,281.20,285.25 --8791.12,-8354.84,-436.29,-8929.43,-9032.26,102.82,-226.19,281.20,284.79 --8471.12,-8000.00,-471.12,-8609.43,-8687.50,78.07,-219.05,281.20,284.68 --8161.12,-7741.94,-419.19,-8299.43,-8354.84,55.40,-259.29,281.20,285.32 --7851.12,-7483.87,-367.25,-7989.43,-8000.00,10.57,-234.85,281.20,284.93 --7541.12,-7161.29,-379.83,-7679.43,-7774.19,94.76,-234.85,281.20,284.93 --7231.12,-6741.94,-489.19,-7369.43,-7548.39,178.95,-249.50,281.20,285.16 --6921.12,-6419.35,-501.77,-7059.43,-7225.81,166.37,-262.69,281.20,285.37 --6611.12,-6193.55,-417.58,-6749.43,-6645.16,-104.27,-211.40,281.20,284.56 --6301.12,-5741.94,-559.19,-6439.43,-5612.90,-826.53,-211.40,281.20,284.56 --5981.12,-4781.25,-1199.87,-6119.43,-5625.00,-494.43,-229.89,281.20,284.85 --5671.12,-4290.32,-1380.80,-5809.43,-5935.48,126.05,-282.05,281.20,285.68 --5311.12,-4638.89,-672.24,-5449.43,-5388.89,-60.55,-149.26,281.20,283.57 --5001.12,-4516.13,-485.00,-5139.43,-4451.61,-687.82,-214.87,281.20,284.61 --4691.12,-3870.97,-820.16,-4829.43,-4032.26,-797.18,-214.87,281.20,284.61 --4381.12,-3161.29,-1219.83,-4519.43,-4161.29,-358.14,-227.55,281.20,284.81 --4071.12,-2709.68,-1361.45,-4209.43,-3870.97,-338.47,-221.45,281.20,284.72 --3761.12,-3000.00,-761.12,-3899.43,-3225.81,-673.63,-240.14,281.20,285.01 --3451.12,-2935.48,-515.64,-3589.43,-2806.45,-782.98,-229.80,281.20,284.85 --3141.12,-2322.58,-818.54,-3279.43,-2967.74,-311.69,-229.80,281.20,284.85 --2831.12,-1645.16,-1185.96,-2969.43,-2612.90,-356.53,-154.08,281.20,283.65 --2531.12,-833.33,-1697.79,-2669.43,-2100.00,-569.43,-162.90,281.20,283.79 --2231.12,-33.33,-2197.79,-2369.43,-1300.00,-1069.43,-112.89,281.20,282.99 --1931.12,-1066.67,-864.46,-2069.43,-866.67,-1202.77,-112.89,281.20,282.99 --1631.12,-1466.67,-164.46,-1769.43,433.33,-2202.77,-162.94,281.20,283.79 --1331.12,-1300.00,-31.12,-1469.43,-133.33,-1336.10,-389.28,281.20,287.38 --1031.12,-100.00,-931.12,-1169.43,-833.33,-336.10,-227.80,281.20,284.82 --741.12,655.17,-1396.30,-879.43,-1241.38,361.94,-227.80,281.20,284.82 --451.12,-103.45,-347.68,-589.43,-241.38,-348.06,-173.97,281.20,283.96 --151.12,-100.00,-51.12,-289.43,366.67,-656.10,-179.19,281.20,284.05 -0.00,33.33,-33.33,0.00,66.67,-66.67,-218.19,281.20,284.67 -0.00,0.00,0.00,0.00,0.00,0.00,-218.19,281.20,284.67 -0.00,0.00,0.00,0.00,0.00,0.00,-226.73,281.20,284.80 -0.00,0.00,0.00,0.00,0.00,0.00,-217.38,281.20,284.65 -0.00,0.00,0.00,0.00,0.00,0.00,-217.38,281.20,284.65 -0.00,0.00,0.00,0.00,0.00,0.00,-207.81,281.20,284.50 -0.00,0.00,0.00,0.00,0.00,0.00,-186.34,281.20,284.16 -0.00,0.00,0.00,0.00,0.00,0.00,-168.65,281.20,283.88 -0.00,0.00,0.00,0.00,0.00,0.00,-168.65,281.20,283.88 -0.00,0.00,0.00,0.00,0.00,0.00,-139.25,281.20,283.41 -0.00,0.00,0.00,0.00,0.00,0.00,-137.75,281.20,283.39 -0.00,0.00,0.00,0.00,0.00,0.00,-137.75,281.20,283.39 -0.00,0.00,0.00,0.00,0.00,0.00,-111.84,281.20,282.98 -0.00,0.00,0.00,0.00,0.00,0.00,-103.14,281.20,282.84 -0.00,0.00,0.00,0.00,0.00,0.00,-90.86,281.20,282.64 -0.00,0.00,0.00,0.00,0.00,0.00,-90.86,281.20,282.64 -0.00,0.00,0.00,0.00,0.00,0.00,-80.58,281.20,282.48 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,282.09 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.87 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.87 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,282.07 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.82 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.82 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.61 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.69 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.80 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.80 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.54 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.66 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.66 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.76 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.89 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.82 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.82 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,282.04 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.55 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.76 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.76 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.88 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.90 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.90 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.85 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.64 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.84 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.84 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.65 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.63 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.63 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.69 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.74 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,282.05 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,282.05 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.83 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.67 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.55 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.55 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.54 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.72 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.72 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.89 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.49 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.82 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.82 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.53 -0.00,0.00,0.00,0.00,0.00,0.00,0.00,281.20,281.83 \ No newline at end of file +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 \ No newline at end of file diff --git a/pid_vis.py b/pid_vis.py index 27ffc9a..0490878 100644 --- a/pid_vis.py +++ b/pid_vis.py @@ -12,6 +12,8 @@ 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: diff --git a/src/robot/control.cpp b/src/robot/control.cpp index db90cea..183bc24 100644 --- a/src/robot/control.cpp +++ b/src/robot/control.cpp @@ -35,9 +35,9 @@ TrapezoidProfile::Constraints profileConstraints(VELOCITY_LIMIT_TPS, ACCELERATIO TrapezoidProfile leftProfile(profileConstraints); TrapezoidProfile rightProfile(profileConstraints); TrapezoidProfile::State leftSetpoint, rightSetpoint; -PIDController encoderAVelocityController(0.00006, 0.000000, 0.00000, -1, +1, 100); // blue on graph // input ticks per second, output duty cycle -PIDController encoderBVelocityController(0.00006, 0.000000, 0.00000, -1, +1, 100); // red on graph // input ticks per second, output duty cycle -ContinuousPIDController headingController(0.001, 0.0000, 0.0000, -0.3, +0.3, 1.0, 0, 360); // input degrees, output duty cycle +PIDController encoderAVelocityController(0.00004, 0.000000, 0.00000, -1, +1, 100); // blue on graph // input ticks per second, output duty cycle +PIDController encoderBVelocityController(0.00004, 0.000000, 0.00000, -1, +1, 100); // red on graph // input ticks per second, output duty cycle +ContinuousPIDController headingController(0.002, 0.0000, 0.0000, -0.3, +0.3, 1.0, 0, 360); // 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; @@ -124,16 +124,14 @@ void testEncoderPID() if (!testEncoderPID_value) { testEncoderPID_value = true; - setLeftMotorControl({POSITION, (float)TICKS_PER_ROTATION * 10}); - setRightMotorControl({POSITION, (float)TICKS_PER_ROTATION * 10}); - setHeadingTarget(magnet->readDegrees()); + setLeftMotorControl({POSITION, (float)TICKS_PER_ROTATION * 6}); + setRightMotorControl({POSITION, (float)TICKS_PER_ROTATION * 6}); } else { testEncoderPID_value = false; setLeftMotorControl({POSITION, 0.0f}); setRightMotorControl({POSITION, 0.0f}); - setHeadingTarget(magnet->readDegrees()); } updateCritRange(); @@ -202,8 +200,9 @@ void setupBot() { headingController.Reset(); if (DO_PID_TEST) { + setHeadingTarget(magnet->readDegrees()); testEncoderPID(); - timerInterval(12000, &testEncoderPID); + timerInterval(8000, &testEncoderPID); } if (DO_TURN_TEST) { @@ -286,8 +285,8 @@ void controlLoop(int loopDelayMs, int8_t framesUntilPrint) { double currentHeading = magnet->readDegrees(); // double currentHeading = getHeadingTarget(); - double controllerOutput = headingController.Compute(headingTarget, currentHeading, loopDelaySeconds); - // double controllerOutput = 0; + // double controllerOutput = headingController.Compute(headingTarget, currentHeading, loopDelaySeconds); + double controllerOutput = 0; // TODO fix magnet calibration, then re-enable heading correction double velocityOffsetFromHeading = controllerOutput * THEORETICAL_MAX_VELOCITY_TPS * MAGNET_CCW_IS_POSITIVE; // if error is positive, then assume we need to turn CCW, so slow left and speed up right double desiredVelocityLeft = leftSetpoint.velocity - velocityOffsetFromHeading; diff --git a/src/utils/config.cpp b/src/utils/config.cpp index 86a1bb0..9869bfd 100644 --- a/src/utils/config.cpp +++ b/src/utils/config.cpp @@ -37,11 +37,11 @@ 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 THEORETICAL_MAX_VELOCITY_TPS = 63000; -float THEORETICAL_MAX_ACCELERATION_TPSPS = 16000; -float VELOCITY_LIMIT_TPS = 40000; -float ACCELERATION_LIMIT_TPSPS = 10000; -float MIN_MOTOR_POWER = 0.12; // Minimum motor power to elicit motor response, empirically determined +float THEORETICAL_MAX_VELOCITY_TPS = 52000; +float THEORETICAL_MAX_ACCELERATION_TPSPS = 252000; +float VELOCITY_LIMIT_TPS = 30000; +float ACCELERATION_LIMIT_TPSPS = 70000; +float MIN_MOTOR_POWER = 0.15; // Minimum motor power to elicit motor response, empirically determined 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 From 3caf9c5796ac0c360432aa59f2adaf93056d37c8 Mon Sep 17 00:00:00 2001 From: democat Date: Wed, 22 Oct 2025 01:57:22 -0500 Subject: [PATCH 46/47] correctly multiply soft iron matrix --- src/robot/magnet.cpp | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/src/robot/magnet.cpp b/src/robot/magnet.cpp index 3db6b4d..96f00e7 100644 --- a/src/robot/magnet.cpp +++ b/src/robot/magnet.cpp @@ -67,14 +67,15 @@ void Magnet::set_soft_iron_matrix(float matrix[3][3]) { MagnetReading Magnet::read_calibrated_data() { sBmm350MagData_t sensor_mag_data = bmm350.getGeomagneticData(); + float hi_data[3]; float mag_data[3]; - mag_data[0] = sensor_mag_data.float_x - hard_iron_offset[0]; - mag_data[1] = sensor_mag_data.float_y - hard_iron_offset[1]; - mag_data[2] = sensor_mag_data.float_z - hard_iron_offset[2]; + 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] * mag_data[0]) + (soft_iron_matrix[i][1] * mag_data[1]) + (soft_iron_matrix[i][2] * mag_data[2]); + 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] }; From 6acde964df383e1645efac8e877b1033614cbb4c Mon Sep 17 00:00:00 2001 From: xXDMOGXx <83487906+xXDMOGXx@users.noreply.github.com> Date: Mon, 10 Nov 2025 23:57:49 -0600 Subject: [PATCH 47/47] Added minimum speed into trapezoid profile, and feed in current position and velocity instead of expected --- include/utils/config.h | 1 + src/robot/control.cpp | 4 ++-- src/robot/trapezoidalProfileNew.cpp | 10 +++++++++- src/utils/config.cpp | 4 +++- 4 files changed, 15 insertions(+), 4 deletions(-) diff --git a/include/utils/config.h b/include/utils/config.h index 7ed8d5e..a271251 100644 --- a/include/utils/config.h +++ b/include/utils/config.h @@ -38,6 +38,7 @@ 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 diff --git a/src/robot/control.cpp b/src/robot/control.cpp index 183bc24..de164f0 100644 --- a/src/robot/control.cpp +++ b/src/robot/control.cpp @@ -267,14 +267,14 @@ void controlLoop(int loopDelayMs, int8_t framesUntilPrint) { // Generate trapezoidal profile setpoints if (getLeftMotorControl().mode == POSITION) { leftSetpoint = leftProfile.calculate(loopDelaySeconds, - leftSetpoint, + TrapezoidProfile::State(profileA.currentPosition, profileA.currentVelocity), TrapezoidProfile::State(getLeftMotorControl().value, 0.0)); } else { leftSetpoint = TrapezoidProfile::State(currentPositionEncoderA, getLeftMotorControl().value); } if (getRightMotorControl().mode == POSITION) { rightSetpoint = rightProfile.calculate(loopDelaySeconds, - rightSetpoint, + TrapezoidProfile::State(profileB.currentPosition, profileB.currentVelocity), TrapezoidProfile::State(getRightMotorControl().value, 0.0)); } else { rightSetpoint = TrapezoidProfile::State(currentPositionEncoderB, getRightMotorControl().value); diff --git a/src/robot/trapezoidalProfileNew.cpp b/src/robot/trapezoidalProfileNew.cpp index f50b75d..f753f6e 100644 --- a/src/robot/trapezoidalProfileNew.cpp +++ b/src/robot/trapezoidalProfileNew.cpp @@ -1,4 +1,5 @@ #include "robot/trapezoidalProfileNew.h" +#include "utils/config.h" TrapezoidProfile::State TrapezoidProfile::calculate(double t, const State ¤t, const State &goal) { @@ -18,7 +19,7 @@ TrapezoidProfile::State TrapezoidProfile::calculate(double t, const State &curre double cutoffBegin = m_current.velocity / m_constraints.maxAcceleration; double cutoffDistBegin = cutoffBegin * cutoffBegin * m_constraints.maxAcceleration / 2.0; - double cutoffEnd = goalDir.velocity / m_constraints.maxAcceleration; + 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; @@ -40,6 +41,9 @@ TrapezoidProfile::State TrapezoidProfile::calculate(double t, const State &curre 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; } else if (t < m_endFullSpeed) @@ -60,5 +64,9 @@ TrapezoidProfile::State TrapezoidProfile::calculate(double t, const State &curre result = goalDir; } + if (abs(result.position - goalDir.position) <= 100) { + result.velocity = 0; + } + return direct(result, m_direction); } diff --git a/src/utils/config.cpp b/src/utils/config.cpp index 9869bfd..6779e66 100644 --- a/src/utils/config.cpp +++ b/src/utils/config.cpp @@ -40,8 +40,9 @@ float WHEEL_DIAMETER_INCHES = 4.75; float THEORETICAL_MAX_VELOCITY_TPS = 52000; float THEORETICAL_MAX_ACCELERATION_TPSPS = 252000; float VELOCITY_LIMIT_TPS = 30000; -float ACCELERATION_LIMIT_TPSPS = 70000; +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 @@ -76,6 +77,7 @@ void setConfig(JsonObject config) { 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"];