diff --git a/.DS_Store b/.DS_Store deleted file mode 100644 index 1e2babc..0000000 Binary files a/.DS_Store and /dev/null differ diff --git a/.gitignore b/.gitignore index 29bfe19..1bb0e28 100644 --- a/.gitignore +++ b/.gitignore @@ -5,4 +5,5 @@ .vscode/settings.json .vscode/ipch env.h -/.history \ No newline at end of file +/.history +.DS_Store diff --git a/include/robot/control.h b/include/robot/control.h index f10a906..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/robot/magnet.h b/include/robot/magnet.h new file mode 100644 index 0000000..edaf561 --- /dev/null +++ b/include/robot/magnet.h @@ -0,0 +1,35 @@ +#ifndef MAGNET_H +#define MAGNET_H + +#include "Arduino.h" +#include "DFRobot_BMM350.h" + +struct MagnetReading { + float x; + float y; + float z; +}; + +class Magnet { + public: + Magnet(); + void set_hard_iron_offset(float x, float y, float z); + void set_soft_iron_matrix(float matrix[3][3]); + struct MagnetReading read_calibrated_data(); + float getCompassDegree(struct MagnetReading mag); + float readDegreesRaw(); + float readDegrees(); + bool isDataReady() { return bmm350.getDataReadyState(); } + 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; + + float previousReading = 0.0; +}; + +#endif // MAGNET_H \ No newline at end of file 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..67e551b --- /dev/null +++ b/include/robot/trapezoidalProfileNew.h @@ -0,0 +1,63 @@ +#ifndef TRAPEZOIDAL_PROFILE_NEW_H +#define TRAPEZOIDAL_PROFILE_NEW_H + +#include +#include + +class TrapezoidProfile +{ +public: + struct Constraints + { + double maxVelocity; + double maxAcceleration; + + Constraints(double maxVelocity, double maxAcceleration) + { + if (maxVelocity < 0.0 || maxAcceleration < 0.0) + { + throw std::runtime_error("Constraints must be non-negative"); + } + this->maxVelocity = maxVelocity; + this->maxAcceleration = maxAcceleration; + // Remove MathSharedStore.reportUsage for now (Java-specific) + } + }; + + struct State + { + double position = 0.0; + double velocity = 0.0; + + State() = default; + State(double position, double velocity) + : position(position), velocity(velocity) {} + + bool operator==(const State& rhs) const + { + return position == rhs.position && velocity == rhs.velocity; + } + }; + + TrapezoidProfile(const Constraints& constraints) + : m_constraints(constraints) {} + + State calculate(double t, const State& current, const State& goal); + + // bool isFinished(double t) const { return t >= totalTime(); } + +private: + static bool shouldFlipAcceleration(const State& initial, const State& goal) + { + return initial.position > goal.position; + } + + State direct(const State& in, int m_direction) const + { + return State(in.position * m_direction, in.velocity * m_direction); + } + + Constraints m_constraints; +}; + +#endif \ No newline at end of file diff --git a/include/utils/config.h b/include/utils/config.h index b98a5cb..803c9b3 100644 --- a/include/utils/config.h +++ b/include/utils/config.h @@ -33,8 +33,11 @@ extern gpio_num_t ONBOARD_LED_PIN; extern int TICKS_PER_ROTATION; extern float TRACK_WIDTH_INCHES; extern float WHEEL_DIAMETER_INCHES; -extern float MAX_VELOCITY_TPS; -extern float MAX_ACCELERATION_TPSPS; +extern float THEORETICAL_MAX_VELOCITY_TPS; +extern float VELOCITY_LIMIT_TPS; +extern float THEORETICAL_MAX_ACCELERATION_TPSPS; +extern float ACCELERATION_LIMIT_TPSPS; +extern float MIN_MOTOR_POWER; extern float TILES_TO_TICKS; extern float PID_POSITION_TOLERANCE; diff --git a/include/utils/logging.h b/include/utils/logging.h index ab1a3ed..41ebcd7 100644 --- a/include/utils/logging.h +++ b/include/utils/logging.h @@ -12,6 +12,7 @@ void serialLog(std::string value, int serialLoggingLevel); void serialLogln(const char *message, int serialLoggingLevel); void serialLogln(int value, int serialLoggingLevel); void serialLogln(double value, int serialLoggingLevel); +void serialLogln(float value, int serialLoggingLevel); void serialLogln(std::string value, int serialLoggingLevel); void serialLogError(char message[], int error); diff --git a/lib/DFRobot_BMM350/LICENSE b/lib/DFRobot_BMM350/LICENSE new file mode 100644 index 0000000..79f3100 --- /dev/null +++ b/lib/DFRobot_BMM350/LICENSE @@ -0,0 +1,7 @@ +Copyright 2010 DFRobot Co.Ltd + +Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. \ No newline at end of file diff --git a/lib/DFRobot_BMM350/README.md b/lib/DFRobot_BMM350/README.md new file mode 100644 index 0000000..3ff4694 --- /dev/null +++ b/lib/DFRobot_BMM350/README.md @@ -0,0 +1,216 @@ +# DFRobot_BMM350 + +* [中文](./README_CN.md) + +The BMM350 is a low-power and low noise 3-axis digital geomagnetic sensor that perfectly matches the requirements of compass applications. Based on Bosch’s proprietary FlipCore technology, the BMM350 provides absolute spatial orientation and motion vectors with high accuracy and dynamics. Featuring small size and lightweight, it is also especially suited for supporting drones in accurate heading. The BMM350 can also be used together with an inertial measurement unit consisting of a 3-axis accelerometer and a 3-axis gyroscope. + +![产品效果图](./resources/images/BMM350.png)![产品效果图](./resources/images/BMM350Size.png) + +## Product Link([https://www.dfrobot.com](https://www.dfrobot.com)) + +```yaml +SKU: SEN0619 +``` + +## Table of Contents + +* [Summary](#summary) +* [Installation](#installation) +* [Methods](#methods) +* [Compatibility](#compatibility) +* [History](#history) +* [Credits](#credits) + +## Summary + +Get geomagnetic data along the XYZ axis. + +1. This module can obtain high threshold and low threshold geomagnetic data.
+2. Geomagnetism on three(xyz) axes can be measured.
+3. This module can choose I2C or I3C communication mode.
+ +## Installation + +To use this library download the zip file, uncompress it to a folder named DFRobot_BMM350. +Download the zip file first to use this library and uncompress it to a folder named DFRobot_BMM350. + +## Methods + +```C++ + /** + * @fn softReset + * @brief Soft reset, restore to suspended mode after soft reset. + */ + void softReset(void); + + /** + * @fn setOperationMode + * @brief Set sensor operation mode + * @param powermode + * @n eBmm350SuspendMode suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + * so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + * @n eBmm350NormalMode normal mode: Get geomagnetic data normally. + * @n eBmm350ForcedMode forced mode: Single measurement, the sensor restores to suspend mode when the measurement is done. + * @n eBmm350ForcedModeFast To reach ODR = 200Hz is only possible by using FM_ FAST. + */ + void setOperationMode(enum eBmm350PowerModes_t powermode); + + + /** + * @fn getOperationMode + * @brief Get sensor operation mode + * @return result Return sensor operation mode as a character string + */ + String getOperationMode(void); + + /** + * @fn setPresetMode + * @brief Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default collection rate is 12.5Hz) + * @param presetMode + * @n BMM350_PRESETMODE_LOWPOWER Low power mode, get a fraction of data and take the mean value. + * @n BMM350_PRESETMODE_REGULAR Regular mode, get a number of data and take the mean value. + * @n BMM350_PRESETMODE_ENHANCED Enhanced mode, get a plenty of data and take the mean value. + * @n BMM350_PRESETMODE_HIGHACCURACY High accuracy mode, get a huge number of data and take the mean value. + */ + void setPresetMode(uint8_t presetMode, uint8_t rate = BMM350_DATA_RATE_12_5HZ); + + /** + * @fn setRate + * @brief Set the rate of obtaining geomagnetic data, the higher, the faster (without delay function) + * @param rate + * @n BMM350_DATA_RATE_1_5625HZ + * @n BMM350_DATA_RATE_3_125HZ + * @n BMM350_DATA_RATE_6_25HZ + * @n BMM350_DATA_RATE_12_5HZ (default rate) + * @n BMM350_DATA_RATE_25HZ + * @n BMM350_DATA_RATE_50HZ + * @n BMM350_DATA_RATE_100HZ + * @n BMM350_DATA_RATE_200HZ + * @n BMM350_DATA_RATE_400HZ + */ + void setRate(uint8_t rate); + + /** + * @fn getRate + * @brief Get the config data rate, unit: HZ + * @return rate + */ + float getRate(void); + + /** + * @fn selfTest + * @brief The sensor self test, the returned value indicate the self test result. + * @param testMode: + * @n eBmm350SelfTestNormal Normal self test, test whether x-axis, y-axis and z-axis are connected or short-circuited + * @return result The returned character string is the self test result + */ + String selfTest(eBmm350SelfTest_t testMode = eBmm350SelfTestNormal); + + /** + * @fn setMeasurementXYZ + * @brief Enable the measurement at x-axis, y-axis and z-axis, default to be enabled. After disabling, the geomagnetic data at x, y, and z axis are wrong. + * @param en_x + * @n BMM350_X_EN Enable the measurement at x-axis + * @n BMM350_X_DIS Disable the measurement at x-axis + * @param en_y + * @n BMM350_Y_EN Enable the measurement at y-axis + * @n BMM350_Y_DIS Disable the measurement at y-axis + * @param en_z + * @n BMM350_Z_EN Enable the measurement at z-axis + * @n BMM350_Z_DIS Disable the measurement at z-axis + */ + void setMeasurementXYZ(enum eBmm350XAxisEnDis_t enX = BMM350_X_EN, enum eBmm350YAxisEnDis_t enY = BMM350_Y_EN, enum eBmm350ZAxisEnDis_t enZ = BMM350_Z_EN); + + /** + * @fn getMeasurementStateXYZ + * @brief Get the enabling status at x-axis, y-axis and z-axis + * @return result Return enabling status as a character string + */ + String getMeasurementStateXYZ(void); + + /** + * @fn getGeomagneticData + * @brief Get the geomagnetic data of 3 axis (x, y, z) + * @return Geomagnetic data structure, unit: (uT) + */ + sBmm350MagData_t getGeomagneticData(void); + + /** + * @fn getCompassDegree + * @brief Get compass degree + * @return Compass degree (0° - 360°) + * @n 0° = North, 90° = East, 180° = South, 270° = West. + */ + float getCompassDegree(void); + + /** + * @fn setDataReadyPin + * @brief Enable or disable data ready interrupt pin + * @n After enabling, the DRDY pin jump when there's data coming. + * @n After disabling, the DRDY pin will not jump when there's data coming. + * @n High polarity: active on high, the default is low level, which turns to high level when the interrupt is triggered. + * @n Low polarity: active on low, default is high level, which turns to low level when the interrupt is triggered. + * @param modes + * @n BMM350_ENABLE_INTERRUPT Enable DRDY + * @n BMM350_DISABLE_INTERRUPT Disable DRDY + * @param polarity + * @n BMM350_ACTIVE_HIGH High polarity + * @n BMM350_ACTIVE_LOW Low polarity + */ + void setDataReadyPin(enum eBmm350InterruptEnableDisable_t modes, enum eBmm350IntrPolarity_t polarity=BMM350_ACTIVE_HIGH); + + /** + * @fn getDataReadyState + * @brief Get the data ready status, determine whether the data is ready + * @return status + * @n true Data ready + * @n false Data is not ready + */ + bool getDataReadyState(void); + + /** + * @fn setThresholdInterrupt(uint8_t modes, int8_t threshold, uint8_t polarity) + * @brief Set threshold interrupt, an interrupt is triggered when the geomagnetic value of a channel is beyond/below the threshold + * @n High polarity: active on high level, the default is low level, which turns to high level when the interrupt is triggered. + * @n Low polarity: active on low level, the default is high level, which turns to low level when the interrupt is triggered. + * @param modes + * @n LOW_THRESHOLD_INTERRUPT Low threshold interrupt mode + * @n HIGH_THRESHOLD_INTERRUPT High threshold interrupt mode + * @param threshold + * @n Threshold, default to expand 16 times, for example: under low threshold mode, if the threshold is set to be 1, actually the geomagnetic data below 16 will trigger an interrupt + * @param polarity + * @n POLARITY_HIGH High polarity + * @n POLARITY_LOW Low polarity + */ + void setThresholdInterrupt(uint8_t modes, int8_t threshold, enum eBmm350IntrPolarity_t polarity); + + /** + * @fn getThresholdData + * @brief Get the data with threshold interrupt occurred + * @return Returns the structure for storing geomagnetic data, the structure stores the data of 3 axis and interrupt status, + * @n The interrupt is not triggered when the data at x-axis, y-axis and z-axis are NO_DATA + * @n mag_x、mag_y、mag_z store geomagnetic data + * @n interrupt_x、interrupt_y、interrupt_z store the xyz axis interrupt state + */ + sBmm350ThresholdData_t getThresholdData(void); +``` + +## Compatibility + +| MCU | Work Well | Work Wrong | Untested | Remarks | +| ------------------ |:---------:|:----------:|:--------:| ------- | +| Arduino uno | √ | | | | +| FireBeetle esp32 | √ | | | | +| FireBeetle esp8266 | √ | | | | +| FireBeetle m0 | √ | | | | +| Leonardo | √ | | | | +| Microbit | √ | | | | +| Arduino MEGA2560 | √ | | | | + +## History + +- 2024/05/08 - Version 1.0.0 released. + +## Credits + +Written by [GDuang](yonglei.ren@dfrobot.com), 2024. (Welcome to our [website](https://www.dfrobot.com/)) diff --git a/lib/DFRobot_BMM350/README_CN.md b/lib/DFRobot_BMM350/README_CN.md new file mode 100644 index 0000000..0da933b --- /dev/null +++ b/lib/DFRobot_BMM350/README_CN.md @@ -0,0 +1,214 @@ +DFRobot_BMP350 +=========================== + +* [English Version](./README.md) + +BMM350 是一款低功耗、低噪声的 3 轴数字地磁传感器,完全符合罗盘应用的要求。 基于博世专有的 FlipCore 技术,BMM350 提供了高精度和动态的绝对空间方向和运动矢量。 体积小、重量轻,特别适用于支持无人机精准航向。 BMM350 还可与由 3 轴加速度计和 3 轴陀螺仪组成的惯性测量单元一起使用。 + +![产品效果图](./resources/images/BMM350.png)![产品效果图](./resources/images/BMM350Size.png) + +## 产品链接([https://www.dfrobot.com.cn](https://www.dfrobot.com.cn)) + +```yaml +SKU: SEN0619 +``` + +## 目录 + +* [概述](#概述) +* [库安装](#库安装) +* [方法](#方法) +* [兼容性](#兼容性) +* [历史](#历史) +* [创作者](#创作者) + +## 概述 + +您可以沿 XYZ 轴获取地磁数据 + +1. 本模块可以获得高阈值和低阈值地磁数据。
+2. 可以测量三个(xyz)轴上的地磁。
+3. 本模块可选择I2C或I3C通讯方式。
+ +## 库安装 + +使用此库前,请首先下载库文件,将其粘贴到\Arduino\libraries目录中,然后打开examples文件夹并在该文件夹中运行演示。 + +## 方法 + +```C++ + /** + * @fn softReset + * @brief 软件复位,软件复位后先恢复为挂起模式 + */ + void softReset(void); + + /** + * @fn setOperationMode + * @brief 设置传感器的执行模式 + * @param opMode mode + * @n eBmm350SuspendMode 挂起模式:挂起模式是芯片上电后BMM350的默认电源模式,在挂起模式下电流消耗最小,因此该模式适用于不需要数据转换的时期(所有寄存器的读写都是可能的) + * @n eBmm350NormalMode 常规模式: 获取地磁数据 + * @n eBmm350ForcedMode 强制模式: 单次测量,测量完成后传感器恢复到暂停模式 + * @n eBmm350ForcedModeFast 只有使用FM_FAST时,ODR才能达到200Hz + */ + void setOperationMode(uint8_t opMode); + + /** + * @fn getOperationMode + * @brief 获取传感器的执行模式 + * @return result 返回字符串为传感器的执行模式 + */ + String getOperationMode(void); + + /** + * @fn setPresetMode + * @brief 设置预置模式,使用户更简单的配置传感器来获取地磁数据(默认的采集速率为12.5Hz) + * @param presetMode + * @n BMM350_PRESETMODE_LOWPOWER 低功率模式,获取少量的数据 取均值 + * @n BMM350_PRESETMODE_REGULAR 普通模式,获取中量数据 取均值 + * @n BMM350_PRESETMODE_ENHANCED 增强模式,获取大量数据 取均值 + * @n BMM350_PRESETMODE_HIGHACCURACY 高精度模式,获取超大量数据 取均值 + */ + void setPresetMode(uint8_t presetMode, uint8_t rate = BMM350_DATA_RATE_12_5HZ); + + /** + * @fn setRate + * @brief 设置获取地磁数据的速率,速率越大获取越快(不加延时函数) + * @param rate + * @n BMM350_DATA_RATE_1_5625HZ + * @n BMM350_DATA_RATE_3_125HZ + * @n BMM350_DATA_RATE_6_25HZ + * @n BMM350_DATA_RATE_12_5HZ (默认速率) + * @n BMM350_DATA_RATE_25HZ + * @n BMM350_DATA_RATE_50HZ + * @n BMM350_DATA_RATE_100HZ + * @n BMM350_DATA_RATE_200HZ + * @n BMM350_DATA_RATE_400HZ + */ + void setRate(uint8_t rate); + + /** + * @fn getRate + * @brief 获取配置的数据速率 单位:HZ + * @return rate + */ + uint8_t getRate(void); + + /** + * @fn selfTest + * @brief 传感器自测,返回值表明自检结果 + * @param testMode: + * @n eBmm350SelfTestNormal 常规自检,检查x轴、y轴、z轴是否接通或短路 + * @return result 返回的字符串为自测的结果 + */ + String selfTest(eBmm350SelfTest_t testMode = eBmm350SelfTestNormal); + + /** + * @fn setMeasurementXYZ + * @brief 使能x y z 轴的测量,默认设置为使能,禁止后xyz轴的地磁数据不准确 + * @param en_x + * @n BMM350_X_EN 使能 x 轴的测量 + * @n BMM350_X_DIS 禁止 x 轴的测量 + * @param en_y + * @n BMM350_Y_EN 使能 y 轴的测量 + * @n BMM350_Y_DIS 禁止 y 轴的测量 + * @param en_z + * @n BMM350_Z_EN 使能 z 轴的测量 + * @n BMM350_Z_DIS 禁止 z 轴的测量 + */ + void setMeasurementXYZ(enum eBmm350XAxisEnDis_t enX = BMM350_X_EN, enum eBmm350YAxisEnDis_t enY = BMM350_Y_EN, enum eBmm350ZAxisEnDis_t enZ = BMM350_Z_EN); + + /** + * @fn getMeasurementStateXYZ + * @brief 获取 x y z 轴的使能状态 + * @return result 返回字符串为使能的状态 + */ + String getMeasurementStateXYZ(void); + + /** + * @fn getGeomagneticData + * @brief 获取x y z 三轴的地磁数据 + * @return 地磁的数据的结构体,单位:微特斯拉(uT) + */ + sBmm350MagData_t getGeomagneticData(void); + + /** + * @fn getCompassDegree + * @brief 获取罗盘方向 + * @return 罗盘方向 (0° - 360°) + * @n 0° = North, 90° = East, 180° = South, 270° = West. + */ + float getCompassDegree(void); + + /** + * @fn setDataReadyPin + * @brief 使能或者禁止数据准备中断引脚 + * @n 使能后有数据来临DRDY引脚跳变 + * @n 禁止后有数据来临DRDY不进行跳变 + * @n 高极性:高电平为活动电平,默认为低电平,触发中断时电平变为高 + * @n 低极性:低电平为活动电平,默认为高电平,触发中断时电平变为低 + * @param modes + * @n BMM350_ENABLE_INTERRUPT 使能DRDY + * @n BMM350_DISABLE_INTERRUPT 禁止DRDY + * @param polarity + * @n BMM350_ACTIVE_HIGH 高极性 + * @n BMM350_ACTIVE_LOW 低极性 + */ + void setDataReadyPin(uint8_t modes, uint8_t polarity=POLARITY_HIGH); + + /** + * @fn getDataReadyState + * @brief 获取数据准备的状态,用来判断数据是否准备好 + * @return status + * @n true 数据准备好了 + * @n false 数据没有准备好 + */ + bool getDataReadyState(void); + + /** + * @fn setThresholdInterrupt(uint8_t modes, int8_t threshold, uint8_t polarity) + * @brief 设置阈值中断,当某个通道的地磁值高/低于阈值时触发中断 + * @n 高极性:高电平为活动电平,默认为低电平,触发中断时电平变为高 + * @n 低极性:低电平为活动电平,默认为高电平,触发中断时电平变为低 + * @param modes + * @n LOW_THRESHOLD_INTERRUPT 低阈值中断模式 + * @n HIGH_THRESHOLD_INTERRUPT 高阈值中断模式 + * @param threshold + * @n 阈值,默认扩大16倍,例如:低阈值模式下传入阈值1,实际低于16的地磁数据都会触发中断 + * @param polarity + * @n POLARITY_HIGH 高极性 + * @n POLARITY_LOW 低极性 + */ + void setThresholdInterrupt(uint8_t modes, int8_t threshold, enum eBmm350IntrPolarity_t polarity); + + /** + * @fn getThresholdData + * @brief 获取发生阈值中断的数据 + * @return 返回存放地磁数据的结构体,结构体存放三轴当数据和中断状态, + * @n xyz轴的数据为 NO_DATA 时,未触发中断 + * @n mag_x、mag_y、mag_z 存放地磁数据 + * @n interrupt_x、interrupt_y、interrupt_z 存放轴中断状态 + */ + sBmm350ThresholdData_t getThresholdData(void); +``` + +## 兼容性 + +| MCU | Work Well | Work Wrong | Untested | Remarks | +| ------------------ |:---------:|:----------:|:--------:| ------- | +| Arduino uno | √ | | | | +| FireBeetle esp32 | √ | | | | +| FireBeetle esp8266 | √ | | | | +| FireBeetle m0 | √ | | | | +| Leonardo | √ | | | | +| Microbit | √ | | | | +| Arduino MEGA2560 | √ | | | | + +## History + +- 2024/05/08 - Version 1.0.0 released. + +## Credits + +Written by [GDuang](yonglei.ren@dfrobot.com), 2024. (Welcome to our [website](https://www.dfrobot.com/)) diff --git a/lib/DFRobot_BMM350/examples/calibration/CalibratedMagnedticData/CalibratedMagnedticData.ino b/lib/DFRobot_BMM350/examples/calibration/CalibratedMagnedticData/CalibratedMagnedticData.ino new file mode 100644 index 0000000..bbde827 --- /dev/null +++ b/lib/DFRobot_BMM350/examples/calibration/CalibratedMagnedticData/CalibratedMagnedticData.ino @@ -0,0 +1,129 @@ +/*! + * @file CalibratedMagnedticData.ino + * @brief Get the Calibrated geomagnetic data at 3 axis (x, y, z), get the compass degree + * @n "Compass Degree", the angle formed when the needle rotates counterclockwise from the current position to the true north + * @n Experimental phenomenon: serial print the geomagnetic data of x-axis, y-axis and z-axis and the compass degree + * @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) + * @license The MIT License (MIT) + * @author [GDuang](yonglei.ren@dfrobot.com) + * @version V1.0.0 + * @date 2024-05-06 + * @url https://github.com/DFRobot/DFRobot_BMM350/ + */ + +// ======================================================= +// 请先阅读项目 https://github.com/DFRobot/DFRobot_BMM350/tree/master/examples/calibration +// Please read https://github.com/DFRobot/DFRobot_BMM350/tree/master/examples/calibration +// 包含使用说明、校准步骤。 +// It contains usage instructions, calibration steps. +// ======================================================= + +#include "DFRobot_BMM350.h" + +DFRobot_BMM350_I2C bmm350(&Wire, I2C_ADDRESS); +//hard iron calibration parameters +const float hard_iron[3] = { -13.45, -28.95, 12.69 }; +//soft iron calibration parameters +const float soft_iron[3][3] = { + { 0.992, -0.006, -0.007 }, + { -0.006, 0.990, -0.004 }, + { -0.007, -0.004, 1.019 } +}; + +void setup() { + Serial.begin(115200); + while (!Serial) + ; + while (bmm350.begin()) { + Serial.println("bmm350 init failed, Please try again!"); + delay(1000); + } + Serial.println("bmm350 init success!"); + + /** + * Set sensor operation mode + * opMode: + * eBmm350SuspendMode // suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + * so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + * eBmm350NormalMode // normal mode Get geomagnetic data normally. + * eBmm350ForcedMode // forced mode Single measurement, the sensor restores to suspend mode when the measurement is done. + * eBmm350ForcedModeFast // To reach ODR = 200Hz is only possible by using FM_ FAST. + */ + bmm350.setOperationMode(eBmm350NormalMode); + + /** + * Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) + * presetMode: + * BMM350_PRESETMODE_LOWPOWER // Low power mode, get a fraction of data and take the mean value. + * BMM350_PRESETMODE_REGULAR // Regular mode, get a number of data and take the mean value. + * BMM350_PRESETMODE_ENHANCED // Enhanced mode, get a plenty of data and take the mean value. + * BMM350_PRESETMODE_HIGHACCURACY // High accuracy mode, get a huge number of take and draw the mean value. + * rate: + * BMM350_DATA_RATE_1_5625HZ + * BMM350_DATA_RATE_3_125HZ + * BMM350_DATA_RATE_6_25HZ + * BMM350_DATA_RATE_12_5HZ (default rate) + * BMM350_DATA_RATE_25HZ + * BMM350_DATA_RATE_50HZ + * BMM350_DATA_RATE_100HZ + * BMM350_DATA_RATE_200HZ + * BMM350_DATA_RATE_400HZ + */ + bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ); + + /** + * Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required, the geomagnetic data at x, y and z will be inaccurate when disabled. + * Refer to setMeasurementXYZ() function in the .h file if you want to configure more parameters. + */ + bmm350.setMeasurementXYZ(); +} + +void loop() { + sBmm350MagData_t magData = bmm350.getGeomagneticData(); + + float mag_data[3]; + + // hard iron calibration + mag_data[0] = magData.float_x + hard_iron[0]; + mag_data[1] = magData.float_y + hard_iron[1]; + mag_data[2] = magData.float_z + hard_iron[2]; + + //soft iron calibration + for (int i = 0; i < 3; i++) { + mag_data[i] = (soft_iron[i][0] * mag_data[0]) + (soft_iron[i][1] * mag_data[1]) + (soft_iron[i][2] * mag_data[2]); + } + + magData.x = mag_data[0]; + magData.y = mag_data[1]; + magData.z = mag_data[2]; + magData.float_x = mag_data[0]; + magData.float_y = mag_data[1]; + magData.float_z = mag_data[2]; + + Serial.print("mag x = ");Serial.print(magData.x);Serial.println(" uT"); + Serial.print("mag y = ");Serial.print(magData.y);Serial.println(" uT"); + Serial.print("mag z = ");Serial.print(magData.z);Serial.println(" uT"); + + // float type data + //Serial.print("mag x = "); Serial.print(magData.float_x); Serial.println(" uT"); + //Serial.print("mag y = "); Serial.print(magData.float_y); Serial.println(" uT"); + //Serial.print("mag z = "); Serial.print(magData.float_z); Serial.println(" uT"); + + float compassDegree = getCompassDegree(magData); + Serial.print("the angle between the pointing direction and north (counterclockwise) is:"); + Serial.println(compassDegree); + Serial.println("--------------------------------"); + delay(3000); +} +float getCompassDegree(sBmm350MagData_t magData) +{ + float compass = 0.0; + compass = atan2(magData.x, magData.y); + if (compass < 0) { + compass += 2 * PI; + } + if (compass > 2 * PI) { + compass -= 2 * PI; + } + return compass * 180 / M_PI; +} diff --git a/lib/DFRobot_BMM350/examples/calibration/README.md b/lib/DFRobot_BMM350/examples/calibration/README.md new file mode 100644 index 0000000..fc0f586 --- /dev/null +++ b/lib/DFRobot_BMM350/examples/calibration/README.md @@ -0,0 +1,175 @@ +# Guide to Calibrating BMM350 Magnetic Field Data Using MotionCal + +* [中文版本](./README_CN.md) + +Magnetometers in real-world applications are susceptible to interference from metal objects, electrical currents, and fluctuations in the Earth's magnetic field. Uncalibrated data can lead to deviations in direction recognition, affecting the accuracy of the heading angle (yaw) or the functionality of the electronic compass. + +--- + +## Required Tools + +* [MotionCal](https://www.pjrc.com/store/prop_shield.html#motioncal) tool (supports Windows/macOS/Linux) +* Arduino IDE +* A development board supported by the DFRobot_BMM350 sensor, with the serial port correctly connected to the PC + +--- + +## Step 1: Upload the Calibration Firmware + +Use a development board supported by the DFRobot_BMM350 sensor and connect the serial port to the PC correctly. + +--- + +## Step 2: Run the MotionCal Tool + +1. Open the [MotionCal](https://www.pjrc.com/store/prop_shield.html#motioncal) download page, select your platform, and download and install the tool. + +![MotionCal download pic](/resources/images/cal_pic1.jpg) + +2. Launch `MotionCal`. +3. Select the correct serial port in the menu (consistent with your device). + +![MotionCal port choose](/resources/images/cal_pic2.jpg) + +4. MotionCal automatically starts receiving and visualizing the data from the magnetometer, accelerometer, and gyroscope. + +> Ensure that no other serial port software is open simultaneously! + +--- + +## Step 3: Rotate the Sensor for Omnidirectional Sampling + +> Slowly rotate the sensor along the **X/Y/Z axes** to ensure that the data graph covers a complete sphere. + +![MotionCal cal](/resources/images/cal_pic3.jpg) + +## Step 4: Apply Compensation in the Code + +![calibration parameters](/resources/images/cal_pic4.jpg) + +The calibration parameters required are located in the top-left corner of the MotionCal software. +Fill in the calibration coefficients in the corresponding positions of the reference code `CalibrateMagnedticData.ino`. + +```cpp +//hard iron calibration parameters +const float hard_iron[3] = { -13.45, -28.95, 12.69 }; +//soft iron calibration parameters +const float soft_iron[3][3] = { + { 0.992, -0.006, -0.007 }, + { -0.006, 0.990, -0.004 }, + { -0.007, -0.004, 1.019 } +}; +``` + +The complete reference code is as follows: + +```cpp +#include "DFRobot_BMM350.h" + +DFRobot_BMM350_I2C bmm350(&Wire, I2C_ADDRESS); +//hard iron calibration parameters +const float hard_iron[3] = { -13.45, -28.95, 12.69 }; +//soft iron calibration parameters +const float soft_iron[3][3] = { + { 0.992, -0.006, -0.007 }, + { -0.006, 0.990, -0.004 }, + { -0.007, -0.004, 1.019 } +}; + +void setup() { + Serial.begin(115200); + while (!Serial) + ; + while (bmm350.begin()) { + Serial.println("bmm350 init failed, Please try again!"); + delay(1000); + } + Serial.println("bmm350 init success!"); + + /** + * Set sensor operation mode + * opMode: + * eBmm350SuspendMode // suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + * so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + * eBmm350NormalMode // normal mode Get geomagnetic data normally. + * eBmm350ForcedMode // forced mode Single measurement, the sensor restores to suspend mode when the measurement is done. + * eBmm350ForcedModeFast // To reach ODR = 200Hz is only possible by using FM_ FAST. + */ + bmm350.setOperationMode(eBmm350NormalMode); + + /** + * Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) + * presetMode: + * BMM350_PRESETMODE_LOWPOWER // Low power mode, get a fraction of data and take the mean value. + * BMM350_PRESETMODE_REGULAR // Regular mode, get a number of data and take the mean value. + * BMM350_PRESETMODE_ENHANCED // Enhanced mode, get a plenty of data and take the mean value. + * BMM350_PRESETMODE_HIGHACCURACY // High accuracy mode, get a huge number of take and draw the mean value. + */ + bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ); + + /** + * Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required, the geomagnetic data at x, y and z will be inaccurate when disabled. + * Refer to setMeasurementXYZ() function in the .h file if you want to configure more parameters. + */ + bmm350.setMeasurementXYZ(); +} + +void loop() { + sBmm350MagData_t magData = bmm350.getGeomagneticData(); + + float mag_data[3]; + + // hard iron calibration + mag_data[0] = magData.float_x + hard_iron[0]; + mag_data[1] = magData.float_y + hard_iron[1]; + mag_data[2] = magData.float_z + hard_iron[2]; + + //soft iron calibration + for (int i = 0; i < 3; i++) { + mag_data[i] = (soft_iron[i][0] * mag_data[0]) + (soft_iron[i][1] * mag_data[1]) + (soft_iron[i][2] * mag_data[2]); + } + + magData.x = mag_data[0]; + magData.y = mag_data[1]; + magData.z = mag_data[2]; + magData.float_x = mag_data[0]; + magData.float_y = mag_data[1]; + magData.float_z = mag_data[2]; + + Serial.print("mag x = ");Serial.print(magData.x);Serial.println(" uT"); + Serial.print("mag y = ");Serial.print(magData.y);Serial.println(" uT"); + Serial.print("mag z = ");Serial.print(magData.z);Serial.println(" uT"); + + // float type data + //Serial.print("mag x = "); Serial.print(magData.float_x); Serial.println(" uT"); + //Serial.print("mag y = "); Serial.print(magData.float_y); Serial.println(" uT"); + //Serial.print("mag z = "); Serial.print(magData.float_z); Serial.println(" uT"); + + float compassDegree = getCompassDegree(magData); + Serial.print("the angle between the pointing direction and north (counterclockwise) is:"); + Serial.println(compassDegree); + Serial.println("--------------------------------"); + delay(3000); +} +float getCompassDegree(sBmm350MagData_t magData) +{ + float compass = 0.0; + compass = atan2(magData.x, magData.y); + if (compass < 0) { + compass += 2 * PI; + } + if (compass > 2 * PI) { + compass -= 2 * PI; + } + return compass * 180 / M_PI; +} +``` + +--- + +--- + +## 📎 Appendix + +* MotionCal download link: [https://www.pjrc.com/store/prop_shield.html#motioncal](https://www.pjrc.com/store/prop_shield.html#motioncal) +* DFRobot BMM350 Sensor: [https://wiki.dfrobot.com.cn/_SKU_SEN0619_Gravity_BMM350_TripleAxis_Magnetometer_Sensor](https://wiki.dfrobot.com.cn/_SKU_SEN0619_Gravity_BMM350_TripleAxis_Magnetometer_Sensor) \ No newline at end of file diff --git a/lib/DFRobot_BMM350/examples/calibration/README_CN.md b/lib/DFRobot_BMM350/examples/calibration/README_CN.md new file mode 100644 index 0000000..d7ada6f --- /dev/null +++ b/lib/DFRobot_BMM350/examples/calibration/README_CN.md @@ -0,0 +1,242 @@ +# 使用 MotionCal 校准磁场数据指南 + +* [English Version](./README.md) + +磁力计在现实应用中易受金属物体、电流干扰和地磁场波动的影响。未经校准的数据可能会导致方向识别偏移,影响航向角(yaw)或电子罗盘功能的准确性。 + +--- + +## 所需工具 + +* [MotionCal](https://www.pjrc.com/store/prop_shield.html#motioncal) 工具(支持 Windows/macOS/Linux) +* Arduino IDE +* DFRobot_BMM350传感器器所支持的开发板,并将串口正确连接到PC + +--- + +## 步骤一:上传校准固件 + +DFRobot_BMM350传感器器所支持的开发板,并将串口正确连接到PC + +```cpp +#include "DFRobot_BMM350.h" + +DFRobot_BMM350_I2C bmm350(&Wire, I2C_ADDRESS); +void setup() { + Serial.begin(115200); + while (!Serial) + ; + while (bmm350.begin()) { + Serial.println("bmm350 init failed, Please try again!"); + delay(1000); + } + Serial.println("bmm350 init success!"); + + /** + * Set sensor operation mode + * opMode: + * eBmm350SuspendMode // suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + * so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + * eBmm350NormalMode // normal mode Get geomagnetic data normally. + * eBmm350ForcedMode // forced mode Single measurement, the sensor restores to suspend mode when the measurement is done. + * eBmm350ForcedModeFast // To reach ODR = 200Hz is only possible by using FM_ FAST. + */ + bmm350.setOperationMode(eBmm350NormalMode); + + /** + * Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) + * presetMode: + * BMM350_PRESETMODE_LOWPOWER // Low power mode, get a fraction of data and take the mean value. + * BMM350_PRESETMODE_REGULAR // Regular mode, get a number of data and take the mean value. + * BMM350_PRESETMODE_ENHANCED // Enhanced mode, get a plenty of data and take the mean value. + * BMM350_PRESETMODE_HIGHACCURACY // High accuracy mode, get a huge number of take and draw the mean value. + */ + bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ); + + /** + * Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required, the geomagnetic data at x, y and z will be inaccurate when disabled. + * Refer to setMeasurementXYZ() function in the .h file if you want to configure more parameters. + */ + bmm350.setMeasurementXYZ(); +} + +void loop() { + sBmm350MagData_t magData = bmm350.getGeomagneticData(); + Serial.print("Raw:"); + Serial.print(0); + Serial.print(','); + Serial.print(0); + Serial.print(','); + Serial.print(0); + Serial.print(','); + Serial.print(0); + Serial.print(','); + Serial.print(0); + Serial.print(','); + Serial.print(0); + Serial.print(','); + Serial.print(magData.x*10); + Serial.print(','); + Serial.print(magData.y*10); + Serial.print(','); + Serial.print(magData.z*10); + Serial.println(); + delay(100); +} +``` + +--- + +## 步骤二:运行 MotionCal 工具 + +1. 打开 [MotionCal](https://www.pjrc.com/store/prop_shield.html#motioncal) 下载页面,选择你的平台并下载安装。 + +![MotionCal download pic](/resources/images/cal_pic1.jpg) + +2. 启动 `MotionCal`。 +3. 在菜单中选择正确的串口(与你的设备一致)。 + +![MotionCal port choose](/resources/images/cal_pic2.jpg) + +4. MotionCal 自动开始自动接收并可视化磁力计、加速度计和陀螺仪数据。 + +> 确保没有其它串口软件同时打开!! + +--- + +## 步骤三:旋转传感器进行全向采样 + +> 将传感器沿 **X/Y/Z 各轴方向**缓慢旋转,使数据图形覆盖完整的球体。 + +![MotionCal cal](/resources/images/cal_pic3.jpg) + +## 步骤四:在代码中应用补偿 + +![calibration parameters](/resources/images/cal_pic4.jpg) + +MotionCal软件左上角即为所需的校正参数 +分别将校正系数填入参考代码`CalibrateMagnedticData.ino`,对应位置 + +```cpp +//hard iron calibration parameters +const float hard_iron[3] = { -13.45, -28.95, 12.69 }; +//soft iron calibration parameters +const float soft_iron[3][3] = { + { 0.992, -0.006, -0.007 }, + { -0.006, 0.990, -0.004 }, + { -0.007, -0.004, 1.019 } +}; +``` + +完整参考代码如下: + +```cpp +#include "DFRobot_BMM350.h" + +DFRobot_BMM350_I2C bmm350(&Wire, I2C_ADDRESS); +//hard iron calibration parameters +const float hard_iron[3] = { -13.45, -28.95, 12.69 }; +//soft iron calibration parameters +const float soft_iron[3][3] = { + { 0.992, -0.006, -0.007 }, + { -0.006, 0.990, -0.004 }, + { -0.007, -0.004, 1.019 } +}; + +void setup() { + Serial.begin(115200); + while (!Serial) + ; + while (bmm350.begin()) { + Serial.println("bmm350 init failed, Please try again!"); + delay(1000); + } + Serial.println("bmm350 init success!"); + + /** + * Set sensor operation mode + * opMode: + * eBmm350SuspendMode // suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + * so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + * eBmm350NormalMode // normal mode Get geomagnetic data normally. + * eBmm350ForcedMode // forced mode Single measurement, the sensor restores to suspend mode when the measurement is done. + * eBmm350ForcedModeFast // To reach ODR = 200Hz is only possible by using FM_ FAST. + */ + bmm350.setOperationMode(eBmm350NormalMode); + + /** + * Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) + * presetMode: + * BMM350_PRESETMODE_LOWPOWER // Low power mode, get a fraction of data and take the mean value. + * BMM350_PRESETMODE_REGULAR // Regular mode, get a number of data and take the mean value. + * BMM350_PRESETMODE_ENHANCED // Enhanced mode, get a plenty of data and take the mean value. + * BMM350_PRESETMODE_HIGHACCURACY // High accuracy mode, get a huge number of take and draw the mean value. + */ + bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ); + + /** + * Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required, the geomagnetic data at x, y and z will be inaccurate when disabled. + * Refer to setMeasurementXYZ() function in the .h file if you want to configure more parameters. + */ + bmm350.setMeasurementXYZ(); +} + +void loop() { + sBmm350MagData_t magData = bmm350.getGeomagneticData(); + + float mag_data[3]; + + // hard iron calibration + mag_data[0] = magData.float_x + hard_iron[0]; + mag_data[1] = magData.float_y + hard_iron[1]; + mag_data[2] = magData.float_z + hard_iron[2]; + + //soft iron calibration + for (int i = 0; i < 3; i++) { + mag_data[i] = (soft_iron[i][0] * mag_data[0]) + (soft_iron[i][1] * mag_data[1]) + (soft_iron[i][2] * mag_data[2]); + } + + magData.x = mag_data[0]; + magData.y = mag_data[1]; + magData.z = mag_data[2]; + magData.float_x = mag_data[0]; + magData.float_y = mag_data[1]; + magData.float_z = mag_data[2]; + + Serial.print("mag x = ");Serial.print(magData.x);Serial.println(" uT"); + Serial.print("mag y = ");Serial.print(magData.y);Serial.println(" uT"); + Serial.print("mag z = ");Serial.print(magData.z);Serial.println(" uT"); + + // float type data + //Serial.print("mag x = "); Serial.print(magData.float_x); Serial.println(" uT"); + //Serial.print("mag y = "); Serial.print(magData.float_y); Serial.println(" uT"); + //Serial.print("mag z = "); Serial.print(magData.float_z); Serial.println(" uT"); + + float compassDegree = getCompassDegree(magData); + Serial.print("the angle between the pointing direction and north (counterclockwise) is:"); + Serial.println(compassDegree); + Serial.println("--------------------------------"); + delay(3000); +} +float getCompassDegree(sBmm350MagData_t magData) +{ + float compass = 0.0; + compass = atan2(magData.x, magData.y); + if (compass < 0) { + compass += 2 * PI; + } + if (compass > 2 * PI) { + compass -= 2 * PI; + } + return compass * 180 / M_PI; +} +``` + +--- + +--- + +## 📎 附录 + +* MotionCal 下载地址:[https://www.pjrc.com/store/prop\_shield.html#motioncal](https://www.pjrc.com/store/prop_shield.html#motioncal) +* DFRobot BMM350 Sensor:[https://wiki.dfrobot.com.cn/_SKU_SEN0619_Gravity_BMM350_TripleAxis_Magnetometer_Sensor](https://wiki.dfrobot.com.cn/_SKU_SEN0619_Gravity_BMM350_TripleAxis_Magnetometer_Sensor) diff --git a/lib/DFRobot_BMM350/examples/calibration/getCalibrateData/getCalibrateData.ino b/lib/DFRobot_BMM350/examples/calibration/getCalibrateData/getCalibrateData.ino new file mode 100644 index 0000000..36ef582 --- /dev/null +++ b/lib/DFRobot_BMM350/examples/calibration/getCalibrateData/getCalibrateData.ino @@ -0,0 +1,92 @@ +/*! + * @file getGeomagneticData.ino + * @brief Get the calibration data + * @n "Compass Degree", the angle formed when the needle rotates counterclockwise from the current position to the true north + * @n Experimental phenomenon: serial print the geomagnetic data of x-axis, y-axis and z-axis and the compass degree + * @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) + * @license The MIT License (MIT) + * @author [GDuang](yonglei.ren@dfrobot.com) + * @version V1.0.0 + * @date 2024-05-06 + * @url https://github.com/DFRobot/DFRobot_BMM350/ + */ + +// ======================================================= +// 请先阅读项目 https://github.com/DFRobot/DFRobot_BMM350/tree/master/examples/calibration +// Please read https://github.com/DFRobot/DFRobot_BMM350/tree/master/examples/calibration +// 包含使用说明、校准步骤。 +// It contains usage instructions, calibration steps. +// ======================================================= +#include "DFRobot_BMM350.h" + +DFRobot_BMM350_I2C bmm350(&Wire, I2C_ADDRESS); +void setup() { + Serial.begin(115200); + while (!Serial) + ; + while (bmm350.begin()) { + Serial.println("bmm350 init failed, Please try again!"); + delay(1000); + } + Serial.println("bmm350 init success!"); + + /** + * Set sensor operation mode + * opMode: + * eBmm350SuspendMode // suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + * so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + * eBmm350NormalMode // normal mode Get geomagnetic data normally. + * eBmm350ForcedMode // forced mode Single measurement, the sensor restores to suspend mode when the measurement is done. + * eBmm350ForcedModeFast // To reach ODR = 200Hz is only possible by using FM_ FAST. + */ + bmm350.setOperationMode(eBmm350NormalMode); + /** + * Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) + * presetMode: + * BMM350_PRESETMODE_LOWPOWER // Low power mode, get a fraction of data and take the mean value. + * BMM350_PRESETMODE_REGULAR // Regular mode, get a number of data and take the mean value. + * BMM350_PRESETMODE_ENHANCED // Enhanced mode, get a plenty of data and take the mean value. + * BMM350_PRESETMODE_HIGHACCURACY // High accuracy mode, get a huge number of take and draw the mean value. + * rate: + * BMM350_DATA_RATE_1_5625HZ + * BMM350_DATA_RATE_3_125HZ + * BMM350_DATA_RATE_6_25HZ + * BMM350_DATA_RATE_12_5HZ (default rate) + * BMM350_DATA_RATE_25HZ + * BMM350_DATA_RATE_50HZ + * BMM350_DATA_RATE_100HZ + * BMM350_DATA_RATE_200HZ + * BMM350_DATA_RATE_400HZ + */ + bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ); + + /** + * Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required, the geomagnetic data at x, y and z will be inaccurate when disabled. + * Refer to setMeasurementXYZ() function in the .h file if you want to configure more parameters. + */ + bmm350.setMeasurementXYZ(); +} + +void loop() { + sBmm350MagData_t magData = bmm350.getGeomagneticData(); + Serial.print("Raw:"); + Serial.print(0); + Serial.print(','); + Serial.print(0); + Serial.print(','); + Serial.print(0); + Serial.print(','); + Serial.print(0); + Serial.print(','); + Serial.print(0); + Serial.print(','); + Serial.print(0); + Serial.print(','); + Serial.print(magData.x*10); + Serial.print(','); + Serial.print(magData.y*10); + Serial.print(','); + Serial.print(magData.z*10); + Serial.println(); + delay(100); +} diff --git a/lib/DFRobot_BMM350/examples/getAllState/getAllState.ino b/lib/DFRobot_BMM350/examples/getAllState/getAllState.ino new file mode 100644 index 0000000..aad0cfa --- /dev/null +++ b/lib/DFRobot_BMM350/examples/getAllState/getAllState.ino @@ -0,0 +1,95 @@ + /*! + * @file getAllState.ino + * @brief Get all the config status, self test status; the sensor turns to sleep mode from normal mode after reset + * @n Experimental phenomenon: serial print the sensor config information and the self-test information + * @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) + * @license The MIT License (MIT) + * @author [GDuang](yonglei.ren@dfrobot.com) + * @version V1.0.0 + * @date 2024-05-06 + * @url https://github.com/DFRobot/DFRobot_BMM350 + */ +#include "DFRobot_BMM350.h" + +DFRobot_BMM350_I2C bmm350(&Wire, I2C_ADDRESS); + +void setup() +{ + Serial.begin(115200); + while(!Serial); + while(bmm350.begin()){ + Serial.println("bmm350 init failed, Please try again!"); + delay(1000); + } Serial.println("bmm350 init success!"); + + /** + * Sensor self test, the returned character string indicates the test result. + */ + Serial.println(bmm350.selfTest()); + + /** + * Set sensor operation mode + * opMode: + * eBmm350SuspendMode // suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + * so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + * eBmm350NormalMode // normal mode Get geomagnetic data normally. + * eBmm350ForcedMode // forced mode Single measurement, the sensor restores to suspend mode when the measurement is done. + * eBmm350ForcedModeFast // To reach ODR = 200Hz is only possible by using FM_ FAST. + */ + bmm350.setOperationMode(eBmm350NormalMode); + /** + * Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) + * presetMode: + * BMM350_PRESETMODE_LOWPOWER // Low power mode, get a fraction of data and take the mean value. + * BMM350_PRESETMODE_REGULAR // Regular mode, get a number of data and take the mean value. + * BMM350_PRESETMODE_ENHANCED // Enhanced mode, get a plenty of data and take the mean value. + * BMM350_PRESETMODE_HIGHACCURACY // High accuracy mode, get a huge number of take and draw the mean value. + * rate: + * BMM350_DATA_RATE_1_5625HZ + * BMM350_DATA_RATE_3_125HZ + * BMM350_DATA_RATE_6_25HZ + * BMM350_DATA_RATE_12_5HZ (default rate) + * BMM350_DATA_RATE_25HZ + * BMM350_DATA_RATE_50HZ + * BMM350_DATA_RATE_100HZ + * BMM350_DATA_RATE_200HZ + * BMM350_DATA_RATE_400HZ + */ + bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ); + + /** + * Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required, the geomagnetic data at x, y and z will be inaccurate when disabled. + * Refer to setMeasurementXYZ() function in the .h file if you want to configure more parameters. + */ + bmm350.setMeasurementXYZ(); + + /** + * Get the config data rate unit: HZ + */ + float rate = bmm350.getRate(); + Serial.print("rate is "); Serial.print(rate); Serial.println(" HZ"); + + /** + * Get the measurement status at x-axis, y-axis and z-axis, return the measurement status as character string + */ + Serial.println(bmm350.getMeasurementStateXYZ()); + + /** + * Get the sensor operation mode, return the sensor operation status as character string + */ + Serial.println(bmm350.getOperationMode()); + + /** + * After the software is reset, it enters the suspended mode. + */ + bmm350.softReset(); +} + +void loop() +{ + /** + * Get the sensor operation mode, return the sensor operation status as character string + */ + Serial.println(bmm350.getOperationMode()); + delay(3000); +} diff --git a/lib/DFRobot_BMM350/examples/getGeomagneticData/getGeomagneticData.ino b/lib/DFRobot_BMM350/examples/getGeomagneticData/getGeomagneticData.ino new file mode 100644 index 0000000..5cb3298 --- /dev/null +++ b/lib/DFRobot_BMM350/examples/getGeomagneticData/getGeomagneticData.ino @@ -0,0 +1,84 @@ + /*! + * @file getGeomagneticData.ino + * @brief Get the geomagnetic data at 3 axis (x, y, z), get the compass degree + * @n "Compass Degree", the angle formed when the needle rotates counterclockwise from the current position to the true north + * @n Experimental phenomenon: serial print the geomagnetic data of x-axis, y-axis and z-axis and the compass degree + * @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) + * @license The MIT License (MIT) + * @author [GDuang](yonglei.ren@dfrobot.com) + * @version V1.0.0 + * @date 2024-05-06 + * @url https://github.com/DFRobot/DFRobot_BMM350 + */ + +#include "DFRobot_BMM350.h" + + +DFRobot_BMM350_I2C bmm350(&Wire, I2C_ADDRESS); + +void setup() +{ + Serial.begin(115200); + while(!Serial); + while(bmm350.begin()){ + Serial.println("bmm350 init failed, Please try again!"); + delay(1000); + } Serial.println("bmm350 init success!"); + + /** + * Set sensor operation mode + * opMode: + * eBmm350SuspendMode // suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + * so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + * eBmm350NormalMode // normal mode Get geomagnetic data normally. + * eBmm350ForcedMode // forced mode Single measurement, the sensor restores to suspend mode when the measurement is done. + * eBmm350ForcedModeFast // To reach ODR = 200Hz is only possible by using FM_ FAST. + */ + bmm350.setOperationMode(eBmm350NormalMode); + + /** + * Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) + * presetMode: + * BMM350_PRESETMODE_LOWPOWER // Low power mode, get a fraction of data and take the mean value. + * BMM350_PRESETMODE_REGULAR // Regular mode, get a number of data and take the mean value. + * BMM350_PRESETMODE_ENHANCED // Enhanced mode, get a plenty of data and take the mean value. + * BMM350_PRESETMODE_HIGHACCURACY // High accuracy mode, get a huge number of take and draw the mean value. + * rate: + * BMM350_DATA_RATE_1_5625HZ + * BMM350_DATA_RATE_3_125HZ + * BMM350_DATA_RATE_6_25HZ + * BMM350_DATA_RATE_12_5HZ (default rate) + * BMM350_DATA_RATE_25HZ + * BMM350_DATA_RATE_50HZ + * BMM350_DATA_RATE_100HZ + * BMM350_DATA_RATE_200HZ + * BMM350_DATA_RATE_400HZ + */ + bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ); + + + /** + * Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required, the geomagnetic data at x, y and z will be inaccurate when disabled. + * Refer to setMeasurementXYZ() function in the .h file if you want to configure more parameters. + */ + bmm350.setMeasurementXYZ(); +} + +void loop() +{ + sBmm350MagData_t magData = bmm350.getGeomagneticData(); + Serial.print("mag x = "); Serial.print(magData.x); Serial.println(" uT"); + Serial.print("mag y = "); Serial.print(magData.y); Serial.println(" uT"); + Serial.print("mag z = "); Serial.print(magData.z); Serial.println(" uT"); + + // float type data + //Serial.print("mag x = "); Serial.print(magData.float_x); Serial.println(" uT"); + //Serial.print("mag y = "); Serial.print(magData.float_y); Serial.println(" uT"); + //Serial.print("mag z = "); Serial.print(magData.float_z); Serial.println(" uT"); + + float compassDegree = bmm350.getCompassDegree(); + Serial.print("the angle between the pointing direction and north (counterclockwise) is:"); + Serial.println(compassDegree); + Serial.println("--------------------------------"); + delay(3000); +} diff --git a/lib/DFRobot_BMM350/examples/magDrdyInterrupt/magDrdyInterrupt.ino b/lib/DFRobot_BMM350/examples/magDrdyInterrupt/magDrdyInterrupt.ino new file mode 100644 index 0000000..56d4331 --- /dev/null +++ b/lib/DFRobot_BMM350/examples/magDrdyInterrupt/magDrdyInterrupt.ino @@ -0,0 +1,186 @@ + /*! + * @file magDrdyInterrupt.ino + * @brief Data ready interrupt, DRDY interrupt will be triggered when the geomagnetic data is ready (the software and hardware can determine whether the interrupt occur) + * @n Experimental phenomenon: serial print the geomagnetic data at x-axis, y-axis and z-axis, unit (uT) + * @n Experimental phenomenon: the main controller interrupt will be triggered by level change caused by DRDY pin interrupt, then the geomagnetic data can be obtained. + * @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) + * @license The MIT License (MIT) + * @author [GDuang](yonglei.ren@dfrobot.com) + * @version V1.0.0 + * @date 2024-05-06 + * @url https://github.com/DFRobot/DFRobot_BMM350 + */ +#include "DFRobot_BMM350.h" + +DFRobot_BMM350_I2C bmm350(&Wire, I2C_ADDRESS); + +volatile uint8_t interruptFlag = 0; +void myInterrupt(void) +{ + interruptFlag = 1; // Interrupt flag + #if defined(ESP32) || defined(ESP8266) || defined(ARDUINO_SAM_ZERO) + detachInterrupt(13); // Detach interrupt + #else + detachInterrupt(0); // Detach interrupt + #endif +} + +void setup() +{ + Serial.begin(115200); + while(!Serial); + while(bmm350.begin()){ + Serial.println("bmm350 init failed, Please try again!"); + delay(1000); + } Serial.println("bmm350 init success!"); + + /** + * Set sensor operation mode + * opMode: + * eBmm350SuspendMode // suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + * so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + * eBmm350NormalMode // normal mode Get geomagnetic data normally. + * eBmm350ForcedMode // forced mode Single measurement, the sensor restores to suspend mode when the measurement is done. + * eBmm350ForcedModeFast // To reach ODR = 200Hz is only possible by using FM_ FAST. + */ + bmm350.setOperationMode(eBmm350NormalMode); + + /** + * Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) + * presetMode: + * BMM350_PRESETMODE_LOWPOWER // Low power mode, get a fraction of data and take the mean value. + * BMM350_PRESETMODE_REGULAR // Regular mode, get a number of data and take the mean value. + * BMM350_PRESETMODE_ENHANCED // Enhanced mode, get a plenty of data and take the mean value. + * BMM350_PRESETMODE_HIGHACCURACY // High accuracy mode, get a huge number of take and draw the mean value. + * rate: + * BMM350_DATA_RATE_1_5625HZ + * BMM350_DATA_RATE_3_125HZ + * BMM350_DATA_RATE_6_25HZ + * BMM350_DATA_RATE_12_5HZ (default rate) + * BMM350_DATA_RATE_25HZ + * BMM350_DATA_RATE_50HZ + * BMM350_DATA_RATE_100HZ + * BMM350_DATA_RATE_200HZ + * BMM350_DATA_RATE_400HZ + */ + bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ); + + + /** + * Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required, the geomagnetic data at x, y and z will be inaccurate when disabled. + * Refer to setMeasurementXYZ() function in the .h file if you want to configure more parameters. + */ + bmm350.setMeasurementXYZ(); + + /** + * Enable or disable data ready interrupt pin, + * After enabling, the DRDY pin level will change when there's data coming. + * After disabling, the DRDY pin level will not change when there's data coming. + * High polarity: active on high level, the default is low level, which turns to high level when the interrupt is triggered. + * Low polarity: active on low level, the default is high level, which turns to low level when the interrupt is triggered. + * modes: + * BMM350_ENABLE_INTERRUPT // Enable DRDY + * BMM350_DISABLE_INTERRUPT // Disable DRDY + * polatily: + * BMM350_ACTIVE_HIGH // High polarity + * BMM350_ACTIVE_LOW // Low polarity + */ + bmm350.setDataReadyPin(BMM350_ENABLE_INTERRUPT, BMM350_ACTIVE_LOW); + + +#if defined(ESP32) || defined(ESP8266) + /** + Select according to the set DADY pin polarity + INPUT_PULLUP // Low polarity, set pin 13 to pull-up input + INPUT_PULLDOWN // High polarity, set pin 13 to pull-down input + interput io + All pins can be used. Pin 13 is recommended + */ + pinMode(/*Pin */13 ,INPUT_PULLUP); + attachInterrupt(/*interput io*/13, myInterrupt, ONLOW); +#elif defined(ARDUINO_SAM_ZERO) + pinMode(/*Pin */13 ,INPUT_PULLUP); + attachInterrupt(/*interput io*/13, myInterrupt, LOW); +#else + /** The Correspondence Table of AVR Series Arduino Interrupt Pins And Terminal Numbers + * --------------------------------------------------------------------------------------- + * | | Pin | 2 | 3 | | + * | Uno, Nano, Mini, other 328-based |--------------------------------------------| + * | | Interrupt No | 0 | 1 | | + * |-------------------------------------------------------------------------------------| + * | | Pin | 2 | 3 | 21 | 20 | 19 | 18 | + * | Mega2560 |--------------------------------------------| + * | | Interrupt No | 0 | 1 | 2 | 3 | 4 | 5 | + * |-------------------------------------------------------------------------------------| + * | | Pin | 3 | 2 | 0 | 1 | 7 | | + * | Leonardo, other 32u4-based |--------------------------------------------| + * | | Interrupt No | 0 | 1 | 2 | 3 | 4 | | + * |-------------------------------------------------------------------------------------- + */ + + /** The Correspondence Table of micro:bit Interrupt Pins And Terminal Numbers + * --------------------------------------------------------------------------------------------------------------------------------------------- + * | micro:bit | DigitalPin |P0-P20 can be used as an external interrupt | + * | (When using as an external interrupt, |---------------------------------------------------------------------------------------------| + * |no need to set it to input mode with pinMode)|Interrupt No|Interrupt number is a pin digital value, such as P0 interrupt number 0, P1 is 1 | + * |-------------------------------------------------------------------------------------------------------------------------------------------| + */ + /** + Select according to the set DADY pin polarity + INPUT_PULLUP // Low polarity, set pin 2 to pull-up input + */ + pinMode(/*Pin */2 ,INPUT_PULLUP); + + /** + Set the pin to interrupt mode + // Open the external interrupt 0, connect INT1/2 to the digital pin of the main control: + function + callback function + state + LOW // When the pin is at low level, the interrupt occur, enter interrupt function + */ + attachInterrupt(/*Interrupt No*/0, /*function*/myInterrupt ,/*state*/LOW ); +#endif +} + +void loop() +{ + /** + * Get data ready status, determine whether the data is ready (get the data ready status through software) + * status: + * true Data ready + * false Data is not ready yet + */ + /* + if(bmm350.getDataReadyState()){ + sBmm350MagData_t magData = bmm350.getGeomagneticData(); + Serial.print("mag x = "); Serial.print(magData.x); Serial.println(" uT"); + Serial.print("mag y = "); Serial.print(magData.y); Serial.println(" uT"); + Serial.print("mag z = "); Serial.print(magData.z); Serial.println(" uT"); + Serial.println(); + } + */ + + /** + When the interrupt occur in DRDY IO, get the geomagnetic data (get the data ready status through hardware) + Enable interrupt again + */ + if(interruptFlag == 1){ + Serial.println("Interrupt triggering!"); + sBmm350MagData_t magData = bmm350.getGeomagneticData(); + Serial.print("mag x = "); Serial.print(magData.x); Serial.println(" uT"); + Serial.print("mag y = "); Serial.print(magData.y); Serial.println(" uT"); + Serial.print("mag z = "); Serial.print(magData.z); Serial.println(" uT"); + Serial.println(); + interruptFlag = 0; + #if defined(ESP32) || defined(ESP8266) + attachInterrupt(13, myInterrupt, ONLOW); + #elif defined(ARDUINO_SAM_ZERO) + attachInterrupt(13, myInterrupt, LOW); + #else + attachInterrupt(0, myInterrupt, LOW); + #endif + } + + delay(1000); +} diff --git a/lib/DFRobot_BMM350/examples/thresholdInterrupt/thresholdInterrupt.ino b/lib/DFRobot_BMM350/examples/thresholdInterrupt/thresholdInterrupt.ino new file mode 100644 index 0000000..a75813f --- /dev/null +++ b/lib/DFRobot_BMM350/examples/thresholdInterrupt/thresholdInterrupt.ino @@ -0,0 +1,194 @@ + /*! + * @file thresholdInterrupt.ino + * @brief Set the interrupt to be triggered when beyond/below threshold, when the interrupt at a axis occur, the relevant data will be printed in the serial port. + * @n Experimental phenomenon: when the geomagnetic data at 3 axis (x, y, z) beyond/below threshold, serial print the geomagnetic data, unit (uT) + * @n Experimental phenomenon: the main controller interrupt will be triggered by level change caused by INT pin interrupt, then the geomagnetic data can be obtained + * @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) + * @license The MIT License (MIT) + * @author [GDuang](yonglei.ren@dfrobot.com) + * @version V1.0.0 + * @date 2024-05-06 + * @url https://github.com/DFRobot/DFRobot_BMM350 + */ +#include "DFRobot_BMM350.h" + +DFRobot_BMM350_I2C bmm350(&Wire, I2C_ADDRESS); + +volatile uint8_t interruptFlag = 0; +void myInterrupt(void) +{ + interruptFlag = 1; // Interrupt flag + #if defined(ESP32) || defined(ESP8266) || defined(ARDUINO_SAM_ZERO) + detachInterrupt(13); // Detach interrupt + #else + detachInterrupt(0); // Detach interrupt + #endif +} + +void setup() +{ + Serial.begin(115200); + while(!Serial); + delay(1000); + while(bmm350.begin()){ + Serial.println("bmm350 init failed, Please try again!"); + delay(1000); + } Serial.println("bmm350 init success!"); + + /** + * Set sensor operation mode + * opMode: + * eBmm350SuspendMode // suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + * so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + * eBmm350NormalMode // normal mode Get geomagnetic data normally. + * eBmm350ForcedMode // forced mode Single measurement, the sensor restores to suspend mode when the measurement is done. + * eBmm350ForcedModeFast // To reach ODR = 200Hz is only possible by using FM_ FAST. + */ + bmm350.setOperationMode(eBmm350NormalMode); + /** + * Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) + * presetMode: + * BMM350_PRESETMODE_LOWPOWER // Low power mode, get a fraction of data and take the mean value. + * BMM350_PRESETMODE_REGULAR // Regular mode, get a number of data and take the mean value. + * BMM350_PRESETMODE_ENHANCED // Enhanced mode, get a plenty of data and take the mean value. + * BMM350_PRESETMODE_HIGHACCURACY // High accuracy mode, get a huge number of take and draw the mean value. + * rate: + * BMM350_DATA_RATE_1_5625HZ + * BMM350_DATA_RATE_3_125HZ + * BMM350_DATA_RATE_6_25HZ + * BMM350_DATA_RATE_12_5HZ (default rate) + * BMM350_DATA_RATE_25HZ + * BMM350_DATA_RATE_50HZ + * BMM350_DATA_RATE_100HZ + * BMM350_DATA_RATE_200HZ + * BMM350_DATA_RATE_400HZ + */ + bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ); + + + /** + * Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required, the geomagnetic data at x, y and z will be inaccurate when disabled. + * Refer to setMeasurementXYZ() function in the .h file if you want to configure more parameters. + */ + bmm350.setMeasurementXYZ(); + + /*! + * Set threshold interrupt, an interrupt is triggered when the geomagnetic value of a channel is beyond/below the threshold + * High polarity: active on high level, the default is low level, which turns to high level when the interrupt is triggered. + * Low polarity: active on low level, the default is high level, which turns to low level when the interrupt is triggered. + * modes: + * LOW_THRESHOLD_INTERRUPT // Low threshold interrupt mode, interrupt is triggered when below the threshold + * HIGH_THRESHOLD_INTERRUPT // High threshold interrupt mode, interrupt is triggered when beyond the threshold + * threshold //Threshold range, default to expand 16 times, for example: under low threshold mode, if the threshold is set to be 1, actually the geomagnetic data below 16 will trigger an interrupt + * polarity: + * BMM350_ACTIVE_HIGH // High polarity + * BMM350_ACTIVE_LOW // Low polarity + * Refer to setThresholdInterrput() function in the .h file if you want to use more parameters. + */ + bmm350.setThresholdInterrupt(LOW_THRESHOLD_INTERRUPT, 0, BMM350_ACTIVE_LOW); + +#if defined(ESP32) || defined(ESP8266) + /** + Select according to the set DADY pin polarity + INPUT_PULLUP // Low polarity, set pin 13 to pull-up input + INPUT_PULLDOWN // High polarity, set pin 13 to pull-down input + interput io + All pins can be used. Pin 13 is recommended + */ + pinMode(/*Pin */13 ,INPUT_PULLUP); + attachInterrupt(/*interput io*/13, myInterrupt, ONLOW); +#elif defined(ARDUINO_SAM_ZERO) + pinMode(/*Pin */13 ,INPUT_PULLUP); + attachInterrupt(/*interput io*/13, myInterrupt, LOW); +#else + /** The Correspondence Table of AVR Series Arduino Interrupt Pins And Terminal Numbers + * --------------------------------------------------------------------------------------- + * | | Pin | 2 | 3 | | + * | Uno, Nano, Mini, other 328-based |--------------------------------------------| + * | | Interrupt No | 0 | 1 | | + * |-------------------------------------------------------------------------------------| + * | | Pin | 2 | 3 | 21 | 20 | 19 | 18 | + * | Mega2560 |--------------------------------------------| + * | | Interrupt No | 0 | 1 | 2 | 3 | 4 | 5 | + * |-------------------------------------------------------------------------------------| + * | | Pin | 3 | 2 | 0 | 1 | 7 | | + * | Leonardo, other 32u4-based |--------------------------------------------| + * | | Interrupt No | 0 | 1 | 2 | 3 | 4 | | + * |-------------------------------------------------------------------------------------- + */ + + /** The Correspondence Table of micro:bit Interrupt Pins And Terminal Numbers + * --------------------------------------------------------------------------------------------------------------------------------------------- + * | micro:bit | DigitalPin |P0-P20 can be used as an external interrupt | + * | (When using as an external interrupt, |---------------------------------------------------------------------------------------------| + * |no need to set it to input mode with pinMode)|Interrupt No|Interrupt number is a pin digital value, such as P0 interrupt number 0, P1 is 1 | + * |-------------------------------------------------------------------------------------------------------------------------------------------| + */ + /** + Select according to the set DADY pin polarity + INPUT_PULLUP // Low polarity, set pin 2 to pull-up input + */ + pinMode(/*Pin */2 ,INPUT_PULLUP); + + /** + Set the pin to interrupt mode + // Open the external interrupt 0, connect INT to the digital pin of the main control: + function + callback function + state + LOW // When the pin is at low level, the interrupt occur, enter interrupt function + */ + attachInterrupt(/*Interrupt No*/0, /*function*/myInterrupt ,/*state*/LOW ); +#endif + +} + +void loop() +{ + /** + * Get the data that threshold interrupt occured and interrupt status (get the data ready status through software) + * Returns the structure for storing geomagnetic data, the structure stores the data of 3 axis and interrupt status, + * No interrupt triggered when the data at x-axis, y-axis and z-axis is NO_DATA + * Refer to .h file if you want to check interrupt status. + */ + /* + sBmm350ThresholdData_t thresholdData = bmm350.getThresholdData(); + if(thresholdData.mag_x != NO_DATA){ + Serial.print("mag x = "); Serial.print(thresholdData.mag_x); Serial.println(" uT"); + } + if(thresholdData.mag_y != NO_DATA){ + Serial.print("mag y = "); Serial.print(thresholdData.mag_y); Serial.println(" uT"); + } + if(thresholdData.mag_z != NO_DATA){ + Serial.print("mag z = "); Serial.print(thresholdData.mag_z); Serial.println(" uT"); + } + Serial.println(); + */ + + /** + When the interrupt occur in INT IO, get the threshold interrupt data (get the threshold interrupt status through hardware) + */ + if(interruptFlag == 1){ + sBmm350ThresholdData_t thresholdData = bmm350.getThresholdData(); + if(thresholdData.mag_x != NO_DATA){ + Serial.print("mag x = "); Serial.print(thresholdData.mag_x); Serial.println(" uT"); + } + if(thresholdData.mag_y != NO_DATA){ + Serial.print("mag y = "); Serial.print(thresholdData.mag_y); Serial.println(" uT"); + } + if(thresholdData.mag_z != NO_DATA){ + Serial.print("mag z = "); Serial.print(thresholdData.mag_z); Serial.println(" uT"); + } + Serial.println(); + interruptFlag = 0; + #if defined(ESP32) || defined(ESP8266) + attachInterrupt(13, myInterrupt, ONLOW); + #elif defined(ARDUINO_SAM_ZERO) + attachInterrupt(13, myInterrupt, LOW); + #else + attachInterrupt(0, myInterrupt, LOW); + #endif + + } + delay(1000); +} diff --git a/lib/DFRobot_BMM350/keywords.txt b/lib/DFRobot_BMM350/keywords.txt new file mode 100644 index 0000000..0432f89 --- /dev/null +++ b/lib/DFRobot_BMM350/keywords.txt @@ -0,0 +1,76 @@ +####################################### +# Syntax Coloring DFRobot_bmm350 +####################################### + +####################################### +# Datatypes (KEYWORD1) +####################################### + +begin KEYWORD2 +softReset KEYWORD2 +selfTest KEYWORD2 +setOperationMode KEYWORD2 +getOperationMode KEYWORD2 +setRate KEYWORD2 +getRate KEYWORD2 +setPresetMode KEYWORD2 +getGeomagneticData KEYWORD2 +getCompassDegree KEYWORD2 +setDataReadyPin KEYWORD2 +getDataReadyState KEYWORD2 +setMeasurementXYZ KEYWORD2 +getMeasurementStateXYZ KEYWORD2 +setThresholdInterrupt KEYWORD2 +getThresholdData KEYWORD2 + +####################################### +# Constants (LITERAL1) +####################################### + +DFRobot_bmm350 KEYWORD1 +DFRobot_bmm350_I2C KEYWORD1 +DFRobot_bmm350_I3C KEYWORD1 + +####################################### +# Methods and Functions (KEYWORD2) +####################################### + +BMM350_OK LITERAL1 + +BMM350_SELF_TEST_ADVANCED LITERAL1 +BMM350_SELF_TEST_NORMAL LITERAL1 + +eBmm350SuspendMode LITERAL1 +eBmm350NormalMode LITERAL1 +eBmm350ForcedMode LITERAL1 +eBmm350ForcedModeFast LITERAL1 + +BMM350_PRESETMODE_LOWPOWER LITERAL1 +BMM350_PRESETMODE_REGULAR LITERAL1 +BMM350_PRESETMODE_HIGHACCURACY LITERAL1 +BMM350_PRESETMODE_ENHANCED LITERAL1 + +BMM350_ODR_1_5625HZ LITERAL1 +BMM350_ODR_3_125HZ LITERAL1 +BMM350_ODR_6_25HZ LITERAL1 +BMM350_ODR_12_5HZ LITERAL1 +BMM350_ODR_25HZ LITERAL1 +BMM350_ODR_50HZ LITERAL1 +BMM350_ODR_100HZ LITERAL1 +BMM350_ODR_200HZ LITERAL1 +BMM350_ODR_400HZ LITERAL1 + +POLARITY_HIGH LITERAL1 +POLARITY_LOW LITERAL1 + +INTERRUPT_X_ENABLE LITERAL1 +INTERRUPT_Y_ENABLE LITERAL1 +INTERRUPT_Z_ENABLE LITERAL1 +INTERRUPT_X_DISABLE LITERAL1 +INTERRUPT_Y_DISABLE LITERAL1 +INTERRUPT_Z_DISABLE LITERAL1 + +ENABLE_INTERRUPT_PIN LITERAL1 +DISABLE_INTERRUPT_PIN LITERAL1 +LOW_THRESHOLD_INTERRUPT LITERAL1 +HIGH_THRESHOLD_INTERRUPT LITERAL1 diff --git a/lib/DFRobot_BMM350/library.properties b/lib/DFRobot_BMM350/library.properties new file mode 100644 index 0000000..23b406c --- /dev/null +++ b/lib/DFRobot_BMM350/library.properties @@ -0,0 +1,9 @@ +name=DFRobot_BMM350 +version=1.0.0 +author=DFRobot +maintainer=[GDuang](yonglei.ren@dfrobot.com) +sentence=DFRobot Standard 3-axis geomagnetic sensor library(SKU:SEN0419). +paragraph=The BMM350 is a low-power and low noise 3-axis digital geomagnetic sensor that perfectly matches the requirements of compass applications. +category=Sensors +url=https://github.com/DFRobot/DFRobot_BMM350 +architectures=* diff --git a/lib/DFRobot_BMM350/python/raspberrypi/DFRobot_bmm350.py b/lib/DFRobot_BMM350/python/raspberrypi/DFRobot_bmm350.py new file mode 100644 index 0000000..b0d8596 --- /dev/null +++ b/lib/DFRobot_BMM350/python/raspberrypi/DFRobot_bmm350.py @@ -0,0 +1,1595 @@ +# -*- coding: utf-8 -* +''' + @file DFRobot_bmm350.py + @note DFRobot_bmm350 Class infrastructure, implementation of underlying methods + @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) + @license The MIT License (MIT) + @author [GDuang](yonglei.ren@dfrobot.com) + @version V1.0.0 + @date 2024-05-06 + @url https://github.com/DFRobot/DFRobot_BMM350 +''' +import serial +import time +import os +import math + + +# Chip id of BMM350 +BMM350_CHIP_ID = 0x33 + +# Variant ID of BMM350 +BMM350_MIN_VAR = 0x10 + +# Sensor interface success code +BMM350_INTF_RET_SUCCESS = 0 + +# API success code +BMM350_OK = 0 + +# API error codes +BMM350_E_NULL_PTR = -1 +BMM350_E_COM_FAIL = -2 +BMM350_E_DEV_NOT_FOUND = -3 +BMM350_E_INVALID_CONFIG = -4 +BMM350_E_BAD_PAD_DRIVE = -5 +BMM350_E_RESET_UNFINISHED = -6 +BMM350_E_INVALID_INPUT = -7 +BMM350_E_SELF_TEST_INVALID_AXIS = -8 +BMM350_E_OTP_BOOT = -9 +BMM350_E_OTP_PAGE_RD = -10 +BMM350_E_OTP_PAGE_PRG = -11 +BMM350_E_OTP_SIGN = -12 +BMM350_E_OTP_INV_CMD = -13 +BMM350_E_OTP_UNDEFINED = -14 +BMM350_E_ALL_AXIS_DISABLED = -15 +BMM350_E_PMU_CMD_VALUE = -16 + +BMM350_NO_ERROR = 0 + +# Sensor delay time settings in microseconds +BMM350_SOFT_RESET_DELAY = 24000/1000000 +BMM350_MAGNETIC_RESET_DELAY = 40000/1000000 +BMM350_START_UP_TIME_FROM_POR = 3000/1000000 +BMM350_GOTO_SUSPEND_DELAY = 6000/1000000 +BMM350_SUSPEND_TO_NORMAL_DELAY = 38000/1000000 +BMM350_SUS_TO_FORCEDMODE_NO_AVG_DELAY = 15000/1000000 +BMM350_SUS_TO_FORCEDMODE_AVG_2_DELAY = 17000/1000000 +BMM350_SUS_TO_FORCEDMODE_AVG_4_DELAY = 20000/1000000 +BMM350_SUS_TO_FORCEDMODE_AVG_8_DELAY = 28000/1000000 +BMM350_SUS_TO_FORCEDMODE_FAST_NO_AVG_DELAY = 4000/1000000 +BMM350_SUS_TO_FORCEDMODE_FAST_AVG_2_DELAY = 5000/1000000 +BMM350_SUS_TO_FORCEDMODE_FAST_AVG_4_DELAY = 9000/1000000 +BMM350_SUS_TO_FORCEDMODE_FAST_AVG_8_DELAY = 16000/1000000 +BMM350_UPD_OAE_DELAY = 1000/1000000 +BMM350_BR_DELAY = 14000/1000000 +BMM350_FGR_DELAY = 18000/1000000 + +# Length macros +BMM350_OTP_DATA_LENGTH = 32 +BMM350_READ_BUFFER_LENGTH = 127 +BMM350_MAG_TEMP_DATA_LEN = 12 + +# Averaging macros +BMM350_AVG_NO_AVG = 0x0 +BMM350_AVG_2 = 0x1 +BMM350_AVG_4 = 0x2 +BMM350_AVG_8 = 0x3 + +# ODR +BMM350_ODR_400HZ = 0x2 +BMM350_ODR_200HZ = 0x3 +BMM350_ODR_100HZ = 0x4 +BMM350_ODR_50HZ = 0x5 +BMM350_ODR_25HZ = 0x6 +BMM350_ODR_12_5HZ = 0x7 # default rate +BMM350_ODR_6_25HZ = 0x8 +BMM350_ODR_3_125HZ = 0x9 +BMM350_ODR_1_5625HZ = 0xA + +# Power modes +BMM350_PMU_CMD_SUS = 0x00 +BMM350_PMU_CMD_NM = 0x01 +BMM350_PMU_CMD_UPD_OAE = 0x02 +BMM350_PMU_CMD_FM = 0x03 +BMM350_PMU_CMD_FM_FAST = 0x04 +BMM350_PMU_CMD_FGR = 0x05 +BMM350_PMU_CMD_FGR_FAST = 0x06 +BMM350_PMU_CMD_BR = 0x07 +BMM350_PMU_CMD_BR_FAST = 0x08 +BMM350_PMU_CMD_NM_TC = 0x09 + +BMM350_PMU_STATUS_0 = 0x0 + +BMM350_DISABLE = 0x0 +BMM350_ENABLE = 0x1 +BMM350_MAP_TO_PIN = BMM350_ENABLE + +BMM350_CMD_NOP = 0x0 +BMM350_CMD_SOFTRESET = 0xB6 + +BMM350_TARGET_PAGE_PAGE0 = 0x0 +BMM350_TARGET_PAGE_PAGE1 = 0x1 + +BMM350_INT_MODE_LATCHED = 0x1 +BMM350_INT_MODE_PULSED = 0x0 + +BMM350_INT_POL_ACTIVE_HIGH = 0x1 +BMM350_INT_POL_ACTIVE_LOW = 0x0 + +BMM350_INT_OD_PUSHPULL = 0x1 +BMM350_INT_OD_OPENDRAIN = 0x0 + +BMM350_INT_OUTPUT_EN_OFF = 0x0 +BMM350_INT_OUTPUT_EN_ON = 0x1 + +BMM350_INT_DRDY_EN = 0x1 +BMM350_INT_DRDY_DIS = 0x0 + +BMM350_MR_MR1K8 = 0x0 +BMM350_MR_MR2K1 = 0x1 +BMM350_MR_MR1K5 = 0x2 +BMM350_MR_MR0K6 = 0x3 + +BMM350_SEL_DTB1X_PAD_PAD_INT = 0x0 +BMM350_SEL_DTB1X_PAD_PAD_BYP = 0x1 + +BMM350_TMR_TST_HIZ_VTMR_VTMR_ON = 0x0 +BMM350_TMR_TST_HIZ_VTMR_VTMR_HIZ = 0x1 + +BMM350_LSB_MASK = 0x00FF +BMM350_MSB_MASK = 0xFF00 + +# Pad drive strength +BMM350_PAD_DRIVE_WEAKEST = 0 +BMM350_PAD_DRIVE_STRONGEST = 7 + +# I2C Register Addresses + +# Register to set I2C address to LOW +BMM350_I2C_ADSEL_SET_LOW = 0x14 + +# Register to set I2C address to HIGH +BMM350_I2C_ADSEL_SET_HIGH = 0x15 + +BMM350_DUMMY_BYTES = 2 + +# Register Addresses + +BMM350_REG_CHIP_ID = 0x00 +BMM350_REG_REV_ID = 0x01 +BMM350_REG_ERR_REG = 0x02 +BMM350_REG_PAD_CTRL = 0x03 +BMM350_REG_PMU_CMD_AGGR_SET = 0x04 +BMM350_REG_PMU_CMD_AXIS_EN = 0x05 +BMM350_REG_PMU_CMD = 0x06 +BMM350_REG_PMU_CMD_STATUS_0 = 0x07 +BMM350_REG_PMU_CMD_STATUS_1 = 0x08 +BMM350_REG_I3C_ERR = 0x09 +BMM350_REG_I2C_WDT_SET = 0x0A +BMM350_REG_TRSDCR_REV_ID = 0x0D +BMM350_REG_TC_SYNC_TU = 0x21 +BMM350_REG_TC_SYNC_ODR = 0x22 +BMM350_REG_TC_SYNC_TPH_1 = 0x23 +BMM350_REG_TC_SYNC_TPH_2 = 0x24 +BMM350_REG_TC_SYNC_DT = 0x25 +BMM350_REG_TC_SYNC_ST_0 = 0x26 +BMM350_REG_TC_SYNC_ST_1 = 0x27 +BMM350_REG_TC_SYNC_ST_2 = 0x28 +BMM350_REG_TC_SYNC_STATUS = 0x29 +BMM350_REG_INT_CTRL = 0x2E +BMM350_REG_INT_CTRL_IBI = 0x2F +BMM350_REG_INT_STATUS = 0x30 +BMM350_REG_MAG_X_XLSB = 0x31 +BMM350_REG_MAG_X_LSB = 0x32 +BMM350_REG_MAG_X_MSB = 0x33 +BMM350_REG_MAG_Y_XLSB = 0x34 +BMM350_REG_MAG_Y_LSB = 0x35 +BMM350_REG_MAG_Y_MSB = 0x36 +BMM350_REG_MAG_Z_XLSB = 0x37 +BMM350_REG_MAG_Z_LSB = 0x38 +BMM350_REG_MAG_Z_MSB = 0x39 +BMM350_REG_TEMP_XLSB = 0x3A +BMM350_REG_TEMP_LSB = 0x3B +BMM350_REG_TEMP_MSB = 0x3C +BMM350_REG_SENSORTIME_XLSB = 0x3D +BMM350_REG_SENSORTIME_LSB = 0x3E +BMM350_REG_SENSORTIME_MSB = 0x3F +BMM350_REG_OTP_CMD_REG = 0x50 +BMM350_REG_OTP_DATA_MSB_REG = 0x52 +BMM350_REG_OTP_DATA_LSB_REG = 0x53 +BMM350_REG_OTP_STATUS_REG = 0x55 +BMM350_REG_TMR_SELFTEST_USER = 0x60 +BMM350_REG_CTRL_USER = 0x61 +BMM350_REG_CMD = 0x7E + +# Macros for OVWR +BMM350_REG_OVWR_VALUE_ANA_0 = 0x3A +BMM350_REG_OVWR_EN_ANA_0 = 0x3B + +# Macros for bit masking + +BMM350_CHIP_ID_OTP_MSK = 0xf +BMM350_CHIP_ID_OTP_POS = 0x0 +BMM350_CHIP_ID_FIXED_MSK = 0xf0 +BMM350_CHIP_ID_FIXED_POS = 0x4 +BMM350_REV_ID_MAJOR_MSK = 0xf0 +BMM350_REV_ID_MAJOR_POS = 0x4 +BMM350_REV_ID_MINOR_MSK = 0xf +BMM350_REV_ID_MINOR_POS = 0x0 +BMM350_PMU_CMD_ERROR_MSK = 0x1 +BMM350_PMU_CMD_ERROR_POS = 0x0 +BMM350_BOOT_UP_ERROR_MSK = 0x2 +BMM350_BOOT_UP_ERROR_POS = 0x1 +BMM350_DRV_MSK = 0x7 +BMM350_DRV_POS = 0x0 +BMM350_AVG_MSK = 0x30 +BMM350_AVG_POS = 0x4 +BMM350_ODR_MSK = 0xf +BMM350_ODR_POS = 0x0 +BMM350_PMU_CMD_MSK = 0xf +BMM350_PMU_CMD_POS = 0x0 +BMM350_EN_X_MSK = 0x01 +BMM350_EN_X_POS = 0x0 +BMM350_EN_Y_MSK = 0x02 +BMM350_EN_Y_POS = 0x1 +BMM350_EN_Z_MSK = 0x04 +BMM350_EN_Z_POS = 0x2 +BMM350_EN_XYZ_MSK = 0x7 +BMM350_EN_XYZ_POS = 0x0 +BMM350_PMU_CMD_BUSY_MSK = 0x1 +BMM350_PMU_CMD_BUSY_POS = 0x0 +BMM350_ODR_OVWR_MSK = 0x2 +BMM350_ODR_OVWR_POS = 0x1 +BMM350_AVG_OVWR_MSK = 0x4 +BMM350_AVG_OVWR_POS = 0x2 +BMM350_PWR_MODE_IS_NORMAL_MSK = 0x8 +BMM350_PWR_MODE_IS_NORMAL_POS = 0x3 +BMM350_CMD_IS_ILLEGAL_MSK = 0x10 +BMM350_CMD_IS_ILLEGAL_POS = 0x4 +BMM350_PMU_CMD_VALUE_MSK = 0xE0 +BMM350_PMU_CMD_VALUE_POS = 0x5 +BMM350_PMU_ODR_S_MSK = 0xf +BMM350_PMU_ODR_S_POS = 0x0 +BMM350_PMU_AVG_S_MSK = 0x30 +BMM350_PMU_AVG_S_POS = 0x4 +BMM350_I3C_ERROR_0_MSK = 0x1 +BMM350_I3C_ERROR_0_POS = 0x0 +BMM350_I3C_ERROR_3_MSK = 0x8 +BMM350_I3C_ERROR_3_POS = 0x3 +BMM350_I2C_WDT_EN_MSK = 0x1 +BMM350_I2C_WDT_EN_POS = 0x0 +BMM350_I2C_WDT_SEL_MSK = 0x2 + +BMM350_I2C_WDT_SEL_POS = 0x1 +BMM350_TRSDCR_REV_ID_OTP_MSK = 0x3 +BMM350_TRSDCR_REV_ID_OTP_POS = 0x0 +BMM350_TRSDCR_REV_ID_FIXED_MSK = 0xfc +BMM350_TRSDCR_REV_ID_FIXED_POS = 0x2 +BMM350_PAGING_EN_MSK = 0x80 +BMM350_PAGING_EN_POS = 0x7 +BMM350_DRDY_DATA_REG_MSK = 0x4 +BMM350_DRDY_DATA_REG_POS = 0x2 +BMM350_INT_MODE_MSK = 0x1 +BMM350_INT_MODE_POS = 0x0 +BMM350_INT_POL_MSK = 0x2 +BMM350_INT_POL_POS = 0x1 +BMM350_INT_OD_MSK = 0x4 +BMM350_INT_OD_POS = 0x2 +BMM350_INT_OUTPUT_EN_MSK = 0x8 +BMM350_INT_OUTPUT_EN_POS = 0x3 +BMM350_DRDY_DATA_REG_EN_MSK = 0x80 +BMM350_DRDY_DATA_REG_EN_POS = 0x7 +BMM350_DRDY_INT_MAP_TO_IBI_MSK = 0x1 +BMM350_DRDY_INT_MAP_TO_IBI_POS = 0x0 +BMM350_CLEAR_DRDY_INT_STATUS_UPON_IBI_MSK = 0x10 +BMM350_CLEAR_DRDY_INT_STATUS_UPON_IBI_POS = 0x4 +BMM350_TC_SYNC_TU_MSK = 0xff +BMM350_TC_SYNC_ODR_MSK = 0xff +BMM350_TC_SYNC_TPH_1_MSK = 0xff +BMM350_TC_SYNC_TPH_2_MSK = 0xff +BMM350_TC_SYNC_DT_MSK = 0xff +BMM350_TC_SYNC_ST_0_MSK = 0xff +BMM350_TC_SYNC_ST_1_MSK = 0xff +BMM350_TC_SYNC_ST_2_MSK = 0xff +BMM350_CFG_FORCE_SOSC_EN_MSK = 0x4 +BMM350_CFG_FORCE_SOSC_EN_POS = 0x2 +BMM350_ST_IGEN_EN_MSK = 0x1 +BMM350_ST_IGEN_EN_POS = 0x0 +BMM350_ST_N_MSK = 0x2 +BMM350_ST_N_POS = 0x1 +BMM350_ST_P_MSK = 0x4 +BMM350_ST_P_POS = 0x2 +BMM350_IST_EN_X_MSK = 0x8 +BMM350_IST_EN_X_POS = 0x3 +BMM350_IST_EN_Y_MSK = 0x10 +BMM350_IST_EN_Y_POS = 0x4 +BMM350_CFG_SENS_TIM_AON_MSK = 0x1 +BMM350_CFG_SENS_TIM_AON_POS = 0x0 +BMM350_DATA_X_7_0_MSK = 0xff +BMM350_DATA_X_7_0_POS = 0x0 +BMM350_DATA_X_15_8_MSK = 0xff +BMM350_DATA_X_15_8_POS = 0x0 +BMM350_DATA_X_23_16_MSK = 0xff +BMM350_DATA_X_23_16_POS = 0x0 +BMM350_DATA_Y_7_0_MSK = 0xff +BMM350_DATA_Y_7_0_POS = 0x0 +BMM350_DATA_Y_15_8_MSK = 0xff +BMM350_DATA_Y_15_8_POS = 0x0 +BMM350_DATA_Y_23_16_MSK = 0xff +BMM350_DATA_Y_23_16_POS = 0x0 +BMM350_DATA_Z_7_0_MSK = 0xff +BMM350_DATA_Z_7_0_POS = 0x0 +BMM350_DATA_Z_15_8_MSK = 0xff +BMM350_DATA_Z_15_8_POS = 0x0 +BMM350_DATA_Z_23_16_MSK = 0xff +BMM350_DATA_Z_23_16_POS = 0x0 +BMM350_DATA_T_7_0_MSK = 0xff +BMM350_DATA_T_7_0_POS = 0x0 +BMM350_DATA_T_15_8_MSK = 0xff +BMM350_DATA_T_15_8_POS = 0x0 +BMM350_DATA_T_23_16_MSK = 0xff +BMM350_DATA_T_23_16_POS = 0x0 +BMM350_DATA_ST_7_0_MSK = 0xff +BMM350_DATA_ST_7_0_POS = 0x0 +BMM350_DATA_ST_15_8_MSK = 0xff +BMM350_DATA_ST_15_8_POS = 0x0 +BMM350_DATA_ST_23_16_MSK = 0xff +BMM350_DATA_ST_23_16_POS = 0x0 +BMM350_SIGN_INVERT_T_MSK = 0x10 +BMM350_SIGN_INVERT_T_POS = 0x4 +BMM350_SIGN_INVERT_X_MSK = 0x20 +BMM350_SIGN_INVERT_X_POS = 0x5 +BMM350_SIGN_INVERT_Y_MSK = 0x40 +BMM350_SIGN_INVERT_Y_POS = 0x6 +BMM350_SIGN_INVERT_Z_MSK = 0x80 +BMM350_SIGN_INVERT_Z_POS = 0x7 +BMM350_DIS_BR_NM_MSK = 0x1 +BMM350_DIS_BR_NM_POS = 0x0 +BMM350_DIS_FGR_NM_MSK = 0x2 +BMM350_DIS_FGR_NM_POS = 0x1 +BMM350_DIS_CRST_AT_ALL_MSK = 0x4 +BMM350_DIS_CRST_AT_ALL_POS = 0x2 +BMM350_DIS_BR_FM_MSK = 0x8 +BMM350_DIS_BR_FM_POS = 0x3 +BMM350_FRC_EN_BUFF_MSK = 0x1 +BMM350_FRC_EN_BUFF_POS = 0x0 +BMM350_FRC_INA_EN1_MSK = 0x2 +BMM350_FRC_INA_EN1_POS = 0x1 +BMM350_FRC_INA_EN2_MSK = 0x4 +BMM350_FRC_INA_EN2_POS = 0x2 +BMM350_FRC_ADC_EN_MSK = 0x8 +BMM350_FRC_ADC_EN_POS = 0x3 +BMM350_FRC_INA_RST_MSK = 0x10 +BMM350_FRC_INA_RST_POS = 0x4 +BMM350_FRC_ADC_RST_MSK = 0x20 +BMM350_FRC_ADC_RST_POS = 0x5 +BMM350_FRC_INA_XSEL_MSK = 0x1 +BMM350_FRC_INA_XSEL_POS = 0x0 +BMM350_FRC_INA_YSEL_MSK = 0x2 +BMM350_FRC_INA_YSEL_POS = 0x1 +BMM350_FRC_INA_ZSEL_MSK = 0x4 +BMM350_FRC_INA_ZSEL_POS = 0x2 +BMM350_FRC_ADC_TEMP_EN_MSK = 0x8 +BMM350_FRC_ADC_TEMP_EN_POS = 0x3 +BMM350_FRC_TSENS_EN_MSK = 0x10 +BMM350_FRC_TSENS_EN_POS = 0x4 +BMM350_DSENS_FM_MSK = 0x20 +BMM350_DSENS_FM_POS = 0x5 +BMM350_DSENS_SEL_MSK = 0x40 +BMM350_DSENS_SEL_POS = 0x6 +BMM350_DSENS_SHORT_MSK = 0x80 +BMM350_DSENS_SHORT_POS = 0x7 +BMM350_ERR_MISS_BR_DONE_MSK = 0x1 +BMM350_ERR_MISS_BR_DONE_POS = 0x0 +BMM350_ERR_MISS_FGR_DONE_MSK = 0x2 +BMM350_ERR_MISS_FGR_DONE_POS = 0x1 +BMM350_TST_CHAIN_LN_MODE_MSK = 0x1 +BMM350_TST_CHAIN_LN_MODE_POS = 0x0 +BMM350_TST_CHAIN_LP_MODE_MSK = 0x2 +BMM350_TST_CHAIN_LP_MODE_POS = 0x1 +BMM350_EN_OVWR_TMR_IF_MSK = 0x1 +BMM350_EN_OVWR_TMR_IF_POS = 0x0 +BMM350_TMR_CKTRIGB_MSK = 0x2 +BMM350_TMR_CKTRIGB_POS = 0x1 +BMM350_TMR_DO_BR_MSK = 0x4 +BMM350_TMR_DO_BR_POS = 0x2 +BMM350_TMR_DO_FGR_MSK = 0x18 +BMM350_TMR_DO_FGR_POS = 0x3 +BMM350_TMR_EN_OSC_MSK = 0x80 +BMM350_TMR_EN_OSC_POS = 0x7 +BMM350_VCM_TRIM_X_MSK = 0x1f +BMM350_VCM_TRIM_X_POS = 0x0 +BMM350_VCM_TRIM_Y_MSK = 0x1f +BMM350_VCM_TRIM_Y_POS = 0x0 +BMM350_VCM_TRIM_Z_MSK = 0x1f +BMM350_VCM_TRIM_Z_POS = 0x0 +BMM350_VCM_TRIM_DSENS_MSK = 0x1f +BMM350_VCM_TRIM_DSENS_POS = 0x0 +BMM350_TWLB_MSK = 0x30 +BMM350_TWLB_POS = 0x4 +BMM350_PRG_PLS_TIM_MSK = 0x30 +BMM350_PRG_PLS_TIM_POS = 0x4 +BMM350_OTP_OVWR_EN_MSK = 0x1 +BMM350_OTP_OVWR_EN_POS = 0x0 +BMM350_OTP_MEM_CLK_MSK = 0x2 +BMM350_OTP_MEM_CLK_POS = 0x1 +BMM350_OTP_MEM_CS_MSK = 0x4 +BMM350_OTP_MEM_CS_POS = 0x2 +BMM350_OTP_MEM_PGM_MSK = 0x8 +BMM350_OTP_MEM_PGM_POS = 0x3 +BMM350_OTP_MEM_RE_MSK = 0x10 +BMM350_OTP_MEM_RE_POS = 0x4 +BMM350_SAMPLE_RDATA_PLS_MSK = 0x80 +BMM350_SAMPLE_RDATA_PLS_POS = 0x7 +BMM350_CFG_FW_MSK = 0x1 +BMM350_CFG_FW_POS = 0x0 +BMM350_EN_BR_X_MSK = 0x2 +BMM350_EN_BR_X_POS = 0x1 +BMM350_EN_BR_Y_MSK = 0x4 +BMM350_EN_BR_Y_POS = 0x2 +BMM350_EN_BR_Z_MSK = 0x8 +BMM350_EN_BR_Z_POS = 0x3 +BMM350_CFG_PAUSE_TIME_MSK = 0x30 +BMM350_CFG_PAUSE_TIME_POS = 0x4 +BMM350_CFG_FGR_PLS_DUR_MSK = 0xf +BMM350_CFG_FGR_PLS_DUR_POS = 0x0 +BMM350_CFG_BR_Z_ORDER_MSK = 0x10 +BMM350_CFG_BR_Z_ORDER_POS = 0x4 +BMM350_CFG_BR_XY_CHOP_MSK = 0x20 +BMM350_CFG_BR_XY_CHOP_POS = 0x5 +BMM350_CFG_BR_PLS_DUR_MSK = 0xc0 +BMM350_CFG_BR_PLS_DUR_POS = 0x6 +BMM350_ENABLE_BR_FGR_TEST_MSK = 0x1 +BMM350_ENABLE_BR_FGR_TEST_POS = 0x0 +BMM350_SEL_AXIS_MSK = 0xe +BMM350_SEL_AXIS_POS = 0x1 +BMM350_TMR_CFG_TEST_CLK_EN_MSK = 0x10 +BMM350_TMR_CFG_TEST_CLK_EN_POS = 0x4 +BMM350_TEST_VAL_BITS_7DOWNTO0_MSK = 0xff +BMM350_TEST_VAL_BITS_7DOWNTO0_POS = 0x0 +BMM350_TEST_VAL_BITS_8_MSK = 0x1 +BMM350_TEST_VAL_BITS_8_POS = 0x0 +BMM350_TEST_P_SAMPLE_MSK = 0x2 +BMM350_TEST_P_SAMPLE_POS = 0x1 +BMM350_TEST_N_SAMPLE_MSK = 0x4 +BMM350_TEST_N_SAMPLE_POS = 0x2 +BMM350_TEST_APPLY_TO_REM_MSK = 0x10 +BMM350_TEST_APPLY_TO_REM_POS = 0x4 +BMM350_UFO_TRM_OSC_RANGE_MSK = 0xf +BMM350_UFO_TRM_OSC_RANGE_POS = 0x0 +BMM350_ISO_CHIP_ID_MSK = 0x78 +BMM350_ISO_CHIP_ID_POS = 0x3 +BMM350_ISO_I2C_DEV_ID_MSK = 0x80 +BMM350_ISO_I2C_DEV_ID_POS = 0x7 +BMM350_I3C_FREQ_BITS_1DOWNTO0_MSK = 0xc +BMM350_I3C_FREQ_BITS_1DOWNTO0_POS = 0x2 +BMM350_I3C_IBI_MDB_SEL_MSK = 0x10 +BMM350_I3C_IBI_MDB_SEL_POS = 0x4 +BMM350_TC_ASYNC_EN_MSK = 0x20 +BMM350_TC_ASYNC_EN_POS = 0x5 +BMM350_TC_SYNC_EN_MSK = 0x40 +BMM350_TC_SYNC_EN_POS = 0x6 +BMM350_I3C_SCL_GATING_EN_MSK = 0x80 +BMM350_I3C_SCL_GATING_EN_POS = 0x7 +BMM350_I3C_INACCURACY_BITS_6DOWNTO0_MSK = 0x7f +BMM350_I3C_INACCURACY_BITS_6DOWNTO0_POS = 0x0 +BMM350_EST_EN_X_MSK = 0x1 +BMM350_EST_EN_X_POS = 0x0 +BMM350_EST_EN_Y_MSK = 0x2 +BMM350_EST_EN_Y_POS = 0x1 +BMM350_CRST_DIS_MSK = 0x4 +BMM350_CRST_DIS_POS = 0x2 +BMM350_BR_TFALL_MSK = 0x7 +BMM350_BR_TFALL_POS = 0x0 +BMM350_BR_TRISE_MSK = 0x70 +BMM350_BR_TRISE_POS = 0x4 +BMM350_TMR_SOFT_START_DIS_MSK = 0x80 +BMM350_TMR_SOFT_START_DIS_POS = 0x7 +BMM350_FOSC_LOW_RANGE_MSK = 0x80 +BMM350_FOSC_LOW_RANGE_POS = 0x7 +BMM350_VCRST_TRIM_FG_MSK = 0x3f +BMM350_VCRST_TRIM_FG_POS = 0x0 +BMM350_VCRST_TRIM_BR_MSK = 0x3f +BMM350_VCRST_TRIM_BR_POS = 0x0 +BMM350_BG_TRIM_VRP_MSK = 0xc0 +BMM350_BG_TRIM_VRP_POS = 0x6 +BMM350_BG_TRIM_TC_MSK = 0xf +BMM350_BG_TRIM_TC_POS = 0x0 +BMM350_BG_TRIM_VRA_MSK = 0xf0 +BMM350_BG_TRIM_VRA_POS = 0x4 +BMM350_BG_TRIM_VRD_MSK = 0xf +BMM350_BG_TRIM_VRD_POS = 0x0 +BMM350_OVWR_REF_IB_EN_MSK = 0x10 +BMM350_OVWR_REF_IB_EN_POS = 0x4 +BMM350_OVWR_VDDA_EN_MSK = 0x20 +BMM350_OVWR_VDDA_EN_POS = 0x5 +BMM350_OVWR_VDDP_EN_MSK = 0x40 +BMM350_OVWR_VDDP_EN_POS = 0x6 +BMM350_OVWR_VDDS_EN_MSK = 0x80 +BMM350_OVWR_VDDS_EN_POS = 0x7 +BMM350_REF_IB_EN_MSK = 0x10 +BMM350_REF_IB_EN_POS = 0x4 +BMM350_VDDA_EN_MSK = 0x20 +BMM350_VDDA_EN_POS = 0x5 +BMM350_VDDP_EN_MSK = 0x40 +BMM350_VDDP_EN_POS = 0x6 +BMM350_VDDS_EN_MSK = 0x80 +BMM350_VDDS_EN_POS = 0x7 +BMM350_OVWR_OTP_PROG_VDD_SW_EN_MSK = 0x8 +BMM350_OVWR_OTP_PROG_VDD_SW_EN_POS = 0x3 +BMM350_OVWR_EN_MFE_BG_FILT_BYPASS_MSK = 0x10 +BMM350_OVWR_EN_MFE_BG_FILT_BYPASS_POS = 0x4 +BMM350_OTP_PROG_VDD_SW_EN_MSK = 0x8 +BMM350_OTP_PROG_VDD_SW_EN_POS = 0x3 +BMM350_CP_COMP_CRST_EN_TM_MSK = 0x10 +BMM350_CP_COMP_CRST_EN_TM_POS = 0x4 +BMM350_CP_COMP_VDD_EN_TM_MSK = 0x20 +BMM350_CP_COMP_VDD_EN_TM_POS = 0x5 +BMM350_CP_INTREFS_EN_TM_MSK = 0x40 +BMM350_CP_INTREFS_EN_TM_POS = 0x6 +BMM350_ADC_LOCAL_CHOP_EN_MSK = 0x20 +BMM350_ADC_LOCAL_CHOP_EN_POS = 0x5 +BMM350_INA_MODE_MSK = 0x40 +BMM350_INA_MODE_POS = 0x6 +BMM350_VDDD_EXT_EN_MSK = 0x20 +BMM350_VDDD_EXT_EN_POS = 0x5 +BMM350_VDDP_EXT_EN_MSK = 0x80 +BMM350_VDDP_EXT_EN_POS = 0x7 +BMM350_ADC_DSENS_EN_MSK = 0x10 +BMM350_ADC_DSENS_EN_POS = 0x4 +BMM350_DSENS_EN_MSK = 0x20 +BMM350_DSENS_EN_POS = 0x5 +BMM350_OTP_TM_CLVWR_EN_MSK = 0x40 +BMM350_OTP_TM_CLVWR_EN_POS = 0x6 +BMM350_OTP_VDDP_DIS_MSK = 0x80 +BMM350_OTP_VDDP_DIS_POS = 0x7 +BMM350_FORCE_HIGH_VREF_IREF_OK_MSK = 0x10 +BMM350_FORCE_HIGH_VREF_IREF_OK_POS = 0x4 +BMM350_FORCE_HIGH_FOSC_OK_MSK = 0x20 +BMM350_FORCE_HIGH_FOSC_OK_POS = 0x5 +BMM350_FORCE_HIGH_MFE_BG_RDY_MSK = 0x40 +BMM350_FORCE_HIGH_MFE_BG_RDY_POS = 0x6 +BMM350_FORCE_HIGH_MFE_VTMR_RDY_MSK = 0x80 +BMM350_FORCE_HIGH_MFE_VTMR_RDY_POS = 0x7 +BMM350_ERR_END_OF_RECHARGE_MSK = 0x1 +BMM350_ERR_END_OF_RECHARGE_POS = 0x0 +BMM350_ERR_END_OF_DISCHARGE_MSK = 0x2 +BMM350_ERR_END_OF_DISCHARGE_POS = 0x1 +BMM350_CP_TMX_DIGTP_SEL_MSK = 0x7 +BMM350_CP_TMX_DIGTP_SEL_POS = 0x0 +BMM350_CP_CPOSC_EN_TM_MSK = 0x80 +BMM350_CP_CPOSC_EN_TM_POS = 0x7 +BMM350_TST_ATM1_CFG_MSK = 0x3f +BMM350_TST_ATM1_CFG_POS = 0x0 +BMM350_TST_TB1_EN_MSK = 0x80 +BMM350_TST_TB1_EN_POS = 0x7 +BMM350_TST_ATM2_CFG_MSK = 0x1f +BMM350_TST_ATM2_CFG_POS = 0x0 +BMM350_TST_TB2_EN_MSK = 0x80 +BMM350_TST_TB2_EN_POS = 0x7 +BMM350_REG_DTB1X_SEL_MSK = 0x7f +BMM350_REG_DTB1X_SEL_POS = 0x0 +BMM350_SEL_DTB1X_PAD_MSK = 0x80 +BMM350_SEL_DTB1X_PAD_POS = 0x7 +BMM350_REG_DTB2X_SEL_MSK = 0x7f +BMM350_REG_DTB2X_SEL_POS = 0x0 +BMM350_TMR_TST_CFG_MSK = 0x7f +BMM350_TMR_TST_CFG_POS = 0x0 +BMM350_TMR_TST_HIZ_VTMR_MSK = 0x80 +BMM350_TMR_TST_HIZ_VTMR_POS = 0x7 + +# OTP MACROS +BMM350_OTP_CMD_DIR_READ = 0x20 +BMM350_OTP_CMD_DIR_PRGM_1B = 0x40 +BMM350_OTP_CMD_DIR_PRGM = 0x60 +BMM350_OTP_CMD_PWR_OFF_OTP = 0x80 +BMM350_OTP_CMD_EXT_READ = 0xA0 +BMM350_OTP_CMD_EXT_PRGM = 0xE0 +BMM350_OTP_CMD_MSK = 0xE0 +BMM350_OTP_WORD_ADDR_MSK = 0x1F + +BMM350_OTP_STATUS_ERROR_MSK = 0xE0 +BMM350_OTP_STATUS_NO_ERROR = 0x00 +BMM350_OTP_STATUS_BOOT_ERR = 0x20 +BMM350_OTP_STATUS_PAGE_RD_ERR = 0x40 +BMM350_OTP_STATUS_PAGE_PRG_ERR = 0x60 +BMM350_OTP_STATUS_SIGN_ERR = 0x80 +BMM350_OTP_STATUS_INV_CMD_ERR = 0xA0 +BMM350_OTP_STATUS_CMD_DONE = 0x01 + +# OTP indices +BMM350_TEMP_OFF_SENS = 0x0D + +BMM350_MAG_OFFSET_X = 0x0E +BMM350_MAG_OFFSET_Y = 0x0F +BMM350_MAG_OFFSET_Z = 0x10 + +BMM350_MAG_SENS_X = 0x10 +BMM350_MAG_SENS_Y = 0x11 +BMM350_MAG_SENS_Z = 0x11 + +BMM350_MAG_TCO_X = 0x12 +BMM350_MAG_TCO_Y = 0x13 +BMM350_MAG_TCO_Z = 0x14 + +BMM350_MAG_TCS_X = 0x12 +BMM350_MAG_TCS_Y = 0x13 +BMM350_MAG_TCS_Z = 0x14 + +BMM350_MAG_DUT_T_0 = 0x18 + +BMM350_CROSS_X_Y = 0x15 +BMM350_CROSS_Y_X = 0x15 +BMM350_CROSS_Z_X = 0x16 +BMM350_CROSS_Z_Y = 0x16 + +BMM350_SENS_CORR_Y = 0.01 +BMM350_TCS_CORR_Z = 0.000 + +# Signed bit macros +BMM350_SIGNED_8_BIT = 8 +BMM350_SIGNED_12_BIT = 12 +BMM350_SIGNED_16_BIT = 16 +BMM350_SIGNED_21_BIT = 21 +BMM350_SIGNED_24_BIT = 24 + +# Self-test macros +BMM350_SELF_TEST_DISABLE = 0x00 +BMM350_SELF_TEST_POS_X = 0x0D +BMM350_SELF_TEST_NEG_X = 0x0B +BMM350_SELF_TEST_POS_Y = 0x15 +BMM350_SELF_TEST_NEG_Y = 0x13 + +BMM350_X_FM_XP_UST_MAX_LIMIT = 150 +BMM350_X_FM_XP_UST_MIN_LIMIT = 50 + +BMM350_X_FM_XN_UST_MAX_LIMIT = -50 +BMM350_X_FM_XN_UST_MIN_LIMIT = -150 + +BMM350_Y_FM_YP_UST_MAX_LIMIT = 150 +BMM350_Y_FM_YP_UST_MIN_LIMIT = 50 + +BMM350_Y_FM_YN_UST_MAX_LIMIT = -50 +BMM350_Y_FM_YN_UST_MIN_LIMIT = -150 + +# PMU command status 0 macros +BMM350_PMU_CMD_STATUS_0_SUS = 0x00 +BMM350_PMU_CMD_STATUS_0_NM = 0x01 +BMM350_PMU_CMD_STATUS_0_UPD_OAE = 0x02 +BMM350_PMU_CMD_STATUS_0_FM = 0x03 +BMM350_PMU_CMD_STATUS_0_FM_FAST = 0x04 +BMM350_PMU_CMD_STATUS_0_FGR = 0x05 +BMM350_PMU_CMD_STATUS_0_FGR_FAST = 0x06 +BMM350_PMU_CMD_STATUS_0_BR = 0x07 +BMM350_PMU_CMD_STATUS_0_BR_FAST = 0x07 + + +# PRESET MODE DEFINITIONS +BMM350_PRESETMODE_LOWPOWER = 0x01 +BMM350_PRESETMODE_REGULAR = 0x02 +BMM350_PRESETMODE_HIGHACCURACY = 0x03 +BMM350_PRESETMODE_ENHANCED = 0x04 + +LOW_THRESHOLD_INTERRUPT = 0 +HIGH_THRESHOLD_INTERRUPT = 1 +INTERRUPT_X_ENABLE = 0 +INTERRUPT_Y_ENABLE = 0 +INTERRUPT_Z_ENABLE = 0 +INTERRUPT_X_DISABLE = 1 +INTERRUPT_Y_DISABLE = 1 +INTERRUPT_Z_DISABLE = 1 +ENABLE_INTERRUPT_PIN = 1 +DISABLE_INTERRUPT_PIN = 0 +NO_DATA = -32768 + +# ------------------------------------------- +BMM350_CHIP_ID_ERROR = -1 + + +# ------------------------------------------- + +BMM350_DISABLE_INTERRUPT = BMM350_DISABLE +BMM350_ENABLE_INTERRUPT = BMM350_ENABLE + +BMM350_SUSPEND_MODE = BMM350_PMU_CMD_SUS +BMM350_NORMAL_MODE = BMM350_PMU_CMD_NM +BMM350_FORCED_MODE = BMM350_PMU_CMD_FM +BMM350_FORCED_MODE_FAST = BMM350_PMU_CMD_FM_FAST + +BMM350_DATA_RATE_400HZ = BMM350_ODR_400HZ +BMM350_DATA_RATE_200HZ = BMM350_ODR_200HZ +BMM350_DATA_RATE_100HZ = BMM350_ODR_100HZ +BMM350_DATA_RATE_50HZ = BMM350_ODR_50HZ +BMM350_DATA_RATE_25HZ = BMM350_ODR_25HZ +BMM350_DATA_RATE_12_5HZ = BMM350_ODR_12_5HZ +BMM350_DATA_RATE_6_25HZ = BMM350_ODR_6_25HZ +BMM350_DATA_RATE_3_125HZ = BMM350_ODR_3_125HZ +BMM350_DATA_RATE_1_5625HZ = BMM350_ODR_1_5625HZ + +BMM350_FLUXGUIDE_9MS = BMM350_PMU_CMD_FGR +BMM350_FLUXGUIDE_FAST = BMM350_PMU_CMD_FGR_FAST +BMM350_BITRESET_9MS = BMM350_PMU_CMD_BR +BMM350_BITRESET_FAST = BMM350_PMU_CMD_BR_FAST +BMM350_NOMAGRESET = 127 + +BMM350_INTR_DISABLE = BMM350_DISABLE +BMM350_INTR_ENABLE = BMM350_ENABLE + +BMM350_UNMAP_FROM_PIN = BMM350_DISABLE +BMM350_MAP_TO_PIN = BMM350_ENABLE + +BMM350_PULSED = BMM350_INT_MODE_PULSED +BMM350_LATCHED = BMM350_INT_MODE_LATCHED + +BMM350_ACTIVE_LOW = BMM350_INT_POL_ACTIVE_LOW +BMM350_ACTIVE_HIGH = BMM350_INT_POL_ACTIVE_HIGH + +BMM350_INTR_OPEN_DRAIN = BMM350_INT_OD_OPENDRAIN +BMM350_INTR_PUSH_PULL = BMM350_INT_OD_PUSHPULL + +BMM350_IBI_DISABLE = BMM350_DISABLE +BMM350_IBI_ENABLE = BMM350_ENABLE + +BMM350_NOCLEAR_ON_IBI = BMM350_DISABLE +BMM350_CLEAR_ON_IBI = BMM350_ENABLE + +BMM350_I2C_WDT_DIS = BMM350_DISABLE +BMM350_I2C_WDT_EN = BMM350_ENABLE + +BMM350_I2C_WDT_SEL_SHORT = BMM350_DISABLE +BMM350_I2C_WDT_SEL_LONG = BMM350_ENABLE + +BMM350_NO_AVERAGING = BMM350_AVG_NO_AVG +BMM350_AVERAGING_2 = BMM350_AVG_2 +BMM350_AVERAGING_4 = BMM350_AVG_4 +BMM350_AVERAGING_8 = BMM350_AVG_8 + +BMM350_ST_IGEN_DIS = BMM350_DISABLE +BMM350_ST_IGEN_EN = BMM350_ENABLE + +BMM350_ST_N_DIS = BMM350_DISABLE +BMM350_ST_N_EN = BMM350_ENABLE + +BMM350_ST_P_DIS = BMM350_DISABLE +BMM350_ST_P_EN = BMM350_ENABLE + +BMM350_IST_X_DIS = BMM350_DISABLE +BMM350_IST_X_EN = BMM350_ENABLE + +BMM350_IST_Y_DIS = BMM350_DISABLE +BMM350_IST_Y_EN = BMM350_ENABLE + +BMM350_CFG_SENS_TIM_AON_DIS = BMM350_DISABLE +BMM350_CFG_SENS_TIM_AON_EN = BMM350_ENABLE + +BMM350_X_DIS = BMM350_DISABLE +BMM350_X_EN = BMM350_ENABLE + +BMM350_Y_DIS = BMM350_DISABLE +BMM350_Y_EN = BMM350_ENABLE + +BMM350_Z_DIS = BMM350_DISABLE +BMM350_Z_EN = BMM350_ENABLE + +PI = 3.141592653 +M_PI = 3.14159265358979323846 + + +# -------------------------------------------- +'''! + @brief bmm350 magnetometer dut offset coefficient structure +''' +class bmm350_dut_offset_coef: + def __init__(self, t_offs: float, offset_x: float, offset_y: float, offset_z: float): + self.t_offs = t_offs + self.offset_x = offset_x + self.offset_y = offset_y + self.offset_z = offset_z + +'''! + @brief bmm350 magnetometer dut sensitivity coefficient structure +''' +class bmm350_dut_sensit_coef: + def __init__(self, t_sens: float, sens_x: float, sens_y: float, sens_z: float): + self.t_sens = t_sens + self.sens_x = sens_x + self.sens_y = sens_y + self.sens_z = sens_z + +'''! + @brief bmm350 magnetometer dut tco structure +''' +class bmm350_dut_tco: + def __init__(self, tco_x: float, tco_y: float, tco_z: float): + self.tco_x = tco_x + self.tco_y = tco_y + self.tco_z = tco_z +'''! + @brief bmm350 magnetometer dut tcs structure +''' +class bmm350_dut_tcs: + def __init__(self, tcs_x: float, tcs_y: float, tcs_z: float): + self.tcs_x = tcs_x + self.tcs_y = tcs_y + self.tcs_z = tcs_z + +'''! + @brief bmm350 magnetometer cross axis compensation structure +''' +class bmm350_cross_axis: + def __init__(self, cross_x_y: float, cross_y_x: float, cross_z_x: float, cross_z_y: float): + self.cross_x_y = cross_x_y + self.cross_y_x = cross_y_x + self.cross_z_x = cross_z_x + self.cross_z_y = cross_z_y + +'''! + @brief bmm350 magnetometer compensate structure +''' +class bmm350_mag_compensate: + def __init__(self, dut_offset_coef: bmm350_dut_offset_coef, dut_sensit_coef: bmm350_dut_sensit_coef, dut_tco: bmm350_dut_tco, dut_tcs: bmm350_dut_tcs, dut_t0: float, cross_axis: bmm350_cross_axis): + self.dut_offset_coef = dut_offset_coef + self.dut_sensit_coef = dut_sensit_coef + self.dut_tco = dut_tco + self.dut_tcs = dut_tcs + self.dut_t0 = dut_t0 + self.cross_axis = cross_axis + +'''! + @brief bmm350 device structure +''' +class bmm350_dev: + def __init__(self, mag_comp: bmm350_mag_compensate): + self.chipID = 0 + self.otp_data = [0] * 32 + self.var_id = 0 + self.mag_comp = mag_comp + self.power_mode = 0 + self.axis_en = 0 + +# Create instances of the required classes with example values +dut_offset_coef = bmm350_dut_offset_coef(t_offs=0, offset_x=0, offset_y=0, offset_z=0) +dut_sensit_coef = bmm350_dut_sensit_coef(t_sens=0, sens_x=0, sens_y=0, sens_z=0) +dut_tco = bmm350_dut_tco(tco_x=0, tco_y=0, tco_z=0) +dut_tcs = bmm350_dut_tcs(tcs_x=0, tcs_y=0, tcs_z=0) +cross_axis = bmm350_cross_axis(cross_x_y=0, cross_y_x=0, cross_z_x=0, cross_z_y=0) +mag_comp = bmm350_mag_compensate( + dut_offset_coef=dut_offset_coef, + dut_sensit_coef=dut_sensit_coef, + dut_tco=dut_tco, + dut_tcs=dut_tcs, + dut_t0=0, + cross_axis=cross_axis +) +# The bmm350_mag_compensate object now contains all the data defined above. +bmm350_sensor = bmm350_dev(mag_comp) + + +# Uncompensated geomagnetic and temperature data +class BMM350RawMagData: + def __init__(self): + self.raw_x_data = 0 + self.raw_y_data = 0 + self.raw_z_data = 0 + self.raw_t_data = 0 +_raw_mag_data = BMM350RawMagData() + +class BMM350MagData: + def __init__(self): + self.x = 0 + self.y = 0 + self.z = 0 + self.temperature = 0 +_mag_data = BMM350MagData() + +class bmm350_pmu_cmd_status_0: + def __init__(self, pmu_cmd_busy, odr_ovwr, avr_ovwr, pwr_mode_is_normal, cmd_is_illegal, pmu_cmd_value): + self.pmu_cmd_busy = pmu_cmd_busy + self.odr_ovwr = odr_ovwr + self.avr_ovwr = avr_ovwr + self.pwr_mode_is_normal = pwr_mode_is_normal + self.cmd_is_illegal = cmd_is_illegal + self.pmu_cmd_value = pmu_cmd_value +pmu_cmd_stat_0 = bmm350_pmu_cmd_status_0(pmu_cmd_busy=0, odr_ovwr=0, avr_ovwr=0, pwr_mode_is_normal=0, cmd_is_illegal=0, pmu_cmd_value=0) + +# -------------------------------------------- +class DFRobot_bmm350(object): + I2C_MODE = 1 + I3C_MODE = 2 + __thresholdMode = 2 + threshold = 0 + + + def __init__(self, bus): + if bus != 0: + self.__i2c_i3c = self.I2C_MODE + else: + self.__i2c_i3c = self.I3C_MODE + + def BMM350_SET_BITS(self, reg_data, bitname_msk, bitname_pos, data): + return (reg_data & ~bitname_msk) | ((data << bitname_pos) & bitname_msk) + + def BMM350_GET_BITS(self, reg_data, mask, pos): + return (reg_data & mask) >> pos + + def BMM350_GET_BITS_POS_0(self, reg_data, mask): + return reg_data & mask + + def BMM350_SET_BITS_POS_0(self, reg_data, mask, data): + return ((reg_data & ~(mask)) | (data & mask)) + + + + # brief This internal API converts the raw data from the IC data registers to signed integer + def fix_sign(self, inval, number_of_bits): + power = 0 + if number_of_bits == BMM350_SIGNED_8_BIT: + power = 128; # 2^7 + elif number_of_bits == BMM350_SIGNED_12_BIT: + power = 2048 # 2^11 + elif number_of_bits == BMM350_SIGNED_16_BIT: + power = 32768 # 2^15 + elif number_of_bits == BMM350_SIGNED_21_BIT: + power = 1048576 # 2^20 + elif number_of_bits == BMM350_SIGNED_24_BIT: + power = 8388608 # 2^23 + else: + power = 0 + if inval >= power: + inval = inval - (power * 2) + return inval + + # brief This internal API is used to update magnetometer offset and sensitivity data. + def update_mag_off_sens(self): + off_x_lsb_msb = bmm350_sensor.otp_data[BMM350_MAG_OFFSET_X] & 0x0FFF + off_y_lsb_msb = ((bmm350_sensor.otp_data[BMM350_MAG_OFFSET_X] & 0xF000) >> 4) + (bmm350_sensor.otp_data[BMM350_MAG_OFFSET_Y] & BMM350_LSB_MASK) + off_z_lsb_msb = (bmm350_sensor.otp_data[BMM350_MAG_OFFSET_Y] & 0x0F00) + (bmm350_sensor.otp_data[BMM350_MAG_OFFSET_Z] & BMM350_LSB_MASK) + t_off = bmm350_sensor.otp_data[BMM350_TEMP_OFF_SENS] & BMM350_LSB_MASK + + bmm350_sensor.mag_comp.dut_offset_coef.offset_x = self.fix_sign(off_x_lsb_msb, BMM350_SIGNED_12_BIT) + bmm350_sensor.mag_comp.dut_offset_coef.offset_y = self.fix_sign(off_y_lsb_msb, BMM350_SIGNED_12_BIT) + bmm350_sensor.mag_comp.dut_offset_coef.offset_z = self.fix_sign(off_z_lsb_msb, BMM350_SIGNED_12_BIT) + bmm350_sensor.mag_comp.dut_offset_coef.t_offs = self.fix_sign(t_off, BMM350_SIGNED_8_BIT) / 5.0 + + sens_x = (bmm350_sensor.otp_data[BMM350_MAG_SENS_X] & BMM350_MSB_MASK) >> 8 + sens_y = (bmm350_sensor.otp_data[BMM350_MAG_SENS_Y] & BMM350_LSB_MASK) + sens_z = (bmm350_sensor.otp_data[BMM350_MAG_SENS_Z] & BMM350_MSB_MASK) >> 8 + t_sens = (bmm350_sensor.otp_data[BMM350_TEMP_OFF_SENS] & BMM350_MSB_MASK) >> 8 + + bmm350_sensor.mag_comp.dut_sensit_coef.sens_x = self.fix_sign(sens_x, BMM350_SIGNED_8_BIT) / 256.0 + bmm350_sensor.mag_comp.dut_sensit_coef.sens_y = (self.fix_sign(sens_y, BMM350_SIGNED_8_BIT) / 256.0) + BMM350_SENS_CORR_Y + bmm350_sensor.mag_comp.dut_sensit_coef.sens_z = self.fix_sign(sens_z, BMM350_SIGNED_8_BIT) / 256.0 + bmm350_sensor.mag_comp.dut_sensit_coef.t_sens = self.fix_sign(t_sens, BMM350_SIGNED_8_BIT) / 512.0 + + tco_x = (bmm350_sensor.otp_data[BMM350_MAG_TCO_X] & BMM350_LSB_MASK) + tco_y = (bmm350_sensor.otp_data[BMM350_MAG_TCO_Y] & BMM350_LSB_MASK) + tco_z = (bmm350_sensor.otp_data[BMM350_MAG_TCO_Z] & BMM350_LSB_MASK) + + bmm350_sensor.mag_comp.dut_tco.tco_x = self.fix_sign(tco_x, BMM350_SIGNED_8_BIT) / 32.0 + bmm350_sensor.mag_comp.dut_tco.tco_y = self.fix_sign(tco_y, BMM350_SIGNED_8_BIT) / 32.0 + bmm350_sensor.mag_comp.dut_tco.tco_z = self.fix_sign(tco_z, BMM350_SIGNED_8_BIT) / 32.0 + + tcs_x = (bmm350_sensor.otp_data[BMM350_MAG_TCS_X] & BMM350_MSB_MASK) >> 8 + tcs_y = (bmm350_sensor.otp_data[BMM350_MAG_TCS_Y] & BMM350_MSB_MASK) >> 8 + tcs_z = (bmm350_sensor.otp_data[BMM350_MAG_TCS_Z] & BMM350_MSB_MASK) >> 8 + + bmm350_sensor.mag_comp.dut_tcs.tcs_x = self.fix_sign(tcs_x, BMM350_SIGNED_8_BIT) / 16384.0 + bmm350_sensor.mag_comp.dut_tcs.tcs_y = self.fix_sign(tcs_y, BMM350_SIGNED_8_BIT) / 16384.0 + bmm350_sensor.mag_comp.dut_tcs.tcs_z = (self.fix_sign(tcs_z, BMM350_SIGNED_8_BIT) / 16384.0) - BMM350_TCS_CORR_Z + + bmm350_sensor.mag_comp.dut_t0 = (self.fix_sign(bmm350_sensor.otp_data[BMM350_MAG_DUT_T_0], BMM350_SIGNED_16_BIT) / 512.0) + 23.0 + + cross_x_y = (bmm350_sensor.otp_data[BMM350_CROSS_X_Y] & BMM350_LSB_MASK) + cross_y_x = (bmm350_sensor.otp_data[BMM350_CROSS_Y_X] & BMM350_MSB_MASK) >> 8 + cross_z_x = (bmm350_sensor.otp_data[BMM350_CROSS_Z_X] & BMM350_LSB_MASK) + cross_z_y = (bmm350_sensor.otp_data[BMM350_CROSS_Z_Y] & BMM350_MSB_MASK) >> 8 + + bmm350_sensor.mag_comp.cross_axis.cross_x_y = self.fix_sign(cross_x_y, BMM350_SIGNED_8_BIT) / 800.0 + bmm350_sensor.mag_comp.cross_axis.cross_y_x = self.fix_sign(cross_y_x, BMM350_SIGNED_8_BIT) / 800.0 + bmm350_sensor.mag_comp.cross_axis.cross_z_x = self.fix_sign(cross_z_x, BMM350_SIGNED_8_BIT) / 800.0 + bmm350_sensor.mag_comp.cross_axis.cross_z_y = self.fix_sign(cross_z_y, BMM350_SIGNED_8_BIT) / 800.0 + + + def bmm350_set_powermode(self, powermode): + last_pwr_mode = self.read_reg(BMM350_REG_PMU_CMD, 1) + if (last_pwr_mode[0] == BMM350_PMU_CMD_NM) or (last_pwr_mode[0] == BMM350_PMU_CMD_UPD_OAE): + self.write_reg(BMM350_REG_PMU_CMD, BMM350_PMU_CMD_SUS) + time.sleep(BMM350_GOTO_SUSPEND_DELAY) + # Array to store suspend to forced mode delay + sus_to_forced_mode =[BMM350_SUS_TO_FORCEDMODE_NO_AVG_DELAY, BMM350_SUS_TO_FORCEDMODE_AVG_2_DELAY, + BMM350_SUS_TO_FORCEDMODE_AVG_4_DELAY, BMM350_SUS_TO_FORCEDMODE_AVG_8_DELAY] + # Array to store suspend to forced mode fast delay + sus_to_forced_mode_fast = [BMM350_SUS_TO_FORCEDMODE_FAST_NO_AVG_DELAY, BMM350_SUS_TO_FORCEDMODE_FAST_AVG_2_DELAY, + BMM350_SUS_TO_FORCEDMODE_FAST_AVG_4_DELAY, BMM350_SUS_TO_FORCEDMODE_FAST_AVG_8_DELAY] + # Set PMU command configuration to desired power mode + self.write_reg(BMM350_REG_PMU_CMD, powermode) + # Get average configuration + get_avg = self.read_reg(BMM350_REG_PMU_CMD_AGGR_SET, 1) + # Mask the average value + avg = ((get_avg[0] & BMM350_AVG_MSK) >> BMM350_AVG_POS) + delay_us = 0 + # Check if desired power mode is normal mode + if powermode == BMM350_NORMAL_MODE: + delay_us = BMM350_SUSPEND_TO_NORMAL_DELAY + # Check if desired power mode is forced mode + if powermode == BMM350_FORCED_MODE: + delay_us = sus_to_forced_mode[avg]; # Store delay based on averaging mode + # Check if desired power mode is forced mode fast + if powermode == BMM350_FORCED_MODE_FAST: + delay_us = sus_to_forced_mode_fast[avg] # Store delay based on averaging mode + # Perform delay based on power mode + time.sleep(delay_us) + bmm350_sensor.power_mode = powermode + + + def bmm350_magnetic_reset_and_wait(self): + # 1. Read PMU CMD status + reg_data = self.read_reg(BMM350_REG_PMU_CMD_STATUS_0, 1) + pmu_cmd_stat_0.pmu_cmd_busy = self.BMM350_GET_BITS_POS_0(reg_data[0], BMM350_PMU_CMD_BUSY_MSK) + pmu_cmd_stat_0.odr_ovwr = self.BMM350_GET_BITS(reg_data[0], BMM350_ODR_OVWR_MSK, BMM350_ODR_OVWR_POS) + pmu_cmd_stat_0.avr_ovwr = self.BMM350_GET_BITS(reg_data[0], BMM350_AVG_OVWR_MSK, BMM350_AVG_OVWR_POS) + pmu_cmd_stat_0.pwr_mode_is_normal = self.BMM350_GET_BITS(reg_data[0], BMM350_PWR_MODE_IS_NORMAL_MSK, BMM350_PWR_MODE_IS_NORMAL_POS) + pmu_cmd_stat_0.cmd_is_illegal = self.BMM350_GET_BITS(reg_data[0], BMM350_CMD_IS_ILLEGAL_MSK, BMM350_CMD_IS_ILLEGAL_POS) + pmu_cmd_stat_0.pmu_cmd_value = self.BMM350_GET_BITS(reg_data[0], BMM350_PMU_CMD_VALUE_MSK, BMM350_PMU_CMD_VALUE_POS) + # 2. Check whether the power mode is normal before magnetic reset + restore_normal = BMM350_DISABLE + if pmu_cmd_stat_0.pwr_mode_is_normal == BMM350_ENABLE: + restore_normal = BMM350_ENABLE + # Reset can only be triggered in suspend + self.bmm350_set_powermode(BMM350_SUSPEND_MODE) + # Set BR to PMU_CMD register + self.write_reg(BMM350_REG_PMU_CMD, BMM350_PMU_CMD_BR) + time.sleep(BMM350_BR_DELAY) + # Set FGR to PMU_CMD register + self.write_reg(BMM350_REG_PMU_CMD, BMM350_PMU_CMD_FGR) + time.sleep(BMM350_FGR_DELAY) + if restore_normal == BMM350_ENABLE: + self.bmm350_set_powermode(BMM350_NORMAL_MODE) + + + def sensor_init(self): + '''! + @brief Init bmm350 check whether the chip id is right + @return + @retval 0 is init success + @retval -1 is init failed + ''' + rslt = BMM350_OK + # Specifies that all axes are enabled + bmm350_sensor.axis_en = BMM350_EN_XYZ_MSK + time.sleep(BMM350_START_UP_TIME_FROM_POR) + # 1. Software reset + self.write_reg(BMM350_REG_CMD, BMM350_CMD_SOFTRESET) + time.sleep(BMM350_SOFT_RESET_DELAY) + # 2. Read chip ID + reg_date = self.read_reg(BMM350_REG_CHIP_ID, 1) + bmm350_sensor.chipID = reg_date[0] + if reg_date[0] == BMM350_CHIP_ID: + # 3. Download OTP compensation data + for indx in range(BMM350_OTP_DATA_LENGTH): + # 3.1 Set the OTP address register -- > Each address corresponds to a different OTP value (total OTP data is 32 bytes) + otp_cmd = BMM350_OTP_CMD_DIR_READ | (indx & BMM350_OTP_WORD_ADDR_MSK) + self.write_reg(BMM350_REG_OTP_CMD_REG, otp_cmd) + while (True): + time.sleep(0.0003) + # 3.2 The OTP status was read + otp_status = self.read_reg(BMM350_REG_OTP_STATUS_REG, 1) + otp_err = otp_status[0] & BMM350_OTP_STATUS_ERROR_MSK + if otp_err != BMM350_OTP_STATUS_NO_ERROR: + break + if (otp_status[0] & BMM350_OTP_STATUS_CMD_DONE): + break + # 3.3 Gets 16 bytes of OTP data from the OTP address specified above + OTP_MSB_data = self.read_reg(BMM350_REG_OTP_DATA_MSB_REG, 1) + OTP_LSB_data = self.read_reg(BMM350_REG_OTP_DATA_LSB_REG, 1) + OTP_data = ((OTP_MSB_data[0] << 8) | OTP_LSB_data[0]) & 0xFFFF + bmm350_sensor.otp_data[indx] = OTP_data + bmm350_sensor.var_id = (bmm350_sensor.otp_data[30] & 0x7f00) >> 9 + # 3.4 Update the magnetometer offset and sensitivity data + self.update_mag_off_sens() + # 4. Disable OTP + self.write_reg(BMM350_REG_OTP_CMD_REG, BMM350_OTP_CMD_PWR_OFF_OTP) + + # 5. Magnetic reset + self.bmm350_magnetic_reset_and_wait() + else: + # The chip id verification failed and initialization failed. Procedure + rslt = BMM350_CHIP_ID_ERROR + return rslt + + + def get_chip_id(self): + chip_id = self.read_reg(BMM350_REG_CHIP_ID, 1) + return chip_id[0] + + + def soft_reset(self): + '''! + @brief Soft reset, restore to suspended mode after soft reset. (You need to manually enter the normal mode) + ''' + self.write_reg(BMM350_REG_CMD, BMM350_CMD_SOFTRESET) # Software reset + time.sleep(BMM350_SOFT_RESET_DELAY) + self.write_reg(BMM350_REG_OTP_CMD_REG, BMM350_OTP_CMD_PWR_OFF_OTP) # Disable OTP + self.bmm350_magnetic_reset_and_wait() # magnetic reset + self.bmm350_set_powermode(BMM350_SUSPEND_MODE) + + + def set_operation_mode(self, modes): + '''! + @brief Set sensor operation mode + @param modes + @n BMM350_SUSPEND_MODE suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + @n BMM350_NORMAL_MODE normal mode: Get geomagnetic data normally. + @n BMM350_FORCED_MODE forced mode: Single measurement, the sensor restores to suspend mode when the measurement is done. + @n BMM350_FORCED_MODE_FAST To reach ODR = 200Hz is only possible by using FM_ FAST. + ''' + self.bmm350_set_powermode(modes) + + + def get_operation_mode(self): + '''! + @brief Get sensor operation mode + @return Return the character string of the operation mode + ''' + result = "" + if bmm350_sensor.power_mode == BMM350_SUSPEND_MODE: + result = "bmm350 is suspend mode!" + elif bmm350_sensor.power_mode == BMM350_NORMAL_MODE: + result = "bmm350 is normal mode!" + elif bmm350_sensor.power_mode == BMM350_FORCED_MODE: + result = "bmm350 is forced mode!" + elif bmm350_sensor.power_mode == BMM350_FORCED_MODE_FAST: + result = "bmm350 is forced_fast mode!" + else: + result = "error mode!" + return result + + + + + + def get_rate(self): + '''! + @brief Get the config data rate, unit: HZ + @return rate + ''' + avg_odr_reg = self.read_reg(BMM350_REG_PMU_CMD_AGGR_SET, 1) + odr_reg = self.BMM350_GET_BITS(avg_odr_reg[0], BMM350_ODR_MSK, BMM350_ODR_POS) + if odr_reg == BMM350_ODR_1_5625HZ: + result = 1.5625 + elif odr_reg == BMM350_ODR_3_125HZ: + result = 3.125 + elif odr_reg == BMM350_ODR_6_25HZ: + result = 6.25 + elif odr_reg == BMM350_ODR_12_5HZ: + result = 12.5 + elif odr_reg == BMM350_ODR_25HZ: + result = 25 + elif odr_reg == BMM350_ODR_50HZ: + result = 50 + elif odr_reg == BMM350_ODR_100HZ: + result = 100 + elif odr_reg == BMM350_ODR_200HZ: + result = 200 + elif odr_reg == BMM350_ODR_400HZ: + result = 400 + return result + + + def set_preset_mode(self, avg, rate = BMM350_DATA_RATE_12_5HZ): + '''! + @brief Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) + @param modes + @n BMM350_PRESETMODE_LOWPOWER Low power mode, get a fraction of data and take the mean value. + @n BMM350_PRESETMODE_REGULAR Regular mode, get a number of data and take the mean value. + @n BMM350_PRESETMODE_ENHANCED Enhanced mode, get a plenty of data and take the mean value. + @n BMM350_PRESETMODE_HIGHACCURACY High accuracy mode, get a huge number of data and take the mean value. + @param rate + @n BMM350_DATA_RATE_1_5625HZ + @n BMM350_DATA_RATE_3_125HZ + @n BMM350_DATA_RATE_6_25HZ + @n BMM350_DATA_RATE_12_5HZ (default rate) + @n BMM350_DATA_RATE_25HZ + @n BMM350_DATA_RATE_50HZ + @n BMM350_DATA_RATE_100HZ + @n BMM350_DATA_RATE_200HZ + @n BMM350_DATA_RATE_400HZ + + ''' + reg_data = (rate & BMM350_ODR_MSK) + reg_data = self.BMM350_SET_BITS(reg_data, BMM350_AVG_MSK, BMM350_AVG_POS, avg) + self.write_reg(BMM350_REG_PMU_CMD_AGGR_SET, reg_data) + self.write_reg(BMM350_REG_PMU_CMD, BMM350_PMU_CMD_UPD_OAE) + + def set_rate(self, rates): + '''! + @brief Set the rate of obtaining geomagnetic data, the higher, the faster (without delay function) + @param rate + @n BMM350_DATA_RATE_1_5625HZ + @n BMM350_DATA_RATE_3_125HZ + @n BMM350_DATA_RATE_6_25HZ + @n BMM350_DATA_RATE_12_5HZ (default rate) + @n BMM350_DATA_RATE_25HZ + @n BMM350_DATA_RATE_50HZ + @n BMM350_DATA_RATE_100HZ + @n BMM350_DATA_RATE_200HZ + @n BMM350_DATA_RATE_400HZ + ''' + # self.bmm350_set_powermode(BMM350_NORMAL_MODE) + avg_odr_reg = self.read_reg(BMM350_REG_PMU_CMD_AGGR_SET, 1) + avg_reg = self.BMM350_GET_BITS(avg_odr_reg[0], BMM350_AVG_MSK, BMM350_AVG_POS) + reg_data = (rates & BMM350_ODR_MSK) + reg_data = self.BMM350_SET_BITS(reg_data, BMM350_AVG_MSK, BMM350_AVG_POS, avg_reg) + self.write_reg(BMM350_REG_PMU_CMD_AGGR_SET, reg_data) + self.write_reg(BMM350_REG_PMU_CMD, BMM350_PMU_CMD_UPD_OAE) + time.sleep(BMM350_UPD_OAE_DELAY) + + def self_test(self): + '''! + @brief Sensor self test, the returned character string indicate the self test result. + @return The character string of the test result + ''' + axis_en = self.read_reg(BMM350_REG_PMU_CMD_AXIS_EN, 1) + en_x = self.BMM350_GET_BITS(axis_en[0], BMM350_EN_X_MSK, BMM350_EN_X_POS) + en_y = self.BMM350_GET_BITS(axis_en[0], BMM350_EN_Y_MSK, BMM350_EN_Y_POS) + en_z = self.BMM350_GET_BITS(axis_en[0], BMM350_EN_Z_MSK, BMM350_EN_Z_POS) + str1 = "" + if en_x & 0x01: + str1 += "x " + if en_y & 0x01: + str1 += "y " + if en_z & 0x01: + str1 += "z " + if axis_en == 0: + str1 = "xyz aix self test fail" + else: + str1 += "aix test success" + return str1 + + + def set_measurement_XYZ(self, en_x = BMM350_X_EN, en_y = BMM350_Y_EN, en_z = BMM350_Z_EN): + '''! + @brief Enable the measurement at x-axis, y-axis and z-axis, default to be enabled. After disabling, the geomagnetic data at x, y, and z axis are wrong. + @param en_x + @n BMM350_X_EN Enable the measurement at x-axis + @n BMM350_X_DIS Disable the measurement at x-axis + @param en_y + @n BMM350_Y_EN Enable the measurement at y-axis + @n BMM350_Y_DIS Disable the measurement at y-axis + @param en_z + @n BMM350_Z_EN Enable the measurement at z-axis + @n BMM350_Z_DIS Disable the measurement at z-axis + ''' + if en_x == BMM350_X_DIS and en_y == BMM350_Y_DIS and en_z == BMM350_Z_DIS: + bmm350_sensor.axis_en = BMM350_DISABLE + else: + axis_en = self.read_reg(BMM350_REG_PMU_CMD_AXIS_EN, 1) + data = self.BMM350_SET_BITS(axis_en[0], BMM350_EN_X_MSK, BMM350_EN_X_POS, en_x) + data = self.BMM350_SET_BITS(data, BMM350_EN_Y_MSK, BMM350_EN_Y_POS, en_y) + data = self.BMM350_SET_BITS(data, BMM350_EN_Z_MSK, BMM350_EN_Z_POS, en_z) + bmm350_sensor.axis_en = data + + + def get_measurement_state_XYZ(self): + '''! + @brief Get the enabling status at x-axis, y-axis and z-axis + @return Return enabling status at x-axis, y-axis and z-axis as a character string + ''' + axis_en = bmm350_sensor.axis_en + en_x = self.BMM350_GET_BITS(axis_en, BMM350_EN_X_MSK, BMM350_EN_X_POS) + en_y = self.BMM350_GET_BITS(axis_en, BMM350_EN_Y_MSK, BMM350_EN_Y_POS) + en_z = self.BMM350_GET_BITS(axis_en, BMM350_EN_Z_MSK, BMM350_EN_Z_POS) + result = "" + result += "The x axis is enable! " if en_x == 1 else "The x axis is disable! " + result += "The y axis is enable! " if en_y == 1 else "The y axis is disable! " + result += "The z axis is enable! " if en_z == 1 else "The z axis is disable! " + return result + + + def get_geomagnetic_data(self): + '''! + @brief Get the geomagnetic data of 3 axis (x, y, z) + @return The list of the geomagnetic data at 3 axis (x, y, z) unit: uT + @ [0] The geomagnetic data at x-axis + @ [1] The geomagnetic data at y-axis + @ [2] The geomagnetic data at z-axis + ''' + # 1. Get raw data without compensation + mag_data = self.read_reg(BMM350_REG_MAG_X_XLSB, BMM350_MAG_TEMP_DATA_LEN) + raw_mag_x = mag_data[0] + (mag_data[1] << 8) + (mag_data[2] << 16) + raw_mag_y = mag_data[3] + (mag_data[4] << 8) + (mag_data[5] << 16) + raw_mag_z = mag_data[6] + (mag_data[7] << 8) + (mag_data[8] << 16) + raw_temp = mag_data[9] + (mag_data[10] << 8) + (mag_data[11] << 16) + if (bmm350_sensor.axis_en & BMM350_EN_X_MSK) == BMM350_DISABLE: + _raw_mag_data.raw_x_data = BMM350_DISABLE + else: + _raw_mag_data.raw_x_data = self.fix_sign(raw_mag_x, BMM350_SIGNED_24_BIT) + if (bmm350_sensor.axis_en & BMM350_EN_Y_MSK) == BMM350_DISABLE: + _raw_mag_data.raw_y_data = BMM350_DISABLE + else: + _raw_mag_data.raw_y_data = self.fix_sign(raw_mag_y, BMM350_SIGNED_24_BIT) + if (bmm350_sensor.axis_en & BMM350_EN_Z_MSK) == BMM350_DISABLE: + _raw_mag_data.raw_z_data = BMM350_DISABLE + else: + _raw_mag_data.raw_z_data = self.fix_sign(raw_mag_z, BMM350_SIGNED_24_BIT) + _raw_mag_data.raw_t_data = self.fix_sign(raw_temp, BMM350_SIGNED_24_BIT) + # 2. The raw data is processed + # 2.1 Parameter preparation + bxy_sens = 14.55 + bz_sens = 9.0 + temp_sens = 0.00204 + ina_xy_gain_trgt = 19.46 + ina_z_gain_trgt = 31.0 + adc_gain = 1 / 1.5 + lut_gain = 0.714607238769531 + power = (1000000.0 / 1048576.0) + lsb_to_ut_degc = [None] * 4 + lsb_to_ut_degc[0] = (power / (bxy_sens * ina_xy_gain_trgt * adc_gain * lut_gain)) + lsb_to_ut_degc[1] = (power / (bxy_sens * ina_xy_gain_trgt * adc_gain * lut_gain)) + lsb_to_ut_degc[2] = (power / (bz_sens * ina_z_gain_trgt * adc_gain * lut_gain)) + lsb_to_ut_degc[3] = 1 / (temp_sens * adc_gain * lut_gain * 1048576) + # 2.1 Start processing raw data + out_data = [None] * 4 + out_data[0] = _raw_mag_data.raw_x_data * lsb_to_ut_degc[0] + out_data[1] = _raw_mag_data.raw_y_data * lsb_to_ut_degc[1] + out_data[2] = _raw_mag_data.raw_z_data * lsb_to_ut_degc[2] + out_data[3] = _raw_mag_data.raw_t_data * lsb_to_ut_degc[3] + if out_data[3] > 0.0: + temp = out_data[3] - (1 * 25.49) + elif out_data[3] < 0.0: + temp = out_data[3] - (-1 * 25.49) + else: + temp = out_data[3] + out_data[3] = temp + # 3. Compensate for the original data + # 3.1 Compensation for temperature data + out_data[3] = (1 + bmm350_sensor.mag_comp.dut_sensit_coef.t_sens) * out_data[3] + bmm350_sensor.mag_comp.dut_offset_coef.t_offs + # 3.2 Store the magnetic compensation data in a list + dut_offset_coef = [None] * 3 + dut_offset_coef[0] = bmm350_sensor.mag_comp.dut_offset_coef.offset_x + dut_offset_coef[1] = bmm350_sensor.mag_comp.dut_offset_coef.offset_y + dut_offset_coef[2] = bmm350_sensor.mag_comp.dut_offset_coef.offset_z + + dut_sensit_coef = [None] * 3 + dut_sensit_coef[0] = bmm350_sensor.mag_comp.dut_sensit_coef.sens_x + dut_sensit_coef[1] = bmm350_sensor.mag_comp.dut_sensit_coef.sens_y + dut_sensit_coef[2] = bmm350_sensor.mag_comp.dut_sensit_coef.sens_z + + dut_tco = [None] * 3 + dut_tco[0] = bmm350_sensor.mag_comp.dut_tco.tco_x + dut_tco[1] = bmm350_sensor.mag_comp.dut_tco.tco_y + dut_tco[2] = bmm350_sensor.mag_comp.dut_tco.tco_z + + dut_tcs = [None] * 3 + dut_tcs[0] = bmm350_sensor.mag_comp.dut_tcs.tcs_x + dut_tcs[1] = bmm350_sensor.mag_comp.dut_tcs.tcs_y + dut_tcs[2] = bmm350_sensor.mag_comp.dut_tcs.tcs_z; + # 3.3 Compensation for magnetic data + for indx in range(3): + out_data[indx] *= 1 + dut_sensit_coef[indx] + out_data[indx] += dut_offset_coef[indx] + out_data[indx] += dut_tco[indx] * (out_data[3] - bmm350_sensor.mag_comp.dut_t0) + out_data[indx] /= 1 + dut_tcs[indx] * (out_data[3] - bmm350_sensor.mag_comp.dut_t0) + + cr_ax_comp_x = (out_data[0] - bmm350_sensor.mag_comp.cross_axis.cross_x_y * out_data[1]) / \ + (1 - bmm350_sensor.mag_comp.cross_axis.cross_y_x * bmm350_sensor.mag_comp.cross_axis.cross_x_y) + cr_ax_comp_y = (out_data[1] - bmm350_sensor.mag_comp.cross_axis.cross_y_x * out_data[0]) / \ + (1 - bmm350_sensor.mag_comp.cross_axis.cross_y_x * bmm350_sensor.mag_comp.cross_axis.cross_x_y) + cr_ax_comp_z = (out_data[2] + (out_data[0] * + (bmm350_sensor.mag_comp.cross_axis.cross_y_x * bmm350_sensor.mag_comp.cross_axis.cross_z_y - bmm350_sensor.mag_comp.cross_axis.cross_z_x) - out_data[1] * + (bmm350_sensor.mag_comp.cross_axis.cross_z_y - bmm350_sensor.mag_comp.cross_axis.cross_x_y * bmm350_sensor.mag_comp.cross_axis.cross_z_x)) / + (1 - bmm350_sensor.mag_comp.cross_axis.cross_y_x * bmm350_sensor.mag_comp.cross_axis.cross_x_y)) + + out_data[0] = cr_ax_comp_x + out_data[1] = cr_ax_comp_y + out_data[2] = cr_ax_comp_z + + if (bmm350_sensor.axis_en & BMM350_EN_X_MSK) == BMM350_DISABLE: + _mag_data.x = BMM350_DISABLE + else: + _mag_data.x = out_data[0] + + if (bmm350_sensor.axis_en & BMM350_EN_Y_MSK) == BMM350_DISABLE: + _mag_data.y = BMM350_DISABLE + else: + _mag_data.y = out_data[1] + + if (bmm350_sensor.axis_en & BMM350_EN_Z_MSK) == BMM350_DISABLE: + _mag_data.z = BMM350_DISABLE + else: + _mag_data.z = out_data[2] + + _mag_data.temperature = out_data[3] + + geomagnetic = [None] * 3 + geomagnetic[0] = _mag_data.x + geomagnetic[1] = _mag_data.y + geomagnetic[2] = _mag_data.z + return geomagnetic + + + def get_compass_degree(self): + '''! + @brief Get compass degree + @return Compass degree (0° - 360°) 0° = North, 90° = East, 180° = South, 270° = West. + ''' + magData = self.get_geomagnetic_data() + compass = math.atan2(magData[0], magData[1]) + if compass < 0: + compass += 2 * PI + if compass > 2 * PI: + compass -= 2 * PI + return compass * 180 / M_PI + + + def set_data_ready_pin(self, modes, polarity): + '''! + @brief Enable or disable data ready interrupt pin + @n After enabling, the DRDY pin jump when there's data coming. + @n After disabling, the DRDY pin will not jump when there's data coming. + @n High polarity active on high, the default is low level, which turns to high level when the interrupt is triggered. + @n Low polarity active on low, default is high level, which turns to low level when the interrupt is triggered. + @param modes + @n BMM350_ENABLE_INTERRUPT Enable DRDY + @n BMM350_DISABLE_INTERRUPT Disable DRDY + @param polarity + @n BMM350_ACTIVE_HIGH High polarity + @n BMM350_ACTIVE_LOW Low polarity + ''' + # 1. Gets and sets the interrupt control configuration + reg_data = self.read_reg(BMM350_REG_INT_CTRL, 1) + reg_data[0] = self.BMM350_SET_BITS_POS_0(reg_data[0], BMM350_INT_MODE_MSK, BMM350_INT_MODE_PULSED) + reg_data[0] = self.BMM350_SET_BITS(reg_data[0], BMM350_INT_POL_MSK, BMM350_INT_POL_POS, polarity) + reg_data[0] = self.BMM350_SET_BITS(reg_data[0], BMM350_INT_OD_MSK, BMM350_INT_OD_POS, BMM350_INT_OD_PUSHPULL) + reg_data[0] = self.BMM350_SET_BITS(reg_data[0], BMM350_INT_OUTPUT_EN_MSK, BMM350_INT_OUTPUT_EN_POS, BMM350_MAP_TO_PIN) + reg_data[0] = self.BMM350_SET_BITS(reg_data[0], BMM350_DRDY_DATA_REG_EN_MSK, BMM350_DRDY_DATA_REG_EN_POS, modes) + # 2. Update interrupt control configuration + self.write_reg(BMM350_REG_INT_CTRL, reg_data[0]) + + + def get_data_ready_state(self): + '''! + @brief Get data ready status, determine whether the data is ready + @return status + @n True Data ready + @n False Data is not ready + ''' + int_status_reg = self.read_reg(BMM350_REG_INT_STATUS, 1) + drdy_status = self.BMM350_GET_BITS(int_status_reg[0], BMM350_DRDY_DATA_REG_MSK, BMM350_DRDY_DATA_REG_POS) + if drdy_status & 0x01: + return True + else: + return False + + + def set_threshold_interrupt(self, modes, threshold, polarity): + '''! + @brief Set threshold interrupt, an interrupt is triggered when the geomagnetic value of a channel is beyond/below the threshold + @n High polarity active on high level, the default is low level, which turns to high level when the interrupt is triggered. + @n Low polarity active on low level, the default is high level, which turns to low level when the interrupt is triggered. + @param modes + @n LOW_THRESHOLD_INTERRUPT Low threshold interrupt mode + @n HIGH_THRESHOLD_INTERRUPT High threshold interrupt mode + @param threshold + @n Threshold, default to expand 16 times, for example: under low threshold mode, if the threshold is set to be 1, actually the geomagnetic data below 16 will trigger an interrupt + @param polarity + @n POLARITY_HIGH High polarity + @n POLARITY_LOW Low polarity + ''' + if modes == LOW_THRESHOLD_INTERRUPT: + self.__thresholdMode = LOW_THRESHOLD_INTERRUPT + self.set_data_ready_pin(BMM350_ENABLE_INTERRUPT, polarity) + self.threshold = threshold + else: + self.__thresholdMode = HIGH_THRESHOLD_INTERRUPT + self.set_data_ready_pin(BMM350_ENABLE_INTERRUPT, polarity) + self.threshold = threshold + + + def get_threshold_data(self): + '''! + @brief Get the data that threshold interrupt occured + @return Return the list for storing geomagnetic data, how the data at 3 axis influence interrupt status, + @n [0] The data triggering threshold at x-axis, when the data is NO_DATA, the interrupt is triggered. + @n [1] The data triggering threshold at y-axis, when the data is NO_DATA, the interrupt is triggered. + @n [2] The data triggering threshold at z-axis, when the data is NO_DATA, the interrupt is triggered. + ''' + Data = [NO_DATA] * 3 + state = self.get_data_ready_state() + if state == True: + magData = self.get_geomagnetic_data() + if self.__thresholdMode == LOW_THRESHOLD_INTERRUPT: + if magData[0] < self.threshold*16: + Data[0] = magData[0] + if magData[1] < self.threshold*16: + Data[1] = magData[1] + if magData[2] < self.threshold*16: + Data[2] = magData[2] + elif self.__thresholdMode == HIGH_THRESHOLD_INTERRUPT: + if magData[0] < self.threshold*16: + Data[0] = magData[0] + if magData[1] < self.threshold*16: + Data[1] = magData[1] + if magData[2] < self.threshold*16: + Data[2] = magData[2] + return Data + +# I2C interface +class DFRobot_bmm350_I2C(DFRobot_bmm350): + '''! + @brief An example of an i2c interface module + ''' + def __init__(self, bus, addr): + self.bus = bus + self.__addr = addr + if self.is_raspberrypi(): + import smbus + self.i2cbus = smbus.SMBus(bus) + else: + self.test_platform() + super(DFRobot_bmm350_I2C, self).__init__(self.bus) + + def is_raspberrypi(self): + import io + try: + with io.open('/sys/firmware/devicetree/base/model', 'r') as m: + if 'raspberry pi' in m.read().lower(): return True + except Exception: pass + return False + + def test_platform(self): + import re + import platform + import subprocess + where = platform.system() + if where == "Linux": + p = subprocess.Popen(['i2cdetect', '-l'], stdout=subprocess.PIPE,) + for i in range(0, 25): + line = str(p.stdout.readline()) + s = re.search("i2c-tiny-usb", line) + if s: + line = re.split(r'\W+', line) + bus = int(line[2]) + import smbus + self.i2cbus = smbus.SMBus(bus) + elif where == "Windows": + from i2c_mp_usb import I2C_MP_USB as SMBus + self.i2cbus = SMBus() + else: + print("Platform not supported") + + + + def write_reg(self, reg, data): + '''! + @brief writes data to a register + @param reg register address + @param data written data + ''' + while 1: + try: + self.i2cbus.write_byte_data(self.__addr, reg, data) + return + except: + print("please check connect w!") + time.sleep(1) + return + + def read_reg(self, reg ,len): + '''! + @brief read the data from the register + @param reg register address + @param len read data length + ''' + while True: + try: + # Read data from I2C bus + temp_buf = self.i2cbus.read_i2c_block_data(self.__addr, reg, len + BMM350_DUMMY_BYTES) + # Copy data after dummy byte indices + reg_data = temp_buf[BMM350_DUMMY_BYTES:] + return reg_data # Assuming this function is part of a larger method + except Exception as e: + time.sleep(1) + print("please check connect r!") diff --git a/lib/DFRobot_BMM350/python/raspberrypi/README.md b/lib/DFRobot_BMM350/python/raspberrypi/README.md new file mode 100644 index 0000000..33c89e6 --- /dev/null +++ b/lib/DFRobot_BMM350/python/raspberrypi/README.md @@ -0,0 +1,201 @@ +# DFRobot_bmm350 + +* [中文](./README_CN.md) + +This RaspberryPi BMM350 sensor board can communicate with RaspberryPi via I2C or I3C.
+The BMM350 is capable of obtaining triaxial geomagnetic data.
+ +![产品效果图](../../resources/images/)![产品效果图](../../resources/images/) + +## Product Link([https://www.dfrobot.com](https://www.dfrobot.com)) + SKU: + +## Table of Contents + +* [Summary](#summary) +* [Installation](#installation) +* [Methods](#methods) +* [History](#history) +* [Credits](#credits) + +## Summary + +Get geomagnetic data along the XYZ axis. + +1. This module can obtain high threshold and low threshold geomagnetic data.
+2. Geomagnetism on three(xyz) axes can be measured.
+3. This module can choose I2C or I3C communication mode.
+ + +## Installation + +This Sensor should work with DFRobot_BMM350 on RaspberryPi.
+Run the program: + +``` +$> python3 get_all_state.py +$> python3 data_ready_interrupt.py +$> python3 get_geomagnetic_data.py +$> python3 threshold_interrupt.py +``` + +## Methods + +```python + '''! + @brief Init bmm350 check whether the chip id is right + @return 0 is init success + -1 is init failed + ''' + def sensor_init(self): + + '''! + @brief Soft reset, restore to suspended mode after soft reset. (You need to manually enter the normal mode) + ''' + def soft_reset(self): + + '''! + @brief Sensor self test, the returned character string indicate the self test result. + @return The character string of the test result + ''' + def self_test(self): + + '''! + @brief Set sensor operation mode + @param modes + @n BMM350_SUSPEND_MODE suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + @n BMM350_NORMAL_MODE normal mode: Get geomagnetic data normally. + @n BMM350_FORCED_MODE forced mode: Single measurement, the sensor restores to suspend mode when the measurement is done. + @n BMM350_FORCED_MODE_FAST To reach ODR = 200Hz is only possible by using FM_ FAST. + ''' + def set_operation_mode(self, modes): + + '''! + @brief Get sensor operation mode + @return Return the character string of the operation mode + ''' + def get_operation_mode(self): + + '''! + @brief Set the rate of obtaining geomagnetic data, the higher, the faster (without delay function) + @param rate + @n BMM350_DATA_RATE_1_5625HZ + @n BMM350_DATA_RATE_3_125HZ + @n BMM350_DATA_RATE_6_25HZ + @n BMM350_DATA_RATE_12_5HZ (default rate) + @n BMM350_DATA_RATE_25HZ + @n BMM350_DATA_RATE_50HZ + @n BMM350_DATA_RATE_100HZ + @n BMM350_DATA_RATE_200HZ + @n BMM350_DATA_RATE_400HZ + ''' + def set_rate(self, rates): + + '''! + @brief Get the config data rate, unit: HZ + @return rate + ''' + def get_rate(self): + + '''! + @brief Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) + @param modes + @n BMM350_PRESETMODE_LOWPOWER Low power mode, get a fraction of data and take the mean value. + @n BMM350_PRESETMODE_REGULAR Regular mode, get a number of data and take the mean value. + @n BMM350_PRESETMODE_ENHANCED Enhanced mode, get a plenty of data and take the mean value. + @n BMM350_PRESETMODE_HIGHACCURACY High accuracy mode, get a huge number of data and take the mean value. + + ''' + def set_preset_mode(self, modes): + + '''! + @brief Enable the measurement at x-axis, y-axis and z-axis, default to be enabled. After disabling, the geomagnetic data at x, y, and z axis are wrong. + @param en_x + @n BMM350_X_EN Enable the measurement at x-axis + @n BMM350_X_DIS Disable the measurement at x-axis + @param en_y + @n BMM350_Y_EN Enable the measurement at y-axis + @n BMM350_Y_DIS Disable the measurement at y-axis + @param en_z + @n BMM350_Z_EN Enable the measurement at z-axis + @n BMM350_Z_DIS Disable the measurement at z-axis + ''' + def set_measurement_XYZ(self, en_x = BMM350_X_EN, en_y = BMM350_Y_EN, en_z = BMM350_Z_EN): + + '''! + @brief Get the enabling status at x-axis, y-axis and z-axis + @return Return enabling status at x-axis, y-axis and z-axis as a character string + ''' + def get_measurement_state_XYZ(self): + + '''! + @brief Get the geomagnetic data of 3 axis (x, y, z) + @return The list of the geomagnetic data at 3 axis (x, y, z) unit: uT + @ [0] The geomagnetic data at x-axis + @ [1] The geomagnetic data at y-axis + @ [2] The geomagnetic data at z-axis + ''' + def get_geomagnetic_data(self): + + '''! + @brief Get compass degree + @return Compass degree (0° - 360°) 0° = North, 90° = East, 180° = South, 270° = West. + ''' + def get_compass_degree(self): + + '''! + @brief Enable or disable data ready interrupt pin + @n After enabling, the DRDY pin jump when there's data coming. + @n After disabling, the DRDY pin will not jump when there's data coming. + @n High polarity: active on high, the default is low level, which turns to high level when the interrupt is triggered. + @n Low polarity: active on low, default is high level, which turns to low level when the interrupt is triggered. + @param modes + @n BMM350_ENABLE_INTERRUPT Enable DRDY + @n BMM350_DISABLE_INTERRUPT Disable DRDY + @param polarity + @n BMM350_ACTIVE_HIGH High polarity + @n BMM350_ACTIVE_LOW Low polarity + ''' + def set_data_ready_pin(self, modes, polarity): + + '''! + @brief Get data ready status, determine whether the data is ready + @return status + @n True Data ready + @n False Data is not ready + ''' + def get_data_ready_state(self): + + '''! + @brief Set threshold interrupt, an interrupt is triggered when the geomagnetic value of a channel is beyond/below the threshold + @n High polarity: active on high level, the default is low level, which turns to high level when the interrupt is triggered. + @n Low polarity: active on low level, the default is high level, which turns to low level when the interrupt is triggered. + @param modes + @n LOW_THRESHOLD_INTERRUPT Low threshold interrupt mode + @n HIGH_THRESHOLD_INTERRUPT High threshold interrupt mode + @param threshold + @n Threshold, default to expand 16 times, for example: under low threshold mode, if the threshold is set to be 1, actually the geomagnetic data below 16 will trigger an interrupt + @param polarity + @n POLARITY_HIGH High polarity + @n POLARITY_LOW Low polarity + ''' + def set_threshold_interrupt(self, modes, threshold, polarity): + + '''! + @brief Get the data that threshold interrupt occured + @return Return the list for storing geomagnetic data, how the data at 3 axis influence interrupt status, + @n [0] The data triggering threshold at x-axis, when the data is NO_DATA, the interrupt is triggered. + @n [1] The data triggering threshold at y-axis, when the data is NO_DATA, the interrupt is triggered. + @n [2] The data triggering threshold at z-axis, when the data is NO_DATA, the interrupt is triggered. + ''' + def get_threshold_data(self): +``` + +## History + +- 2024/05/11 - Version 1.0.0 released. + +## Credits + +Written by [GDuang](yonglei.ren@dfrobot.com), 2024. (Welcome to our website) diff --git a/lib/DFRobot_BMM350/python/raspberrypi/README_CN.md b/lib/DFRobot_BMM350/python/raspberrypi/README_CN.md new file mode 100644 index 0000000..71331e8 --- /dev/null +++ b/lib/DFRobot_BMM350/python/raspberrypi/README_CN.md @@ -0,0 +1,218 @@ +# DFRobot_bmm350 + +- [English Version](./README.md) + +BMM350 是一款低功耗、低噪声的 3 轴数字地磁传感器,完全符合罗盘应用的要求。 基于博世专有的 FlipCore 技术,BMM350 提供了高精度和动态的绝对空间方向和运动矢量。 体积小、重量轻,特别适用于支持无人机精准航向。 BMM350 还可与由 3 轴加速度计和 3 轴陀螺仪组成的惯性测量单元一起使用。 + +![产品效果图](../../resources/images)![产品效果图](../../resources/images) + + +## 产品链接([https://www.dfrobot.com.cn](https://www.dfrobot.com.cn)) + SKU: + +## 目录 + + * [概述](#概述) + * [库安装](#库安装) + * [方法](#方法) + * [兼容性](#兼容性) + * [历史](#历史) + * [创作者](#创作者) + +## 概述 + +您可以沿 XYZ 轴获取地磁数据 + +1. 本模块可以获得高阈值和低阈值地磁数据。
+2. 可以测量三个(xyz)轴上的地磁。
+3. 本模块可选择I2C或I3C通讯方式。
+ + +## 库安装 +1. 下载库至树莓派,要使用这个库,首先要将库下载到Raspberry Pi,命令下载方法如下:
+```python +sudo git clone https://github.com/DFRobot/DFRobot_BMM350 +``` +2. 打开并运行例程,要执行一个例程demo_x.py,请在命令行中输入python demo_x.py。例如,要执行data_ready_interrupt.py例程,你需要输入:
+ +```python +python3 data_ready_interrupt.py +``` + +## 方法 + +```python + '''! + @brief 初始化bmm350 判断芯片id是否正确 + @return 0 is init success + @n -1 is init failed + ''' + def sensor_init(self): + + '''! + @brief 软件复位,软件复位后先恢复为挂起模式(需手动进行普通模式) + ''' + def soft_reset(self): + + '''! + @brief 传感器自测,返回字符串表明自检结果 + @return 测试结果的字符串 + ''' + def self_test(self): + + '''! + @brief 设置传感器的执行模式 + @param modes + @n BMM350_SUSPEND_MODE 挂起模式: 挂起模式是芯片上电后BMM350的默认电源模式,在挂起模式下电流消耗最小,因此,这种模式在不需要进行数据转换时非常有用。所有寄存器的读写是可能的 + @n BMM350_NORMAL_MODE 普通模式: 正常获取地磁数据 + @n BMM350_FORCED_MODE 强制模式: 单次测量,测量完成后传感器恢复到暂停模式 + @n BMM350_FORCED_MODE_FAST 只有使用FM_ FAST才能达到ODR = 200Hz + ''' + def set_operation_mode(self, modes): + + '''! + @brief 获取传感器的执行模式 + @return 返回模式的字符串 + ''' + def get_operation_mode(self): + + '''! + @brief 设置地磁数据获取的速率,速率越大获取越快(不加延时函数) + @param rate + @n BMM350_DATA_RATE_1_5625HZ + @n BMM350_DATA_RATE_3_125HZ + @n BMM350_DATA_RATE_6_25HZ + @n BMM350_DATA_RATE_12_5HZ (default rate) + @n BMM350_DATA_RATE_25HZ + @n BMM350_DATA_RATE_50HZ + @n BMM350_DATA_RATE_100HZ + @n BMM350_DATA_RATE_200HZ + @n BMM350_DATA_RATE_400HZ + ''' + def set_rate(self, rates): + + '''! + @brief 获取配置的数据速率 单位:HZ + @return rate + ''' + def get_rate(self): + + '''! + @brief 设置预置模式,使用户更简单的配置传感器来获取地磁数据 (默认的采集速率为12.5Hz) + @param modes + @n BMM350_PRESETMODE_LOWPOWER 低功率模式,获取少量的数据 取均值 + @n BMM350_PRESETMODE_REGULAR 普通模式,获取中量数据 取均值 + @n BMM350_PRESETMODE_ENHANCED 增强模式,获取大量数据 取均值 + @n BMM350_PRESETMODE_HIGHACCURACY 高精度模式,获取超大量数据 取均值 + ''' + def set_preset_mode(self, modes): + + '''! + @brief 使能x y z 轴的测量,默认设置为使能不需要配置,禁止后xyz轴的地磁数据不准确 + @param en_x + @n BMM350_X_EN 使能 x 轴的测量 + @n BMM350_X_DIS 禁止 x 轴的测量 + @param channel_y + @n BMM350_Y_EN 使能 y 轴的测量 + @n BMM350_Y_DIS 禁止 y 轴的测量 + @param channel_z + @n BMM350_Z_EN 使能 z 轴的测量 + @n BMM350_Z_DIS 禁止 z 轴的测量 + ''' + def set_measurement_XYZ(self, en_x = BMM350_X_EN, en_y = BMM350_Y_EN, en_z = BMM350_Z_EN): + + '''! + @brief 获取 x y z 轴的使能状态 + @return 返回xyz 轴的使能状态的字符串 + ''' + def get_measurement_state_XYZ(self): + + '''! + @brief 获取x y z 三轴的地磁数据 + @return x y z 三轴的地磁数据的列表 单位:微特斯拉(uT) + @n [0] x 轴地磁的数据 + @n [1] y 轴地磁的数据 + @n [2] z 轴地磁的数据 + ''' + def get_geomagnetic_data(self): + + '''! + @brief 获取罗盘方向 + @return 罗盘方向 (0° - 360°) 0° = North, 90° = East, 180° = South, 270° = West. + ''' + def get_compass_degree(self): + + '''! + @brief 使能或者禁止数据准备中断引脚 + @n 使能后有数据来临DRDY引脚跳变 + @n 禁止后有数据来临DRDY不进行跳变 + @n 高极性:高电平为活动电平,默认为低电平,触发中断时电平变为高 + @n 低极性:低电平为活动电平,默认为高电平,触发中断时电平变为低 + @param modes + @n BMM350_ENABLE_INTERRUPT 使能DRDY + @n BMM350_DISABLE_INTERRUPT 禁止DRDY + @param polarity + @n BMM350_ACTIVE_HIGH 高极性 + @n BMM350_ACTIVE_LOW 低极性 + ''' + def set_data_ready_pin(self, modes, polarity): + + '''! + @brief 获取数据准备的状态,用来判断数据是否准备好 + @return status + @n True 表示数据已准备好 + @n False 表示数据还未准备好 + ''' + def get_data_ready_state(self): + + '''! + @brief 设置阈值中断,当某个通道的地磁值高/低于阈值时触发中断 + @n 高极性:高电平为活动电平,默认为低电平,触发中断时电平变为高 + @n 低极性:低电平为活动电平,默认为高电平,触发中断时电平变为低 + @param modes + @n LOW_THRESHOLD_INTERRUPT 低阈值中断模式 + @n HIGH_THRESHOLD_INTERRUPT 高阈值中断模式 + @param threshold 阈值,默认扩大16倍,例如:低阈值模式下传入阈值1,实际低于16的地磁数据都会触发中断 + @param polarity + @n POLARITY_HIGH 高极性 + @n POLARITY_LOW 低极性 + ''' + def set_threshold_interrupt(self, modes, threshold, polarity): + + '''! + @brief 获取发生阈值中断的数据 + @return 返回存放地磁数据的列表,列表三轴当数据和中断状态, + @n [0] x 轴触发阈值的数据 ,当数据为NO_DATA时为触发中断 + @n [1] y 轴触发阈值的数据 ,当数据为NO_DATA时为触发中断 + @n [2] z 轴触发阈值的数据 ,当数据为NO_DATA时为触发中断 + ''' + def get_threshold_data(self): +``` + +## 兼容性 + +| 主板 | 通过 | 未通过 | 未测试 | 备注 | +| ------------ | :--: | :----: | :----: | :--: | +| RaspberryPi2 | | | √ | | +| RaspberryPi3 | | | √ | | +| RaspberryPi4 | √ | | | | + +* Python 版本 + +| Python | 通过 | 未通过 | 未测试 | 备注 | +| ------- | :--: | :----: | :----: | ---- | +| Python3 | √ | | | | + +## 历史 + +- 2024/05/11 - 1.0.0 版本 + +## 创作者 + +Written by [GDuang](yonglei.ren@dfrobot.com), 2024. (Welcome to our [website](https://www.dfrobot.com/)) + + + + + + diff --git a/lib/DFRobot_BMM350/python/raspberrypi/examples/data_ready_interrupt.py b/lib/DFRobot_BMM350/python/raspberrypi/examples/data_ready_interrupt.py new file mode 100644 index 0000000..3bd60c3 --- /dev/null +++ b/lib/DFRobot_BMM350/python/raspberrypi/examples/data_ready_interrupt.py @@ -0,0 +1,111 @@ +# -*- coding:utf-8 -*- +''' + @file demo_data_ready_interrupt.py + @brief Data ready interrupt, DRDY interrupt will be triggered when the geomagnetic data is ready (the software and hardware can determine whether the interrupt occur) + @n Experimental phenomenon: serial print the geomagnetic data at x-axis, y-axis and z-axis, unit (uT) + @n Experimental phenomenon: the main controller interrupt will be triggered by level change caused by DRDY pin interrupt, then the geomagnetic data can be obtained. + @n Connect the sensor DADY pin to the interrupt pin (RASPBERR_PIN_DRDY) of the main controller + @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) + @license The MIT License (MIT) + @author [GDuang](yonglei.ren@dfrobot.com) + @version V1.0.0 + @date 2024-05-11 + @url https://github.com/DFRobot/DFRobot_BMM350 +''' +import sys +import os + +sys.path.append(os.path.dirname(os.path.dirname(os.path.realpath(__file__)))) +from DFRobot_bmm350 import * + +''' + If you want to use I2C to drive this module, uncomment the codes below, and connect the module with Raspberry Pi via I2C port + Connect to VCC, GND, SCL, SDA pin +''' +I2C_BUS = 0x01 #default use I2C1 +bmm350 = DFRobot_bmm350_I2C(I2C_BUS, 0x14) + +def setup(): + while BMM350_CHIP_ID_ERROR == bmm350.sensor_init(): + print("sensor init error, please check connect") + time.sleep(1) + + ''' + Set sensor operation mode + opMode: + BMM350_SUSPEND_MODE suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + BMM350_NORMAL_MODE normal mode: Get geomagnetic data normally. + BMM350_FORCED_MODE forced mode: Single measurement, the sensor restores to suspend mode when the measurement is done. + BMM350_FORCED_MODE_FAST To reach ODR = 200Hz is only possible by using FM_ FAST. + ''' + bmm350.set_operation_mode(BMM350_NORMAL_MODE) + + ''' + Get the operation mode character string of the sensor + ''' + print('Current power mode: ', bmm350.get_operation_mode()) + + ''' + Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) + presetMode: + BMM350_PRESETMODE_LOWPOWER Low power mode, get a small number of data and draw the mean value. + BMM350_PRESETMODE_REGULAR Regular mode, get a number of data and draw the mean value. + BMM350_PRESETMODE_ENHANCED Enhanced mode, get a large number of data and draw the mean value. + BMM350_PRESETMODE_HIGHACCURACY High accuracy mode, get a huge number of data and draw the mean value. + rate: + BMM350_DATA_RATE_1_5625HZ + BMM350_DATA_RATE_3_125HZ + BMM350_DATA_RATE_6_25HZ + BMM350_DATA_RATE_12_5HZ (default rate) + BMM350_DATA_RATE_25HZ + BMM350_DATA_RATE_50HZ + BMM350_DATA_RATE_100HZ + BMM350_DATA_RATE_200HZ + BMM350_DATA_RATE_400HZ + ''' + bmm350.set_preset_mode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ) + + ''' + Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required. When disabled, the geomagnetic data at x, y, and z will be inaccurate. + Refer to readme file if you want to configure more parameters. + ''' + bmm350.set_measurement_XYZ() + + ''' + Enable or disable data ready interrupt pin + After enabling, the pin DRDY signal jump when there's data coming. + After disabling, the pin DRDY signal does not jump when there's data coming. + High polarity: active on high, the default is low level, which turns to high level when the interrupt is triggered. + Low polarity: active on low, the default is high level, which turns to low level when the interrupt is triggered. + modes: + BMM350_ENABLE_INTERRUPT Enable DRDY + BMM350_DISABLE_INTERRUPT Disable DRDY + polarity: + BMM350_ACTIVE_HIGH High polarity + BMM350_ACTIVE_LOW Low polarity + ''' + bmm350.set_data_ready_pin(BMM350_ENABLE_INTERRUPT, BMM350_ACTIVE_LOW) + + +def loop(): + ''' + Get data ready status, determine whether the data is ready (through software) + status: + True Data ready + False Data is not ready yet + ''' + if bmm350.get_data_ready_state() == 1: + rslt = bmm350.get_geomagnetic_data() + print("mag x = %d ut"%rslt[0]) + print("mag y = %d ut"%rslt[1]) + print("mag z = %d ut"%rslt[2]) + print("") + else: + time.sleep(1) + + +if __name__ == "__main__": + setup() + while True: + loop() diff --git a/lib/DFRobot_BMM350/python/raspberrypi/examples/demo_data_ready_interrupt.py b/lib/DFRobot_BMM350/python/raspberrypi/examples/demo_data_ready_interrupt.py new file mode 100644 index 0000000..f7e1110 --- /dev/null +++ b/lib/DFRobot_BMM350/python/raspberrypi/examples/demo_data_ready_interrupt.py @@ -0,0 +1,112 @@ +# -*- coding:utf-8 -*- +''' + @file demo_data_ready_interrupt.py + @brief Data ready interrupt, DRDY interrupt will be triggered when the geomagnetic data is ready (the software and hardware can determine whether the interrupt occur) + @n Experimental phenomenon: serial print the geomagnetic data at x-axis, y-axis and z-axis, unit (uT) + @n Experimental phenomenon: the main controller interrupt will be triggered by level change caused by DRDY pin interrupt, then the geomagnetic data can be obtained. + @n Connect the sensor DADY pin to the interrupt pin (RASPBERR_PIN_DRDY) of the main controller + @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) + @license The MIT License (MIT) + @author [GDuang](yonglei.ren@dfrobot.com) + @version V1.0.0 + @date 2024-05-11 + @url https://github.com/DFRobot/DFRobot_BMM350 +''' +import sys +import os + +sys.path.append(os.path.dirname(os.path.dirname(os.path.realpath(__file__)))) +from DFRobot_bmm350 import * + +''' + If you want to use I2C to drive this module, uncomment the codes below, and connect the module with Raspberry Pi via I2C port + Connect to VCC,GND,SCL,SDA pin +''' +I2C_BUS = 0x01 #default use I2C1 +bmm350 = DFRobot_bmm350_I2C(I2C_BUS, 0x14) + +def setup(): + while BMM350_CHIP_ID_ERROR == bmm350.sensor_init(): + print("sensor init error, please check connect") + time.sleep(1) + + ''' + Set sensor operation mode + opMode: + BMM350_SUSPEND_MODE suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + BMM350_NORMAL_MODE normal mode: Get geomagnetic data normally. + BMM350_FORCED_MODE forced mode: Single measurement, the sensor restores to suspend mode when the measurement is done. + BMM350_FORCED_MODE_FAST To reach ODR = 200Hz is only possible by using FM_ FAST. + ''' + bmm350.set_operation_mode(BMM350_NORMAL_MODE) + + ''' + Get the operation mode character string of the sensor + ''' + print('Current power mode: ', bmm350.get_operation_mode()) + + ''' + Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) + presetMode: + BMM350_PRESETMODE_LOWPOWER Low power mode, get a small number of data and draw the mean value. + BMM350_PRESETMODE_REGULAR Regular mode, get a number of data and draw the mean value. + BMM350_PRESETMODE_ENHANCED Enhanced mode, get a large number of data and draw the mean value. + BMM350_PRESETMODE_HIGHACCURACY High accuracy mode, get a huge number of data and draw the mean value. + rate: + BMM350_DATA_RATE_1_5625HZ + BMM350_DATA_RATE_3_125HZ + BMM350_DATA_RATE_6_25HZ + BMM350_DATA_RATE_12_5HZ (default rate) + BMM350_DATA_RATE_25HZ + BMM350_DATA_RATE_50HZ + BMM350_DATA_RATE_100HZ + BMM350_DATA_RATE_200HZ + BMM350_DATA_RATE_400HZ + ''' + bmm350.set_preset_mode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ) + + + ''' + Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required. When disabled, the geomagnetic data at x, y, and z will be inaccurate. + Refer to readme file if you want to configure more parameters. + ''' + bmm350.set_measurement_XYZ() + + ''' + Enable or disable data ready interrupt pin + After enabling, the pin DRDY signal jump when there's data coming. + After disabling, the pin DRDY signal does not jump when there's data coming. + High polarity: active on high, the default is low level, which turns to high level when the interrupt is triggered. + Low polarity: active on low, the default is high level, which turns to low level when the interrupt is triggered. + modes: + BMM350_ENABLE_INTERRUPT Enable DRDY + BMM350_DISABLE_INTERRUPT Disable DRDY + polarity: + BMM350_ACTIVE_HIGH High polarity + BMM350_ACTIVE_LOW Low polarity + ''' + bmm350.set_data_ready_pin(BMM350_ENABLE_INTERRUPT, BMM350_ACTIVE_LOW) + + +def loop(): + ''' + Get data ready status, determine whether the data is ready (through software) + status: + True Data ready + False Data is not ready yet + ''' + if bmm350.get_data_ready_state() == 1: + rslt = bmm350.get_geomagnetic_data() + print("mag x = %d ut"%rslt[0]) + print("mag y = %d ut"%rslt[1]) + print("mag z = %d ut"%rslt[2]) + print("") + else: + time.sleep(1) + + +if __name__ == "__main__": + setup() + while True: + loop() diff --git a/lib/DFRobot_BMM350/python/raspberrypi/examples/demo_get_all_state.py b/lib/DFRobot_BMM350/python/raspberrypi/examples/demo_get_all_state.py new file mode 100644 index 0000000..7faa65e --- /dev/null +++ b/lib/DFRobot_BMM350/python/raspberrypi/examples/demo_get_all_state.py @@ -0,0 +1,107 @@ +# -*- coding:utf-8 -*- +''' + @file demo_get_all_state.py + @brief Get all the config and self test status, the sensor can change from normal mode to sleep mode after soft reset + @n Experimental phenomenon: the sensor config and self test information are printed in the serial port. + @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) + @license The MIT License (MIT) + @author [GDuang](yonglei.ren@dfrobot.com) + @version V1.0.0 + @date 2024-05-11 + @url https://github.com/DFRobot/DFRobot_BMM350 +''' +import sys +import os + +sys.path.append(os.path.dirname(os.path.dirname(os.path.realpath(__file__)))) +from DFRobot_bmm350 import * + + +''' + If you want to use I2C to drive this module, uncomment the codes below, and connect the module with Raspberry Pi via I2C port + Connect to VCC,GND,SCL,SDA pin +''' +I2C_BUS = 0x01 #default use I2C1 +bmm350 = DFRobot_bmm350_I2C(I2C_BUS, 0x14) + +def setup(): + while BMM350_CHIP_ID_ERROR == bmm350.sensor_init(): + print("sensor init error, please check connect") + time.sleep(1) + + print('Power mode after sensor initialization: ', bmm350.get_operation_mode()) + + ''' + Sensor self test, the returned character string indicates the test result. + ''' + print(bmm350.self_test()) + + ''' + Set sensor operation mode + opMode: + BMM350_SUSPEND_MODE suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + BMM350_NORMAL_MODE normal mode: Get geomagnetic data normally. + BMM350_FORCED_MODE forced mode: Single measurement, the sensor restores to suspend mode when the measurement is done. + BMM350_FORCED_MODE_FAST To reach ODR = 200Hz is only possible by using FM_ FAST. + ''' + bmm350.set_operation_mode(BMM350_NORMAL_MODE) + + ''' + Get the operation mode character string of the sensor + ''' + print('Current power mode: ', bmm350.get_operation_mode()) + + ''' + Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) + presetMode: + BMM350_PRESETMODE_LOWPOWER Low power mode, get a small number of data and draw the mean value. + BMM350_PRESETMODE_REGULAR Regular mode, get a number of data and draw the mean value. + BMM350_PRESETMODE_ENHANCED Enhanced mode, get a large number of data and draw the mean value. + BMM350_PRESETMODE_HIGHACCURACY High accuracy mode, get a huge number of data and draw the mean value. + rate: + BMM350_DATA_RATE_1_5625HZ + BMM350_DATA_RATE_3_125HZ + BMM350_DATA_RATE_6_25HZ + BMM350_DATA_RATE_12_5HZ (default rate) + BMM350_DATA_RATE_25HZ + BMM350_DATA_RATE_50HZ + BMM350_DATA_RATE_100HZ + BMM350_DATA_RATE_200HZ + BMM350_DATA_RATE_400HZ + ''' + bmm350.set_preset_mode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ) + ''' + Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required. When disabled, the geomagnetic data at x, y, and z will be inaccurate. + Refer to readme file if you want to configure more parameters. + ''' + bmm350.set_measurement_XYZ() + + ''' + Get the config data rate unit: HZ + ''' + print("rates is %d HZ"%bmm350.get_rate() ) + + ''' + Get the character string of enabling status at x-axis, y-axis and z-axis + ''' + print(bmm350.get_measurement_state_XYZ()) + + ''' + @brief Soft reset, restore to suspended mode after soft reset. (You need to manually enter the normal mode) + ''' + bmm350.soft_reset() + print('Power mode after software reset: ', bmm350.get_operation_mode()) + +def loop(): + ''' + Get the operation mode character string of the sensor + ''' + print('Current power mode: ', bmm350.get_operation_mode()) + exit() + + +if __name__ == "__main__": + setup() + while True: + loop() diff --git a/lib/DFRobot_BMM350/python/raspberrypi/examples/demo_get_geomagnetic_data.py b/lib/DFRobot_BMM350/python/raspberrypi/examples/demo_get_geomagnetic_data.py new file mode 100644 index 0000000..f64ffcf --- /dev/null +++ b/lib/DFRobot_BMM350/python/raspberrypi/examples/demo_get_geomagnetic_data.py @@ -0,0 +1,90 @@ +# -*- coding:utf-8 -*- +''' + @file demo_get_geomagnetic_data.py + @brief Get the geomagnetic data at 3 axis (x, y, z), get the compass degree + @n "Compass Degree", the angle formed when the needle rotates counterclockwise from the current position to the true north + @n Experimental phenomenon: serial print the geomagnetic data at x-axis, y-axis and z-axis and the angle formed when the needle rotates counterclockwise from the current position to the true north + @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) + @license The MIT License (MIT) + @author [GDuang](yonglei.ren@dfrobot.com) + @version V1.0.0 + @date 2024-05-11 + @url https://github.com/DFRobot/DFRobot_BMM350 +''' +import sys +import os + +sys.path.append(os.path.dirname(os.path.dirname(os.path.realpath(__file__)))) +from DFRobot_bmm350 import * + +''' + If you want to use I2C to drive this module, uncomment the codes below, and connect the module with Raspberry Pi via I2C port + Connect to VCC,GND,SCL,SDA pin +''' +I2C_BUS = 0x01 #default use I2C1 +bmm350 = DFRobot_bmm350_I2C(I2C_BUS, 0x14) + +def setup(): + while BMM350_CHIP_ID_ERROR == bmm350.sensor_init(): + print("sensor init error, please check connect") + time.sleep(1) + + ''' + Set sensor operation mode + opMode: + BMM350_SUSPEND_MODE suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + BMM350_NORMAL_MODE normal mode: Get geomagnetic data normally. + BMM350_FORCED_MODE forced mode: Single measurement, the sensor restores to suspend mode when the measurement is done. + BMM350_FORCED_MODE_FAST To reach ODR = 200Hz is only possible by using FM_ FAST. + ''' + bmm350.set_operation_mode(BMM350_NORMAL_MODE) + + ''' + Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) + presetMode: + BMM350_PRESETMODE_LOWPOWER Low power mode, get a small number of data and draw the mean value. + BMM350_PRESETMODE_REGULAR Regular mode, get a number of data and draw the mean value. + BMM350_PRESETMODE_ENHANCED Enhanced mode, get a large number of data and draw the mean value. + BMM350_PRESETMODE_HIGHACCURACY High accuracy mode, get a huge number of data and draw the mean value. + rate: + BMM350_DATA_RATE_1_5625HZ + BMM350_DATA_RATE_3_125HZ + BMM350_DATA_RATE_6_25HZ + BMM350_DATA_RATE_12_5HZ (default rate) + BMM350_DATA_RATE_25HZ + BMM350_DATA_RATE_50HZ + BMM350_DATA_RATE_100HZ + BMM350_DATA_RATE_200HZ + BMM350_DATA_RATE_400HZ + ''' + bmm350.set_preset_mode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ) + + + ''' + Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required. When disabled, the geomagnetic data at x, y, and z will be inaccurate. + Refer to readme file if you want to configure more parameters. + ''' + bmm350.set_measurement_XYZ() + +def loop(): + geomagnetic = bmm350.get_geomagnetic_data() + print("mag x = %d ut"%geomagnetic[0]) + print("mag y = %d ut"%geomagnetic[1]) + print("mag z = %d ut"%geomagnetic[2]) + + # get float type data + # geomagnetic = bmm350.get_geomagnetic_data() + # print("---------------------------------") + # print("mag x = %.2f ut"%geomagnetic[0]) + # print("mag y = %.2f ut"%geomagnetic[1]) + # print("mag z = %.2f ut"%geomagnetic[2]) + degree = bmm350.get_compass_degree() + print("---------------------------------") + print("the angle between the pointing direction and north (counterclockwise) is: %.2f "%degree) + time.sleep(1) + +if __name__ == "__main__": + setup() + while True: + loop() diff --git a/lib/DFRobot_BMM350/python/raspberrypi/examples/demo_threshold_interrupt.py b/lib/DFRobot_BMM350/python/raspberrypi/examples/demo_threshold_interrupt.py new file mode 100644 index 0000000..2b4434e --- /dev/null +++ b/lib/DFRobot_BMM350/python/raspberrypi/examples/demo_threshold_interrupt.py @@ -0,0 +1,115 @@ +# -*- coding:utf-8 -*- +''' + @file demo_threshold_interrupt.py + @brief Set the interrupt to be triggered when beyond/below threshold, when the interrupt at a axis occur, the data will be printed in the serial port. + @n When the geomagnetic data at 3 axis (x, y, z) beyond/below the set threshold, the data will be printed in the serial port, unit (uT) + @n Experimental phenomenon: the main controller interrupt will be triggered by level change caused by INT pin interrupt, then the geomagnetic data can be obtained + @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) + @license The MIT License (MIT) + @author [GDuang](yonglei.ren@dfrobot.com) + @version V1.0.0 + @date 2024-05-11 + @url https://github.com/DFRobot/DFRobot_BMM350 +''' +import sys +import os + +sys.path.append(os.path.dirname(os.path.dirname(os.path.realpath(__file__)))) +from DFRobot_bmm350 import * + +''' + If you want to use I2C to drive this module, uncomment the codes below, and connect the module with Raspberry Pi via I2C port + Connect to VCC,GND,SCL,SDA pin +''' +I2C_BUS = 0x01 #default use I2C1 +bmm350 = DFRobot_bmm350_I2C(I2C_BUS, 0x14) + +def setup(): + while BMM350_CHIP_ID_ERROR == bmm350.sensor_init(): + print("sensor init error ,please check connect") + time.sleep(1) + + ''' + Set sensor operation mode + opMode: + BMM350_SUSPEND_MODE suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + BMM350_NORMAL_MODE normal mode: Get geomagnetic data normally. + BMM350_FORCED_MODE forced mode: Single measurement, the sensor restores to suspend mode when the measurement is done. + BMM350_FORCED_MODE_FAST To reach ODR = 200Hz is only possible by using FM_ FAST. + ''' + bmm350.set_operation_mode(BMM350_NORMAL_MODE) + + ''' + Get the operation mode character string of the sensor + ''' + print('Current power mode: ', bmm350.get_operation_mode()) + + ''' + Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) + presetMode: + BMM350_PRESETMODE_LOWPOWER Low power mode, get a small number of data and draw the mean value. + BMM350_PRESETMODE_REGULAR Regular mode, get a number of data and draw the mean value. + BMM350_PRESETMODE_ENHANCED Enhanced mode, get a large number of data and draw the mean value. + BMM350_PRESETMODE_HIGHACCURACY High accuracy mode, get a huge number of data and draw the mean value. + rate: + BMM350_DATA_RATE_1_5625HZ + BMM350_DATA_RATE_3_125HZ + BMM350_DATA_RATE_6_25HZ + BMM350_DATA_RATE_12_5HZ (default rate) + BMM350_DATA_RATE_25HZ + BMM350_DATA_RATE_50HZ + BMM350_DATA_RATE_100HZ + BMM350_DATA_RATE_200HZ + BMM350_DATA_RATE_400HZ + ''' + bmm350.set_preset_mode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ) + + ''' + Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required. When disabled, the geomagnetic data at x, y, and z will be inaccurate. + Refer to readme file if you want to configure more parameters. + ''' + bmm350.set_measurement_XYZ() + + + ''' + Set threshold interrupt, an interrupt is triggered when the geomagnetic value of a channel is beyond/below the threshold + High polarity: active on high, the default is low level, which turns to high level when the interrupt is triggered. + Low polarity: active on low, the default is high level, which turns to low level when the interrupt is triggered. + modes: + LOW_THRESHOLD_INTERRUPT Low threshold interrupt mode, interrupt is triggered when below the threshold + HIGH_THRESHOLD_INTERRUPT High threshold interrupt mode, interrupt is triggered when beyond the threshold + threshold + Threshold range, default to expand 16 times, for example: under low threshold mode, if the threshold is set to be 1, actually the geomagnetic data below 16 will trigger an interrupt + polarity: + BMM350_ACTIVE_HIGH High polarity + BMM350_ACTIVE_LOW Low polarity + View the use method in the readme file if you want to use more configs + ''' + bmm350.set_threshold_interrupt(LOW_THRESHOLD_INTERRUPT, 0, BMM350_ACTIVE_LOW) + + +def loop(): + ''' + Get the data that threshold interrupt occured (get the threshold interrupt status through software) + That the data at (x, y, z) axis are printed in the serial port indicates threshold interrupt occur at (x, y, z) axis + Return the list for storing geomagnetic data, how the data at 3 axis influence interrupt status + [0] The data triggering threshold at x-axis, when the data is NO_DATA, the interrupt is triggered. + [1] The data triggering threshold at y-axis, when the data is NO_DATA, the interrupt is triggered. + [2] The data triggering threshold at z-axis, when the data is NO_DATA, the interrupt is triggered. + ''' + threshold_data = bmm350.get_threshold_data() + if threshold_data[0] != NO_DATA: + print("mag x = %d ut"%threshold_data[0]) + if threshold_data[1] != NO_DATA: + print("mag y = %d ut"%threshold_data[1]) + if threshold_data[2] != NO_DATA: + print("mag z = %d ut"%threshold_data[2]) + print("") + time.sleep(1) + + +if __name__ == "__main__": + setup() + while True: + loop() diff --git a/lib/DFRobot_BMM350/python/raspberrypi/examples/get_all_state.py b/lib/DFRobot_BMM350/python/raspberrypi/examples/get_all_state.py new file mode 100644 index 0000000..36023cc --- /dev/null +++ b/lib/DFRobot_BMM350/python/raspberrypi/examples/get_all_state.py @@ -0,0 +1,108 @@ +# -*- coding:utf-8 -*- +''' + @file demo_get_all_state.py + @brief Get all the config and self test status, the sensor can change from normal mode to sleep mode after soft reset + @n Experimental phenomenon: the sensor config and self test information are printed in the serial port. + @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) + @license The MIT License (MIT) + @author [GDuang](yonglei.ren@dfrobot.com) + @version V1.0.0 + @date 2024-05-11 + @url https://github.com/DFRobot/DFRobot_BMM350 +''' +import sys +import os + +sys.path.append(os.path.dirname(os.path.dirname(os.path.realpath(__file__)))) +from DFRobot_bmm350 import * + + +''' + If you want to use I2C to drive this module, uncomment the codes below, and connect the module with Raspberry Pi via I2C port + Connect to VCC, GND, SCL, SDA pin +''' +I2C_BUS = 0x01 #default use I2C1 +bmm350 = DFRobot_bmm350_I2C(I2C_BUS, 0x14) + +def setup(): + while BMM350_CHIP_ID_ERROR == bmm350.sensor_init(): + print("sensor init error, please check connect") + time.sleep(1) + + print('Power mode after sensor initialization: ', bmm350.get_operation_mode()) + + ''' + Sensor self test, the returned character string indicates the test result. + ''' + print(bmm350.self_test()) + + ''' + Set sensor operation mode + opMode: + BMM350_SUSPEND_MODE suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + BMM350_NORMAL_MODE normal mode: Get geomagnetic data normally. + BMM350_FORCED_MODE forced mode: Single measurement, the sensor restores to suspend mode when the measurement is done. + BMM350_FORCED_MODE_FAST To reach ODR = 200Hz is only possible by using FM_ FAST. + ''' + bmm350.set_operation_mode(BMM350_NORMAL_MODE) + + ''' + Get the operation mode character string of the sensor + ''' + print('Current power mode: ', bmm350.get_operation_mode()) + + ''' + Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) + presetMode: + BMM350_PRESETMODE_LOWPOWER Low power mode, get a small number of data and draw the mean value. + BMM350_PRESETMODE_REGULAR Regular mode, get a number of data and draw the mean value. + BMM350_PRESETMODE_ENHANCED Enhanced mode, get a large number of data and draw the mean value. + BMM350_PRESETMODE_HIGHACCURACY High accuracy mode, get a huge number of data and draw the mean value. + rate: + BMM350_DATA_RATE_1_5625HZ + BMM350_DATA_RATE_3_125HZ + BMM350_DATA_RATE_6_25HZ + BMM350_DATA_RATE_12_5HZ (default rate) + BMM350_DATA_RATE_25HZ + BMM350_DATA_RATE_50HZ + BMM350_DATA_RATE_100HZ + BMM350_DATA_RATE_200HZ + BMM350_DATA_RATE_400HZ + ''' + bmm350.set_preset_mode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ) + + ''' + Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required. When disabled, the geomagnetic data at x, y, and z will be inaccurate. + Refer to readme file if you want to configure more parameters. + ''' + bmm350.set_measurement_XYZ() + + ''' + Get the config data rate unit: HZ + ''' + print("rates is %d HZ"%bmm350.get_rate() ) + + ''' + Get the character string of enabling status at x-axis, y-axis and z-axis + ''' + print(bmm350.get_measurement_state_XYZ()) + + ''' + @brief Soft reset, restore to suspended mode after soft reset. (You need to manually enter the normal mode) + ''' + bmm350.soft_reset() + print('Power mode after software reset: ', bmm350.get_operation_mode()) + +def loop(): + ''' + Get the operation mode character string of the sensor + ''' + print('Current power mode: ', bmm350.get_operation_mode()) + exit() + + +if __name__ == "__main__": + setup() + while True: + loop() diff --git a/lib/DFRobot_BMM350/python/raspberrypi/examples/get_calibrated_geomagnetic_data.py b/lib/DFRobot_BMM350/python/raspberrypi/examples/get_calibrated_geomagnetic_data.py new file mode 100644 index 0000000..2ef2d11 --- /dev/null +++ b/lib/DFRobot_BMM350/python/raspberrypi/examples/get_calibrated_geomagnetic_data.py @@ -0,0 +1,107 @@ +# -*- coding:utf-8 -*- +''' + @file get_calibrated_geomagnetic_data.py + @brief Get the geomagnetic data at 3 axis (x, y, z), get the compass degree + @n "Compass Degree", the angle formed when the needle rotates counterclockwise from the current position to the true north + @n Experimental phenomenon: serial print the geomagnetic data at x-axis, y-axis and z-axis and the angle formed when the needle rotates counterclockwise from the current position to the true north + @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) + @license The MIT License (MIT) + @author [GDuang](yonglei.ren@dfrobot.com) + @version V1.0.0 + @date 2024-05-11 + @url https://github.com/DFRobot/DFRobot_BMM350 +''' +import sys +import os +import math +sys.path.append(os.path.dirname(os.path.dirname(os.path.realpath(__file__)))) +from DFRobot_bmm350 import * + +''' + If you want to use I2C to drive this module, uncomment the codes below, and connect the module with Raspberry Pi via I2C port + Connect to VCC,GND,SCL,SDA pin +''' +I2C_BUS = 0x01 #default use I2C1 +bmm350 = DFRobot_bmm350_I2C(I2C_BUS, 0x14) + +def setup(): + while BMM350_CHIP_ID_ERROR == bmm350.sensor_init(): + print("sensor init error, please check connect") + time.sleep(1) + + ''' + Set sensor operation mode + opMode: + BMM350_SUSPEND_MODE suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + BMM350_NORMAL_MODE normal mode: Get geomagnetic data normally. + BMM350_FORCED_MODE forced mode: Single measurement, the sensor restores to suspend mode when the measurement is done. + BMM350_FORCED_MODE_FAST To reach ODR = 200Hz is only possible by using FM_ FAST. + ''' + bmm350.set_operation_mode(BMM350_NORMAL_MODE) + + ''' + Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) + presetMode: + BMM350_PRESETMODE_LOWPOWER Low power mode, get a small number of data and draw the mean value. + BMM350_PRESETMODE_REGULAR Regular mode, get a number of data and draw the mean value. + BMM350_PRESETMODE_ENHANCED Enhanced mode, get a large number of data and draw the mean value. + BMM350_PRESETMODE_HIGHACCURACY High accuracy mode, get a huge number of data and draw the mean value. + rate: + BMM350_DATA_RATE_1_5625HZ + BMM350_DATA_RATE_3_125HZ + BMM350_DATA_RATE_6_25HZ + BMM350_DATA_RATE_12_5HZ (default rate) + BMM350_DATA_RATE_25HZ + BMM350_DATA_RATE_50HZ + BMM350_DATA_RATE_100HZ + BMM350_DATA_RATE_200HZ + BMM350_DATA_RATE_400HZ + ''' + bmm350.set_preset_mode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ) + + + ''' + Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required. When disabled, the geomagnetic data at x, y, and z will be inaccurate. + Refer to readme file if you want to configure more parameters. + ''' + bmm350.set_measurement_XYZ() + +def loop(): + geomagnetic = bmm350.get_geomagnetic_data() + #hard iron calibration parameters + hard_iron= (-13.45, -28.95, 12.69 ) + #soft iron calibration parameters + soft_iron= [ + ( 0.992, -0.006, -0.007 ), + ( -0.006, 0.990, -0.004 ), + ( -0.007, -0.004, 1.019 ) + ] + + # hard iron calibration + geomagnetic[0] =geomagnetic[0] + hard_iron[0] + geomagnetic[1] =geomagnetic[1] + hard_iron[1] + geomagnetic[2] = geomagnetic[2] + hard_iron[2] + + #soft iron calibration + for i in range(3): + geomagnetic[i] = (soft_iron[i][0] * geomagnetic[0]) + (soft_iron[i][1] * geomagnetic[1]) + (soft_iron[i][2] * geomagnetic[2]) + + compass = math.atan2(geomagnetic[0], geomagnetic[1]) + if compass < 0: + compass += 2 * PI + if compass > 2 * PI: + compass -= 2 * PI + degree=compass * 180 / M_PI + print("---------------------------------") + print("mag x = %.2f ut"%geomagnetic[0]) + print("mag y = %.2f ut"%geomagnetic[1]) + print("mag z = %.2f ut"%geomagnetic[2]) + print("---------------------------------") + print("the angle between the pointing direction and north (counterclockwise) is: %.2f "%degree) + time.sleep(1) + +if __name__ == "__main__": + setup() + while True: + loop() diff --git a/lib/DFRobot_BMM350/python/raspberrypi/examples/get_geomagnetic_data.py b/lib/DFRobot_BMM350/python/raspberrypi/examples/get_geomagnetic_data.py new file mode 100644 index 0000000..1989b7f --- /dev/null +++ b/lib/DFRobot_BMM350/python/raspberrypi/examples/get_geomagnetic_data.py @@ -0,0 +1,89 @@ +# -*- coding:utf-8 -*- +''' + @file demo_get_geomagnetic_data.py + @brief Get the geomagnetic data at 3 axis (x, y, z), get the compass degree + @n "Compass Degree", the angle formed when the needle rotates counterclockwise from the current position to the true north + @n Experimental phenomenon: serial print the geomagnetic data at x-axis, y-axis and z-axis and the angle formed when the needle rotates counterclockwise from the current position to the true north + @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) + @license The MIT License (MIT) + @author [GDuang](yonglei.ren@dfrobot.com) + @version V1.0.0 + @date 2024-05-11 + @url https://github.com/DFRobot/DFRobot_BMM350 +''' +import sys +import os + +sys.path.append(os.path.dirname(os.path.dirname(os.path.realpath(__file__)))) +from DFRobot_bmm350 import * + +''' + If you want to use I2C to drive this module, uncomment the codes below, and connect the module with Raspberry Pi via I2C port + Connect to VCC, GND, SCL, SDA pin +''' +I2C_BUS = 0x01 #default use I2C1 +bmm350 = DFRobot_bmm350_I2C(I2C_BUS, 0x14) + +def setup(): + while BMM350_CHIP_ID_ERROR == bmm350.sensor_init(): + print("sensor init error, please check connect") + time.sleep(1) + + ''' + Set sensor operation mode + opMode: + BMM350_SUSPEND_MODE suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + BMM350_NORMAL_MODE normal mode: Get geomagnetic data normally. + BMM350_FORCED_MODE forced mode: Single measurement, the sensor restores to suspend mode when the measurement is done. + BMM350_FORCED_MODE_FAST To reach ODR = 200Hz is only possible by using FM_ FAST. + ''' + bmm350.set_operation_mode(BMM350_NORMAL_MODE) + + ''' + Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) + presetMode: + BMM350_PRESETMODE_LOWPOWER Low power mode, get a small number of data and draw the mean value. + BMM350_PRESETMODE_REGULAR Regular mode, get a number of data and draw the mean value. + BMM350_PRESETMODE_ENHANCED Enhanced mode, get a large number of data and draw the mean value. + BMM350_PRESETMODE_HIGHACCURACY High accuracy mode, get a huge number of data and draw the mean value. + rate: + BMM350_DATA_RATE_1_5625HZ + BMM350_DATA_RATE_3_125HZ + BMM350_DATA_RATE_6_25HZ + BMM350_DATA_RATE_12_5HZ (default rate) + BMM350_DATA_RATE_25HZ + BMM350_DATA_RATE_50HZ + BMM350_DATA_RATE_100HZ + BMM350_DATA_RATE_200HZ + BMM350_DATA_RATE_400HZ + ''' + bmm350.set_preset_mode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ) + + ''' + Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required. When disabled, the geomagnetic data at x, y, and z will be inaccurate. + Refer to readme file if you want to configure more parameters. + ''' + bmm350.set_measurement_XYZ() + +def loop(): + geomagnetic = bmm350.get_geomagnetic_data() + print("mag x = %d ut"%geomagnetic[0]) + print("mag y = %d ut"%geomagnetic[1]) + print("mag z = %d ut"%geomagnetic[2]) + + # get float type data + # geomagnetic = bmm350.get_geomagnetic_data() + # print("---------------------------------") + # print("mag x = %.2f ut"%geomagnetic[0]) + # print("mag y = %.2f ut"%geomagnetic[1]) + # print("mag z = %.2f ut"%geomagnetic[2]) + degree = bmm350.get_compass_degree() + print("---------------------------------") + print("the angle between the pointing direction and north (counterclockwise) is: %.2f "%degree) + time.sleep(1) + +if __name__ == "__main__": + setup() + while True: + loop() diff --git a/lib/DFRobot_BMM350/python/raspberrypi/examples/threshold_interrupt.py b/lib/DFRobot_BMM350/python/raspberrypi/examples/threshold_interrupt.py new file mode 100644 index 0000000..ff0893f --- /dev/null +++ b/lib/DFRobot_BMM350/python/raspberrypi/examples/threshold_interrupt.py @@ -0,0 +1,115 @@ +# -*- coding:utf-8 -*- +''' + @file demo_threshold_interrupt.py + @brief Set the interrupt to be triggered when beyond/below threshold, when the interrupt at a axis occur, the data will be printed in the serial port. + @n When the geomagnetic data at 3 axis (x, y, z) beyond/below the set threshold, the data will be printed in the serial port, unit (uT) + @n Experimental phenomenon: the main controller interrupt will be triggered by level change caused by INT pin interrupt, then the geomagnetic data can be obtained + @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) + @license The MIT License (MIT) + @author [GDuang](yonglei.ren@dfrobot.com) + @version V1.0.0 + @date 2024-05-11 + @url https://github.com/DFRobot/DFRobot_BMM350 +''' +import sys +import os + +sys.path.append(os.path.dirname(os.path.dirname(os.path.realpath(__file__)))) +from DFRobot_bmm350 import * + +''' + If you want to use I2C to drive this module, uncomment the codes below, and connect the module with Raspberry Pi via I2C port + Connect to VCC, GND, SCL, SDA pin +''' +I2C_BUS = 0x01 #default use I2C1 +bmm350 = DFRobot_bmm350_I2C(I2C_BUS, 0x14) + +def setup(): + while BMM350_CHIP_ID_ERROR == bmm350.sensor_init(): + print("sensor init error ,please check connect") + time.sleep(1) + + ''' + Set sensor operation mode + opMode: + BMM350_SUSPEND_MODE suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + BMM350_NORMAL_MODE normal mode: Get geomagnetic data normally. + BMM350_FORCED_MODE forced mode: Single measurement, the sensor restores to suspend mode when the measurement is done. + BMM350_FORCED_MODE_FAST To reach ODR = 200Hz is only possible by using FM_ FAST. + ''' + bmm350.set_operation_mode(BMM350_NORMAL_MODE) + + ''' + Get the operation mode character string of the sensor + ''' + print('Current power mode: ', bmm350.get_operation_mode()) + + ''' + Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) + presetMode: + BMM350_PRESETMODE_LOWPOWER Low power mode, get a small number of data and draw the mean value. + BMM350_PRESETMODE_REGULAR Regular mode, get a number of data and draw the mean value. + BMM350_PRESETMODE_ENHANCED Enhanced mode, get a large number of data and draw the mean value. + BMM350_PRESETMODE_HIGHACCURACY High accuracy mode, get a huge number of data and draw the mean value. + rate: + BMM350_DATA_RATE_1_5625HZ + BMM350_DATA_RATE_3_125HZ + BMM350_DATA_RATE_6_25HZ + BMM350_DATA_RATE_12_5HZ (default rate) + BMM350_DATA_RATE_25HZ + BMM350_DATA_RATE_50HZ + BMM350_DATA_RATE_100HZ + BMM350_DATA_RATE_200HZ + BMM350_DATA_RATE_400HZ + ''' + bmm350.set_preset_mode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ) + + ''' + Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required. When disabled, the geomagnetic data at x, y, and z will be inaccurate. + Refer to readme file if you want to configure more parameters. + ''' + bmm350.set_measurement_XYZ() + + + ''' + Set threshold interrupt, an interrupt is triggered when the geomagnetic value of a channel is beyond/below the threshold + High polarity: active on high, the default is low level, which turns to high level when the interrupt is triggered. + Low polarity: active on low, the default is high level, which turns to low level when the interrupt is triggered. + modes: + LOW_THRESHOLD_INTERRUPT Low threshold interrupt mode, interrupt is triggered when below the threshold + HIGH_THRESHOLD_INTERRUPT High threshold interrupt mode, interrupt is triggered when beyond the threshold + threshold + Threshold range, default to expand 16 times, for example: under low threshold mode, if the threshold is set to be 1, actually the geomagnetic data below 16 will trigger an interrupt + polarity: + BMM350_ACTIVE_HIGH High polarity + BMM350_ACTIVE_LOW Low polarity + View the use method in the readme file if you want to use more configs + ''' + bmm350.set_threshold_interrupt(LOW_THRESHOLD_INTERRUPT, 0, BMM350_ACTIVE_LOW) + + +def loop(): + ''' + Get the data that threshold interrupt occured (get the threshold interrupt status through software) + That the data at (x, y, z) axis are printed in the serial port indicates threshold interrupt occur at (x, y, z) axis + Return the list for storing geomagnetic data, how the data at 3 axis influence interrupt status + [0] The data triggering threshold at x-axis, when the data is NO_DATA, the interrupt is triggered. + [1] The data triggering threshold at y-axis, when the data is NO_DATA, the interrupt is triggered. + [2] The data triggering threshold at z-axis, when the data is NO_DATA, the interrupt is triggered. + ''' + threshold_data = bmm350.get_threshold_data() + if threshold_data[0] != NO_DATA: + print("mag x = %d ut"%threshold_data[0]) + if threshold_data[1] != NO_DATA: + print("mag y = %d ut"%threshold_data[1]) + if threshold_data[2] != NO_DATA: + print("mag z = %d ut"%threshold_data[2]) + print("") + time.sleep(1) + + +if __name__ == "__main__": + setup() + while True: + loop() diff --git a/lib/DFRobot_BMM350/resources/images/BMM350.png b/lib/DFRobot_BMM350/resources/images/BMM350.png new file mode 100644 index 0000000..7978f22 Binary files /dev/null and b/lib/DFRobot_BMM350/resources/images/BMM350.png differ diff --git a/lib/DFRobot_BMM350/resources/images/BMM350Size.png b/lib/DFRobot_BMM350/resources/images/BMM350Size.png new file mode 100644 index 0000000..427e3e3 Binary files /dev/null and b/lib/DFRobot_BMM350/resources/images/BMM350Size.png differ 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 0000000..c47206f Binary files /dev/null and b/lib/DFRobot_BMM350/resources/images/cal_pic1.jpg differ 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 0000000..0c427f0 Binary files /dev/null and b/lib/DFRobot_BMM350/resources/images/cal_pic2.jpg differ 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 0000000..5cbc8ab Binary files /dev/null and b/lib/DFRobot_BMM350/resources/images/cal_pic3.jpg differ diff --git a/lib/DFRobot_BMM350/resources/images/cal_pic4.jpg b/lib/DFRobot_BMM350/resources/images/cal_pic4.jpg new file mode 100644 index 0000000..9a5be03 Binary files /dev/null and b/lib/DFRobot_BMM350/resources/images/cal_pic4.jpg differ diff --git a/lib/DFRobot_BMM350/src/DFRobot_BMM350.cpp b/lib/DFRobot_BMM350/src/DFRobot_BMM350.cpp new file mode 100644 index 0000000..b29b225 --- /dev/null +++ b/lib/DFRobot_BMM350/src/DFRobot_BMM350.cpp @@ -0,0 +1,483 @@ + +/** + * @file DFRobot_BMM350.cpp + * @brief Define the infrastructure of the DFRobot_BMM350 class and the implementation of the underlying methods + * @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) + * @license The MIT License (MIT) + * @author [GDuang](yonglei.ren@dfrobot.com) + * @version V1.0.0 + * @date 2024-05-06 + * @url https://github.com/DFRobot/DFRobot_BMM350 + */ + +#include "DFRobot_BMM350.h" + +static struct bmm350_dev bmm350Sensor; +/*! Variable that holds the I2C device address selection */ +static uint8_t devAddr; +TwoWire *_pWire = NULL; +uint8_t bmm350I2CAddr = 0; + +void bmm350DelayUs(uint32_t period, void *intfPtr) +{ + UNUSED(intfPtr); + if (period > 1000) + { + delay(period / 1000); + } + else + { + delayMicroseconds(period); + } +} + +DFRobot_BMM350::DFRobot_BMM350(pBmm350ReadFptr_t bmm350ReadReg, pBmm350WriteFptr_t bmm350WriteReg, pBmm350DelayUsFptr_t bmm350DelayUs, eBmm350Interface_t interface) +{ + switch (interface) + { + case eBmm350InterfaceI2C: + devAddr = BMM350_I2C_ADSEL_SET_LOW; + bmm350Sensor.intfPtr = &devAddr; + break; + case eBmm350InterfaceI3C: + break; + } + bmm350Sensor.read = bmm350ReadReg; + bmm350Sensor.write = bmm350WriteReg; + bmm350Sensor.delayUs = bmm350DelayUs; +} + +DFRobot_BMM350::~DFRobot_BMM350() +{ +} + +bool DFRobot_BMM350::sensorInit(void) +{ + return bmm350Init(&bmm350Sensor) == 0; +} + +uint8_t DFRobot_BMM350::getChipID(void) +{ + return bmm350Sensor.chipId; +} + +void DFRobot_BMM350::softReset(void) +{ + bmm350SoftReset(&bmm350Sensor); + bmm350SetPowerMode(eBmm350SuspendMode, &bmm350Sensor); +} + +void DFRobot_BMM350::setOperationMode(enum eBmm350PowerModes_t powermode) +{ + bmm350SetPowerMode(powermode, &bmm350Sensor); +} + +String DFRobot_BMM350::getOperationMode(void) +{ + String result; + switch (bmm350Sensor.powerMode) + { + case eBmm350SuspendMode: + result = "bmm350 is suspend mode!"; + break; + case eBmm350NormalMode: + result = "bmm350 is normal mode!"; + break; + case eBmm350ForcedMode: + result = "bmm350 is forced mode!"; + break; + case eBmm350ForcedModeFast: + result = "bmm350 is forced_fast mode!"; + break; + default: + result = "error mode!"; + break; + } + return result; +} + +void DFRobot_BMM350::setPresetMode(uint8_t presetMode, enum eBmm350DataRates_t rate) +{ + switch (presetMode) + { + case BMM350_PRESETMODE_LOWPOWER: + bmm350SetOdrPerformance(rate, BMM350_NO_AVERAGING, &bmm350Sensor); + break; + case BMM350_PRESETMODE_REGULAR: + bmm350SetOdrPerformance(rate, BMM350_AVERAGING_2, &bmm350Sensor); + break; + case BMM350_PRESETMODE_ENHANCED: + bmm350SetOdrPerformance(rate, BMM350_AVERAGING_4, &bmm350Sensor); + break; + case BMM350_PRESETMODE_HIGHACCURACY: + bmm350SetOdrPerformance(rate, BMM350_AVERAGING_8, &bmm350Sensor); + break; + default: + break; + } +} +void DFRobot_BMM350::setRate(uint8_t rate) +{ + /* Variable to store the function result */ + int8_t rslt; + + uint8_t avgOdrReg = 0; + uint8_t avgReg = 0; + uint8_t regData = 0; + + switch(rate){ + case BMM350_DATA_RATE_1_5625HZ: + case BMM350_DATA_RATE_3_125HZ: + case BMM350_DATA_RATE_6_25HZ: + case BMM350_DATA_RATE_12_5HZ: + case BMM350_DATA_RATE_25HZ: + case BMM350_DATA_RATE_50HZ: + case BMM350_DATA_RATE_100HZ: + case BMM350_DATA_RATE_200HZ: + case BMM350_DATA_RATE_400HZ: + /* Get the configurations for ODR and performance */ + rslt = bmm350GetRegs(BMM350_REG_PMU_CMD_AGGR_SET, &avgOdrReg, 1, &bmm350Sensor); + if (rslt == BMM350_OK){ + /* Read the performance status */ + avgReg = BMM350_GET_BITS(avgOdrReg, BMM350_AVG); + } + /* ODR is an enum taking the generated constants from the register map */ + regData = ((uint8_t)rate & BMM350_ODR_MSK); + /* AVG / performance is an enum taking the generated constants from the register map */ + regData = BMM350_SET_BITS(regData, BMM350_AVG, (uint8_t)avgReg); + /* Set PMU command configurations for ODR and performance */ + rslt = bmm350SetRegs(BMM350_REG_PMU_CMD_AGGR_SET, ®Data, 1, &bmm350Sensor); + if (rslt == BMM350_OK){ + /* Set PMU command configurations to update odr and average */ + regData = BMM350_PMU_CMD_UPD_OAE; + /* Set PMU command configuration */ + rslt = bmm350SetRegs(BMM350_REG_PMU_CMD, ®Data, 1, &bmm350Sensor); + if (rslt == BMM350_OK){ + rslt = bmm350DelayUs(BMM350_UPD_OAE_DELAY, &bmm350Sensor); + } + } + break; + default: + break; + } +} + +float DFRobot_BMM350::getRate(void) +{ + /* Variable to store the function result */ + int8_t rslt; + + uint8_t avgOdrReg = 0; + uint8_t odrReg = 0; + float result = 0; + + /* Get the configurations for ODR and performance */ + rslt = bmm350GetRegs(BMM350_REG_PMU_CMD_AGGR_SET, &avgOdrReg, 1, &bmm350Sensor); + if (rslt == BMM350_OK) + { + /* Read the performance status */ + odrReg = BMM350_GET_BITS(avgOdrReg, BMM350_ODR); + } + switch (odrReg) + { + case BMM350_DATA_RATE_1_5625HZ: + result = 1.5625; + break; + case BMM350_DATA_RATE_3_125HZ: + result = 3.125; + break; + case BMM350_DATA_RATE_6_25HZ: + result = 6.25; + break; + case BMM350_DATA_RATE_12_5HZ: + result = 12.5; + break; + case BMM350_DATA_RATE_25HZ: + result = 25; + break; + case BMM350_DATA_RATE_50HZ: + result = 50; + break; + case BMM350_DATA_RATE_100HZ: + result = 100; + break; + case BMM350_DATA_RATE_200HZ: + result = 200; + break; + case BMM350_DATA_RATE_400HZ: + result = 400; + break; + default: + break; + } + return result; +} + +String DFRobot_BMM350::selfTest(eBmm350SelfTest_t testMode) +{ + String result; + /* Structure instance of self-test data */ + struct sBmm350SelfTest_t stData; + memset(&stData, 0, sizeof(stData)); + switch (testMode) + { + case eBmm350SelfTestNormal: + setOperationMode(eBmm350NormalMode); + setMeasurementXYZ(); + sBmm350MagData_t magData = getGeomagneticData(); + if ((magData.x < 2000) && (magData.x > -2000)) + { + result += "x aixs self test success!\n"; + } + else + { + result += "x aixs self test failed!\n"; + } + if ((magData.y < 2000) && (magData.y > -2000)) + { + result += "y aixs self test success!\n"; + } + else + { + result += "y aixs self test failed!\n"; + } + if ((magData.z < 2000) && (magData.z > -2000)) + { + result += "z aixs self test success!\n"; + } + else + { + result += "z aixs self test failed!\n"; + } + break; + } + return result; +} + +void DFRobot_BMM350::setMeasurementXYZ(enum eBmm350XAxisEnDis_t enX, enum eBmm350YAxisEnDis_t enY, enum eBmm350ZAxisEnDis_t enZ) +{ + bmm350_enable_axes(enX, enY, enZ, &bmm350Sensor); +} + +String DFRobot_BMM350::getMeasurementStateXYZ(void) +{ + uint8_t axisReg = 0; + uint8_t enX = 0; + uint8_t enY = 0; + uint8_t enZ = 0; + char result[100] = ""; + + /* Get the configurations for ODR and performance */ + axisReg = bmm350Sensor.axisEn; + + /* Read the performance status */ + enX = BMM350_GET_BITS(axisReg, BMM350_EN_X); + enY = BMM350_GET_BITS(axisReg, BMM350_EN_Y); + enZ = BMM350_GET_BITS(axisReg, BMM350_EN_Z); + + strcat(result, (enX == 1 ? "The x axis is enable! " : "The x axis is disable! ")); + strcat(result, (enY == 1 ? "The y axis is enable! " : "The y axis is disable! ")); + strcat(result, (enZ == 1 ? "The z axis is enable! " : "The z axis is disable! ")); + return result; +} + +sBmm350MagData_t DFRobot_BMM350::getGeomagneticData(void) +{ + sBmm350MagData_t magData; + struct sBmm350MagTempData_t magTempData; + memset(&magData, 0, sizeof(magData)); + memset(&magTempData, 0, sizeof(magTempData)); + bmm350GetCompensatedMagXYZTempData(&magTempData, &bmm350Sensor); + magData.x = magTempData.x; + magData.y = magTempData.y; + magData.z = magTempData.z; + magData.temperature = magTempData.temperature; + magData.float_x = magTempData.x; + magData.float_y = magTempData.y; + magData.float_z = magTempData.z; + magData.float_temperature = magTempData.temperature; + return magData; +} + +float DFRobot_BMM350::getCompassDegree(void) +{ + float compass = 0.0; + sBmm350MagData_t magData = getGeomagneticData(); + compass = atan2(magData.x, magData.y); + if (compass < 0) + { + compass += 2 * PI; + } + if (compass > 2 * PI) + { + compass -= 2 * PI; + } + return compass * 180 / M_PI; +} + +void DFRobot_BMM350::setDataReadyPin(enum eBmm350InterruptEnableDisable_t modes, enum eBmm350IntrPolarity_t polarity) +{ + /* Variable to get interrupt control configuration */ + uint8_t regData = 0; + /* Variable to store the function result */ + int8_t rslt; + /* Get interrupt control configuration */ + rslt = bmm350GetRegs(BMM350_REG_INT_CTRL, ®Data, 1, &bmm350Sensor); + if (rslt == BMM350_OK) + { + regData = BMM350_SET_BITS_POS_0(regData, BMM350_INT_MODE, BMM350_PULSED); + regData = BMM350_SET_BITS(regData, BMM350_INT_POL, polarity); + regData = BMM350_SET_BITS(regData, BMM350_INT_OD, BMM350_INTR_PUSH_PULL); + regData = BMM350_SET_BITS(regData, BMM350_INT_OUTPUT_EN, BMM350_MAP_TO_PIN); + regData = BMM350_SET_BITS(regData, BMM350_DRDY_DATA_REG_EN, (uint8_t)modes); + /* Finally transfer the interrupt configurations */ + rslt = bmm350SetRegs(BMM350_REG_INT_CTRL, ®Data, 1, &bmm350Sensor); + } +} + +bool DFRobot_BMM350::getDataReadyState(void) +{ + uint8_t drdyStatus = 0x0; + bmm350GetInterruptStatus(&drdyStatus, &bmm350Sensor); + if (drdyStatus & 0x01) + { + return true; + } + else + { + return false; + } +} + +void DFRobot_BMM350::setThresholdInterrupt(uint8_t modes, int8_t threshold, enum eBmm350IntrPolarity_t polarity) +{ + if (modes == LOW_THRESHOLD_INTERRUPT) + { + __thresholdMode = LOW_THRESHOLD_INTERRUPT; + setDataReadyPin(BMM350_ENABLE_INTERRUPT, polarity); + this->threshold = threshold; + } + else + { + __thresholdMode = HIGH_THRESHOLD_INTERRUPT; + setDataReadyPin(BMM350_ENABLE_INTERRUPT, polarity); + this->threshold = threshold; + } +} + +sBmm350ThresholdData_t DFRobot_BMM350::getThresholdData(void) +{ + sBmm350MagData_t magData; + memset(&magData, 0, sizeof(magData)); + thresholdData.mag_x = NO_DATA; + thresholdData.mag_y = NO_DATA; + thresholdData.mag_z = NO_DATA; + thresholdData.interrupt_x = 0; + thresholdData.interrupt_y = 0; + thresholdData.interrupt_z = 0; + bool state = getDataReadyState(); + if (state == true) + { + magData = getGeomagneticData(); + if (__thresholdMode == LOW_THRESHOLD_INTERRUPT) + { + if (magData.x < (int32_t)threshold * 16) + { + thresholdData.mag_x = magData.x; + thresholdData.interrupt_x = 1; + } + if (magData.y < (int32_t)threshold * 16) + { + thresholdData.mag_y = magData.y; + thresholdData.interrupt_y = 1; + } + if (magData.z < (int32_t)threshold * 16) + { + thresholdData.mag_z = magData.z; + thresholdData.interrupt_z = 1; + } + } + else if (__thresholdMode == HIGH_THRESHOLD_INTERRUPT) + { + if (magData.x > (int32_t)threshold * 16) + { + thresholdData.mag_x = magData.x; + thresholdData.interrupt_x = 1; + } + if (magData.y > (int32_t)threshold * 16) + { + thresholdData.mag_y = magData.y; + thresholdData.interrupt_y = 1; + } + if (magData.z > (int32_t)threshold * 16) + { + thresholdData.mag_z = magData.z; + thresholdData.interrupt_z = 1; + } + } + } + + return thresholdData; +} + +static int8_t bmm350I2cReadData(uint8_t Reg, uint8_t *Data, uint32_t len, void *intfPtr) +{ + uint8_t deviceAddr = *(uint8_t *)intfPtr; + _pWire->begin(); + int i = 0; + _pWire->beginTransmission(deviceAddr); + _pWire->write(Reg); + if (_pWire->endTransmission() != 0) + { + return -1; + } + _pWire->requestFrom(deviceAddr, (uint8_t)len); + while (_pWire->available()) + { + Data[i++] = _pWire->read(); + } + return 0; +} + +static int8_t bmm350I2cWriteData(uint8_t Reg, const uint8_t *Data, uint32_t len, void *intfPtr) +{ + uint8_t deviceAddr = *(uint8_t *)intfPtr; + _pWire->begin(); + _pWire->beginTransmission(deviceAddr); + _pWire->write(Reg); + for (uint8_t i = 0; i < len; i++) + { + _pWire->write(Data[i]); + } + _pWire->endTransmission(); + return 0; +} + +DFRobot_BMM350_I2C::DFRobot_BMM350_I2C(TwoWire *pWire, uint8_t addr) : DFRobot_BMM350(bmm350I2cReadData, bmm350I2cWriteData, bmm350DelayUs, eBmm350InterfaceI2C) +{ + _pWire = pWire; + bmm350I2CAddr = addr; +} + +uint8_t DFRobot_BMM350_I2C::begin() +{ + _pWire->begin(); + _pWire->beginTransmission(bmm350I2CAddr); + if (_pWire->endTransmission() == 0) + { + if (sensorInit()) + { + return 0; + } + else + { + DBG("Chip id error ,please check sensor!"); + return 2; + } + } + else + { + DBG("I2C device address error or no connection!"); + return 1; + } +} diff --git a/lib/DFRobot_BMM350/src/DFRobot_BMM350.h b/lib/DFRobot_BMM350/src/DFRobot_BMM350.h new file mode 100644 index 0000000..67600f4 --- /dev/null +++ b/lib/DFRobot_BMM350/src/DFRobot_BMM350.h @@ -0,0 +1,250 @@ +/** + * @file DFRobot_BMM350.h + * @brief Defines the infrastructure of the DFRobot_BMM350 class + * @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) + * @license The MIT License (MIT) + * @author [GDuang](yonglei.ren@dfrobot.com) + * @version V1.0.0 + * @date 2024-05-06 + * @url https://github.com/DFRobot/DFRobot_BMM350 + */ +#ifndef __DFRobot_BMM350_H__ +#define __DFRobot_BMM350_H__ + +#include "bmm350_defs.h" +#include "bmm350.h" + +#include "Arduino.h" +#include +#include +#include + + +//#define ENABLE_DBG //< Open this macro to see the program running in detail + +#ifdef ENABLE_DBG +#define DBG(...) {Serial.print("[");Serial.print(__FUNCTION__); Serial.print("(): "); Serial.print(__LINE__); Serial.print(" ] "); Serial.println(__VA_ARGS__);} +#else +#define DBG(...) +#endif + +#define BMM350_INTERFACE_I2C UINT8_C(0x00) +#define BMM350_INTERFACE_I3C UINT8_C(0x01) +#define BMM350_SELF_TEST_NORMAL UINT8_C(0x00) +#define BMM350_SELF_TEST_ADVANCED UINT8_C(0x01) + +enum eBmm350Interface_t { + eBmm350InterfaceI2C = BMM350_INTERFACE_I2C, + eBmm350InterfaceI3C = BMM350_INTERFACE_I3C +}; + +enum eBmm350SelfTest_t { + eBmm350SelfTestNormal = BMM350_SELF_TEST_NORMAL +}; + +void bmm350DelayUs(uint32_t period); + +class DFRobot_BMM350{ +public: + DFRobot_BMM350(pBmm350ReadFptr_t bmm350ReadReg, pBmm350WriteFptr_t bmm350WriteReg, pBmm350DelayUsFptr_t bmm350DelayUs, eBmm350Interface_t interface); + + ~DFRobot_BMM350(); + + /** + * @fn softReset + * @brief Soft reset, restore to suspended mode after soft reset. (You need to manually enter the normal mode) + */ + void softReset(void); + + /** + * @fn setOperationMode + * @brief Set sensor operation mode + * @param powermode + * @n eBmm350SuspendMode suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + * so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + * @n eBmm350NormalMode normal mode: Get geomagnetic data normally. + * @n eBmm350ForcedMode forced mode: Single measurement, the sensor restores to suspend mode when the measurement is done. + * @n eBmm350ForcedModeFast To reach ODR = 200Hz is only possible by using FM_ FAST. + */ + void setOperationMode(enum eBmm350PowerModes_t powermode); + + /** + * @fn getOperationMode + * @brief Get sensor operation mode + * @return result Return sensor operation mode as a character string + */ + String getOperationMode(void); + + /** + * @fn setPresetMode + * @brief Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default collection rate is 12.5Hz) + * @param presetMode + * @n BMM350_PRESETMODE_LOWPOWER Low power mode, get a fraction of data and take the mean value. + * @n BMM350_PRESETMODE_REGULAR Regular mode, get a number of data and take the mean value. + * @n BMM350_PRESETMODE_ENHANCED Enhanced mode, get a plenty of data and take the mean value. + * @n BMM350_PRESETMODE_HIGHACCURACY High accuracy mode, get a huge number of data and take the mean value. + * @param rate + * @n BMM350_DATA_RATE_1_5625HZ + * @n BMM350_DATA_RATE_3_125HZ + * @n BMM350_DATA_RATE_6_25HZ + * @n BMM350_DATA_RATE_12_5HZ + * @n BMM350_DATA_RATE_25HZ + * @n BMM350_DATA_RATE_50HZ + * @n BMM350_DATA_RATE_100HZ + * @n BMM350_DATA_RATE_200HZ + * @n BMM350_DATA_RATE_400HZ + */ + void setPresetMode(uint8_t presetMode, enum eBmm350DataRates_t rate=BMM350_DATA_RATE_12_5HZ); + /** + * @fn setRate + * @brief Set the rate of obtaining geomagnetic data, the higher, the faster (without delay function) + * @param rate + * @n BMM350_DATA_RATE_1_5625HZ + * @n BMM350_DATA_RATE_3_125HZ + * @n BMM350_DATA_RATE_6_25HZ + * @n BMM350_DATA_RATE_12_5HZ (default rate) + * @n BMM350_DATA_RATE_25HZ + * @n BMM350_DATA_RATE_50HZ + * @n BMM350_DATA_RATE_100HZ + * @n BMM350_DATA_RATE_200HZ + * @n BMM350_DATA_RATE_400HZ + */ + void setRate(uint8_t rate); + + /** + * @fn getRate + * @brief Get the config data rate, unit: HZ + * @return rate + */ + float getRate(void); + + /** + * @fn selfTest + * @brief The sensor self test, the returned value indicate the self test result. + * @param testMode: + * @n eBmm350SelfTestNormal Normal self test, test whether x-axis, y-axis and z-axis are connected or short-circuited + * @return result The returned character string is the self test result + */ + String selfTest(eBmm350SelfTest_t testMode = eBmm350SelfTestNormal); + + /** + * @fn setMeasurementXYZ + * @brief Enable the measurement at x-axis, y-axis and z-axis, default to be enabled. After disabling, the geomagnetic data at x, y, and z axis are wrong. + * @param en_x + * @n BMM350_X_EN Enable the measurement at x-axis + * @n BMM350_X_DIS Disable the measurement at x-axis + * @param en_y + * @n BMM350_Y_EN Enable the measurement at y-axis + * @n BMM350_Y_DIS Disable the measurement at y-axis + * @param en_z + * @n BMM350_Z_EN Enable the measurement at z-axis + * @n BMM350_Z_DIS Disable the measurement at z-axis + */ + void setMeasurementXYZ(enum eBmm350XAxisEnDis_t enX = BMM350_X_EN, enum eBmm350YAxisEnDis_t enY = BMM350_Y_EN, enum eBmm350ZAxisEnDis_t enZ = BMM350_Z_EN); + + /** + * @fn getMeasurementStateXYZ + * @brief Get the enabling status at x-axis, y-axis and z-axis + * @return result Return enabling status as a character string + */ + String getMeasurementStateXYZ(void); + + /** + * @fn getGeomagneticData + * @brief Get the geomagnetic data of 3 axis (x, y, z) + * @return Geomagnetic data structure, unit: (uT) + */ + sBmm350MagData_t getGeomagneticData(void); + + + /** + * @fn getCompassDegree + * @brief Get compass degree + * @return Compass degree (0° - 360°) + * @n 0° = North, 90° = East, 180° = South, 270° = West. + */ + float getCompassDegree(void); + + /** + * @fn setDataReadyPin + * @brief Enable or disable data ready interrupt pin + * @n After enabling, the DRDY pin jump when there's data coming. + * @n After disabling, the DRDY pin will not jump when there's data coming. + * @n High polarity: active on high, the default is low level, which turns to high level when the interrupt is triggered. + * @n Low polarity: active on low, default is high level, which turns to low level when the interrupt is triggered. + * @param modes + * @n BMM350_ENABLE_INTERRUPT Enable DRDY + * @n BMM350_DISABLE_INTERRUPT Disable DRDY + * @param polarity + * @n BMM350_ACTIVE_HIGH High polarity + * @n BMM350_ACTIVE_LOW Low polarity + */ + void setDataReadyPin(enum eBmm350InterruptEnableDisable_t modes, enum eBmm350IntrPolarity_t polarity=BMM350_ACTIVE_HIGH); + + /** + * @fn getDataReadyState + * @brief Get the data ready status, determine whether the data is ready + * @return status + * @retval true Data ready + * @retval false Data is not ready + */ + bool getDataReadyState(void); + + /** + * @fn setThresholdInterrupt(uint8_t modes, int8_t threshold, enum eBmm350IntrPolarity_t polarity) + * @brief Set threshold interrupt, an interrupt is triggered when the geomagnetic value of a channel is beyond/below the threshold + * @n High polarity: active on high level, the default is low level, which turns to high level when the interrupt is triggered. + * @n Low polarity: active on low level, the default is high level, which turns to low level when the interrupt is triggered. + * @param modes + * @n LOW_THRESHOLD_INTERRUPT Low threshold interrupt mode + * @n HIGH_THRESHOLD_INTERRUPT High threshold interrupt mode + * @param threshold + * @n Threshold, default to expand 16 times, for example: under low threshold mode, if the threshold is set to be 1, actually the geomagnetic data below 16 will trigger an interrupt + * @param polarity + * @n POLARITY_HIGH High polarity + * @n POLARITY_LOW Low polarity + */ + void setThresholdInterrupt(uint8_t modes, int8_t threshold, enum eBmm350IntrPolarity_t polarity); + + /** + * @fn getThresholdData + * @brief Get the data with threshold interrupt occurred + * @return Returns the structure for storing geomagnetic data, the structure stores the data of 3 axis and interrupt status, + * @n The interrupt is not triggered when the data at x-axis, y-axis and z-axis are NO_DATA + * @n mag_x、mag_y、mag_z store geomagnetic data + * @n interrupt_x、interrupt_y、interrupt_z store the xyz axis interrupt state + */ + sBmm350ThresholdData_t getThresholdData(void); + +protected: + /** + * @fn sensorInit + * @brief Init bmm350 check whether the chip id is right + * @return state + * @retval true Chip id is right init succeeds + * @retval false Chip id is wrong init failed + */ + bool sensorInit(void); + + /** + * @fn getChipID + * @brief get bmm350 chip id + * @return chip id + */ + uint8_t getChipID(void); + +private: + uint8_t __thresholdMode = 3; + int8_t threshold = 0; + sBmm350ThresholdData_t thresholdData; +}; + +class DFRobot_BMM350_I2C:public DFRobot_BMM350 +{ + public: + DFRobot_BMM350_I2C(TwoWire *pWire, uint8_t addr = 0x14); + uint8_t begin(void); +}; + + +#endif diff --git a/lib/DFRobot_BMM350/src/bmm350.c b/lib/DFRobot_BMM350/src/bmm350.c new file mode 100644 index 0000000..21b7f72 --- /dev/null +++ b/lib/DFRobot_BMM350/src/bmm350.c @@ -0,0 +1,1781 @@ +/** +* Copyright (c) 2023 Bosch Sensortec GmbH. All rights reserved. +* +* BSD-3-Clause +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* 1. Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* +* 2. Redistributions in binary form must reproduce the above copyright +* notice, this list of conditions and the following disclaimer in the +* documentation and/or other materials provided with the distribution. +* +* 3. Neither the name of the copyright holder nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) +* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, +* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING +* IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* @file bmm350.c +* @date 2023-05-26 +* @version v1.4.0 +* +*/ + +/*************************** Header files *******************************/ +#include "bmm350.h" + +#ifdef __KERNEL__ +#include +#include +#else +#include +#include +#endif + +/********************** Static function declarations ************************/ + +/*! + * @brief This internal API is used to validate the device pointer for + * null conditions. + * + * @param[in] dev : Structure instance of bmm350_dev. + * + * @return Result of API execution status + * @retval = 0 -> Success + * @retval < 0 -> Error + */ +static int8_t null_ptr_check(const struct bmm350_dev *dev); + +/*! + * @brief This internal API is used to update magnetometer offset and sensitivity data. + * + * @param[in] dev : Structure instance of bmm350_dev. + * + * @return void + */ +static void update_mag_off_sens(struct bmm350_dev *dev); + +/*! + * @brief This internal API converts the raw data from the IC data registers to signed integer + * + * @param[in] inval : Unsigned data from data registers + * @param[in number_of_bits : Width of data register + * + * @return Conversion to signed integer + */ +static int32_t fix_sign(uint32_t inval, int8_t number_of_bits); + +/*! + * @brief This internal API is used to read OTP word + * + * @param[in] addr : Stores OTP address + * @param[in, out] lsb_msb : Pointer to store OTP word + * @param[in, out] dev : Structure instance of bmm350_dev. + * + * @return Result of API execution status + * @retval = 0 -> Success + * @retval < 0 -> Error + */ +static int8_t read_otp_word(uint8_t addr, uint16_t *lsb_msb, struct bmm350_dev *dev); + +/*! + * @brief This internal API is used to read raw magnetic x,y and z axis data along with temperature. + * + * @param[out] out_data : Pointer variable to store mag and temperature data. + * @param[in, out] dev : Structure instance of bmm350_dev. + * + * @return Result of API execution status + * @retval = 0 -> Success + * @retval < 0 -> Error + */ +static int8_t read_out_raw_data(float *out_data, struct bmm350_dev *dev); + +/*! + * @brief This internal API is used to convert raw mag lsb data to uT and raw temperature data to degC. + * + * @param[in,out] lsb_to_ut_degc : Float variable to store converted value of mag lsb in micro tesla(uT) and + * temperature data in degC. + * + * @return void + */ +static void update_default_coefiecents(float *lsb_to_ut_degc); + +/*! + * @brief This internal API is used to read OTP data after boot in user mode. + * + * @param[in, out] dev : Structure instance of bmm350_dev. + * + * @return Result of API execution status + * @retval = 0 -> Success + * @retval < 0 -> Error + */ +static int8_t otp_dump_after_boot(struct bmm350_dev *dev); + +/*! + * @brief This internal API is used for self-test entry configuration + * + * @param[in, out] dev : Structure instance of bmm350_dev. + * + * @return Result of API execution status + * @retval = 0 -> Success + * @retval < 0 -> Error + */ +static int8_t self_test_entry_config(struct bmm350_dev *dev); + +/*! + * @brief This internal API is used to test self-test for X and Y axis + * + * @param[in, out] out_data : Structure instance of sBmm350SelfTest_t. + * @param[in, out] dev : Structure instance of bmm350_dev. + * + * @return Result of API execution status + * @retval = 0 -> Success + * @retval < 0 -> Error + */ +static int8_t self_test_xy_axis(struct sBmm350SelfTest_t *out_data, struct bmm350_dev *dev); + +/*! + * @brief This internal API is used to set self-test configurations. + * + * @param[in] st_cmd : Variable to store self-test command. + * @param[in] pmu_cmd : Variable to store PMU command. + * @param[in, out] out_data : Structure instance of sBmm350SelfTest_t. + * @param[in, out] dev : Structure instance of bmm350_dev. + * + * @return Result of API execution status + * @retval = 0 -> Success + * @retval < 0 -> Error + */ +static int8_t self_test_config(uint8_t st_cmd, + uint8_t pmu_cmd, + struct sBmm350SelfTest_t *out_data, + struct bmm350_dev *dev); + +/*! + * @brief This internal API is used to set powermode. + * + * @param[in] powermode : Variable to set new powermode. + * @param[in, out] dev : Structure instance of bmm350_dev. + * + * @return Result of API execution status + * @retval = 0 -> Success + * @retval < 0 -> Error + */ +static int8_t set_powermode(enum eBmm350PowerModes_t powermode, struct bmm350_dev *dev); + +/********************** Global function definitions ************************/ + +/*! + * @brief This API is the entry point. Call this API before using other APIs. + */ +int8_t bmm350Init(struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + /* Variable to get chip id */ + uint8_t chipId = BMM350_DISABLE; + + /* Variable to store the command to power-off the OTP */ + uint8_t otp_cmd = BMM350_OTP_CMD_PWR_OFF_OTP; + + /* Variable to store soft-reset command */ + uint8_t soft_reset; + + /* Check for null pointer in the device structure */ + rslt = null_ptr_check(dev); + /* Proceed if null check is fine */ + if (rslt == BMM350_OK) + { + dev->chipId = 0; + + /* Assign axisEn with all axis enabled (BMM350_EN_XYZ_MSK) */ + dev->axisEn = BMM350_EN_XYZ_MSK; + rslt = bmm350DelayUs(BMM350_START_UP_TIME_FROM_POR, dev); + + if (rslt == BMM350_OK) + { + /* Soft-reset */ + soft_reset = BMM350_CMD_SOFTRESET; + /* Set the command in the command register */ + rslt = bmm350SetRegs(BMM350_REG_CMD, &soft_reset, 1, dev); + + if (rslt == BMM350_OK) + { + rslt = bmm350DelayUs(BMM350_SOFT_RESET_DELAY, dev); + } + } + + if (rslt == BMM350_OK) + { + /* Chip ID of the sensor is read */ + rslt = bmm350GetRegs(BMM350_REG_CHIP_ID, &chipId, 1, dev); + + if (rslt == BMM350_OK) + { + /* Assign chipId to dev->chipId */ + dev->chipId = chipId; + } + } + /* Check for chip id validity */ + if ((rslt == BMM350_OK) && (dev->chipId == BMM350_CHIP_ID)) + { + /* Download OTP memory */ + rslt = otp_dump_after_boot(dev); + if (rslt == BMM350_OK) + { + /* Power off OTP */ + rslt = bmm350SetRegs(BMM350_REG_OTP_CMD_REG, &otp_cmd, 1, dev); + + if (rslt == BMM350_OK) + { + rslt = bmm350_magnetic_reset_and_wait(dev); + } + } + } + else + { + rslt = BMM350_E_DEV_NOT_FOUND; + } + } + + return rslt; +} + +/*! + * @brief This API writes the given data to the register address + * of the sensor. + */ +int8_t bmm350SetRegs(uint8_t reg_addr, const uint8_t *reg_data, uint16_t len, struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + /* Check for null pointer in the device structure */ + rslt = null_ptr_check(dev); + + /* Proceed if null check is fine */ + if ((rslt == BMM350_OK) && (reg_data != NULL) && (len != 0)) + { + /* Write the data to the reg_addr */ + dev->intf_rslt = dev->write(reg_addr, reg_data, len, dev->intfPtr); + + if (dev->intf_rslt != BMM350_INTF_RET_SUCCESS) + { + rslt = BMM350_E_COM_FAIL; + } + } + else + { + rslt = BMM350_E_NULL_PTR; + } + + return rslt; +} + +/*! + * @brief This API reads the data from the given register address of sensor. + */ +int8_t bmm350GetRegs(uint8_t reg_addr, uint8_t *reg_data, uint16_t len, struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + /* Variable to define temporary length */ + uint16_t temp_len = len + BMM350_DUMMY_BYTES; + + /* Variable to define temporary buffer */ + uint8_t temp_buf[BMM350_READ_BUFFER_LENGTH]; + + /* Variable to define loop */ + uint16_t index = 0; + + /* Check for null pointer in the device structure */ + rslt = null_ptr_check(dev); + + /* Proceed if null check is fine */ + if ((rslt == BMM350_OK) && (reg_data != NULL)) + { + /* Read the data from the reg_addr */ + dev->intf_rslt = dev->read(reg_addr, temp_buf, temp_len, dev->intfPtr); + + if (dev->intf_rslt == BMM350_INTF_RET_SUCCESS) + { + /* Copy data after dummy byte indices */ + while (index < len) + { + reg_data[index] = temp_buf[index + BMM350_DUMMY_BYTES]; + index++; + } + } + else + { + rslt = BMM350_E_COM_FAIL; + } + } + else + { + rslt = BMM350_E_NULL_PTR; + } + + return rslt; +} + +/*! + * @brief This function provides the delay for required time (Microsecond) as per the input provided in some of the + * APIs. + */ +int8_t bmm350DelayUs(uint32_t period_us, const struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + /* Check for null pointer in the device structure */ + rslt = null_ptr_check(dev); + + if (rslt == BMM350_OK) + { + dev->delayUs(period_us, dev->intfPtr); + } + + return rslt; +} + +/*! + * @brief This API is used to perform soft-reset of the sensor + * where all the registers are reset to their default values + */ +int8_t bmm350SoftReset(struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + uint8_t reg_data; + + /* Variable to store the command to power-off the OTP */ + uint8_t otp_cmd = BMM350_OTP_CMD_PWR_OFF_OTP; + + /* Check for null pointer in the device structure */ + rslt = null_ptr_check(dev); + + if (rslt == BMM350_OK) + { + reg_data = BMM350_CMD_SOFTRESET; + + /* Set the command in the command register */ + rslt = bmm350SetRegs(BMM350_REG_CMD, ®_data, 1, dev); + + if (rslt == BMM350_OK) + { + rslt = bmm350DelayUs(BMM350_SOFT_RESET_DELAY, dev); + + if (rslt == BMM350_OK) + { + /* Power off OTP */ + rslt = bmm350SetRegs(BMM350_REG_OTP_CMD_REG, &otp_cmd, 1, dev); + + if (rslt == BMM350_OK) + { + rslt = bmm350_magnetic_reset_and_wait(dev); + } + } + } + } + + return rslt; +} + +/*! + * @brief This API is used to read the sensor time. + * It converts the sensor time register values to the representative time value. + * Returns the sensor time in ticks. + */ +int8_t bmm350_read_sensortime(uint32_t *seconds, uint32_t *nanoseconds, struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + uint64_t time; + + uint8_t reg_data[3]; + + if ((seconds != NULL) && (nanoseconds != NULL)) + { + /* Get sensor time raw data */ + rslt = bmm350GetRegs(BMM350_REG_SENSORTIME_XLSB, reg_data, 3, dev); + + if (rslt == BMM350_OK) + { + time = (uint32_t)(reg_data[0] + ((uint32_t)reg_data[1] << 8) + ((uint32_t)reg_data[2] << 16)); + + /* 1 LSB is 39.0625us. Converting to nanoseconds */ + time *= UINT64_C(390625); + time /= UINT64_C(10); + *seconds = (uint32_t)(time / UINT64_C(1000000000)); + *nanoseconds = (uint32_t)(time - ((*seconds) * UINT64_C(1000000000))); + } + } + else + { + rslt = BMM350_E_NULL_PTR; + } + + return rslt; +} + +/*! + * @brief This API is used to get the status flags of all interrupt + * which is used to check for the assertion of interrupts + */ +int8_t bmm350GetInterruptStatus(uint8_t *drdy_status, struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + uint8_t int_status_reg; + + if (drdy_status != NULL) + { + /* Get the status of interrupt */ + rslt = bmm350GetRegs(BMM350_REG_INT_STATUS, &int_status_reg, 1, dev); + + if (rslt == BMM350_OK) + { + /* Read the interrupt status */ + (*drdy_status) = BMM350_GET_BITS(int_status_reg, BMM350_DRDY_DATA_REG); + } + } + else + { + rslt = BMM350_E_NULL_PTR; + } + + return rslt; +} + +/*! + * @brief This API is used to set the power mode of the sensor + */ +int8_t bmm350SetPowerMode(enum eBmm350PowerModes_t powermode, struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + uint8_t last_pwr_mode; + uint8_t reg_data; + + /* Check for null pointer in the device structure */ + rslt = null_ptr_check(dev); + + if (rslt == BMM350_OK) + { + rslt = bmm350GetRegs(BMM350_REG_PMU_CMD, &last_pwr_mode, 1, dev); + + if (rslt == BMM350_OK) + { + if (last_pwr_mode > BMM350_PMU_CMD_NM_TC) + { + rslt = BMM350_E_INVALID_CONFIG; + } + + if ((rslt == BMM350_OK) && + ((last_pwr_mode == BMM350_PMU_CMD_NM) || (last_pwr_mode == BMM350_PMU_CMD_UPD_OAE))) + { + reg_data = BMM350_PMU_CMD_SUS; + + /* Set PMU command configuration */ + rslt = bmm350SetRegs(BMM350_REG_PMU_CMD, ®_data, 1, dev); + + if (rslt == BMM350_OK) + { + rslt = bmm350DelayUs(BMM350_GOTO_SUSPEND_DELAY, dev); + } + } + + if (rslt == BMM350_OK) + { + rslt = set_powermode(powermode, dev); + } + } + } + if (rslt == BMM350_OK) dev->powerMode = powermode; + return rslt; +} + +/*! + * @brief This API sets the ODR and averaging factor. + */ +int8_t bmm350SetOdrPerformance(enum eBmm350DataRates_t odr, + enum bmm350_performance_parameters performance, + struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + /* Variable to get PMU command */ + uint8_t reg_data = 0; + + enum bmm350_performance_parameters performance_fix = performance; + + /* Check for null pointer in the device structure */ + rslt = null_ptr_check(dev); + + if (rslt == BMM350_OK) + { + /* Reduce the performance setting when too high for the chosen ODR */ + if ((odr == BMM350_DATA_RATE_400HZ) && (performance >= BMM350_AVERAGING_2)) + { + performance_fix = BMM350_NO_AVERAGING; + } + else if ((odr == BMM350_DATA_RATE_200HZ) && (performance >= BMM350_AVERAGING_4)) + { + performance_fix = BMM350_AVERAGING_2; + } + else if ((odr == BMM350_DATA_RATE_100HZ) && (performance >= BMM350_AVERAGING_8)) + { + performance_fix = BMM350_AVERAGING_4; + } + + /* ODR is an enum taking the generated constants from the register map */ + reg_data = ((uint8_t)odr & BMM350_ODR_MSK); + + /* AVG / performance is an enum taking the generated constants from the register map */ + reg_data = BMM350_SET_BITS(reg_data, BMM350_AVG, (uint8_t)performance_fix); + + /* Set PMU command configurations for ODR and performance */ + rslt = bmm350SetRegs(BMM350_REG_PMU_CMD_AGGR_SET, ®_data, 1, dev); + + if (rslt == BMM350_OK) + { + /* Set PMU command configurations to update odr and average */ + reg_data = BMM350_PMU_CMD_UPD_OAE; + + /* Set PMU command configuration */ + rslt = bmm350SetRegs(BMM350_REG_PMU_CMD, ®_data, 1, dev); + + if (rslt == BMM350_OK) + { + rslt = bmm350DelayUs(BMM350_UPD_OAE_DELAY, dev); + } + } + } + + return rslt; +} + +/*! + * @brief This API is used to enable or disable the magnetic + * measurement of x,y,z axes + */ +int8_t bmm350_enable_axes(enum eBmm350XAxisEnDis_t en_x, + enum eBmm350YAxisEnDis_t en_y, + enum eBmm350ZAxisEnDis_t en_z, + struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + /* Variable to store axis data */ + uint8_t data; + + /* Check for null pointer in the device structure */ + rslt = null_ptr_check(dev); + + if (rslt == BMM350_OK) + { + if ((en_x == BMM350_X_DIS) && (en_y == BMM350_Y_DIS) && (en_z == BMM350_Z_DIS)) + { + rslt = BMM350_E_ALL_AXIS_DISABLED; + + /* Assign axisEn with all axis disabled status */ + dev->axisEn = BMM350_DISABLE; + } + else + { + data = (en_x & BMM350_EN_X_MSK); + data = BMM350_SET_BITS(data, BMM350_EN_Y, en_y); + data = BMM350_SET_BITS(data, BMM350_EN_Z, en_z); + + rslt = bmm350SetRegs(BMM350_REG_PMU_CMD_AXIS_EN, &data, 1, dev); + + if (rslt == BMM350_OK) + { + /* Assign axisEn with the axis selection done */ + dev->axisEn = data; + } + } + } + + return rslt; +} + +/*! + * @brief This API is used to enable or disable the data ready interrupt + */ +int8_t bmm350_enable_interrupt(enum eBmm350InterruptEnableDisable_t enable_disable, struct bmm350_dev *dev) +{ + /* Variable to get interrupt control configuration */ + uint8_t reg_data = 0; + + /* Variable to store the function result */ + int8_t rslt; + + /* Get interrupt control configuration */ + rslt = bmm350GetRegs(BMM350_REG_INT_CTRL, ®_data, 1, dev); + + if (rslt == BMM350_OK) + { + reg_data = BMM350_SET_BITS(reg_data, BMM350_DRDY_DATA_REG_EN, (uint8_t)enable_disable); + + /* Finally transfer the interrupt configurations */ + rslt = bmm350SetRegs(BMM350_REG_INT_CTRL, ®_data, 1, dev); + } + + return rslt; +} + +/*! + * @brief This API is used to configure the interrupt control settings + */ +int8_t bmm350_configure_interrupt(enum bmm350_intr_latch latching, + enum eBmm350IntrPolarity_t polarity, + enum bmm350_intr_drive drivertype, + enum bmm350_intr_map map_nomap, + struct bmm350_dev *dev) +{ + /* Variable to get interrupt control configuration */ + uint8_t reg_data = 0; + + /* Variable to store the function result */ + int8_t rslt; + + /* Get interrupt control configuration */ + rslt = bmm350GetRegs(BMM350_REG_INT_CTRL, ®_data, 1, dev); + + if (rslt == BMM350_OK) + { + reg_data = BMM350_SET_BITS_POS_0(reg_data, BMM350_INT_MODE, latching); + reg_data = BMM350_SET_BITS(reg_data, BMM350_INT_POL, polarity); + reg_data = BMM350_SET_BITS(reg_data, BMM350_INT_OD, drivertype); + reg_data = BMM350_SET_BITS(reg_data, BMM350_INT_OUTPUT_EN, map_nomap); + + /* Finally transfer the interrupt configurations */ + rslt = bmm350SetRegs(BMM350_REG_INT_CTRL, ®_data, 1, dev); + } + + return rslt; +} + +/*! + * @brief This API is used to read uncompensated mag and temperature data. + */ +int8_t bmm350_read_uncomp_mag_temp_data(struct bmm350_raw_mag_data *raw_data, struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + uint8_t mag_data[12] = { 0 }; + + uint32_t raw_mag_x, raw_mag_y, raw_mag_z, raw_temp; + + if (raw_data != NULL) + { + /* Get uncompensated mag data */ + rslt = bmm350GetRegs(BMM350_REG_MAG_X_XLSB, mag_data, BMM350_MAG_TEMP_DATA_LEN, dev); + + if (rslt == BMM350_OK) + { + raw_mag_x = mag_data[0] + ((uint32_t)mag_data[1] << 8) + ((uint32_t)mag_data[2] << 16); + raw_mag_y = mag_data[3] + ((uint32_t)mag_data[4] << 8) + ((uint32_t)mag_data[5] << 16); + raw_mag_z = mag_data[6] + ((uint32_t)mag_data[7] << 8) + ((uint32_t)mag_data[8] << 16); + raw_temp = mag_data[9] + ((uint32_t)mag_data[10] << 8) + ((uint32_t)mag_data[11] << 16); + + if ((dev->axisEn & BMM350_EN_X_MSK) == BMM350_DISABLE) + { + raw_data->raw_xdata = BMM350_DISABLE; + } + else + { + raw_data->raw_xdata = fix_sign(raw_mag_x, BMM350_SIGNED_24_BIT); + } + + if ((dev->axisEn & BMM350_EN_Y_MSK) == BMM350_DISABLE) + { + raw_data->raw_ydata = BMM350_DISABLE; + } + else + { + raw_data->raw_ydata = fix_sign(raw_mag_y, BMM350_SIGNED_24_BIT); + } + + if ((dev->axisEn & BMM350_EN_Z_MSK) == BMM350_DISABLE) + { + raw_data->raw_zdata = BMM350_DISABLE; + } + else + { + raw_data->raw_zdata = fix_sign(raw_mag_z, BMM350_SIGNED_24_BIT); + } + + raw_data->raw_data_t = fix_sign(raw_temp, BMM350_SIGNED_24_BIT); + } + } + else + { + rslt = BMM350_E_NULL_PTR; + } + + return rslt; +} + +/*! + * @brief This API sets the interrupt control IBI configurations to the sensor. + */ +int8_t bmm350_set_int_ctrl_ibi(enum bmm350_drdy_int_map_to_ibi en_dis, + enum bmm350_clear_drdy_int_status_upon_ibi clear_on_ibi, + struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + /* Variable to get interrupt control configuration */ + uint8_t reg_data = 0; + + /* Get interrupt control configuration */ + rslt = bmm350GetRegs(BMM350_REG_INT_CTRL_IBI, ®_data, 1, dev); + + if (rslt == BMM350_OK) + { + reg_data = BMM350_SET_BITS_POS_0(reg_data, BMM350_DRDY_INT_MAP_TO_IBI, en_dis); + reg_data = BMM350_SET_BITS(reg_data, BMM350_CLEAR_DRDY_INT_STATUS_UPON_IBI, clear_on_ibi); + + /* Set the IBI control configuration */ + rslt = bmm350SetRegs(BMM350_REG_INT_CTRL_IBI, ®_data, 1, dev); + + if (en_dis == BMM350_IBI_ENABLE) + { + /* Enable data ready interrupt if IBI is enabled */ + rslt = bmm350_enable_interrupt(BMM350_ENABLE_INTERRUPT, dev); + } + } + + return rslt; +} + +/*! + * @brief This API is used to set the pad drive strength + */ +int8_t bmm350_set_pad_drive(uint8_t drive, struct bmm350_dev *dev) +{ + uint8_t reg_data; + + /* Variable to store the function result */ + int8_t rslt = BMM350_E_BAD_PAD_DRIVE; + + if (drive <= BMM350_PAD_DRIVE_STRONGEST) + { + reg_data = drive & BMM350_DRV_MSK; + + /* Set drive */ + rslt = bmm350SetRegs(BMM350_REG_PAD_CTRL, ®_data, 1, dev); + } + + return rslt; +} + +/*! + * @brief This API is used to perform the magnetic reset of the sensor + * which is necessary after a field shock (400mT field applied to sensor). + * It sends flux guide or bit reset to the device in suspend mode. + */ +int8_t bmm350_magnetic_reset_and_wait(struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + uint8_t pmu_cmd = 0; + struct bmm350_pmu_cmd_status_0 pmu_cmd_stat_0 = { 0 }; + uint8_t restore_normal = BMM350_DISABLE; + + rslt = null_ptr_check(dev); + + if ((rslt == BMM350_OK) && (dev->mraw_override) && (dev->var_id >= BMM350_MIN_VAR)) + { + rslt = dev->mraw_override(dev); + } + else + { + /* Read PMU CMD status */ + rslt = bmm350_get_pmu_cmd_status_0(&pmu_cmd_stat_0, dev); + + /* Check the powermode is normal before performing magnetic reset */ + if ((rslt == BMM350_OK) && (pmu_cmd_stat_0.pwr_mode_is_normal == BMM350_ENABLE)) + { + restore_normal = BMM350_ENABLE; + + /* Reset can only be triggered in suspend */ + rslt = bmm350SetPowerMode(eBmm350SuspendMode, dev); + } + + if (rslt == BMM350_OK) + { + /* Set BR to PMU_CMD register */ + pmu_cmd = BMM350_PMU_CMD_BR; + + rslt = bmm350SetRegs(BMM350_REG_PMU_CMD, &pmu_cmd, 1, dev); + + if (rslt == BMM350_OK) + { + rslt = bmm350DelayUs(BMM350_BR_DELAY, dev); + } + } + + if (rslt == BMM350_OK) + { + /* Verify if PMU_CMD_STATUS_0 register has BR set */ + rslt = bmm350_get_pmu_cmd_status_0(&pmu_cmd_stat_0, dev); + + if ((rslt == BMM350_OK) && (pmu_cmd_stat_0.pmu_cmd_value != BMM350_PMU_CMD_STATUS_0_BR)) + { + rslt = BMM350_E_PMU_CMD_VALUE; + } + } + + if (rslt == BMM350_OK) + { + /* Set FGR to PMU_CMD register */ + pmu_cmd = BMM350_PMU_CMD_FGR; + + rslt = bmm350SetRegs(BMM350_REG_PMU_CMD, &pmu_cmd, 1, dev); + + if (rslt == BMM350_OK) + { + rslt = bmm350DelayUs(BMM350_FGR_DELAY, dev); + } + } + + if (rslt == BMM350_OK) + { + /* Verify if PMU_CMD_STATUS_0 register has FGR set */ + rslt = bmm350_get_pmu_cmd_status_0(&pmu_cmd_stat_0, dev); + + if ((rslt == BMM350_OK) && (pmu_cmd_stat_0.pmu_cmd_value != BMM350_PMU_CMD_STATUS_0_FGR)) + { + rslt = BMM350_E_PMU_CMD_VALUE; + } + } + + if ((rslt == BMM350_OK) && (restore_normal == BMM350_ENABLE)) + { + rslt = bmm350SetPowerMode(eBmm350NormalMode, dev); + } + } + + return rslt; +} + +/*! + * @brief This API is used to perform compensation for raw magnetometer and temperature data. + */ +int8_t bmm350GetCompensatedMagXYZTempData(struct sBmm350MagTempData_t *mag_temp_data, struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + uint8_t indx; + float out_data[4] = { 0.0f }; + float dut_offset_coef[3], dut_sensit_coef[3], dut_tco[3], dut_tcs[3]; + float cr_ax_comp_x, cr_ax_comp_y, cr_ax_comp_z; + + if (mag_temp_data != NULL) + { + /* Reads raw magnetic x,y and z axis along with temperature */ + rslt = read_out_raw_data(out_data, dev); + + if (rslt == BMM350_OK) + { + /* Apply compensation to temperature reading */ + out_data[3] = (1 + dev->mag_comp.dut_sensit_coef.t_sens) * out_data[3] + + dev->mag_comp.dut_offset_coef.t_offs; + + /* Store magnetic compensation structure to an array */ + dut_offset_coef[0] = dev->mag_comp.dut_offset_coef.offset_x; + dut_offset_coef[1] = dev->mag_comp.dut_offset_coef.offset_y; + dut_offset_coef[2] = dev->mag_comp.dut_offset_coef.offset_z; + + dut_sensit_coef[0] = dev->mag_comp.dut_sensit_coef.sens_x; + dut_sensit_coef[1] = dev->mag_comp.dut_sensit_coef.sens_y; + dut_sensit_coef[2] = dev->mag_comp.dut_sensit_coef.sens_z; + + dut_tco[0] = dev->mag_comp.dut_tco.tco_x; + dut_tco[1] = dev->mag_comp.dut_tco.tco_y; + dut_tco[2] = dev->mag_comp.dut_tco.tco_z; + + dut_tcs[0] = dev->mag_comp.dut_tcs.tcs_x; + dut_tcs[1] = dev->mag_comp.dut_tcs.tcs_y; + dut_tcs[2] = dev->mag_comp.dut_tcs.tcs_z; + + /* Compensate raw magnetic data */ + for (indx = 0; indx < 3; indx++) + { + out_data[indx] *= 1 + dut_sensit_coef[indx]; + out_data[indx] += dut_offset_coef[indx]; + out_data[indx] += dut_tco[indx] * (out_data[3] - dev->mag_comp.dut_t0); + out_data[indx] /= 1 + dut_tcs[indx] * (out_data[3] - dev->mag_comp.dut_t0); + } + + cr_ax_comp_x = (out_data[0] - dev->mag_comp.cross_axis.cross_x_y * out_data[1]) / + (1 - dev->mag_comp.cross_axis.cross_y_x * dev->mag_comp.cross_axis.cross_x_y); + cr_ax_comp_y = (out_data[1] - dev->mag_comp.cross_axis.cross_y_x * out_data[0]) / + (1 - dev->mag_comp.cross_axis.cross_y_x * dev->mag_comp.cross_axis.cross_x_y); + cr_ax_comp_z = + (out_data[2] + + (out_data[0] * + (dev->mag_comp.cross_axis.cross_y_x * dev->mag_comp.cross_axis.cross_z_y - + dev->mag_comp.cross_axis.cross_z_x) - out_data[1] * + (dev->mag_comp.cross_axis.cross_z_y - dev->mag_comp.cross_axis.cross_x_y * + dev->mag_comp.cross_axis.cross_z_x)) / + (1 - dev->mag_comp.cross_axis.cross_y_x * dev->mag_comp.cross_axis.cross_x_y)); + + out_data[0] = cr_ax_comp_x; + out_data[1] = cr_ax_comp_y; + out_data[2] = cr_ax_comp_z; + } + + if (rslt == BMM350_OK) + { + if ((dev->axisEn & BMM350_EN_X_MSK) == BMM350_DISABLE) + { + mag_temp_data->x = BMM350_DISABLE; + } + else + { + mag_temp_data->x = out_data[0]; + } + + if ((dev->axisEn & BMM350_EN_Y_MSK) == BMM350_DISABLE) + { + mag_temp_data->y = BMM350_DISABLE; + } + else + { + mag_temp_data->y = out_data[1]; + } + + if ((dev->axisEn & BMM350_EN_Z_MSK) == BMM350_DISABLE) + { + mag_temp_data->z = BMM350_DISABLE; + } + else + { + mag_temp_data->z = out_data[2]; + } + + mag_temp_data->temperature = out_data[3]; + } + } + else + { + rslt = BMM350_E_NULL_PTR; + } + + return rslt; +} + +/*! + * @brief This function executes FGR and BR sequences to initialize TMR sensor and performs the user self-test. + */ +int8_t bmm350PerformSelfTest(struct sBmm350SelfTest_t *out_data, struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + /* Variable to store last powermode */ + uint8_t last_pwr_mode; + + if (out_data != NULL) + { + rslt = bmm350GetRegs(BMM350_REG_PMU_CMD, &last_pwr_mode, 1, dev); + + if (rslt == BMM350_OK) + { + /* Self-test entry configuration */ + rslt = self_test_entry_config(dev); + + if (rslt == BMM350_OK) + { + /* Updates self-test values to structure */ + rslt = self_test_xy_axis(out_data, dev); + } + } + + if (rslt == BMM350_OK) + { + /* Setup DUT: disable user self-test */ + rslt = bmm350_set_tmr_selftest_user(BMM350_ST_IGEN_DIS, + BMM350_ST_N_DIS, + BMM350_ST_P_DIS, + BMM350_IST_X_DIS, + BMM350_IST_Y_DIS, + dev); + + if (rslt == BMM350_OK) + { + rslt = bmm350DelayUs(1000, dev); + } + + if (last_pwr_mode == BMM350_PMU_CMD_NM) + { + rslt = bmm350SetPowerMode(eBmm350NormalMode, dev); + } + } + } + else + { + rslt = BMM350_E_NULL_PTR; + } + + return rslt; +} + +/*! + * @brief This API sets the I2C watchdog timer configurations to the sensor. + */ +int8_t bmm350_set_i2c_wdt(enum bmm350_i2c_wdt_en i2c_wdt_en_dis, + enum bmm350_i2c_wdt_sel i2c_wdt_sel, + struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + uint8_t reg_data; + + /* Get I2C WDT configuration */ + rslt = bmm350GetRegs(BMM350_REG_I2C_WDT_SET, ®_data, 1, dev); + + if (rslt == BMM350_OK) + { + reg_data = BMM350_SET_BITS_POS_0(reg_data, BMM350_I2C_WDT_EN, i2c_wdt_en_dis); + reg_data = BMM350_SET_BITS(reg_data, BMM350_I2C_WDT_SEL, i2c_wdt_sel); + + /* Set I2C WDT configuration */ + rslt = bmm350SetRegs(BMM350_REG_I2C_WDT_SET, ®_data, 1, dev); + } + + return rslt; +} + +/*! + * @brief This API sets the TMR user self-test register + */ +int8_t bmm350_set_tmr_selftest_user(enum bmm350_st_igen_en st_igen_en_dis, + enum bmm350_st_n st_n_en_dis, + enum bmm350_st_p st_p_en_dis, + enum bmm350_ist_en_x ist_x_en_dis, + enum bmm350_ist_en_y ist_y_en_dis, + struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + uint8_t reg_data; + + /* Get TMR self-test user configuration */ + rslt = bmm350GetRegs(BMM350_REG_TMR_SELFTEST_USER, ®_data, 1, dev); + + if (rslt == BMM350_OK) + { + reg_data = BMM350_SET_BITS_POS_0(reg_data, BMM350_ST_IGEN_EN, st_igen_en_dis); + reg_data = BMM350_SET_BITS(reg_data, BMM350_ST_N, st_n_en_dis); + reg_data = BMM350_SET_BITS(reg_data, BMM350_ST_P, st_p_en_dis); + reg_data = BMM350_SET_BITS(reg_data, BMM350_IST_EN_X, ist_x_en_dis); + reg_data = BMM350_SET_BITS(reg_data, BMM350_IST_EN_Y, ist_y_en_dis); + + /* Set TMR self-test user configuration */ + rslt = bmm350SetRegs(BMM350_REG_TMR_SELFTEST_USER, ®_data, 1, dev); + } + + return rslt; +} + +/*! + * @brief This API sets the control user configurations to the sensor which forces the sensor timer to be always + * running, even in suspend mode. + */ +int8_t bmm350_set_ctrl_user(enum bmm350_ctrl_user cfg_sens_tim_aon_en_dis, struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + uint8_t reg_data; + + /* Get control user configuration */ + rslt = bmm350GetRegs(BMM350_REG_CTRL_USER, ®_data, 1, dev); + + if (rslt == BMM350_OK) + { + reg_data = BMM350_SET_BITS_POS_0(reg_data, BMM350_CFG_SENS_TIM_AON, cfg_sens_tim_aon_en_dis); + + /* Set control user configuration */ + rslt = bmm350SetRegs(BMM350_REG_CTRL_USER, ®_data, 1, dev); + } + + return rslt; +} + +/*! + * @brief This API gets the PMU command status 0 value + */ +int8_t bmm350_get_pmu_cmd_status_0(struct bmm350_pmu_cmd_status_0 *pmu_cmd_stat_0, struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + uint8_t reg_data; + + if (pmu_cmd_stat_0 != NULL) + { + /* Get PMU command status 0 data */ + rslt = bmm350GetRegs(BMM350_REG_PMU_CMD_STATUS_0, ®_data, 1, dev); + + if (rslt == BMM350_OK) + { + pmu_cmd_stat_0->pmu_cmd_busy = BMM350_GET_BITS_POS_0(reg_data, BMM350_PMU_CMD_BUSY); + + pmu_cmd_stat_0->odr_ovwr = BMM350_GET_BITS(reg_data, BMM350_ODR_OVWR); + + pmu_cmd_stat_0->avr_ovwr = BMM350_GET_BITS(reg_data, BMM350_AVG_OVWR); + + pmu_cmd_stat_0->pwr_mode_is_normal = BMM350_GET_BITS(reg_data, BMM350_PWR_MODE_IS_NORMAL); + + pmu_cmd_stat_0->cmd_is_illegal = BMM350_GET_BITS(reg_data, BMM350_CMD_IS_ILLEGAL); + + pmu_cmd_stat_0->pmu_cmd_value = BMM350_GET_BITS(reg_data, BMM350_PMU_CMD_VALUE); + } + } + else + { + rslt = BMM350_E_NULL_PTR; + } + + return rslt; +} + +/****************************************************************************/ +/**\name INTERNAL APIs */ + +/*! + * @brief This internal API is used to validate the device structure pointer for + * null conditions. + */ +static int8_t null_ptr_check(const struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + if ((dev == NULL) || (dev->read == NULL) || (dev->write == NULL) || (dev->delayUs == NULL)) + { + /* Device structure pointer is not valid */ + rslt = BMM350_E_NULL_PTR; + } + else + { + /* Device structure is fine */ + rslt = BMM350_OK; + } + + return rslt; +} + +/*! + * @brief This internal API converts the raw data from the IC data registers to signed integer + */ +static int32_t fix_sign(uint32_t inval, int8_t number_of_bits) +{ + int32_t power = 0; + int32_t retval; + + switch (number_of_bits) + { + case BMM350_SIGNED_8_BIT: + power = 128; /* 2^7 */ + break; + + case BMM350_SIGNED_12_BIT: + power = 2048; /* 2^11 */ + break; + + case BMM350_SIGNED_16_BIT: + power = 32768; /* 2^15 */ + break; + + case BMM350_SIGNED_21_BIT: + power = 1048576; /* 2^20 */ + break; + + case BMM350_SIGNED_24_BIT: + power = 8388608; /* 2^23 */ + break; + + default: + power = 0; + break; + } + + retval = (int32_t)inval; + + if (retval >= power) + { + retval = retval - (power * 2); + } + + return retval; +} + +/*! + * @brief This internal API is used to read OTP word + */ +static int8_t read_otp_word(uint8_t addr, uint16_t *lsb_msb, struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + uint8_t otp_cmd, otp_status = 0, otp_err = BMM350_OTP_STATUS_NO_ERROR, lsb = 0, msb = 0; + + if (lsb_msb != NULL) + { + /* Set OTP command at specified address */ + otp_cmd = BMM350_OTP_CMD_DIR_READ | (addr & BMM350_OTP_WORD_ADDR_MSK); + rslt = bmm350SetRegs(BMM350_REG_OTP_CMD_REG, &otp_cmd, 1, dev); + if (rslt == BMM350_OK) + { + do + { + rslt = bmm350DelayUs(300, dev); + + if (rslt == BMM350_OK) + { + /* Get OTP status */ + rslt = bmm350GetRegs(BMM350_REG_OTP_STATUS_REG, &otp_status, 1, dev); + + otp_err = BMM350_OTP_STATUS_ERROR(otp_status); + if (otp_err != BMM350_OTP_STATUS_NO_ERROR) + { + break; + } + } + } while ((!(otp_status & BMM350_OTP_STATUS_CMD_DONE)) && (rslt == BMM350_OK)); + + if (otp_err != BMM350_OTP_STATUS_NO_ERROR) + { + switch (otp_err) + { + case BMM350_OTP_STATUS_BOOT_ERR: + rslt = BMM350_E_OTP_BOOT; + break; + case BMM350_OTP_STATUS_PAGE_RD_ERR: + rslt = BMM350_E_OTP_PAGE_RD; + break; + case BMM350_OTP_STATUS_PAGE_PRG_ERR: + rslt = BMM350_E_OTP_PAGE_PRG; + break; + case BMM350_OTP_STATUS_SIGN_ERR: + rslt = BMM350_E_OTP_SIGN; + break; + case BMM350_OTP_STATUS_INV_CMD_ERR: + rslt = BMM350_E_OTP_INV_CMD; + break; + default: + rslt = BMM350_E_OTP_UNDEFINED; + break; + } + } + } + + if (rslt == BMM350_OK) + { + /* Get OTP MSB data */ + rslt = bmm350GetRegs(BMM350_REG_OTP_DATA_MSB_REG, &msb, 1, dev); + if (rslt == BMM350_OK) + { + /* Get OTP LSB data */ + rslt = bmm350GetRegs(BMM350_REG_OTP_DATA_LSB_REG, &lsb, 1, dev); + *lsb_msb = ((uint16_t)(msb << 8) | lsb) & 0xFFFF; + } + } + } + else + { + rslt = BMM350_E_NULL_PTR; + } + + return rslt; +} + +/*! + * @brief This internal API is used to update magnetometer offset and sensitivity data. + */ +static void update_mag_off_sens(struct bmm350_dev *dev) +{ + uint16_t off_x_lsb_msb, off_y_lsb_msb, off_z_lsb_msb, t_off; + uint8_t sens_x, sens_y, sens_z, t_sens; + uint8_t tco_x, tco_y, tco_z; + uint8_t tcs_x, tcs_y, tcs_z; + uint8_t cross_x_y, cross_y_x, cross_z_x, cross_z_y; + + off_x_lsb_msb = dev->otp_data[BMM350_MAG_OFFSET_X] & 0x0FFF; + off_y_lsb_msb = ((dev->otp_data[BMM350_MAG_OFFSET_X] & 0xF000) >> 4) + + (dev->otp_data[BMM350_MAG_OFFSET_Y] & BMM350_LSB_MASK); + off_z_lsb_msb = (dev->otp_data[BMM350_MAG_OFFSET_Y] & 0x0F00) + + (dev->otp_data[BMM350_MAG_OFFSET_Z] & BMM350_LSB_MASK); + t_off = dev->otp_data[BMM350_TEMP_OFF_SENS] & BMM350_LSB_MASK; + + dev->mag_comp.dut_offset_coef.offset_x = fix_sign(off_x_lsb_msb, BMM350_SIGNED_12_BIT); + dev->mag_comp.dut_offset_coef.offset_y = fix_sign(off_y_lsb_msb, BMM350_SIGNED_12_BIT); + dev->mag_comp.dut_offset_coef.offset_z = fix_sign(off_z_lsb_msb, BMM350_SIGNED_12_BIT); + dev->mag_comp.dut_offset_coef.t_offs = fix_sign(t_off, BMM350_SIGNED_8_BIT) / 5.0f; + + sens_x = (dev->otp_data[BMM350_MAG_SENS_X] & BMM350_MSB_MASK) >> 8; + sens_y = (dev->otp_data[BMM350_MAG_SENS_Y] & BMM350_LSB_MASK); + sens_z = (dev->otp_data[BMM350_MAG_SENS_Z] & BMM350_MSB_MASK) >> 8; + t_sens = (dev->otp_data[BMM350_TEMP_OFF_SENS] & BMM350_MSB_MASK) >> 8; + + dev->mag_comp.dut_sensit_coef.sens_x = fix_sign(sens_x, BMM350_SIGNED_8_BIT) / 256.0f; + dev->mag_comp.dut_sensit_coef.sens_y = (fix_sign(sens_y, BMM350_SIGNED_8_BIT) / 256.0f) + BMM350_SENS_CORR_Y; + dev->mag_comp.dut_sensit_coef.sens_z = fix_sign(sens_z, BMM350_SIGNED_8_BIT) / 256.0f; + dev->mag_comp.dut_sensit_coef.t_sens = fix_sign(t_sens, BMM350_SIGNED_8_BIT) / 512.0f; + + tco_x = (dev->otp_data[BMM350_MAG_TCO_X] & BMM350_LSB_MASK); + tco_y = (dev->otp_data[BMM350_MAG_TCO_Y] & BMM350_LSB_MASK); + tco_z = (dev->otp_data[BMM350_MAG_TCO_Z] & BMM350_LSB_MASK); + + dev->mag_comp.dut_tco.tco_x = fix_sign(tco_x, BMM350_SIGNED_8_BIT) / 32.0f; + dev->mag_comp.dut_tco.tco_y = fix_sign(tco_y, BMM350_SIGNED_8_BIT) / 32.0f; + dev->mag_comp.dut_tco.tco_z = fix_sign(tco_z, BMM350_SIGNED_8_BIT) / 32.0f; + + tcs_x = (dev->otp_data[BMM350_MAG_TCS_X] & BMM350_MSB_MASK) >> 8; + tcs_y = (dev->otp_data[BMM350_MAG_TCS_Y] & BMM350_MSB_MASK) >> 8; + tcs_z = (dev->otp_data[BMM350_MAG_TCS_Z] & BMM350_MSB_MASK) >> 8; + + dev->mag_comp.dut_tcs.tcs_x = fix_sign(tcs_x, BMM350_SIGNED_8_BIT) / 16384.0f; + dev->mag_comp.dut_tcs.tcs_y = fix_sign(tcs_y, BMM350_SIGNED_8_BIT) / 16384.0f; + dev->mag_comp.dut_tcs.tcs_z = (fix_sign(tcs_z, BMM350_SIGNED_8_BIT) / 16384.0f) - BMM350_TCS_CORR_Z; + + dev->mag_comp.dut_t0 = (fix_sign(dev->otp_data[BMM350_MAG_DUT_T_0], BMM350_SIGNED_16_BIT) / 512.0f) + 23.0f; + + cross_x_y = (dev->otp_data[BMM350_CROSS_X_Y] & BMM350_LSB_MASK); + cross_y_x = (dev->otp_data[BMM350_CROSS_Y_X] & BMM350_MSB_MASK) >> 8; + cross_z_x = (dev->otp_data[BMM350_CROSS_Z_X] & BMM350_LSB_MASK); + cross_z_y = (dev->otp_data[BMM350_CROSS_Z_Y] & BMM350_MSB_MASK) >> 8; + + dev->mag_comp.cross_axis.cross_x_y = fix_sign(cross_x_y, BMM350_SIGNED_8_BIT) / 800.0f; + dev->mag_comp.cross_axis.cross_y_x = fix_sign(cross_y_x, BMM350_SIGNED_8_BIT) / 800.0f; + dev->mag_comp.cross_axis.cross_z_x = fix_sign(cross_z_x, BMM350_SIGNED_8_BIT) / 800.0f; + dev->mag_comp.cross_axis.cross_z_y = fix_sign(cross_z_y, BMM350_SIGNED_8_BIT) / 800.0f; +} + +/*! + * @brief This internal API is used to read raw magnetic x,y and z axis along with temperature + */ +static int8_t read_out_raw_data(float *out_data, struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + float temp = 0.0; + struct bmm350_raw_mag_data raw_data = { 0 }; + + /* Float variable to convert mag lsb to uT and temp lsb to degC */ + float lsb_to_ut_degc[4]; + + if (out_data != NULL) + { + rslt = bmm350_read_uncomp_mag_temp_data(&raw_data, dev); + + if (rslt == BMM350_OK) + { + /* Convert mag lsb to uT and temp lsb to degC */ + update_default_coefiecents(lsb_to_ut_degc); + + out_data[0] = (float)raw_data.raw_xdata * lsb_to_ut_degc[0]; + out_data[1] = (float)raw_data.raw_ydata * lsb_to_ut_degc[1]; + out_data[2] = (float)raw_data.raw_zdata * lsb_to_ut_degc[2]; + out_data[3] = (float)raw_data.raw_data_t * lsb_to_ut_degc[3]; + + if (out_data[3] > 0.0) + { + temp = (float)(out_data[3] - (1 * 25.49)); + } + else if (out_data[3] < 0.0) + { + temp = (float)(out_data[3] - (-1 * 25.49)); + } + else + { + temp = (float)(out_data[3]); + } + + out_data[3] = temp; + } + } + else + { + rslt = BMM350_E_NULL_PTR; + } + + return rslt; +} + +/*! + * @brief This internal API is used to convert lsb to uT and degC. + */ +static void update_default_coefiecents(float *lsb_to_ut_degc) +{ + float bxy_sens, bz_sens, temp_sens, ina_xy_gain_trgt, ina_z_gain_trgt, adc_gain, lut_gain; + float power; + + bxy_sens = 14.55f; + bz_sens = 9.0f; + temp_sens = 0.00204f; + + ina_xy_gain_trgt = 19.46f; + + ina_z_gain_trgt = 31.0; + + adc_gain = 1 / 1.5f; + lut_gain = 0.714607238769531f; + + power = (float)(1000000.0 / 1048576.0); + + lsb_to_ut_degc[0] = (power / (bxy_sens * ina_xy_gain_trgt * adc_gain * lut_gain)); + lsb_to_ut_degc[1] = (power / (bxy_sens * ina_xy_gain_trgt * adc_gain * lut_gain)); + lsb_to_ut_degc[2] = (power / (bz_sens * ina_z_gain_trgt * adc_gain * lut_gain)); + lsb_to_ut_degc[3] = 1 / (temp_sens * adc_gain * lut_gain * 1048576); +} + +/*! + * @brief This internal API is used to read OTP data after boot in user mode. + */ +static int8_t otp_dump_after_boot(struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + uint16_t otp_word = 0; + uint8_t indx; + + for (indx = 0; indx < BMM350_OTP_DATA_LENGTH; indx++) + { + rslt = read_otp_word(indx, &otp_word, dev); + dev->otp_data[indx] = otp_word; + } + + dev->var_id = (dev->otp_data[30] & 0x7f00) >> 9; + + /* Update magnetometer offset and sensitivity data. */ + update_mag_off_sens(dev); + + return rslt; +} + +/*! + * @brief This internal API is used for self-test entry configuration + */ +static int8_t self_test_entry_config(struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + /* Variable to store PMU command */ + uint8_t cmd; + + /* Structure instance of PMU command status 0 */ + struct bmm350_pmu_cmd_status_0 pmu_cmd_stat_0 = { 0 }; + + /* Set suspend mode */ + cmd = BMM350_PMU_CMD_SUS; + + rslt = bmm350SetRegs(BMM350_REG_PMU_CMD, &cmd, 1, dev); + + if (rslt == BMM350_OK) + { + rslt = bmm350DelayUs(30000, dev); + } + + /* Read DUT outputs in FORCED mode */ + if (rslt == BMM350_OK) + { + rslt = bmm350SetOdrPerformance(BMM350_DATA_RATE_100HZ, BMM350_AVERAGING_2, dev); + + if (rslt == BMM350_OK) + { + /* Enable all axis */ + rslt = bmm350_enable_axes(BMM350_X_EN, BMM350_Y_EN, BMM350_Z_EN, dev); + } + } + + /* Execute FGR with full CRST recharge */ + cmd = BMM350_PMU_CMD_FGR; + + if (rslt == BMM350_OK) + { + rslt = bmm350SetRegs(BMM350_REG_PMU_CMD, &cmd, 1, dev); + + if (rslt == BMM350_OK) + { + rslt = bmm350DelayUs(30000, dev); + } + } + + if (rslt == BMM350_OK) + { + rslt = bmm350_get_pmu_cmd_status_0(&pmu_cmd_stat_0, dev); + + if ((rslt == BMM350_OK) && (pmu_cmd_stat_0.pmu_cmd_value == BMM350_PMU_CMD_STATUS_0_FGR)) + { + /* Execute BR with full CRST recharge */ + cmd = BMM350_PMU_CMD_BR_FAST; + + rslt = bmm350SetRegs(BMM350_REG_PMU_CMD, &cmd, 1, dev); + + if (rslt == BMM350_OK) + { + rslt = bmm350DelayUs(4000, dev); + } + } + } + + if (rslt == BMM350_OK) + { + rslt = bmm350_get_pmu_cmd_status_0(&pmu_cmd_stat_0, dev); + } + + if ((rslt == BMM350_OK) && (pmu_cmd_stat_0.pmu_cmd_value == BMM350_PMU_CMD_STATUS_0_BR_FAST)) + { + cmd = BMM350_PMU_CMD_FM_FAST; + + rslt = bmm350SetRegs(BMM350_REG_PMU_CMD, &cmd, 1, dev); + + if (rslt == BMM350_OK) + { + rslt = bmm350DelayUs(16000, dev); + } + + if (rslt == BMM350_OK) + { + rslt = bmm350_get_pmu_cmd_status_0(&pmu_cmd_stat_0, dev); + + if ((rslt == BMM350_OK) && (pmu_cmd_stat_0.pmu_cmd_value == BMM350_PMU_CMD_STATUS_0_FM_FAST)) + { + rslt = bmm350DelayUs(10, dev); + } + } + } + + return rslt; +} + +/*! + * @brief This internal API is used to test self-test for X and Y axis + */ +static int8_t self_test_xy_axis(struct sBmm350SelfTest_t *out_data, struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + /* Set pmu command */ + uint8_t cmd = BMM350_PMU_CMD_FM_FAST; + + /* Setup DUT: enable positive user self-test on x-axis */ + rslt = self_test_config(BMM350_SELF_TEST_POS_X, cmd, out_data, dev); + + if (rslt == BMM350_OK) + { + /* Setup DUT: enable negative user self-test on x-axis */ + rslt = self_test_config(BMM350_SELF_TEST_NEG_X, cmd, out_data, dev); + + if (rslt == BMM350_OK) + { + /* Setup DUT: enable positive user self-test on y-axis */ + rslt = self_test_config(BMM350_SELF_TEST_POS_Y, cmd, out_data, dev); + + if (rslt == BMM350_OK) + { + /* Setup DUT: enable negative user self-test on y-axis */ + rslt = self_test_config(BMM350_SELF_TEST_NEG_Y, cmd, out_data, dev); + } + } + } + + return rslt; +} + +/*! + * @brief This internal API is used to set self-test configurations. + */ +static int8_t self_test_config(uint8_t st_cmd, + uint8_t pmu_cmd, + struct sBmm350SelfTest_t *out_data, + struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + float out_ust[4]; + + struct bmm350_pmu_cmd_status_0 pmu_cmd_stat_0 = { 0 }; + + static float out_ustxh = 0.0, out_ustxl = 0.0, out_ustyh = 0.0, out_ustyl = 0.0; + + rslt = bmm350SetRegs(BMM350_REG_TMR_SELFTEST_USER, &st_cmd, 1, dev); + + if (rslt == BMM350_OK) + { + rslt = bmm350DelayUs(1000, dev); + } + + if (rslt == BMM350_OK) + { + rslt = bmm350SetRegs(BMM350_REG_PMU_CMD, &pmu_cmd, 1, dev); + + if (rslt == BMM350_OK) + { + rslt = bmm350DelayUs(6000, dev); + + if (rslt == BMM350_OK) + { + rslt = bmm350_get_pmu_cmd_status_0(&pmu_cmd_stat_0, dev); + } + } + } + + if ((rslt == BMM350_OK) && (pmu_cmd_stat_0.pmu_cmd_value == BMM350_PMU_CMD_STATUS_0_FM_FAST)) + { + /* Reads raw magnetic x and y axis */ + rslt = read_out_raw_data(out_ust, dev); + + if (rslt == BMM350_OK) + { + /* Read DUT outputs in FORCED mode (XP_UST) */ + if (st_cmd == BMM350_SELF_TEST_POS_X) + { + out_ustxh = out_ust[0]; + } + /* Read DUT outputs in FORCED mode (XN_UST) */ + else if (st_cmd == BMM350_SELF_TEST_NEG_X) + { + out_ustxl = out_ust[0]; + } + /* Read DUT outputs in FORCED mode (YP_UST) */ + else if (st_cmd == BMM350_SELF_TEST_POS_Y) + { + out_ustyh = out_ust[1]; + } + /* Read DUT outputs in FORCED mode (YN_UST) */ + else if (st_cmd == BMM350_SELF_TEST_NEG_Y) + { + out_ustyl = out_ust[1]; + } + else + { + /* Returns error if self-test axis is wrong */ + rslt = BMM350_E_SELF_TEST_INVALID_AXIS; + } + + if (rslt == BMM350_OK) + { + out_data->out_ust_x = out_ustxh - out_ustxl; + out_data->out_ust_y = out_ustyh - out_ustyl; + } + } + } + + return rslt; +} + +/*! + * @brief This internal API is used to switch from suspend mode to normal mode or forced mode. + */ +static int8_t set_powermode(enum eBmm350PowerModes_t powermode, struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + uint8_t reg_data = powermode; + uint8_t get_avg; + + /* Array to store suspend to forced mode delay */ + uint32_t sus_to_forced_mode[4] = + { BMM350_SUS_TO_FORCEDMODE_NO_AVG_DELAY, BMM350_SUS_TO_FORCEDMODE_AVG_2_DELAY, BMM350_SUS_TO_FORCEDMODE_AVG_4_DELAY, + BMM350_SUS_TO_FORCEDMODE_AVG_8_DELAY }; + + /* Array to store suspend to forced mode fast delay */ + uint32_t sus_to_forced_mode_fast[4] = + { BMM350_SUS_TO_FORCEDMODE_FAST_NO_AVG_DELAY, BMM350_SUS_TO_FORCEDMODE_FAST_AVG_2_DELAY, + BMM350_SUS_TO_FORCEDMODE_FAST_AVG_4_DELAY, BMM350_SUS_TO_FORCEDMODE_FAST_AVG_8_DELAY }; + + uint8_t avg = 0; + uint32_t delay_us = 0; + + rslt = null_ptr_check(dev); + + if (rslt == BMM350_OK) + { + /* Set PMU command configuration to desired power mode */ + rslt = bmm350SetRegs(BMM350_REG_PMU_CMD, ®_data, 1, dev); + + if (rslt == BMM350_OK) + { + /* Get average configuration */ + rslt = bmm350GetRegs(BMM350_REG_PMU_CMD_AGGR_SET, &get_avg, 1, dev); + + if (rslt == BMM350_OK) + { + /* Mask the average value */ + avg = ((get_avg & BMM350_AVG_MSK) >> BMM350_AVG_POS); + } + } + } + + if (rslt == BMM350_OK) + { + /* Check if desired power mode is normal mode */ + if (powermode == eBmm350NormalMode) + { + delay_us = BMM350_SUSPEND_TO_NORMAL_DELAY; + } + + /* Check if desired power mode is forced mode */ + if (powermode == eBmm350ForcedMode) + { + /* Store delay based on averaging mode */ + delay_us = sus_to_forced_mode[avg]; + } + + /* Check if desired power mode is forced mode fast */ + if (powermode == eBmm350ForcedModeFast) + { + /* Store delay based on averaging mode */ + delay_us = sus_to_forced_mode_fast[avg]; + } + + /* Perform delay based on power mode */ + rslt = bmm350DelayUs(delay_us, dev); + } + + return rslt; +} diff --git a/lib/DFRobot_BMM350/src/bmm350.h b/lib/DFRobot_BMM350/src/bmm350.h new file mode 100644 index 0000000..e1653fe --- /dev/null +++ b/lib/DFRobot_BMM350/src/bmm350.h @@ -0,0 +1,595 @@ +/** +* Copyright (c) 2023 Bosch Sensortec GmbH. All rights reserved. +* +* BSD-3-Clause +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* 1. Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* +* 2. Redistributions in binary form must reproduce the above copyright +* notice, this list of conditions and the following disclaimer in the +* documentation and/or other materials provided with the distribution. +* +* 3. Neither the name of the copyright holder nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) +* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, +* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING +* IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* @file bmm350.h +* @date 2023-05-26 +* @version v1.4.0 +* +*/ + +/*! + * @defgroup bmm350 BMM350 + * @brief Sensor driver for BMM350 sensor + */ + +#ifndef _BMM350_H +#define _BMM350_H + +/*! CPP guard */ +#ifdef __cplusplus +extern "C" { +#endif + +/*************************** Header files *******************************/ + +#include "bmm350_defs.h" + +/******************* Function prototype declarations ********************/ + +/** + * \ingroup bmm350 + * \defgroup bmm350ApiInit Initialization + * @brief Initialize the sensor and device structure + */ + +/*! +* \ingroup bmm350ApiInit +* \page bmm350_api_bmm350Init bmm350Init +* \code +* int8_t bmm350Init(struct bmm350_dev *dev); +* \endcode +* @details This API is the entry point. Call this API before using other APIs. +* This API reads the chip-id of the sensor which is the first step to +* verify the sensor and also it configures the read mechanism of I2C and +* I3C interface. +* +* @param[in,out] dev : Structure instance of bmm350_dev +* +* @return Result of API execution status +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ +int8_t bmm350Init(struct bmm350_dev *dev); + +/** + * \ingroup bmm350 + * \defgroup bmm350ApiReset Reset + * @brief Reset APIs + */ + +/*! +* \ingroup bmm350ApiReset +* \page bmm350_api_bmm350SoftReset bmm350SoftReset +* \code +* int8_t bmm350SoftReset(struct bmm350_dev *dev); +* \endcode +* @details This API is used to perform soft-reset of the sensor +* where all the registers are reset to their default values. +* +* @param[in] dev : Structure instance of bmm350_dev. +* +* @return Result of API execution status +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ + +int8_t bmm350SoftReset(struct bmm350_dev *dev); + +/** + * \ingroup bmm350 + * \defgroup bmm350ApiSetGet Set-Get + * @brief Set and Get APIs + */ + +/*! +* \ingroup bmm350ApiSetGet +* \page bmm350_api_bmm350SetRegs bmm350SetRegs +* \code +* int8_t bmm350SetRegs(uint8_t reg_addr, const uint8_t *reg_data, uint16_t len, struct bmm350_dev *dev); +* \endcode +* @details This API writes the given data to the register address +* of the sensor. +* +* @param[in] reg_addr : Register address from where the data to be written. +* @param[in] reg_data : Pointer to data buffer which is to be written +* in the reg_addr of sensor. +* @param[in] len : No of bytes of data to write.. +* @param[in, out] dev : Structure instance of bmm350_dev. +* +* @return Result of API execution status +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ +int8_t bmm350SetRegs(uint8_t reg_addr, const uint8_t *reg_data, uint16_t len, struct bmm350_dev *dev); + +/*! +* \ingroup bmm350ApiSetGet +* \page bmm350_api_bmm350GetRegs bmm350GetRegs +* \code +* int8_t bmm350GetRegs(uint8_t reg_addr, uint8_t *reg_data, uint16_t len, struct bmm350_dev *dev); +* \endcode +* @details This API reads the data from the given register address of sensor. +* +* @param[in] reg_addr : Register address from where the data to be read +* @param[out] reg_data : Pointer to data buffer to store the read data. +* @param[in] len : No of bytes of data to be read. +* @param[in] dev : Structure instance of bmm350_dev. +* +* @return Result of API execution status +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ +int8_t bmm350GetRegs(uint8_t reg_addr, uint8_t *reg_data, uint16_t len, struct bmm350_dev *dev); + +/** + * \ingroup bmm350 + * \defgroup bmm350ApiDelay Delay + * @brief Delay function in microseconds + */ + +/*! +* \ingroup bmm350ApiDelay +* \page bmm350_api_bmm350DelayUs bmm350DelayUs +* \code +* int8_t bmm350DelayUs(uint32_t period_us, const struct bmm350_dev *dev); +* \endcode +* @details This function provides the delay for required time (Microsecond) as per the input provided in some of the +* APIs. +* +* @param[in] period_us : The required wait time in microsecond. +* @param[in] dev : Structure instance of bmm350_dev. +* +* @return Result of API execution status +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ +int8_t bmm350DelayUs(uint32_t period_us, const struct bmm350_dev *dev); + +/*! +* \ingroup bmm350ApiSetGet +* \page bmm350_api_bmm350GetInterruptStatus bmm350GetInterruptStatus +* \code +* int8_t bmm350GetInterruptStatus(uint8_t *drdy_status, struct bmm350_dev *dev); +* \endcode +* @details This API obtains the status flags of all interrupt +* which is used to check for the assertion of interrupts +* +* @param[in,out] drdy_status : Variable to store data ready interrupt status. +* @param[in,out] dev : Structure instance of bmm350_dev. +* +* +* @return Result of API execution status and self test result. +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ +int8_t bmm350GetInterruptStatus(uint8_t *drdy_status, struct bmm350_dev *dev); + +/*! +* \ingroup bmm350ApiSetGet +* \page bmm350_api_bmm350SetPowerMode bmm350SetPowerMode +* \code +* int8_t bmm350SetPowerMode(enum eBmm350PowerModes_t powermode, struct bmm350_dev *dev); +* \endcode +* @details This API is used to set the power mode of the sensor +* +* @param[in] powermode : Set power mode +* @param[in] dev : Structure instance of bmm350_dev. +* +*@verbatim + powermode | Power mode + -------------------------|----------------------- + | eBmm350SuspendMode + | eBmm350NormalMode + | eBmm350ForcedMode + | eBmm350ForcedModeFast +*@endverbatim +* +* @return Result of API execution status +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ +int8_t bmm350SetPowerMode(enum eBmm350PowerModes_t powermode, struct bmm350_dev *dev); + +/*! +* \ingroup bmm350ApiSetGet +* \page bmm350_api_bmm350SetOdrPerformance bmm350SetOdrPerformance +* \code +* int8_t bmm350SetOdrPerformance(enum eBmm350DataRates_t odr, +* enum bmm350_performance_parameters avg, +* struct bmm350_dev *dev); +* +* \endcode +* @details This API sets the ODR and averaging factor. +* If ODR and performance is a combination which is not allowed, then +* the combination setting is corrected to the next lower possible setting +* +* @param[in] odr : enum eBmm350DataRates_t +* +*@verbatim + Data rate (ODR) | odr + -------------------------|----------------------- + 400Hz | BMM350_DATA_RATE_400HZ + 200Hz | BMM350_DATA_RATE_200HZ + 100Hz | BMM350_DATA_RATE_100HZ + 50Hz | BMM350_DATA_RATE_50HZ + 25Hz | BMM350_DATA_RATE_25HZ + 12.5Hz | BMM350_DATA_RATE_12_5HZ + 6.25Hz | BMM350_DATA_RATE_6_25HZ + 3.125Hz | BMM350_DATA_RATE_3_125HZ + 1.5625Hz | BMM350_DATA_RATE_1_5625HZ +*@endverbatim +* +* @param[in] avg : enum bmm350_performance_parameters +* +*@verbatim + avg | averaging factor alias + ---------------------------|------------------------------------------ + low power/highest noise | BMM350_NO_AVERAGING BMM350_LOWPOWER + lesser noise | BMM350_AVERAGING_2 BMM350_REGULARPOWER + even lesser noise | BMM350_AVERAGING_4 BMM350_LOWNOISE + lowest noise/highest power | BMM350_AVERAGING_8 BMM350_ULTRALOWNOISE +*@endverbatim +* +* @param[in,out] dev : Structure instance of bmm350_dev +* +* @return Result of API execution status +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ +int8_t bmm350SetOdrPerformance(enum eBmm350DataRates_t odr, + enum bmm350_performance_parameters avg, + struct bmm350_dev *dev); + +/*! +* \ingroup bmm350ApiSetGet +* \page bmm350_api_bmm350_enable_axes bmm350_enable_axes +* \code +* int8_t bmm350_enable_axes(enum eBmm350XAxisEnDis_t en_x, enum eBmm350YAxisEnDis_t en_y, enum eBmm350ZAxisEnDis_t en_z, struct bmm350_dev *dev); +* \endcode +* @details This API is used to enable or disable the magnetic +* measurement of x,y,z axes +* +* @param[in] en_x : Enable or disable X axis +* @param[in] en_y : Enable or disable Y axis +* @param[in] en_z : Enable or disable Z axis +* @param[in,out] dev : Structure instance of bmm350_dev. +* +*@verbatim + Value | Axis (en_x, en_y, en_z) + -------------------|----------------------- + BMM350_ENABLE | Enabled + BMM350_DISABLE | Disabled +*@endverbatim +* +* @return Result of API execution status +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ +int8_t bmm350_enable_axes(enum eBmm350XAxisEnDis_t en_x, + enum eBmm350YAxisEnDis_t en_y, + enum eBmm350ZAxisEnDis_t en_z, + struct bmm350_dev *dev); + +/** + * \ingroup bmm350 + * \defgroup bmm350ApiRead Sensortime + * @brief Reads sensortime + */ + +/*! +* \ingroup bmm350ApiRead +* \page bmm350_api_bmm350_read_sensortime bmm350_read_sensortime +* \code +* int8_t bmm350_read_sensortime(uint32_t *seconds, uint32_t *nanoseconds, struct bmm350_dev *dev); +* \endcode +* @details This API is used to read the sensor time. +* It converts the sensor time register values to the representative time value. +* Returns the sensor time in ticks. +* +* @param[out] seconds : Variable to get sensor time in seconds. +* @param[out] nanoseconds : Variable to get sensor time in nanoseconds. +* @param[in] dev : Structure instance of bmm350_dev. +* +* @return Result of API execution status +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ +int8_t bmm350_read_sensortime(uint32_t *seconds, uint32_t *nanoseconds, struct bmm350_dev *dev); + +/** + * \ingroup bmm350 + * \defgroup bmm350ApiInterrupt Enable Interrupt + * @brief Interrupt enable APIs + */ + +/*! +* \ingroup bmm350ApiInterrupt +* \page bmm350_api_bmm350_enable_interrupt bmm350_enable_interrupt +* \code +* int8_t bmm350_enable_interrupt(enum eBmm350InterruptEnableDisable_t enable_disable, struct bmm350_dev *dev); +* \endcode +* @details This API is used to enable or disable the data ready interrupt +* +* @param[in] enable_disable : Enable/ Disable data ready interrupt. +* @param[in] dev : Structure instance of bmm350_dev. +* +* @return Result of API execution status +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ +int8_t bmm350_enable_interrupt(enum eBmm350InterruptEnableDisable_t enable_disable, struct bmm350_dev *dev); + +/*! +* \ingroup bmm350ApiInterrupt +* \page bmm350_api_bmm350_configure_interrupt bmm350_configure_interrupt +* \code +* int8_t bmm350_configure_interrupt(enum bmm350_intr_latch latching, +* enum eBmm350IntrPolarity_t polarity, +* enum bmm350_intr_drive drivertype, +* enum bmm350_intr_map map_nomap, +* struct bmm350_dev *dev); +* \endcode +* @details This API is used to configure the interrupt control settings. +* +* @param[in] latching : Sets either latched or pulsed. +* @param[in] polarity : Sets either polarity high or low. +* @param[in] drivertype : Sets either open drain or push pull. +* @param[in] map_nomap : Sets either map or unmap the pins. +* @param[in] dev : Structure instance of bmm350_dev. +* +* @return Result of API execution status +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ +int8_t bmm350_configure_interrupt(enum bmm350_intr_latch latching, + enum eBmm350IntrPolarity_t polarity, + enum bmm350_intr_drive drivertype, + enum bmm350_intr_map map_nomap, + struct bmm350_dev *dev); + +/** + * \ingroup bmm350 + * \defgroup bmm350ApiUncompMag Uncompensated mag + * @brief Reads uncompensated mag and temperature data + */ + +/*! +* \ingroup bmm350ApiUncompMag +* \page bmm350_api_bmm350_read_uncomp_mag_temp_data bmm350_read_uncomp_mag_temp_data +* \code +* int8_t bmm350_read_uncomp_mag_temp_data(struct bmm350_raw_mag_data *raw_data, struct bmm350_dev *dev); +* \endcode +* @details This API is used to read uncompensated mag and temperature data +* +* @param[in, out] raw_data : Structure instance of bmm350_raw_mag_data. +* @param[in, out] dev : Structure instance of bmm350_dev. +* +* @return Result of API execution status +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ +int8_t bmm350_read_uncomp_mag_temp_data(struct bmm350_raw_mag_data *raw_data, struct bmm350_dev *dev); + +/*! +* \ingroup bmm350ApiSetGet +* \page bmm350_api_bmm350_set_int_ctrl_ibi bmm350_set_int_ctrl_ibi +* \code +* int8_t bmm350_set_int_ctrl_ibi(enum bmm350_drdy_int_map_to_ibi en_dis, +* enum bmm350_clear_drdy_int_status_upon_ibi clear_on_ibi, struct bmm350_dev *dev); +* \endcode +* @details This API sets the interrupt control IBI configurations to the sensor. +* And enables conventional interrupt if IBI is enabled. +* +* @param[in] en_dis : Sets either enable or disable IBI. +* @param[in] clear_on_ibi : sets either clear or no clear on IBI. +* @param[in] dev : Structure instance of bmm350_dev. +* +* @return Result of API execution status +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ +int8_t bmm350_set_int_ctrl_ibi(enum bmm350_drdy_int_map_to_ibi en_dis, + enum bmm350_clear_drdy_int_status_upon_ibi clear_on_ibi, + struct bmm350_dev *dev); + +/*! +* \ingroup bmm350ApiSetGet +* \page bmm350_api_bmm350_set_pad_drive bmm350_set_pad_drive +* \code +* int8_t bmm350_set_pad_drive(uint8_t drive, struct bmm350_dev *dev); +* \endcode +* @details This API is used to set the pad drive strength +* +* @param[in] drive : Drive settings, range 0 (weak) ..7(strong) +* @param[in] dev : Structure instance of bmm350_dev. +* +* @return Result of API execution status +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ +int8_t bmm350_set_pad_drive(uint8_t drive, struct bmm350_dev *dev); + +/*! +* \ingroup bmm350ApiReset +* \page bmm350_api_bmm350_magnetic_reset_and_wait bmm350_magnetic_reset_and_wait +* \code +* int8_t bmm350_magnetic_reset_and_wait(struct bmm350_dev *dev) +* \endcode +* @details This API is used to perform the magnetic reset of the sensor +* which is necessary after a field shock (400mT field applied to sensor). +* It sends flux guide or bit reset to the device in suspend mode. +* +* @param[in] dev : Structure instance of bmm350_dev. +* +* @return Result of API execution status +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ +int8_t bmm350_magnetic_reset_and_wait(struct bmm350_dev *dev); + +/** + * \ingroup bmm350 + * \defgroup bmm350ApiMagComp Compensation + * @brief Compensation for mag x,y,z axis and temperature API + */ + +/*! +* \ingroup bmm350ApiMagComp +* \page bmm350_api_bmm350GetCompensatedMagXYZTempData bmm350GetCompensatedMagXYZTempData +* \code +* int8_t bmm350GetCompensatedMagXYZTempData(struct sBmm350MagTempData_t *mag_temp_data, struct bmm350_dev *dev); +* \endcode +* @details This API is used to perform compensation for raw magnetometer and temperature data. +* +* @param[out] mag_temp_data : Structure instance of sBmm350MagTempData_t. +* @param[in] dev : Structure instance of bmm350_dev. +* +* @return Result of API execution status +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ +int8_t bmm350GetCompensatedMagXYZTempData(struct sBmm350MagTempData_t *mag_temp_data, struct bmm350_dev *dev); + +/** + * \ingroup bmm350 + * \defgroup bmm350ApiSelftest Self-test + * @brief Perform self-test for x and y axis + */ + +/*! +* \ingroup bmm350ApiSelftest +* \page bmm350_api_bmm350PerformSelfTest bmm350PerformSelfTest +* \code +* int8_t bmm350PerformSelfTest(struct sBmm350SelfTest_t *out_data, struct bmm350_dev *dev); +* \endcode +* @details This API executes FGR and BR sequences to initialize TMR sensor and performs self-test for x and y axis. +* +* @param[in, out] out_data : Structure instance of sBmm350SelfTest_t. +* @param[in] dev : Structure instance of bmm350_dev. +* +* @return Result of API execution status +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ +int8_t bmm350PerformSelfTest(struct sBmm350SelfTest_t *out_data, struct bmm350_dev *dev); + +/*! +* \ingroup bmm350ApiSetGet +* \page bmm350_api_bmm350_set_i2c_wdt bmm350_set_i2c_wdt +* \code +* int8_t bmm350_set_i2c_wdt(enum bmm350_i2c_wdt_en i2c_wdt_en_dis, enum bmm350_i2c_wdt_sel i2c_wdt_sel, +* struct bmm350_dev *dev); +* \endcode +* @details This API sets the I2C watchdog timer configurations to the sensor. +* +* @param[in] i2c_wdt_en_dis : Enable/ Disable I2C watchdog timer. +* @param[in] i2c_wdt_sel : I2C watchdog timer selection period. +* @param[in] dev : Structure instance of bmm350_dev. +* +* @return Result of API execution status +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ +int8_t bmm350_set_i2c_wdt(enum bmm350_i2c_wdt_en i2c_wdt_en_dis, + enum bmm350_i2c_wdt_sel i2c_wdt_sel, + struct bmm350_dev *dev); + +/*! +* \ingroup bmm350ApiSetGet +* \page bmm350_api_bmm350_set_tmr_selftest_user bmm350_set_tmr_selftest_user +* \code +* int8_t bmm350_set_tmr_selftest_user(enum bmm350_st_igen_en st_igen_en_dis, +* enum bmm350_st_n st_n_en_dis, +* enum bmm350_st_p st_p_en_dis, +* enum bmm350_ist_en_x ist_x_en_dis, +* enum bmm350_ist_en_y ist_y_en_dis, +* struct bmm350_dev *dev); +* \endcode +* @details This API sets the TMR user self-test register +* +* @param[in] st_igen_en_dis : Enable/ Disable self-test internal current gen. +* @param[in] st_n_en_dis : Enable/ Disable dc_st_n signal. +* @param[in] st_p_en_dis : Enable/ Disable dc_st_p signal. +* @param[in] ist_x_en_dis : Enable/ Disable dc_ist_en_x signal. +* @param[in] ist_y_en_dis : Enable/ Disable dc_ist_en_y signal. +* @param[in] dev : Structure instance of bmm350_dev. +* +* @return Result of API execution status +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ +int8_t bmm350_set_tmr_selftest_user(enum bmm350_st_igen_en st_igen_en_dis, + enum bmm350_st_n st_n_en_dis, + enum bmm350_st_p st_p_en_dis, + enum bmm350_ist_en_x ist_x_en_dis, + enum bmm350_ist_en_y ist_y_en_dis, + struct bmm350_dev *dev); + +/*! +* \ingroup bmm350ApiSetGet +* \page bmm350_api_bmm350_set_ctrl_user bmm350_set_ctrl_user +* \code +* int8_t bmm350_set_ctrl_user(enum bmm350_ctrl_user cfg_sens_tim_aon_en_dis, struct bmm350_dev *dev); +* \endcode +* @details This API sets the control user configurations to the sensor. +* +* @param[in] cfg_sens_tim_aon_en_dis : Enable/ Disable configuration of sensor time to run on suspend mode. +* @param[in] dev : Structure instance of bmm350_dev. +* +* @return Result of API execution status +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ +int8_t bmm350_set_ctrl_user(enum bmm350_ctrl_user cfg_sens_tim_aon_en_dis, struct bmm350_dev *dev); + +/*! +* \ingroup bmm350ApiSetGet +* \page bmm350_api_bmm350_get_pmu_cmd_status_0 bmm350_get_pmu_cmd_status_0 +* \code +* int8_t bmm350_get_pmu_cmd_status_0(struct bmm350_pmu_cmd_status_0 *pmu_cmd_stat_0, struct bmm350_dev *dev); +* \endcode +* @details This API gets the PMU command status 0 value. +* +* @param[out] pmu_cmd_stat_0 : Structure instance of bmm350_pmu_cmd_status_0. +* @param[in] dev : Structure instance of bmm350_dev. +* +* @return Result of API execution status +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ +int8_t bmm350_get_pmu_cmd_status_0(struct bmm350_pmu_cmd_status_0 *pmu_cmd_stat_0, struct bmm350_dev *dev); + +#ifdef __cplusplus +} +#endif /* End of CPP guard */ + +#endif /* _BMM350_H */ diff --git a/lib/DFRobot_BMM350/src/bmm350_defs.h b/lib/DFRobot_BMM350/src/bmm350_defs.h new file mode 100644 index 0000000..cb9a59c --- /dev/null +++ b/lib/DFRobot_BMM350/src/bmm350_defs.h @@ -0,0 +1,1215 @@ +/** +* Copyright (c) 2023 Bosch Sensortec GmbH. All rights reserved. +* +* BSD-3-Clause +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* 1. Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* +* 2. Redistributions in binary form must reproduce the above copyright +* notice, this list of conditions and the following disclaimer in the +* documentation and/or other materials provided with the distribution. +* +* 3. Neither the name of the copyright holder nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) +* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, +* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING +* IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* @file bmm350_defs.h +* @date 2023-05-26 +* @version v1.4.0 +* +*/ + +#ifndef _BMM350_DEFS_H +#define _BMM350_DEFS_H + +/*************************** Header files *******************************/ + +#ifdef __KERNEL__ +#include +#include +#else +#include +#include +#endif + +/***************************** Common Macros *****************************/ + +#ifdef __KERNEL__ +#if !defined(UINT8_C) && !defined(INT8_C) +#define INT8_C(x) S8_C(x) +#define UINT8_C(x) U8_C(x) +#endif + +#if !defined(UINT16_C) && !defined(INT16_C) +#define INT16_C(x) S16_C(x) +#define UINT16_C(x) U16_C(x) +#endif + +#if !defined(INT32_C) && !defined(UINT32_C) +#define INT32_C(x) S32_C(x) +#define UINT32_C(x) U32_C(x) +#endif + +#if !defined(INT64_C) && !defined(UINT64_C) +#define INT64_C(x) S64_C(x) +#define UINT64_C(x) U64_C(x) +#endif +#endif + +/*! C standard macros */ +#ifndef NULL +#ifdef __cplusplus +#define NULL 0 +#else +#define NULL ((void *) 0) +#endif +#endif + +/******************************************************************************/ +/*! @name Compiler switch macros Definitions */ +/******************************************************************************/ + +/************************* General Macro definitions ***************************/ + +/* Macro to SET and GET BITS of a register*/ +#define BMM350_SET_BITS(reg_data, bitname, data) \ + ((reg_data & ~(bitname##_MSK)) | \ + ((data << bitname##_POS) & bitname##_MSK)) + +#define BMM350_GET_BITS(reg_data, bitname) ((reg_data & (bitname##_MSK)) >> (bitname##_POS)) + +#define BMM350_GET_BITS_POS_0(reg_data, bitname) (reg_data & (bitname##_MSK)) + +#define BMM350_SET_BITS_POS_0(reg_data, bitname, data) \ + ((reg_data & ~(bitname##_MSK)) | \ + (data & bitname##_MSK)) + +#ifndef BMM350_INTF_RET_TYPE +#define BMM350_INTF_RET_TYPE int8_t +#endif + +#define UNUSED(x) (void)(x) + +/*! Chip id of BMM350 */ +#define BMM350_CHIP_ID UINT8_C(0x33) + +/*! Variant ID of BMM350 */ +#define BMM350_MIN_VAR UINT8_C(0x10) + +/************************* Sensor interface success code **************************/ +#define BMM350_INTF_RET_SUCCESS INT8_C(0) + +/************************* API success code **************************/ +#define BMM350_OK INT8_C(0) + +/* API error codes */ +#define BMM350_E_NULL_PTR INT8_C(-1) +#define BMM350_E_COM_FAIL INT8_C(-2) +#define BMM350_E_DEV_NOT_FOUND INT8_C(-3) +#define BMM350_E_INVALID_CONFIG INT8_C(-4) +#define BMM350_E_BAD_PAD_DRIVE INT8_C(-5) +#define BMM350_E_RESET_UNFINISHED INT8_C(-6) +#define BMM350_E_INVALID_INPUT INT8_C(-7) +#define BMM350_E_SELF_TEST_INVALID_AXIS INT8_C(-8) +#define BMM350_E_OTP_BOOT INT8_C(-9) +#define BMM350_E_OTP_PAGE_RD INT8_C(-10) +#define BMM350_E_OTP_PAGE_PRG INT8_C(-11) +#define BMM350_E_OTP_SIGN INT8_C(-12) +#define BMM350_E_OTP_INV_CMD INT8_C(-13) +#define BMM350_E_OTP_UNDEFINED INT8_C(-14) +#define BMM350_E_ALL_AXIS_DISABLED INT8_C(-15) +#define BMM350_E_PMU_CMD_VALUE INT8_C(-16) + +#define BMM350_NO_ERROR UINT8_C(0) + +/************************* Sensor delay time settings in microseconds **************************/ +#define BMM350_SOFT_RESET_DELAY UINT32_C(24000) +#define BMM350_MAGNETIC_RESET_DELAY UINT32_C(40000) +#define BMM350_START_UP_TIME_FROM_POR UINT32_C(3000) + +#define BMM350_GOTO_SUSPEND_DELAY UINT32_C(6000) +#define BMM350_SUSPEND_TO_NORMAL_DELAY UINT32_C(38000) + +#define BMM350_SUS_TO_FORCEDMODE_NO_AVG_DELAY UINT32_C(15000) +#define BMM350_SUS_TO_FORCEDMODE_AVG_2_DELAY UINT32_C(17000) +#define BMM350_SUS_TO_FORCEDMODE_AVG_4_DELAY UINT32_C(20000) +#define BMM350_SUS_TO_FORCEDMODE_AVG_8_DELAY UINT32_C(28000) + +#define BMM350_SUS_TO_FORCEDMODE_FAST_NO_AVG_DELAY UINT32_C(4000) +#define BMM350_SUS_TO_FORCEDMODE_FAST_AVG_2_DELAY UINT32_C(5000) +#define BMM350_SUS_TO_FORCEDMODE_FAST_AVG_4_DELAY UINT32_C(9000) +#define BMM350_SUS_TO_FORCEDMODE_FAST_AVG_8_DELAY UINT32_C(16000) + +#define BMM350_UPD_OAE_DELAY UINT16_C(1000) + +#define BMM350_BR_DELAY UINT16_C(14000) +#define BMM350_FGR_DELAY UINT16_C(18000) + +/************************ Length macros ************************/ +#define BMM350_OTP_DATA_LENGTH UINT8_C(32) +#define BMM350_READ_BUFFER_LENGTH UINT8_C(127) +#define BMM350_MAG_TEMP_DATA_LEN UINT8_C(12) + +/************************ Averaging macros **********************/ +#define BMM350_AVG_NO_AVG UINT8_C(0x0) +#define BMM350_AVG_2 UINT8_C(0x1) +#define BMM350_AVG_4 UINT8_C(0x2) +#define BMM350_AVG_8 UINT8_C(0x3) + +/******************************* ODR **************************/ +#define BMM350_ODR_400HZ UINT8_C(0x2) +#define BMM350_ODR_200HZ UINT8_C(0x3) +#define BMM350_ODR_100HZ UINT8_C(0x4) +#define BMM350_ODR_50HZ UINT8_C(0x5) +#define BMM350_ODR_25HZ UINT8_C(0x6) +#define BMM350_ODR_12_5HZ UINT8_C(0x7) +#define BMM350_ODR_6_25HZ UINT8_C(0x8) +#define BMM350_ODR_3_125HZ UINT8_C(0x9) +#define BMM350_ODR_1_5625HZ UINT8_C(0xA) + +/********************* Power modes *************************/ +#define BMM350_PMU_CMD_SUS UINT8_C(0x00) +#define BMM350_PMU_CMD_NM UINT8_C(0x01) +#define BMM350_PMU_CMD_UPD_OAE UINT8_C(0x02) +#define BMM350_PMU_CMD_FM UINT8_C(0x03) +#define BMM350_PMU_CMD_FM_FAST UINT8_C(0x04) +#define BMM350_PMU_CMD_FGR UINT8_C(0x05) +#define BMM350_PMU_CMD_FGR_FAST UINT8_C(0x06) +#define BMM350_PMU_CMD_BR UINT8_C(0x07) +#define BMM350_PMU_CMD_BR_FAST UINT8_C(0x08) +#define BMM350_PMU_CMD_NM_TC UINT8_C(0x09) + +#define BMM350_PMU_STATUS_0 UINT8_C(0x0) + +#define BMM350_DISABLE UINT8_C(0x0) +#define BMM350_ENABLE UINT8_C(0x1) + +#define BMM350_CMD_NOP UINT8_C(0x0) +#define BMM350_CMD_SOFTRESET UINT8_C(0xB6) + +#define BMM350_TARGET_PAGE_PAGE0 UINT8_C(0x0) +#define BMM350_TARGET_PAGE_PAGE1 UINT8_C(0x1) + +#define BMM350_INT_MODE_LATCHED UINT8_C(0x1) +#define BMM350_INT_MODE_PULSED UINT8_C(0x0) + +#define BMM350_INT_POL_ACTIVE_HIGH UINT8_C(0x1) +#define BMM350_INT_POL_ACTIVE_LOW UINT8_C(0x0) + +#define BMM350_INT_OD_PUSHPULL UINT8_C(0x1) +#define BMM350_INT_OD_OPENDRAIN UINT8_C(0x0) + +#define BMM350_INT_OUTPUT_EN_OFF UINT8_C(0x0) +#define BMM350_INT_OUTPUT_EN_ON UINT8_C(0x1) + +#define BMM350_INT_DRDY_EN UINT8_C(0x1) +#define BMM350_INT_DRDY_DIS UINT8_C(0x0) + +#define BMM350_MR_MR1K8 UINT8_C(0x0) +#define BMM350_MR_MR2K1 UINT8_C(0x1) +#define BMM350_MR_MR1K5 UINT8_C(0x2) +#define BMM350_MR_MR0K6 UINT8_C(0x3) + +#define BMM350_SEL_DTB1X_PAD_PAD_INT UINT8_C(0x0) +#define BMM350_SEL_DTB1X_PAD_PAD_BYP UINT8_C(0x1) + +#define BMM350_TMR_TST_HIZ_VTMR_VTMR_ON UINT8_C(0x0) +#define BMM350_TMR_TST_HIZ_VTMR_VTMR_HIZ UINT8_C(0x1) + +#define BMM350_LSB_MASK UINT16_C(0x00FF) +#define BMM350_MSB_MASK UINT16_C(0xFF00) + +/********************** Pad drive strength ************************/ +#define BMM350_PAD_DRIVE_WEAKEST UINT8_C(0) +#define BMM350_PAD_DRIVE_STRONGEST UINT8_C(7) + +/********************** I2C Register Addresses ************************/ + +/*! Register to set I2C address to LOW */ +#define BMM350_I2C_ADSEL_SET_LOW UINT8_C(0x14) + +/*! Register to set I2C address to HIGH */ +#define BMM350_I2C_ADSEL_SET_HIGH UINT8_C(0x15) + +#define BMM350_DUMMY_BYTES UINT8_C(2) + +/********************** Register Addresses ************************/ + +#define BMM350_REG_CHIP_ID UINT8_C(0x00) +#define BMM350_REG_REV_ID UINT8_C(0x01) +#define BMM350_REG_ERR_REG UINT8_C(0x02) +#define BMM350_REG_PAD_CTRL UINT8_C(0x03) +#define BMM350_REG_PMU_CMD_AGGR_SET UINT8_C(0x04) +#define BMM350_REG_PMU_CMD_AXIS_EN UINT8_C(0x05) +#define BMM350_REG_PMU_CMD UINT8_C(0x06) +#define BMM350_REG_PMU_CMD_STATUS_0 UINT8_C(0x07) +#define BMM350_REG_PMU_CMD_STATUS_1 UINT8_C(0x08) +#define BMM350_REG_I3C_ERR UINT8_C(0x09) +#define BMM350_REG_I2C_WDT_SET UINT8_C(0x0A) +#define BMM350_REG_TRSDCR_REV_ID UINT8_C(0x0D) +#define BMM350_REG_TC_SYNC_TU UINT8_C(0x21) +#define BMM350_REG_TC_SYNC_ODR UINT8_C(0x22) +#define BMM350_REG_TC_SYNC_TPH_1 UINT8_C(0x23) +#define BMM350_REG_TC_SYNC_TPH_2 UINT8_C(0x24) +#define BMM350_REG_TC_SYNC_DT UINT8_C(0x25) +#define BMM350_REG_TC_SYNC_ST_0 UINT8_C(0x26) +#define BMM350_REG_TC_SYNC_ST_1 UINT8_C(0x27) +#define BMM350_REG_TC_SYNC_ST_2 UINT8_C(0x28) +#define BMM350_REG_TC_SYNC_STATUS UINT8_C(0x29) +#define BMM350_REG_INT_CTRL UINT8_C(0x2E) +#define BMM350_REG_INT_CTRL_IBI UINT8_C(0x2F) +#define BMM350_REG_INT_STATUS UINT8_C(0x30) +#define BMM350_REG_MAG_X_XLSB UINT8_C(0x31) +#define BMM350_REG_MAG_X_LSB UINT8_C(0x32) +#define BMM350_REG_MAG_X_MSB UINT8_C(0x33) +#define BMM350_REG_MAG_Y_XLSB UINT8_C(0x34) +#define BMM350_REG_MAG_Y_LSB UINT8_C(0x35) +#define BMM350_REG_MAG_Y_MSB UINT8_C(0x36) +#define BMM350_REG_MAG_Z_XLSB UINT8_C(0x37) +#define BMM350_REG_MAG_Z_LSB UINT8_C(0x38) +#define BMM350_REG_MAG_Z_MSB UINT8_C(0x39) +#define BMM350_REG_TEMP_XLSB UINT8_C(0x3A) +#define BMM350_REG_TEMP_LSB UINT8_C(0x3B) +#define BMM350_REG_TEMP_MSB UINT8_C(0x3C) +#define BMM350_REG_SENSORTIME_XLSB UINT8_C(0x3D) +#define BMM350_REG_SENSORTIME_LSB UINT8_C(0x3E) +#define BMM350_REG_SENSORTIME_MSB UINT8_C(0x3F) +#define BMM350_REG_OTP_CMD_REG UINT8_C(0x50) +#define BMM350_REG_OTP_DATA_MSB_REG UINT8_C(0x52) +#define BMM350_REG_OTP_DATA_LSB_REG UINT8_C(0x53) +#define BMM350_REG_OTP_STATUS_REG UINT8_C(0x55) +#define BMM350_REG_TMR_SELFTEST_USER UINT8_C(0x60) +#define BMM350_REG_CTRL_USER UINT8_C(0x61) +#define BMM350_REG_CMD UINT8_C(0x7E) + +/*********************** Macros for OVWR ***************************/ +#define BMM350_REG_OVWR_VALUE_ANA_0 UINT8_C(0x3A) +#define BMM350_REG_OVWR_EN_ANA_0 UINT8_C(0x3B) + +/*********************** Macros for bit masking ***************************/ + +#define BMM350_CHIP_ID_OTP_MSK UINT8_C(0xf) +#define BMM350_CHIP_ID_OTP_POS UINT8_C(0x0) +#define BMM350_CHIP_ID_FIXED_MSK UINT8_C(0xf0) +#define BMM350_CHIP_ID_FIXED_POS UINT8_C(0x4) +#define BMM350_REV_ID_MAJOR_MSK UINT8_C(0xf0) +#define BMM350_REV_ID_MAJOR_POS UINT8_C(0x4) +#define BMM350_REV_ID_MINOR_MSK UINT8_C(0xf) +#define BMM350_REV_ID_MINOR_POS UINT8_C(0x0) +#define BMM350_PMU_CMD_ERROR_MSK UINT8_C(0x1) +#define BMM350_PMU_CMD_ERROR_POS UINT8_C(0x0) +#define BMM350_BOOT_UP_ERROR_MSK UINT8_C(0x2) +#define BMM350_BOOT_UP_ERROR_POS UINT8_C(0x1) +#define BMM350_DRV_MSK UINT8_C(0x7) +#define BMM350_DRV_POS UINT8_C(0x0) +#define BMM350_AVG_MSK UINT8_C(0x30) +#define BMM350_AVG_POS UINT8_C(0x4) +#define BMM350_ODR_MSK UINT8_C(0xf) +#define BMM350_ODR_POS UINT8_C(0x0) +#define BMM350_PMU_CMD_MSK UINT8_C(0xf) +#define BMM350_PMU_CMD_POS UINT8_C(0x0) +#define BMM350_EN_X_MSK UINT8_C(0x01) +#define BMM350_EN_X_POS UINT8_C(0x0) +#define BMM350_EN_Y_MSK UINT8_C(0x02) +#define BMM350_EN_Y_POS UINT8_C(0x1) +#define BMM350_EN_Z_MSK UINT8_C(0x04) +#define BMM350_EN_Z_POS UINT8_C(0x2) +#define BMM350_EN_XYZ_MSK UINT8_C(0x7) +#define BMM350_EN_XYZ_POS UINT8_C(0x0) +#define BMM350_PMU_CMD_BUSY_MSK UINT8_C(0x1) +#define BMM350_PMU_CMD_BUSY_POS UINT8_C(0x0) +#define BMM350_ODR_OVWR_MSK UINT8_C(0x2) +#define BMM350_ODR_OVWR_POS UINT8_C(0x1) +#define BMM350_AVG_OVWR_MSK UINT8_C(0x4) +#define BMM350_AVG_OVWR_POS UINT8_C(0x2) +#define BMM350_PWR_MODE_IS_NORMAL_MSK UINT8_C(0x8) +#define BMM350_PWR_MODE_IS_NORMAL_POS UINT8_C(0x3) +#define BMM350_CMD_IS_ILLEGAL_MSK UINT8_C(0x10) +#define BMM350_CMD_IS_ILLEGAL_POS UINT8_C(0x4) +#define BMM350_PMU_CMD_VALUE_MSK UINT8_C(0xE0) +#define BMM350_PMU_CMD_VALUE_POS UINT8_C(0x5) +#define BMM350_PMU_ODR_S_MSK UINT8_C(0xf) +#define BMM350_PMU_ODR_S_POS UINT8_C(0x0) +#define BMM350_PMU_AVG_S_MSK UINT8_C(0x30) +#define BMM350_PMU_AVG_S_POS UINT8_C(0x4) +#define BMM350_I3C_ERROR_0_MSK UINT8_C(0x1) +#define BMM350_I3C_ERROR_0_POS UINT8_C(0x0) +#define BMM350_I3C_ERROR_3_MSK UINT8_C(0x8) +#define BMM350_I3C_ERROR_3_POS UINT8_C(0x3) +#define BMM350_I2C_WDT_EN_MSK UINT8_C(0x1) +#define BMM350_I2C_WDT_EN_POS UINT8_C(0x0) +#define BMM350_I2C_WDT_SEL_MSK UINT8_C(0x2) +#define BMM350_I2C_WDT_SEL_POS UINT8_C(0x1) +#define BMM350_TRSDCR_REV_ID_OTP_MSK UINT8_C(0x3) +#define BMM350_TRSDCR_REV_ID_OTP_POS UINT8_C(0x0) +#define BMM350_TRSDCR_REV_ID_FIXED_MSK UINT8_C(0xfc) +#define BMM350_TRSDCR_REV_ID_FIXED_POS UINT8_C(0x2) +#define BMM350_PAGING_EN_MSK UINT8_C(0x80) +#define BMM350_PAGING_EN_POS UINT8_C(0x7) +#define BMM350_DRDY_DATA_REG_MSK UINT8_C(0x4) +#define BMM350_DRDY_DATA_REG_POS UINT8_C(0x2) +#define BMM350_INT_MODE_MSK UINT8_C(0x1) +#define BMM350_INT_MODE_POS UINT8_C(0x0) +#define BMM350_INT_POL_MSK UINT8_C(0x2) +#define BMM350_INT_POL_POS UINT8_C(0x1) +#define BMM350_INT_OD_MSK UINT8_C(0x4) +#define BMM350_INT_OD_POS UINT8_C(0x2) +#define BMM350_INT_OUTPUT_EN_MSK UINT8_C(0x8) +#define BMM350_INT_OUTPUT_EN_POS UINT8_C(0x3) +#define BMM350_DRDY_DATA_REG_EN_MSK UINT8_C(0x80) +#define BMM350_DRDY_DATA_REG_EN_POS UINT8_C(0x7) +#define BMM350_DRDY_INT_MAP_TO_IBI_MSK UINT8_C(0x1) +#define BMM350_DRDY_INT_MAP_TO_IBI_POS UINT8_C(0x0) +#define BMM350_CLEAR_DRDY_INT_STATUS_UPON_IBI_MSK UINT8_C(0x10) +#define BMM350_CLEAR_DRDY_INT_STATUS_UPON_IBI_POS UINT8_C(0x4) +#define BMM350_TC_SYNC_TU_MSK UINT8_C(0xff) +#define BMM350_TC_SYNC_ODR_MSK UINT8_C(0xff) +#define BMM350_TC_SYNC_TPH_1_MSK UINT8_C(0xff) +#define BMM350_TC_SYNC_TPH_2_MSK UINT8_C(0xff) +#define BMM350_TC_SYNC_DT_MSK UINT8_C(0xff) +#define BMM350_TC_SYNC_ST_0_MSK UINT8_C(0xff) +#define BMM350_TC_SYNC_ST_1_MSK UINT8_C(0xff) +#define BMM350_TC_SYNC_ST_2_MSK UINT8_C(0xff) +#define BMM350_CFG_FORCE_SOSC_EN_MSK UINT8_C(0x4) +#define BMM350_CFG_FORCE_SOSC_EN_POS UINT8_C(0x2) +#define BMM350_ST_IGEN_EN_MSK UINT8_C(0x1) +#define BMM350_ST_IGEN_EN_POS UINT8_C(0x0) +#define BMM350_ST_N_MSK UINT8_C(0x2) +#define BMM350_ST_N_POS UINT8_C(0x1) +#define BMM350_ST_P_MSK UINT8_C(0x4) +#define BMM350_ST_P_POS UINT8_C(0x2) +#define BMM350_IST_EN_X_MSK UINT8_C(0x8) +#define BMM350_IST_EN_X_POS UINT8_C(0x3) +#define BMM350_IST_EN_Y_MSK UINT8_C(0x10) +#define BMM350_IST_EN_Y_POS UINT8_C(0x4) +#define BMM350_CFG_SENS_TIM_AON_MSK UINT8_C(0x1) +#define BMM350_CFG_SENS_TIM_AON_POS UINT8_C(0x0) +#define BMM350_DATA_X_7_0_MSK UINT8_C(0xff) +#define BMM350_DATA_X_7_0_POS UINT8_C(0x0) +#define BMM350_DATA_X_15_8_MSK UINT8_C(0xff) +#define BMM350_DATA_X_15_8_POS UINT8_C(0x0) +#define BMM350_DATA_X_23_16_MSK UINT8_C(0xff) +#define BMM350_DATA_X_23_16_POS UINT8_C(0x0) +#define BMM350_DATA_Y_7_0_MSK UINT8_C(0xff) +#define BMM350_DATA_Y_7_0_POS UINT8_C(0x0) +#define BMM350_DATA_Y_15_8_MSK UINT8_C(0xff) +#define BMM350_DATA_Y_15_8_POS UINT8_C(0x0) +#define BMM350_DATA_Y_23_16_MSK UINT8_C(0xff) +#define BMM350_DATA_Y_23_16_POS UINT8_C(0x0) +#define BMM350_DATA_Z_7_0_MSK UINT8_C(0xff) +#define BMM350_DATA_Z_7_0_POS UINT8_C(0x0) +#define BMM350_DATA_Z_15_8_MSK UINT8_C(0xff) +#define BMM350_DATA_Z_15_8_POS UINT8_C(0x0) +#define BMM350_DATA_Z_23_16_MSK UINT8_C(0xff) +#define BMM350_DATA_Z_23_16_POS UINT8_C(0x0) +#define BMM350_DATA_T_7_0_MSK UINT8_C(0xff) +#define BMM350_DATA_T_7_0_POS UINT8_C(0x0) +#define BMM350_DATA_T_15_8_MSK UINT8_C(0xff) +#define BMM350_DATA_T_15_8_POS UINT8_C(0x0) +#define BMM350_DATA_T_23_16_MSK UINT8_C(0xff) +#define BMM350_DATA_T_23_16_POS UINT8_C(0x0) +#define BMM350_DATA_ST_7_0_MSK UINT8_C(0xff) +#define BMM350_DATA_ST_7_0_POS UINT8_C(0x0) +#define BMM350_DATA_ST_15_8_MSK UINT8_C(0xff) +#define BMM350_DATA_ST_15_8_POS UINT8_C(0x0) +#define BMM350_DATA_ST_23_16_MSK UINT8_C(0xff) +#define BMM350_DATA_ST_23_16_POS UINT8_C(0x0) +#define BMM350_SIGN_INVERT_T_MSK UINT8_C(0x10) +#define BMM350_SIGN_INVERT_T_POS UINT8_C(0x4) +#define BMM350_SIGN_INVERT_X_MSK UINT8_C(0x20) +#define BMM350_SIGN_INVERT_X_POS UINT8_C(0x5) +#define BMM350_SIGN_INVERT_Y_MSK UINT8_C(0x40) +#define BMM350_SIGN_INVERT_Y_POS UINT8_C(0x6) +#define BMM350_SIGN_INVERT_Z_MSK UINT8_C(0x80) +#define BMM350_SIGN_INVERT_Z_POS UINT8_C(0x7) +#define BMM350_DIS_BR_NM_MSK UINT8_C(0x1) +#define BMM350_DIS_BR_NM_POS UINT8_C(0x0) +#define BMM350_DIS_FGR_NM_MSK UINT8_C(0x2) +#define BMM350_DIS_FGR_NM_POS UINT8_C(0x1) +#define BMM350_DIS_CRST_AT_ALL_MSK UINT8_C(0x4) +#define BMM350_DIS_CRST_AT_ALL_POS UINT8_C(0x2) +#define BMM350_DIS_BR_FM_MSK UINT8_C(0x8) +#define BMM350_DIS_BR_FM_POS UINT8_C(0x3) +#define BMM350_FRC_EN_BUFF_MSK UINT8_C(0x1) +#define BMM350_FRC_EN_BUFF_POS UINT8_C(0x0) +#define BMM350_FRC_INA_EN1_MSK UINT8_C(0x2) +#define BMM350_FRC_INA_EN1_POS UINT8_C(0x1) +#define BMM350_FRC_INA_EN2_MSK UINT8_C(0x4) +#define BMM350_FRC_INA_EN2_POS UINT8_C(0x2) +#define BMM350_FRC_ADC_EN_MSK UINT8_C(0x8) +#define BMM350_FRC_ADC_EN_POS UINT8_C(0x3) +#define BMM350_FRC_INA_RST_MSK UINT8_C(0x10) +#define BMM350_FRC_INA_RST_POS UINT8_C(0x4) +#define BMM350_FRC_ADC_RST_MSK UINT8_C(0x20) +#define BMM350_FRC_ADC_RST_POS UINT8_C(0x5) +#define BMM350_FRC_INA_XSEL_MSK UINT8_C(0x1) +#define BMM350_FRC_INA_XSEL_POS UINT8_C(0x0) +#define BMM350_FRC_INA_YSEL_MSK UINT8_C(0x2) +#define BMM350_FRC_INA_YSEL_POS UINT8_C(0x1) +#define BMM350_FRC_INA_ZSEL_MSK UINT8_C(0x4) +#define BMM350_FRC_INA_ZSEL_POS UINT8_C(0x2) +#define BMM350_FRC_ADC_TEMP_EN_MSK UINT8_C(0x8) +#define BMM350_FRC_ADC_TEMP_EN_POS UINT8_C(0x3) +#define BMM350_FRC_TSENS_EN_MSK UINT8_C(0x10) +#define BMM350_FRC_TSENS_EN_POS UINT8_C(0x4) +#define BMM350_DSENS_FM_MSK UINT8_C(0x20) +#define BMM350_DSENS_FM_POS UINT8_C(0x5) +#define BMM350_DSENS_SEL_MSK UINT8_C(0x40) +#define BMM350_DSENS_SEL_POS UINT8_C(0x6) +#define BMM350_DSENS_SHORT_MSK UINT8_C(0x80) +#define BMM350_DSENS_SHORT_POS UINT8_C(0x7) +#define BMM350_ERR_MISS_BR_DONE_MSK UINT8_C(0x1) +#define BMM350_ERR_MISS_BR_DONE_POS UINT8_C(0x0) +#define BMM350_ERR_MISS_FGR_DONE_MSK UINT8_C(0x2) +#define BMM350_ERR_MISS_FGR_DONE_POS UINT8_C(0x1) +#define BMM350_TST_CHAIN_LN_MODE_MSK UINT8_C(0x1) +#define BMM350_TST_CHAIN_LN_MODE_POS UINT8_C(0x0) +#define BMM350_TST_CHAIN_LP_MODE_MSK UINT8_C(0x2) +#define BMM350_TST_CHAIN_LP_MODE_POS UINT8_C(0x1) +#define BMM350_EN_OVWR_TMR_IF_MSK UINT8_C(0x1) +#define BMM350_EN_OVWR_TMR_IF_POS UINT8_C(0x0) +#define BMM350_TMR_CKTRIGB_MSK UINT8_C(0x2) +#define BMM350_TMR_CKTRIGB_POS UINT8_C(0x1) +#define BMM350_TMR_DO_BR_MSK UINT8_C(0x4) +#define BMM350_TMR_DO_BR_POS UINT8_C(0x2) +#define BMM350_TMR_DO_FGR_MSK UINT8_C(0x18) +#define BMM350_TMR_DO_FGR_POS UINT8_C(0x3) +#define BMM350_TMR_EN_OSC_MSK UINT8_C(0x80) +#define BMM350_TMR_EN_OSC_POS UINT8_C(0x7) +#define BMM350_VCM_TRIM_X_MSK UINT8_C(0x1f) +#define BMM350_VCM_TRIM_X_POS UINT8_C(0x0) +#define BMM350_VCM_TRIM_Y_MSK UINT8_C(0x1f) +#define BMM350_VCM_TRIM_Y_POS UINT8_C(0x0) +#define BMM350_VCM_TRIM_Z_MSK UINT8_C(0x1f) +#define BMM350_VCM_TRIM_Z_POS UINT8_C(0x0) +#define BMM350_VCM_TRIM_DSENS_MSK UINT8_C(0x1f) +#define BMM350_VCM_TRIM_DSENS_POS UINT8_C(0x0) +#define BMM350_TWLB_MSK UINT8_C(0x30) +#define BMM350_TWLB_POS UINT8_C(0x4) +#define BMM350_PRG_PLS_TIM_MSK UINT8_C(0x30) +#define BMM350_PRG_PLS_TIM_POS UINT8_C(0x4) +#define BMM350_OTP_OVWR_EN_MSK UINT8_C(0x1) +#define BMM350_OTP_OVWR_EN_POS UINT8_C(0x0) +#define BMM350_OTP_MEM_CLK_MSK UINT8_C(0x2) +#define BMM350_OTP_MEM_CLK_POS UINT8_C(0x1) +#define BMM350_OTP_MEM_CS_MSK UINT8_C(0x4) +#define BMM350_OTP_MEM_CS_POS UINT8_C(0x2) +#define BMM350_OTP_MEM_PGM_MSK UINT8_C(0x8) +#define BMM350_OTP_MEM_PGM_POS UINT8_C(0x3) +#define BMM350_OTP_MEM_RE_MSK UINT8_C(0x10) +#define BMM350_OTP_MEM_RE_POS UINT8_C(0x4) +#define BMM350_SAMPLE_RDATA_PLS_MSK UINT8_C(0x80) +#define BMM350_SAMPLE_RDATA_PLS_POS UINT8_C(0x7) +#define BMM350_CFG_FW_MSK UINT8_C(0x1) +#define BMM350_CFG_FW_POS UINT8_C(0x0) +#define BMM350_EN_BR_X_MSK UINT8_C(0x2) +#define BMM350_EN_BR_X_POS UINT8_C(0x1) +#define BMM350_EN_BR_Y_MSK UINT8_C(0x4) +#define BMM350_EN_BR_Y_POS UINT8_C(0x2) +#define BMM350_EN_BR_Z_MSK UINT8_C(0x8) +#define BMM350_EN_BR_Z_POS UINT8_C(0x3) +#define BMM350_CFG_PAUSE_TIME_MSK UINT8_C(0x30) +#define BMM350_CFG_PAUSE_TIME_POS UINT8_C(0x4) +#define BMM350_CFG_FGR_PLS_DUR_MSK UINT8_C(0xf) +#define BMM350_CFG_FGR_PLS_DUR_POS UINT8_C(0x0) +#define BMM350_CFG_BR_Z_ORDER_MSK UINT8_C(0x10) +#define BMM350_CFG_BR_Z_ORDER_POS UINT8_C(0x4) +#define BMM350_CFG_BR_XY_CHOP_MSK UINT8_C(0x20) +#define BMM350_CFG_BR_XY_CHOP_POS UINT8_C(0x5) +#define BMM350_CFG_BR_PLS_DUR_MSK UINT8_C(0xc0) +#define BMM350_CFG_BR_PLS_DUR_POS UINT8_C(0x6) +#define BMM350_ENABLE_BR_FGR_TEST_MSK UINT8_C(0x1) +#define BMM350_ENABLE_BR_FGR_TEST_POS UINT8_C(0x0) +#define BMM350_SEL_AXIS_MSK UINT8_C(0xe) +#define BMM350_SEL_AXIS_POS UINT8_C(0x1) +#define BMM350_TMR_CFG_TEST_CLK_EN_MSK UINT8_C(0x10) +#define BMM350_TMR_CFG_TEST_CLK_EN_POS UINT8_C(0x4) +#define BMM350_TEST_VAL_BITS_7DOWNTO0_MSK UINT8_C(0xff) +#define BMM350_TEST_VAL_BITS_7DOWNTO0_POS UINT8_C(0x0) +#define BMM350_TEST_VAL_BITS_8_MSK UINT8_C(0x1) +#define BMM350_TEST_VAL_BITS_8_POS UINT8_C(0x0) +#define BMM350_TEST_P_SAMPLE_MSK UINT8_C(0x2) +#define BMM350_TEST_P_SAMPLE_POS UINT8_C(0x1) +#define BMM350_TEST_N_SAMPLE_MSK UINT8_C(0x4) +#define BMM350_TEST_N_SAMPLE_POS UINT8_C(0x2) +#define BMM350_TEST_APPLY_TO_REM_MSK UINT8_C(0x10) +#define BMM350_TEST_APPLY_TO_REM_POS UINT8_C(0x4) +#define BMM350_UFO_TRM_OSC_RANGE_MSK UINT8_C(0xf) +#define BMM350_UFO_TRM_OSC_RANGE_POS UINT8_C(0x0) +#define BMM350_ISO_CHIP_ID_MSK UINT8_C(0x78) +#define BMM350_ISO_CHIP_ID_POS UINT8_C(0x3) +#define BMM350_ISO_I2C_DEV_ID_MSK UINT8_C(0x80) +#define BMM350_ISO_I2C_DEV_ID_POS UINT8_C(0x7) +#define BMM350_I3C_FREQ_BITS_1DOWNTO0_MSK UINT8_C(0xc) +#define BMM350_I3C_FREQ_BITS_1DOWNTO0_POS UINT8_C(0x2) +#define BMM350_I3C_IBI_MDB_SEL_MSK UINT8_C(0x10) +#define BMM350_I3C_IBI_MDB_SEL_POS UINT8_C(0x4) +#define BMM350_TC_ASYNC_EN_MSK UINT8_C(0x20) +#define BMM350_TC_ASYNC_EN_POS UINT8_C(0x5) +#define BMM350_TC_SYNC_EN_MSK UINT8_C(0x40) +#define BMM350_TC_SYNC_EN_POS UINT8_C(0x6) +#define BMM350_I3C_SCL_GATING_EN_MSK UINT8_C(0x80) +#define BMM350_I3C_SCL_GATING_EN_POS UINT8_C(0x7) +#define BMM350_I3C_INACCURACY_BITS_6DOWNTO0_MSK UINT8_C(0x7f) +#define BMM350_I3C_INACCURACY_BITS_6DOWNTO0_POS UINT8_C(0x0) +#define BMM350_EST_EN_X_MSK UINT8_C(0x1) +#define BMM350_EST_EN_X_POS UINT8_C(0x0) +#define BMM350_EST_EN_Y_MSK UINT8_C(0x2) +#define BMM350_EST_EN_Y_POS UINT8_C(0x1) +#define BMM350_CRST_DIS_MSK UINT8_C(0x4) +#define BMM350_CRST_DIS_POS UINT8_C(0x2) +#define BMM350_BR_TFALL_MSK UINT8_C(0x7) +#define BMM350_BR_TFALL_POS UINT8_C(0x0) +#define BMM350_BR_TRISE_MSK UINT8_C(0x70) +#define BMM350_BR_TRISE_POS UINT8_C(0x4) +#define BMM350_TMR_SOFT_START_DIS_MSK UINT8_C(0x80) +#define BMM350_TMR_SOFT_START_DIS_POS UINT8_C(0x7) +#define BMM350_FOSC_LOW_RANGE_MSK UINT8_C(0x80) +#define BMM350_FOSC_LOW_RANGE_POS UINT8_C(0x7) +#define BMM350_VCRST_TRIM_FG_MSK UINT8_C(0x3f) +#define BMM350_VCRST_TRIM_FG_POS UINT8_C(0x0) +#define BMM350_VCRST_TRIM_BR_MSK UINT8_C(0x3f) +#define BMM350_VCRST_TRIM_BR_POS UINT8_C(0x0) +#define BMM350_BG_TRIM_VRP_MSK UINT8_C(0xc0) +#define BMM350_BG_TRIM_VRP_POS UINT8_C(0x6) +#define BMM350_BG_TRIM_TC_MSK UINT8_C(0xf) +#define BMM350_BG_TRIM_TC_POS UINT8_C(0x0) +#define BMM350_BG_TRIM_VRA_MSK UINT8_C(0xf0) +#define BMM350_BG_TRIM_VRA_POS UINT8_C(0x4) +#define BMM350_BG_TRIM_VRD_MSK UINT8_C(0xf) +#define BMM350_BG_TRIM_VRD_POS UINT8_C(0x0) +#define BMM350_OVWR_REF_IB_EN_MSK UINT8_C(0x10) +#define BMM350_OVWR_REF_IB_EN_POS UINT8_C(0x4) +#define BMM350_OVWR_VDDA_EN_MSK UINT8_C(0x20) +#define BMM350_OVWR_VDDA_EN_POS UINT8_C(0x5) +#define BMM350_OVWR_VDDP_EN_MSK UINT8_C(0x40) +#define BMM350_OVWR_VDDP_EN_POS UINT8_C(0x6) +#define BMM350_OVWR_VDDS_EN_MSK UINT8_C(0x80) +#define BMM350_OVWR_VDDS_EN_POS UINT8_C(0x7) +#define BMM350_REF_IB_EN_MSK UINT8_C(0x10) +#define BMM350_REF_IB_EN_POS UINT8_C(0x4) +#define BMM350_VDDA_EN_MSK UINT8_C(0x20) +#define BMM350_VDDA_EN_POS UINT8_C(0x5) +#define BMM350_VDDP_EN_MSK UINT8_C(0x40) +#define BMM350_VDDP_EN_POS UINT8_C(0x6) +#define BMM350_VDDS_EN_MSK UINT8_C(0x80) +#define BMM350_VDDS_EN_POS UINT8_C(0x7) +#define BMM350_OVWR_OTP_PROG_VDD_SW_EN_MSK UINT8_C(0x8) +#define BMM350_OVWR_OTP_PROG_VDD_SW_EN_POS UINT8_C(0x3) +#define BMM350_OVWR_EN_MFE_BG_FILT_BYPASS_MSK UINT8_C(0x10) +#define BMM350_OVWR_EN_MFE_BG_FILT_BYPASS_POS UINT8_C(0x4) +#define BMM350_OTP_PROG_VDD_SW_EN_MSK UINT8_C(0x8) +#define BMM350_OTP_PROG_VDD_SW_EN_POS UINT8_C(0x3) +#define BMM350_CP_COMP_CRST_EN_TM_MSK UINT8_C(0x10) +#define BMM350_CP_COMP_CRST_EN_TM_POS UINT8_C(0x4) +#define BMM350_CP_COMP_VDD_EN_TM_MSK UINT8_C(0x20) +#define BMM350_CP_COMP_VDD_EN_TM_POS UINT8_C(0x5) +#define BMM350_CP_INTREFS_EN_TM_MSK UINT8_C(0x40) +#define BMM350_CP_INTREFS_EN_TM_POS UINT8_C(0x6) +#define BMM350_ADC_LOCAL_CHOP_EN_MSK UINT8_C(0x20) +#define BMM350_ADC_LOCAL_CHOP_EN_POS UINT8_C(0x5) +#define BMM350_INA_MODE_MSK UINT8_C(0x40) +#define BMM350_INA_MODE_POS UINT8_C(0x6) +#define BMM350_VDDD_EXT_EN_MSK UINT8_C(0x20) +#define BMM350_VDDD_EXT_EN_POS UINT8_C(0x5) +#define BMM350_VDDP_EXT_EN_MSK UINT8_C(0x80) +#define BMM350_VDDP_EXT_EN_POS UINT8_C(0x7) +#define BMM350_ADC_DSENS_EN_MSK UINT8_C(0x10) +#define BMM350_ADC_DSENS_EN_POS UINT8_C(0x4) +#define BMM350_DSENS_EN_MSK UINT8_C(0x20) +#define BMM350_DSENS_EN_POS UINT8_C(0x5) +#define BMM350_OTP_TM_CLVWR_EN_MSK UINT8_C(0x40) +#define BMM350_OTP_TM_CLVWR_EN_POS UINT8_C(0x6) +#define BMM350_OTP_VDDP_DIS_MSK UINT8_C(0x80) +#define BMM350_OTP_VDDP_DIS_POS UINT8_C(0x7) +#define BMM350_FORCE_HIGH_VREF_IREF_OK_MSK UINT8_C(0x10) +#define BMM350_FORCE_HIGH_VREF_IREF_OK_POS UINT8_C(0x4) +#define BMM350_FORCE_HIGH_FOSC_OK_MSK UINT8_C(0x20) +#define BMM350_FORCE_HIGH_FOSC_OK_POS UINT8_C(0x5) +#define BMM350_FORCE_HIGH_MFE_BG_RDY_MSK UINT8_C(0x40) +#define BMM350_FORCE_HIGH_MFE_BG_RDY_POS UINT8_C(0x6) +#define BMM350_FORCE_HIGH_MFE_VTMR_RDY_MSK UINT8_C(0x80) +#define BMM350_FORCE_HIGH_MFE_VTMR_RDY_POS UINT8_C(0x7) +#define BMM350_ERR_END_OF_RECHARGE_MSK UINT8_C(0x1) +#define BMM350_ERR_END_OF_RECHARGE_POS UINT8_C(0x0) +#define BMM350_ERR_END_OF_DISCHARGE_MSK UINT8_C(0x2) +#define BMM350_ERR_END_OF_DISCHARGE_POS UINT8_C(0x1) +#define BMM350_CP_TMX_DIGTP_SEL_MSK UINT8_C(0x7) +#define BMM350_CP_TMX_DIGTP_SEL_POS UINT8_C(0x0) +#define BMM350_CP_CPOSC_EN_TM_MSK UINT8_C(0x80) +#define BMM350_CP_CPOSC_EN_TM_POS UINT8_C(0x7) +#define BMM350_TST_ATM1_CFG_MSK UINT8_C(0x3f) +#define BMM350_TST_ATM1_CFG_POS UINT8_C(0x0) +#define BMM350_TST_TB1_EN_MSK UINT8_C(0x80) +#define BMM350_TST_TB1_EN_POS UINT8_C(0x7) +#define BMM350_TST_ATM2_CFG_MSK UINT8_C(0x1f) +#define BMM350_TST_ATM2_CFG_POS UINT8_C(0x0) +#define BMM350_TST_TB2_EN_MSK UINT8_C(0x80) +#define BMM350_TST_TB2_EN_POS UINT8_C(0x7) +#define BMM350_REG_DTB1X_SEL_MSK UINT8_C(0x7f) +#define BMM350_REG_DTB1X_SEL_POS UINT8_C(0x0) +#define BMM350_SEL_DTB1X_PAD_MSK UINT8_C(0x80) +#define BMM350_SEL_DTB1X_PAD_POS UINT8_C(0x7) +#define BMM350_REG_DTB2X_SEL_MSK UINT8_C(0x7f) +#define BMM350_REG_DTB2X_SEL_POS UINT8_C(0x0) +#define BMM350_TMR_TST_CFG_MSK UINT8_C(0x7f) +#define BMM350_TMR_TST_CFG_POS UINT8_C(0x0) +#define BMM350_TMR_TST_HIZ_VTMR_MSK UINT8_C(0x80) +#define BMM350_TMR_TST_HIZ_VTMR_POS UINT8_C(0x7) + +/****************************** OTP MACROS ***************************/ +#define BMM350_OTP_CMD_DIR_READ UINT8_C(0x20) +#define BMM350_OTP_CMD_DIR_PRGM_1B UINT8_C(0x40) +#define BMM350_OTP_CMD_DIR_PRGM UINT8_C(0x60) +#define BMM350_OTP_CMD_PWR_OFF_OTP UINT8_C(0x80) +#define BMM350_OTP_CMD_EXT_READ UINT8_C(0xA0) +#define BMM350_OTP_CMD_EXT_PRGM UINT8_C(0xE0) +#define BMM350_OTP_CMD_MSK UINT8_C(0xE0) +#define BMM350_OTP_WORD_ADDR_MSK UINT8_C(0x1F) + +#define BMM350_OTP_STATUS_ERROR_MSK UINT8_C(0xE0) +#define BMM350_OTP_STATUS_ERROR(val) (val & BMM350_OTP_STATUS_ERROR_MSK) +#define BMM350_OTP_STATUS_NO_ERROR UINT8_C(0x00) +#define BMM350_OTP_STATUS_BOOT_ERR UINT8_C(0x20) +#define BMM350_OTP_STATUS_PAGE_RD_ERR UINT8_C(0x40) +#define BMM350_OTP_STATUS_PAGE_PRG_ERR UINT8_C(0x60) +#define BMM350_OTP_STATUS_SIGN_ERR UINT8_C(0x80) +#define BMM350_OTP_STATUS_INV_CMD_ERR UINT8_C(0xA0) +#define BMM350_OTP_STATUS_CMD_DONE UINT8_C(0x01) + +/****************************** OTP indices ***************************/ +#define BMM350_TEMP_OFF_SENS UINT8_C(0x0D) + +#define BMM350_MAG_OFFSET_X UINT8_C(0x0E) +#define BMM350_MAG_OFFSET_Y UINT8_C(0x0F) +#define BMM350_MAG_OFFSET_Z UINT8_C(0x10) + +#define BMM350_MAG_SENS_X UINT8_C(0x10) +#define BMM350_MAG_SENS_Y UINT8_C(0x11) +#define BMM350_MAG_SENS_Z UINT8_C(0x11) + +#define BMM350_MAG_TCO_X UINT8_C(0x12) +#define BMM350_MAG_TCO_Y UINT8_C(0x13) +#define BMM350_MAG_TCO_Z UINT8_C(0x14) + +#define BMM350_MAG_TCS_X UINT8_C(0x12) +#define BMM350_MAG_TCS_Y UINT8_C(0x13) +#define BMM350_MAG_TCS_Z UINT8_C(0x14) + +#define BMM350_MAG_DUT_T_0 UINT8_C(0x18) + +#define BMM350_CROSS_X_Y UINT8_C(0x15) +#define BMM350_CROSS_Y_X UINT8_C(0x15) +#define BMM350_CROSS_Z_X UINT8_C(0x16) +#define BMM350_CROSS_Z_Y UINT8_C(0x16) + +#define BMM350_SENS_CORR_Y (0.01f) +#define BMM350_TCS_CORR_Z (0.0001f) + +/**************************** Signed bit macros **********************/ +#define BMM350_SIGNED_8_BIT UINT8_C(8) +#define BMM350_SIGNED_12_BIT UINT8_C(12) +#define BMM350_SIGNED_16_BIT UINT8_C(16) +#define BMM350_SIGNED_21_BIT UINT8_C(21) +#define BMM350_SIGNED_24_BIT UINT8_C(24) + +/**************************** Self-test macros **********************/ +#define BMM350_SELF_TEST_DISABLE UINT8_C(0x00) +#define BMM350_SELF_TEST_POS_X UINT8_C(0x0D) +#define BMM350_SELF_TEST_NEG_X UINT8_C(0x0B) +#define BMM350_SELF_TEST_POS_Y UINT8_C(0x15) +#define BMM350_SELF_TEST_NEG_Y UINT8_C(0x13) + +#define BMM350_X_FM_XP_UST_MAX_LIMIT INT16_C(150) +#define BMM350_X_FM_XP_UST_MIN_LIMIT INT16_C(50) + +#define BMM350_X_FM_XN_UST_MAX_LIMIT INT16_C(-50) +#define BMM350_X_FM_XN_UST_MIN_LIMIT INT16_C(-150) + +#define BMM350_Y_FM_YP_UST_MAX_LIMIT INT16_C(150) +#define BMM350_Y_FM_YP_UST_MIN_LIMIT INT16_C(50) + +#define BMM350_Y_FM_YN_UST_MAX_LIMIT INT16_C(-50) +#define BMM350_Y_FM_YN_UST_MIN_LIMIT INT16_C(-150) + +/**************************** PMU command status 0 macros **********************/ +#define BMM350_PMU_CMD_STATUS_0_SUS UINT8_C(0x00) +#define BMM350_PMU_CMD_STATUS_0_NM UINT8_C(0x01) +#define BMM350_PMU_CMD_STATUS_0_UPD_OAE UINT8_C(0x02) +#define BMM350_PMU_CMD_STATUS_0_FM UINT8_C(0x03) +#define BMM350_PMU_CMD_STATUS_0_FM_FAST UINT8_C(0x04) +#define BMM350_PMU_CMD_STATUS_0_FGR UINT8_C(0x05) +#define BMM350_PMU_CMD_STATUS_0_FGR_FAST UINT8_C(0x06) +#define BMM350_PMU_CMD_STATUS_0_BR UINT8_C(0x07) +#define BMM350_PMU_CMD_STATUS_0_BR_FAST UINT8_C(0x07) + + +/**************************** PRESET MODE DEFINITIONS **********************/ +#define BMM350_PRESETMODE_LOWPOWER UINT8_C(0x01) +#define BMM350_PRESETMODE_REGULAR UINT8_C(0x02) +#define BMM350_PRESETMODE_HIGHACCURACY UINT8_C(0x03) +#define BMM350_PRESETMODE_ENHANCED UINT8_C(0x04) + +#define LOW_THRESHOLD_INTERRUPT 0 +#define HIGH_THRESHOLD_INTERRUPT 1 +#define INTERRUPT_X_ENABLE 0 +#define INTERRUPT_Y_ENABLE 0 +#define INTERRUPT_Z_ENABLE 0 +#define INTERRUPT_X_DISABLE 1 +#define INTERRUPT_Y_DISABLE 1 +#define INTERRUPT_Z_DISABLE 1 +#define ENABLE_INTERRUPT_PIN 1 +#define DISABLE_INTERRUPT_PIN 0 +#define NO_DATA -32768 + +#define I2C_ADDRESS 0x14 + +/****************************** Enumerators ***************************/ +enum eBmm350InterruptEnableDisable_t { + BMM350_DISABLE_INTERRUPT = BMM350_DISABLE, + BMM350_ENABLE_INTERRUPT = BMM350_ENABLE +}; + +enum eBmm350PowerModes_t { + eBmm350SuspendMode = BMM350_PMU_CMD_SUS, + eBmm350NormalMode = BMM350_PMU_CMD_NM, + eBmm350ForcedMode = BMM350_PMU_CMD_FM, + eBmm350ForcedModeFast = BMM350_PMU_CMD_FM_FAST +}; + +enum eBmm350DataRates_t { + BMM350_DATA_RATE_400HZ = BMM350_ODR_400HZ, + BMM350_DATA_RATE_200HZ = BMM350_ODR_200HZ, + BMM350_DATA_RATE_100HZ = BMM350_ODR_100HZ, + BMM350_DATA_RATE_50HZ = BMM350_ODR_50HZ, + BMM350_DATA_RATE_25HZ = BMM350_ODR_25HZ, + BMM350_DATA_RATE_12_5HZ = BMM350_ODR_12_5HZ, + BMM350_DATA_RATE_6_25HZ = BMM350_ODR_6_25HZ, + BMM350_DATA_RATE_3_125HZ = BMM350_ODR_3_125HZ, + BMM350_DATA_RATE_1_5625HZ = BMM350_ODR_1_5625HZ +}; + +enum bmm350_magreset_type { + BMM350_FLUXGUIDE_9MS = BMM350_PMU_CMD_FGR, + BMM350_FLUXGUIDE_FAST = BMM350_PMU_CMD_FGR_FAST, + BMM350_BITRESET_9MS = BMM350_PMU_CMD_BR, + BMM350_BITRESET_FAST = BMM350_PMU_CMD_BR_FAST, + BMM350_NOMAGRESET = UINT8_C(127) +}; + +enum bmm350_intr_en_dis { + BMM350_INTR_DISABLE = BMM350_DISABLE, + BMM350_INTR_ENABLE = BMM350_ENABLE +}; + +enum bmm350_intr_map { + BMM350_UNMAP_FROM_PIN = BMM350_DISABLE, + BMM350_MAP_TO_PIN = BMM350_ENABLE +}; +enum bmm350_intr_latch { + BMM350_PULSED = BMM350_INT_MODE_PULSED, + BMM350_LATCHED = BMM350_INT_MODE_LATCHED +}; + +enum eBmm350IntrPolarity_t { + BMM350_ACTIVE_LOW = BMM350_INT_POL_ACTIVE_LOW, + BMM350_ACTIVE_HIGH = BMM350_INT_POL_ACTIVE_HIGH +}; + +enum bmm350_intr_drive { + BMM350_INTR_OPEN_DRAIN = BMM350_INT_OD_OPENDRAIN, + BMM350_INTR_PUSH_PULL = BMM350_INT_OD_PUSHPULL +}; + +enum bmm350_drdy_int_map_to_ibi { + BMM350_IBI_DISABLE = BMM350_DISABLE, + BMM350_IBI_ENABLE = BMM350_ENABLE +}; + +enum bmm350_clear_drdy_int_status_upon_ibi { + BMM350_NOCLEAR_ON_IBI = BMM350_DISABLE, + BMM350_CLEAR_ON_IBI = BMM350_ENABLE +}; + +enum bmm350_i2c_wdt_en { + BMM350_I2C_WDT_DIS = BMM350_DISABLE, + BMM350_I2C_WDT_EN = BMM350_ENABLE +}; + +enum bmm350_i2c_wdt_sel { + BMM350_I2C_WDT_SEL_SHORT = BMM350_DISABLE, + BMM350_I2C_WDT_SEL_LONG = BMM350_ENABLE +}; + +enum bmm350_performance_parameters { + BMM350_NO_AVERAGING = BMM350_AVG_NO_AVG, + BMM350_AVERAGING_2 = BMM350_AVG_2, + BMM350_AVERAGING_4 = BMM350_AVG_4, + BMM350_AVERAGING_8 = BMM350_AVG_8, + /*lint -e849*/ + BMM350_ULTRALOWNOISE = BMM350_AVG_8, + BMM350_LOWNOISE = BMM350_AVG_4, + BMM350_REGULARPOWER = BMM350_AVG_2, + BMM350_LOWPOWER = BMM350_AVG_NO_AVG +}; + +enum bmm350_st_igen_en { + BMM350_ST_IGEN_DIS = BMM350_DISABLE, + BMM350_ST_IGEN_EN = BMM350_ENABLE +}; + +enum bmm350_st_n { + BMM350_ST_N_DIS = BMM350_DISABLE, + BMM350_ST_N_EN = BMM350_ENABLE +}; + +enum bmm350_st_p { + BMM350_ST_P_DIS = BMM350_DISABLE, + BMM350_ST_P_EN = BMM350_ENABLE +}; + +enum bmm350_ist_en_x { + BMM350_IST_X_DIS = BMM350_DISABLE, + BMM350_IST_X_EN = BMM350_ENABLE +}; + +enum bmm350_ist_en_y { + BMM350_IST_Y_DIS = BMM350_DISABLE, + BMM350_IST_Y_EN = BMM350_ENABLE +}; + +enum bmm350_ctrl_user { + BMM350_CFG_SENS_TIM_AON_DIS = BMM350_DISABLE, + BMM350_CFG_SENS_TIM_AON_EN = BMM350_ENABLE +}; + +enum eBmm350XAxisEnDis_t { + BMM350_X_DIS = BMM350_DISABLE, + BMM350_X_EN = BMM350_ENABLE +}; + +enum eBmm350YAxisEnDis_t { + BMM350_Y_DIS = BMM350_DISABLE, + BMM350_Y_EN = BMM350_ENABLE +}; + +enum eBmm350ZAxisEnDis_t { + BMM350_Z_DIS = BMM350_DISABLE, + BMM350_Z_EN = BMM350_ENABLE +}; + +/******************************************************************************/ +/*! @name Function Pointers */ +/******************************************************************************/ + +/*! + * @brief Bus communication function pointer which should be mapped to + * the platform specific read functions of the user + * + * @param[in] reg_addr : Register address from which data is read. + * @param[out] reg_data : Pointer to data buffer where read data is stored. + * @param[in] len : Number of bytes of data to be read. + * @param[in, out] intfPtr : Void pointer that can enable the linking of descriptors + * for interface related call backs. + * + * retval = 0 -> Success + * retval < 0 -> Failure + * + */ +typedef BMM350_INTF_RET_TYPE (*pBmm350ReadFptr_t)(uint8_t reg_addr, uint8_t *reg_data, uint32_t len, void *intfPtr); + +/*! + * @brief Bus communication function pointer which should be mapped to + * the platform specific write functions of the user + * + * @param[in] reg_addr : Register address to which the data is written. + * @param[in] reg_data : Pointer to data buffer in which data to be written + * is stored. + * @param[in] len : Number of bytes of data to be written. + * @param[in, out] intfPtr : Void pointer that can enable the linking of descriptors + * for interface related call backs + * + * retval = 0 -> Success + * retval < 0 -> Failure + * + */ +typedef BMM350_INTF_RET_TYPE (*pBmm350WriteFptr_t)(uint8_t reg_addr, const uint8_t *reg_data, uint32_t len, + void *intfPtr); + +/*! + * @brief Delay function pointer which should be mapped to + * delay function of the user + * + * @param[in] period : Delay in microseconds. + * @param[in, out] intfPtr : Void pointer that can enable the linking of descriptors + * for interface related call backs + * + */ +typedef void (*pBmm350DelayUsFptr_t)(uint32_t period, void *intfPtr); + +/* Pre-declaration */ +struct bmm350_dev; + +/*! + * @brief Function pointer for the magnetic reset and wait override + * + * @param[in] dev : Structure instance of bmm350_dev. + * @return Result of API execution status + * @retval = 0 -> Success + * @retval < 0 -> Error + */ +typedef int8_t (*bmm350_mraw_override_t)(struct bmm350_dev *dev); + +/************************* STRUCTURE DEFINITIONS *************************/ + +/*! + * @brief bmm350 un-compensated (raw) magnetometer data, signed integer + */ +struct bmm350_raw_mag_data +{ + /*! Raw mag X data */ + int32_t raw_xdata; + + /*! Raw mag Y data */ + int32_t raw_ydata; + + /*! Raw mag Z data */ + int32_t raw_zdata; + + /*! Raw mag temperature value */ + int32_t raw_data_t; +}; + +/*! + * @brief bmm350 compensated magnetometer data and temperature data + */ +struct sBmm350MagTempData_t +{ + /*! Compensated mag X data */ + float x; + + /*! Compensated mag Y data */ + float y; + + /*! Compensated mag Z data */ + float z; + + /*! Temperature */ + float temperature; +}; + +/*! + * @brief bmm350 magnetometer dut offset coefficient structure + */ +struct bmm350_dut_offset_coef +{ + /*! Temperature offset */ + float t_offs; + + /*! Offset x-axis */ + float offset_x; + + /*! Offset y-axis */ + float offset_y; + + /*! Offset z-axis */ + float offset_z; +}; + +/*! + * @brief bmm350 magnetometer dut sensitivity coefficient structure + */ +struct bmm350_dut_sensit_coef +{ + /*! Temperature sensitivity */ + float t_sens; + + /*! Sensitivity x-axis */ + float sens_x; + + /*! Sensitivity y-axis */ + float sens_y; + + /*! Sensitivity z-axis */ + float sens_z; +}; + +/*! + * @brief bmm350 magnetometer dut tco structure + */ +struct bmm350_dut_tco +{ + float tco_x; + float tco_y; + float tco_z; +}; + +/*! + * @brief bmm350 magnetometer dut tcs structure + */ +struct bmm350_dut_tcs +{ + float tcs_x; + float tcs_y; + float tcs_z; +}; + +/*! + * @brief bmm350 magnetometer cross axis compensation structure + */ +struct bmm350_cross_axis +{ + float cross_x_y; + float cross_y_x; + float cross_z_x; + float cross_z_y; +}; + +/*! + * @brief bmm350 magnetometer compensate structure + */ +struct bmm350_mag_compensate +{ + /*! Structure to store dut offset coefficient */ + struct bmm350_dut_offset_coef dut_offset_coef; + + /*! Structure to store dut sensitivity coefficient */ + struct bmm350_dut_sensit_coef dut_sensit_coef; + + /*! Structure to store dut tco */ + struct bmm350_dut_tco dut_tco; + + /*! Structure to store dut tcs */ + struct bmm350_dut_tcs dut_tcs; + + /*! Initialize T0_reading parameter */ + float dut_t0; + + /*! Structure to define cross axis compensation */ + struct bmm350_cross_axis cross_axis; +}; + +/*! + * @brief bmm350 device structure + */ +struct bmm350_dev +{ + /*! + * The interface pointer is used to enable the user + * to link their interface descriptors for reference during the + * implementation of the read and write interfaces to the + * hardware. + */ + void* intfPtr; + + /*! Chip Id of BMM350 */ + uint8_t chipId; + + /*! Bus read function pointer */ + pBmm350ReadFptr_t read; + + /*! Bus write function pointer */ + pBmm350WriteFptr_t write; + + /*! delay(in us) function pointer */ + pBmm350DelayUsFptr_t delayUs; + + /*! To store interface pointer error */ + BMM350_INTF_RET_TYPE intf_rslt; + + /*! Variable to store status of axes enabled */ + uint8_t axisEn; + + /*! Structure for mag compensate */ + struct bmm350_mag_compensate mag_comp; + + /*! Array to store OTP data */ + uint16_t otp_data[BMM350_OTP_DATA_LENGTH]; + + /*! Variant ID */ + uint8_t var_id; + + /*! Magnetic reset and wait override */ + bmm350_mraw_override_t mraw_override; + + /*! power mode */ + uint8_t powerMode; +}; + +/*! + * @brief bmm350 self-test structure + */ +struct sBmm350SelfTest_t +{ + /* Variable to store self-test data on x-axis */ + float out_ust_x; + + /* Variable to store self-test data on y-axis */ + float out_ust_y; +}; + +/*! + * @brief bmm350 PMU command status 0 structure + */ +struct bmm350_pmu_cmd_status_0 +{ + /*! The previous PMU CMD is still in processing */ + uint8_t pmu_cmd_busy; + + /*! The previous PMU_CMD_AGGR_SET.odr has been overwritten */ + uint8_t odr_ovwr; + + /*! The previous PMU_CMD_AGGR_SET.avg has been overwritten */ + uint8_t avr_ovwr; + + /*! The chip is in normal power mode */ + uint8_t pwr_mode_is_normal; + + /*! CMD value is not allowed */ + uint8_t cmd_is_illegal; + + /*! Stores the latest PMU_CMD code processed */ + uint8_t pmu_cmd_value; +}; + +/** + * @brief bmm350 compensated magnetometer data in int16_t format + */ +typedef struct{ + int32_t x; /**< compensated mag X data */ + int32_t y; /**< compensated mag Y data */ + int32_t z; /**< compensated mag Z data */ + int32_t temperature; /**< compensated temperature data */ + float float_x; + float float_y; + float float_z; + float float_temperature; +}sBmm350MagData_t; + +typedef struct{ + int16_t mag_x; /**< mag X data */ + int16_t mag_y; /**< mag Y data */ + int16_t mag_z; /**< mag Z data */ + uint8_t interrupt_x; /**< X-axis interrupt trigger flag*/ + uint8_t interrupt_y; /**< Y-axis interrupt trigger flag*/ + uint8_t interrupt_z; /**< Z-axis interrupt trigger flag*/ +}sBmm350ThresholdData_t; + +#endif /* _BMM350_DEFS_H */ diff --git a/lib/DFRobot_BMM350/src/bmm350_oor.c b/lib/DFRobot_BMM350/src/bmm350_oor.c new file mode 100644 index 0000000..c587891 --- /dev/null +++ b/lib/DFRobot_BMM350/src/bmm350_oor.c @@ -0,0 +1,329 @@ +/** +* Copyright (c) 2023 Bosch Sensortec GmbH. All rights reserved. +* +* BSD-3-Clause +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* 1. Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* +* 2. Redistributions in binary form must reproduce the above copyright +* notice, this list of conditions and the following disclaimer in the +* documentation and/or other materials provided with the distribution. +* +* 3. Neither the name of the copyright holder nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) +* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, +* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING +* IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* @file bmm350_oor.c +* @date 2023-05-26 +* @version v1.4.0 +* +*/ + +#include "bmm350_oor.h" + +#ifdef BMM350_OOR_HALF_SELF_TEST + +/*! + * @brief This internal API is used to trigger half self-test + */ +static int8_t trigger_half_selftest(struct bmm350_oor_params *oor, struct bmm350_dev *dev) +{ + int8_t rslt = BMM350_OK; + + oor->st_cmd = BMM350_SELF_TEST_DISABLE; + + /* Trigger a self-test on every alternate measurement if needed */ + if (oor->enable_selftest) + { + oor->st_counter++; + + switch (oor->st_counter) + { + case 1: + oor->st_cmd = BMM350_SELF_TEST_POS_X; + break; + case 2: + oor->st_cmd = BMM350_SELF_TEST_DISABLE; + break; + case 3: + oor->st_cmd = BMM350_SELF_TEST_POS_Y; + break; + case 4: + oor->st_cmd = BMM350_SELF_TEST_DISABLE; + break; + + default: + oor->st_counter = 0; + oor->st_cmd = BMM350_SELF_TEST_DISABLE; + break; + } + + rslt = bmm350SetRegs(BMM350_REG_TMR_SELFTEST_USER, &(oor->st_cmd), 1, dev); + } + else + { + if (oor->last_st_cmd != BMM350_SELF_TEST_DISABLE) + { + rslt = bmm350SetRegs(BMM350_REG_TMR_SELFTEST_USER, &(oor->st_cmd), 1, dev); + oor->st_counter = 0; + } + } + + return rslt; +} + +/*! + * @brief This internal API is used to validate half self-test + */ +static void validate_half_selftest(const struct sBmm350MagTempData_t *data, struct bmm350_oor_params *oor) +{ + switch (oor->last_st_cmd) + { + case BMM350_SELF_TEST_DISABLE: + oor->mag_xn = data->x; + oor->mag_yn = data->y; + break; + + case BMM350_SELF_TEST_POS_X: + oor->mag_xp = data->x; + oor->x_failed = (oor->mag_xp - oor->mag_xn) < BMM350_HALF_ST_THRESHOLD ? true : false; + break; + + case BMM350_SELF_TEST_POS_Y: + oor->mag_yp = data->y; + oor->y_failed = (oor->mag_yp - oor->mag_yn) < BMM350_HALF_ST_THRESHOLD ? true : false; + break; + + default: + break; + } +} +#else + +/*! + * @brief This internal API is used to trigger full self-test + */ +static int8_t trigger_full_selftest(struct bmm350_oor_params *oor, struct bmm350_dev *dev) +{ + int8_t rslt = BMM350_OK; + + oor->st_cmd = BMM350_SELF_TEST_DISABLE; + + /* Trigger a self-test on every alternate measurement if needed */ + if (oor->enable_selftest) + { + oor->st_counter++; + + switch (oor->st_counter) + { + case 1: + oor->st_cmd = BMM350_SELF_TEST_POS_X; + break; + case 2: + oor->st_cmd = BMM350_SELF_TEST_NEG_X; + break; + case 3: + oor->st_cmd = BMM350_SELF_TEST_POS_Y; + break; + case 4: + oor->st_cmd = BMM350_SELF_TEST_NEG_Y; + break; + + default: + oor->st_counter = 0; + oor->st_cmd = BMM350_SELF_TEST_DISABLE; + break; + } + + rslt = bmm350SetRegs(BMM350_REG_TMR_SELFTEST_USER, &(oor->st_cmd), 1, dev); + } + else + { + if (oor->last_st_cmd != BMM350_SELF_TEST_DISABLE) + { + rslt = bmm350SetRegs(BMM350_REG_TMR_SELFTEST_USER, &(oor->st_cmd), 1, dev); + oor->st_counter = 0; + } + } + + return rslt; +} + +/*! + * @brief This internal API is used to validate full self-test + */ +static void validate_full_selftest(const struct sBmm350MagTempData_t *data, struct bmm350_oor_params *oor) +{ + switch (oor->last_st_cmd) + { + case BMM350_SELF_TEST_POS_X: + oor->mag_xp = data->x; + break; + + case BMM350_SELF_TEST_NEG_X: + oor->mag_xn = data->x; + oor->x_failed = (oor->mag_xp - oor->mag_xn) < BMM350_FULL_ST_THRESHOLD ? true : false; + break; + + case BMM350_SELF_TEST_POS_Y: + oor->mag_yp = data->y; + break; + + case BMM350_SELF_TEST_NEG_Y: + oor->mag_yn = data->y; + oor->y_failed = (oor->mag_yp - oor->mag_yn) < BMM350_FULL_ST_THRESHOLD ? true : false; + break; + + default: + break; + } +} +#endif + +/*! + * @brief This internal API is used to validate out of range. + */ +static void validate_out_of_range(bool *out_of_range, + const struct sBmm350MagTempData_t *data, + struct bmm350_oor_params *oor) +{ + float field_str = 0.0f; + + /* Threshold to start out of range detection */ + float threshold = BMM350_OUT_OF_RANGE_THRESHOLD; + + /* Threshold to start self-tests */ + float st_threshold = BMM350_SELF_TEST_THRESHOLD; + + /* If either self-test failed, alert that the sensor is out of range and continue self-tests */ + if (oor->x_failed || oor->y_failed) + { + *out_of_range = true; + oor->enable_selftest = true; + } + else + { + field_str = sqrtf((data->x * data->x) + (data->y * data->y) + (data->z * data->z)); + + /* Check for the self-test threshold and perform self-tests to catch if the sensor is out of range */ + if ((fabsf(data->x) >= st_threshold) || (fabsf(data->y) >= st_threshold) || (fabsf(data->z) >= st_threshold) || + (field_str >= st_threshold)) + { + oor->enable_selftest = true; + } + else if (oor->st_counter == 0) /* If a self-test procedure has started, wait for it to complete */ + { + oor->enable_selftest = false; + } + + /* If out of range was previously detected, reduce the threshold to get back in range, + * effectively preventing hysteresis. Selecting 400uT */ + if (*out_of_range) + { + threshold = BMM350_IN_RANGE_THRESHOLD; + } + + /* Check if X or Y or Z > the threshold or the magnitude of all 3 is greater */ + if ((fabsf(data->x) >= threshold) || (fabsf(data->y) >= threshold) || (fabsf(data->z) >= threshold) || + (field_str >= threshold)) + { + *out_of_range = true; + } + else if (oor->st_counter == 0) /* If a self-test procedure has started, wait for it to complete */ + { + *out_of_range = false; + } + } +} + +/*! + * @brief This API is used to perform reset sequence in forced mode. + */ +int8_t bmm350_oor_perform_reset_sequence_forced(struct bmm350_oor_params *oor, struct bmm350_dev *dev) +{ + int8_t rslt = 0; + uint8_t pmu_cmd = 0; + + oor->reset_counter++; + + switch (oor->reset_counter) + { + case 1: /* Trigger the Bit reset fast */ + pmu_cmd = BMM350_PMU_CMD_BR_FAST; + rslt = bmm350SetRegs(BMM350_REG_PMU_CMD, &pmu_cmd, 1, dev); + break; + + case 2: /* Trigger Flux Guide reset */ + pmu_cmd = BMM350_PMU_CMD_FGR; + rslt = bmm350SetRegs(BMM350_REG_PMU_CMD, &pmu_cmd, 1, dev); + break; + + case 3: /* Flux Guide dummy */ + break; + + default: /* Default acts like the Flux guide reset dummy */ + oor->reset_counter = 0; + oor->trigger_reset = false; + break; + } + + return rslt; +} + +/*! + * @brief This API is used to read out of range in half or full self-test. + */ +int8_t bmm350_oor_read(bool *out_of_range, + struct sBmm350MagTempData_t *data, + struct bmm350_oor_params *oor, + struct bmm350_dev *dev) +{ + int8_t rslt = 0; + uint8_t pmu_cmd = BMM350_PMU_CMD_SUS; + +#ifdef BMM350_OOR_HALF_SELF_TEST + rslt = trigger_half_selftest(oor, dev); +#else + rslt = trigger_full_selftest(oor, dev); +#endif + + if (rslt == BMM350_OK) + { + pmu_cmd = BMM350_PMU_CMD_FM_FAST; + rslt = bmm350SetRegs(BMM350_REG_PMU_CMD, &pmu_cmd, 1, dev); + + if (rslt == BMM350_OK) + { + rslt = bmm350GetCompensatedMagXYZTempData(data, dev); + } + } + +#ifdef BMM350_OOR_HALF_SELF_TEST + validate_half_selftest(data, oor); +#else + validate_full_selftest(data, oor); +#endif + + validate_out_of_range(out_of_range, data, oor); + + oor->last_st_cmd = oor->st_cmd; + + return rslt; +} diff --git a/lib/DFRobot_BMM350/src/bmm350_oor.h b/lib/DFRobot_BMM350/src/bmm350_oor.h new file mode 100644 index 0000000..41b3eb7 --- /dev/null +++ b/lib/DFRobot_BMM350/src/bmm350_oor.h @@ -0,0 +1,136 @@ +/** +* Copyright (c) 2023 Bosch Sensortec GmbH. All rights reserved. +* +* BSD-3-Clause +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* 1. Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* +* 2. Redistributions in binary form must reproduce the above copyright +* notice, this list of conditions and the following disclaimer in the +* documentation and/or other materials provided with the distribution. +* +* 3. Neither the name of the copyright holder nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) +* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, +* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING +* IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* @file bmm350_oor.h +* @date 2023-05-26 +* @version v1.4.0 +* +*/ + +#ifndef _BMM350_OOR_H +#define _BMM350_OOR_H + +#include +#include + +#include "bmm350.h" + +/*! CPP guard */ +#ifdef __cplusplus +extern "C" { +#endif + +/******************************************************************************/ +/*! @name General Macro Definitions */ +/******************************************************************************/ + +/*! Macro to define half self-test for out of range + * NOTE: Comment this to use both positive and negative self tests */ +#define BMM350_OOR_HALF_SELF_TEST + +/*! Macro to define mag data minimum and maximum range in uT */ +#define BMM350_HALF_ST_THRESHOLD (130.0f) +#define BMM350_FULL_ST_THRESHOLD (300.0f) + +/*! Macro to define threshold values of in range, out of range and self-test */ +#define BMM350_IN_RANGE_THRESHOLD (2000.0f) +#define BMM350_OUT_OF_RANGE_THRESHOLD (2400.0f) +#define BMM350_SELF_TEST_THRESHOLD (2600.0f) + +/************************* Structure definitions *************************/ + +/*! + * @brief Structure to define bmm350 out of range parameters + */ +struct bmm350_oor_params +{ + /*! Counter to track what self test to trigger */ + uint8_t st_counter; + + /*! Current self-test command */ + uint8_t st_cmd; + + /*! Stores the last applied self test configuration */ + uint8_t last_st_cmd; + + /*! Store the last measurements for comparing against the self-test */ + float mag_xp, mag_xn, mag_yp, mag_yn; + + /*! Flags to track if the test failed to redo it */ + bool x_failed, y_failed; + + /*! Flags to enable self-test */ + bool enable_selftest; + + /*! Flags to trigger reset */ + bool trigger_reset; + + /*! Variable to store reset counter value */ + uint8_t reset_counter; +}; + +/******************* Function prototype declarations ********************/ + +/*! + * @brief Function to read data and validate if the sensor is out of range + * + * @param[in,out] out_of_range : Flag that indicates that the sensor is out of range + * @param[out] data : Sensor data + * @param[out] oor : Structure that stores the state of the out of range detector + * @param[in,out] dev : Device structure of the BMM350 + * + * @return Result of API execution status + * @retval = 0 -> Success + * @retval < 0 -> Error + */ +int8_t bmm350_oor_read(bool *out_of_range, + struct sBmm350MagTempData_t *data, + struct bmm350_oor_params *oor, + struct bmm350_dev *dev); + +/*! + * @brief Function to perform reset sequence in forced mode. + * + * @param[in,out] oor : Structure that stores the state of the out of range detector + * @param[in,out] dev : Structure instance of bmm350_dev. + * + * @return Result of API execution status + * @retval = 0 -> Success + * @retval < 0 -> Error + */ +int8_t bmm350_oor_perform_reset_sequence_forced(struct bmm350_oor_params *oor, struct bmm350_dev *dev); + +#ifdef __cplusplus +} +#endif /* End of CPP guard */ + +#endif /* _BMM350_OOR_H */ diff --git a/pid_test.csv b/pid_test.csv index 11adc7a..d888e93 100644 --- a/pid_test.csv +++ b/pid_test.csv @@ -1,755 +1,5736 @@ -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,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 diff --git a/pid_vis.py b/pid_vis.py index da21df8..e298db5 100644 --- a/pid_vis.py +++ b/pid_vis.py @@ -2,37 +2,66 @@ import csv from collections import defaultdict from matplotlib import pyplot as plt +import numpy as np with Path('pid_test.csv').open('r') as f: reader = csv.DictReader(filter(lambda line: not line.startswith('#'), f)) + lists = defaultdict(list) - header = "EncoderLeft,EncoderRight,DesiredVelocityLeft,DesiredVelocityRight,CurrentVelocityLeft,CurrentVelocityRight,LeftPower,RightPower,EncoderTargetLeft,EncoderTargetRight" + # header = "EncoderLeft,EncoderRight,DesiredVelocityLeft,DesiredVelocityRight,CurrentVelocityLeft,CurrentVelocityRight,LeftPower,RightPower,EncoderTargetLeft,EncoderTargetRight" + header = "LeftSetpoint,LeftVelocity,LeftError,RightSetpoint,RightVelocity,RightError,Heading" keys = header.split(",") 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"]) - 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() +# 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 279268d..eb17f22 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -16,10 +16,12 @@ #include "robot/encoder.h" #include "../env.h" #include "robot/pidController.h" +#include "robot/magnet.h" //alright SCREW YOU serial monitor i won't print every frame then if you wanna play that game const int8_t PRINT_INTERVAL = 60; int8_t framesUntilPrint = 60; +unsigned long previousTime = 0; // For loop timing // Setup gets run at startup void setup() { @@ -29,7 +31,6 @@ void setup() { delay(STARTUP_DELAY); serialLogln("Finished Delay!", 2); - // Any setup needed to get bot ready setupBot(); @@ -44,6 +45,8 @@ void setup() { if (DO_DRIVE_TICKS_TEST) driveTicks(20000, "NULL"); if (DO_HARDWARE_TEST) timerDelay(5000, &startMotorAndEncoderTest); + + previousTime = millis() - loopDelayMilliseconds; } // After setup gets run, loop is run over and over as fast ass possible @@ -68,7 +71,10 @@ void loop() { } // Run control loop - controlLoop(loopDelayMilliseconds, framesUntilPrint); + // TODO change time parameter to be actual delta time, not just delay between loops + unsigned long deltaTime = millis() - previousTime; + previousTime = millis(); + controlLoop(deltaTime, framesUntilPrint); // This delay determines how often the code in loop is run // (Forcefully pauses the thread for about the amount of milliseconds passed in) diff --git a/src/robot/control.cpp b/src/robot/control.cpp index 5631c5a..d40e2e5 100644 --- a/src/robot/control.cpp +++ b/src/robot/control.cpp @@ -3,7 +3,6 @@ // Associated Header File #include "robot/control.h" -#include "robot/trapezoidalProfile.h" // Built-In Libraries #include "Arduino.h" @@ -24,9 +23,20 @@ #include #include "utils/functions.h" -//PLEASE ONLY USE CHESSBOT #4 FOR TESTING -PIDController encoderAVelocityController(0.00008, 0.0000035, 0.000001, -1, +1); //Blue -PIDController encoderBVelocityController(0.00008, 0.0000035, 0.000001, -1, +1); //Red +#include "robot/profiledPIDController.h" +#include "robot/trapezoidalProfileNew.h" +#include "robot/magnet.h" + + +Magnet *magnet = nullptr; // Declare a pointer to Magnet + +// pid constants +TrapezoidProfile::Constraints profileConstraints(VELOCITY_LIMIT_TPS, ACCELERATION_LIMIT_TPSPS); +TrapezoidProfile 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 //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; @@ -175,6 +185,17 @@ void setupBot() { setupMotors(); 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(); @@ -244,27 +265,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 / THEORETICAL_MAX_VELOCITY_TPS; + double rightFeedForward = rightSetpoint.velocity / THEORETICAL_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; @@ -272,47 +296,64 @@ 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(", ", 2); - serialLog("Current encoder B pos: ", 2); - serialLog(currentEncoderB, 2); - serialLog(", ", 2); - serialLog("Desired encoder A speed: ", 2); - serialLog(desiredVelocityA, 2); - serialLog(", ", 2); - serialLog("Desired encoder B speed: ", 2); - serialLog(desiredVelocityB, 2); - serialLog(", ", 2); - serialLog("current encoder a speed: ", 2); - serialLog(currentVelocityA, 2); - serialLog(", ", 2); - serialLog("current encoder b speed: ", 2); - serialLog(currentVelocityB, 2); - serialLog(", ", 2); - serialLog("current left motor power: ", 2); - serialLog(leftMotorPower, 2); - serialLog(", ", 2); - serialLog("current right motor power: ", 2); - serialLog(rightMotorPower, 2); - serialLog(", ", 2); - serialLog("current encoder a target: ", 2); - serialLog(leftMotorControl.mode == POSITION ? leftMotorControl.value : 0, 2); - serialLog(", ", 2); - serialLog("current encoder b target: ", 2); - serialLog(rightMotorControl.mode == POSITION ? rightMotorControl.value : 0, 2); // TODO log results of trapezoidal profile into csv (on motor value graph) - serialLog(", ", 2); - serialLog("is robot pid at target? ", 2); - serialLog(isRobotPidAtTarget(), 2); - serialLog(", ", 2); - serialLogln(loopDelaySeconds, 2); + // 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); } - - #endif + + 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); + serialLog(rightSetpoint.velocity - currentVelocityB, 3); + serialLog(",", 3); + // test magnet data + float heading = magnet->readDegrees(); + serialLogln(heading, 3); + // serialLogln(0, 3); + +#endif drive( leftMotorPower, // leftMotorPower, @@ -483,6 +524,7 @@ bool checkIfCanUpdateMovement() void setLeftMotorControl(ControlSetting control) { leftMotorControl = control; + leftSetpoint = TrapezoidProfile::State(readLeftEncoder(), profileA.currentVelocity); if (control.mode == POSITION) profileA.targetPosition = control.value; else @@ -491,6 +533,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 @@ -535,10 +578,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/robot/magnet.cpp b/src/robot/magnet.cpp new file mode 100644 index 0000000..7cceee1 --- /dev/null +++ b/src/robot/magnet.cpp @@ -0,0 +1,91 @@ +#include "DFRobot_BMM350.h" +#include "robot/magnet.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(); + 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); +} + +void Magnet::set_hard_iron_offset(float x, float y, float z) { + hard_iron_offset[0] = x; + hard_iron_offset[1] = y; + hard_iron_offset[2] = z; +} + +void Magnet::set_soft_iron_matrix(float matrix[3][3]) { + for (int i = 0; i < 3; i++) { + for (int j = 0; j < 3; j++) { + soft_iron_matrix[i][j] = matrix[i][j]; + } + } +} + +MagnetReading Magnet::read_calibrated_data() { + sBmm350MagData_t sensor_mag_data = bmm350.getGeomagneticData(); + float 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; +} + +float Magnet::readDegreesRaw() { + MagnetReading mag = read_calibrated_data(); + return getCompassDegree(mag); +} + +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 + } + 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; +} diff --git a/src/robot/trapezoidalProfileNew.cpp b/src/robot/trapezoidalProfileNew.cpp new file mode 100644 index 0000000..962fe6f --- /dev/null +++ b/src/robot/trapezoidalProfileNew.cpp @@ -0,0 +1,61 @@ +#include "robot/trapezoidalProfileNew.h" + +TrapezoidProfile::State TrapezoidProfile::calculate(double t, const State ¤t, const State &goal) +{ + int m_direction = shouldFlipAcceleration(current, goal) ? -1 : 1; + State m_current = direct(current, m_direction); + State goalDir = direct(goal, m_direction); + + if (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; + } + + double m_endAccel = accelerationTime - cutoffBegin; + double m_endFullSpeed = m_endAccel + fullSpeedDist / m_constraints.maxVelocity; + double m_endDecel = m_endFullSpeed + accelerationTime - cutoffEnd; + State result(m_current.position, m_current.velocity); + + if (t < m_endAccel) + { + result.velocity += t * m_constraints.maxAcceleration; + 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, m_direction); +} diff --git a/src/utils/config.cpp b/src/utils/config.cpp index 6049e39..2f9aebc 100644 --- a/src/utils/config.cpp +++ b/src/utils/config.cpp @@ -37,8 +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 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 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; @@ -68,8 +71,9 @@ void setConfig(JsonObject config) { if (config["TICKS_PER_ROTATION"].is()) TICKS_PER_ROTATION = config["TICKS_PER_ROTATION"]; if (config["TRACK_WIDTH_INCHES"].is()) TRACK_WIDTH_INCHES = config["TRACK_WIDTH_INCHES"]; if (config["WHEEL_DIAMETER_INCHES"].is()) WHEEL_DIAMETER_INCHES = config["WHEEL_DIAMETER_INCHES"]; - if (config["MAX_VELOCITY_TPS"].is()) MAX_VELOCITY_TPS = config["MAX_VELOCITY_TPS"]; - if (config["MAX_ACCELERATION_TPSPS"].is()) MAX_ACCELERATION_TPSPS = config["MAX_ACCELERATION_TPSPS"]; + if (config["THEORETICAL_MAX_VELOCITY_TPS"].is()) THEORETICAL_MAX_VELOCITY_TPS = config["THEORETICAL_MAX_VELOCITY_TPS"]; + if (config["THEORETICAL_MAX_ACCELERATION_TPSPS"].is()) THEORETICAL_MAX_ACCELERATION_TPSPS = config["THEORETICAL_MAX_ACCELERATION_TPSPS"]; + if (config["MIN_MOTOR_POWER"].is()) MIN_MOTOR_POWER = config["MIN_MOTOR_POWER"]; serialLogln("Config Set!", 2); } diff --git a/src/utils/logging.cpp b/src/utils/logging.cpp index 58ffb88..56baaa0 100644 --- a/src/utils/logging.cpp +++ b/src/utils/logging.cpp @@ -55,6 +55,12 @@ void serialLogln(double value, int serialLoggingLevel) Serial.println(value); } +void serialLogln(float value, int serialLoggingLevel) +{ + if (serialLoggingLevel <= LOGGING_LEVEL) + Serial.println(value); +} + void serialLogln(std::string value, int serialLoggingLevel) { serialLogln(value.c_str(), serialLoggingLevel);