diff --git a/.vscode/c_cpp_properties.json b/.vscode/c_cpp_properties.json index a41cd2089e3c3d93d8ae7ebeae9a6546e2645f57..dc630721eef6582109b785e60a3cefa307d246cf 100644 --- a/.vscode/c_cpp_properties.json +++ b/.vscode/c_cpp_properties.json @@ -8,7 +8,7 @@ "defines": [ "DEBUG", "_ARCH_CORTEXM4_STM32F4", - "_BOARD_STM32F407VG_STM32F4DISCOVERY", + "_BOARD_STM32F4DISCOVERY", "_MIOSIX_BOARDNAME=stm32f407vg_stm32f4discovery", "HSE_VALUE=8000000", "SYSCLK_FREQ_168MHz=168000000", @@ -51,8 +51,7 @@ "${workspaceFolder}/src/tests" ], "limitSymbolsToIncludedHeaders": true - }, - "compileCommands": "${workspaceFolder}/build/compile_commands.json" + } }, { "name": "stm32f429zi_stm32f4discovery", @@ -115,7 +114,7 @@ "defines": [ "DEBUG", "_ARCH_CORTEXM4_STM32F4", - "_BOARD_STM32F429ZI_SKYWARD_DEATH_STACK_X", + "_BOARD_STM32F429ZI_SKYWARD_DEATHST_X", "_MIOSIX_BOARDNAME=stm32f429zi_skyward_death_stack_x", "HSE_VALUE=8000000", "SYSCLK_FREQ_168MHz=168000000", @@ -161,23 +160,129 @@ } }, { - "name": "stm32f429zi_parafoil", + "name": "stm32f429zi_skyward_death_stack_v3", + "cStandard": "c11", + "cppStandard": "c++11", + "compilerPath": "/opt/arm-miosix-eabi/bin/arm-miosix-eabi-g++", + "defines": [ + "DEBUG", + "_ARCH_CORTEXM4_STM32F4", + "_BOARD_STM32F429ZI_SKYWARD_DEATHST_X", + "_MIOSIX_BOARDNAME=stm32f429zi_skyward_death_stack_v3", + "HSE_VALUE=8000000", + "SYSCLK_FREQ_168MHz=168000000", + "_MIOSIX", + "__cplusplus=201103L" + ], + "includePath": [ + "${workspaceFolder}/libs/miosix-kernel/miosix/config/arch/cortexM4_stm32f4/stm32f429zi_skyward_death_stack_v3", + "${workspaceFolder}/libs/miosix-kernel/miosix/arch/cortexM4_stm32f4/stm32f429zi_skyward_death_stack_v3", + "${workspaceFolder}/libs/miosix-kernel/miosix/arch/cortexM4_stm32f4/common", + "${workspaceFolder}/libs/miosix-kernel/miosix/arch/common", + "${workspaceFolder}/libs/miosix-kernel/miosix", + "${workspaceFolder}/libs/mavlink-skyward-lib", + "${workspaceFolder}/libs/fmt/include", + "${workspaceFolder}/libs/eigen", + "${workspaceFolder}/libs/tscpp", + "${workspaceFolder}/libs", + "${workspaceFolder}/src/shared", + "${workspaceFolder}/src/tests" + ], + "browse": { + "path": [ + "${workspaceFolder}/libs/miosix-kernel/miosix/config/arch/cortexM4_stm32f4/stm32f429zi_skyward_death_stack_v3", + "${workspaceFolder}/libs/miosix-kernel/miosix/arch/cortexM4_stm32f4/stm32f429zi_skyward_death_stack_v3", + "${workspaceFolder}/libs/miosix-kernel/miosix/arch/cortexM4_stm32f4/common", + "${workspaceFolder}/libs/miosix-kernel/miosix/stdlib_integration", + "${workspaceFolder}/libs/miosix-kernel/miosix/arch/common", + "${workspaceFolder}/libs/miosix-kernel/miosix/interfaces", + "${workspaceFolder}/libs/miosix-kernel/miosix/filesystem", + "${workspaceFolder}/libs/miosix-kernel/miosix/kernel", + "${workspaceFolder}/libs/miosix-kernel/miosix/util", + "${workspaceFolder}/libs/miosix-kernel/miosix/e20", + "${workspaceFolder}/libs/miosix-kernel/miosix/*", + "${workspaceFolder}/libs/mavlink-skyward-lib", + "${workspaceFolder}/libs/eigen", + "${workspaceFolder}/libs/tscpp", + "${workspaceFolder}/libs/mxgui", + "${workspaceFolder}/libs/fmt", + "${workspaceFolder}/src/shared", + "${workspaceFolder}/src/tests" + ], + "limitSymbolsToIncludedHeaders": true + } + }, + { + "name": "stm32f429zi_skyward_parafoil", + "cStandard": "c11", + "cppStandard": "c++11", + "compilerPath": "/opt/arm-miosix-eabi/bin/arm-miosix-eabi-g++", + "defines": [ + "DEBUG", + "_ARCH_CORTEXM4_STM32F4", + "_BOARD_STM32F429ZI_SKYWARD_PARAFOIL", + "_MIOSIX_BOARDNAME=stm32f429zi_skyward_parafoil", + "HSE_VALUE=8000000", + "SYSCLK_FREQ_168MHz=168000000", + "_MIOSIX", + "__cplusplus=201103L" + ], + "includePath": [ + "${workspaceFolder}/libs/miosix-kernel/miosix/config/arch/cortexM4_stm32f4/stm32f429zi_skyward_parafoil", + "${workspaceFolder}/libs/miosix-kernel/miosix/arch/cortexM4_stm32f4/stm32f429zi_skyward_parafoil", + "${workspaceFolder}/libs/miosix-kernel/miosix/arch/cortexM4_stm32f4/common", + "${workspaceFolder}/libs/miosix-kernel/miosix/arch/common", + "${workspaceFolder}/libs/miosix-kernel/miosix", + "${workspaceFolder}/libs/mavlink-skyward-lib", + "${workspaceFolder}/libs/fmt/include", + "${workspaceFolder}/libs/eigen", + "${workspaceFolder}/libs/tscpp", + "${workspaceFolder}/libs", + "${workspaceFolder}/src/shared", + "${workspaceFolder}/src/tests" + ], + "browse": { + "path": [ + "${workspaceFolder}/libs/miosix-kernel/miosix/config/arch/cortexM4_stm32f4/stm32f429zi_skyward_parafoil", + "${workspaceFolder}/libs/miosix-kernel/miosix/arch/cortexM4_stm32f4/stm32f429zi_skyward_parafoil", + "${workspaceFolder}/libs/miosix-kernel/miosix/arch/cortexM4_stm32f4/common", + "${workspaceFolder}/libs/miosix-kernel/miosix/stdlib_integration", + "${workspaceFolder}/libs/miosix-kernel/miosix/arch/common", + "${workspaceFolder}/libs/miosix-kernel/miosix/interfaces", + "${workspaceFolder}/libs/miosix-kernel/miosix/filesystem", + "${workspaceFolder}/libs/miosix-kernel/miosix/kernel", + "${workspaceFolder}/libs/miosix-kernel/miosix/util", + "${workspaceFolder}/libs/miosix-kernel/miosix/e20", + "${workspaceFolder}/libs/miosix-kernel/miosix/*", + "${workspaceFolder}/libs/mavlink-skyward-lib", + "${workspaceFolder}/libs/eigen", + "${workspaceFolder}/libs/tscpp", + "${workspaceFolder}/libs/mxgui", + "${workspaceFolder}/libs/fmt", + "${workspaceFolder}/src/shared", + "${workspaceFolder}/src/tests" + ], + "limitSymbolsToIncludedHeaders": true + } + }, + { + "name": "stm32f429zi_skyward_pyxis_auxiliary", "cStandard": "c11", "cppStandard": "c++11", "compilerPath": "/opt/arm-miosix-eabi/bin/arm-miosix-eabi-g++", "defines": [ "DEBUG", "_ARCH_CORTEXM4_STM32F4", - "_BOARD_STM32F429ZI_PARAFOIL", - "_MIOSIX_BOARDNAME=stm32f429zi_parafoil", + "_BOARD_STM32F429ZI_SKYWARD_PYXIS_AUXILIARY", + "_MIOSIX_BOARDNAME=stm32f429zi_skyward_pyxis_auxiliary", "HSE_VALUE=8000000", "SYSCLK_FREQ_168MHz=168000000", "_MIOSIX", "__cplusplus=201103L" ], "includePath": [ - "${workspaceFolder}/libs/miosix-kernel/miosix/config/arch/cortexM4_stm32f4/stm32f429zi_parafoil", - "${workspaceFolder}/libs/miosix-kernel/miosix/arch/cortexM4_stm32f4/stm32f429zi_parafoil", + "${workspaceFolder}/libs/miosix-kernel/miosix/config/arch/cortexM4_stm32f4/stm32f429zi_skyward_pyxis_auxiliary", + "${workspaceFolder}/libs/miosix-kernel/miosix/arch/cortexM4_stm32f4/stm32f429zi_skyward_pyxis_auxiliary", "${workspaceFolder}/libs/miosix-kernel/miosix/arch/cortexM4_stm32f4/common", "${workspaceFolder}/libs/miosix-kernel/miosix/arch/common", "${workspaceFolder}/libs/miosix-kernel/miosix", @@ -191,8 +296,8 @@ ], "browse": { "path": [ - "${workspaceFolder}/libs/miosix-kernel/miosix/config/arch/cortexM4_stm32f4/stm32f429zi_parafoil", - "${workspaceFolder}/libs/miosix-kernel/miosix/arch/cortexM4_stm32f4/stm32f429zi_parafoil", + "${workspaceFolder}/libs/miosix-kernel/miosix/config/arch/cortexM4_stm32f4/stm32f429zi_skyward_pyxis_auxiliary", + "${workspaceFolder}/libs/miosix-kernel/miosix/arch/cortexM4_stm32f4/stm32f429zi_skyward_pyxis_auxiliary", "${workspaceFolder}/libs/miosix-kernel/miosix/arch/cortexM4_stm32f4/common", "${workspaceFolder}/libs/miosix-kernel/miosix/stdlib_integration", "${workspaceFolder}/libs/miosix-kernel/miosix/arch/common", @@ -212,6 +317,59 @@ ], "limitSymbolsToIncludedHeaders": true } + }, + { + "name": "stm32f205rc_skyward_ciuti", + "cStandard": "c11", + "cppStandard": "c++11", + "compilerPath": "/opt/arm-miosix-eabi/bin/arm-miosix-eabi-g++", + "defines": [ + "DEBUG", + "_ARCH_CORTEXM3_STM32F2", + "_BOARD_STM32F205RC_SKYWARD_CIUTI", + "_MIOSIX_BOARDNAME=stm32f205RC_skyward_ciuti", + "HSE_VALUE=25000000", + "SYSCLK_FREQ_120MHz=120000000", + "_MIOSIX", + "__cplusplus=201103L" + ], + "includePath": [ + "${workspaceFolder}/libs/miosix-kernel/miosix/config/arch/cortexM3_stm32f2/stm32f205rc_skyward_ciuti", + "${workspaceFolder}/libs/miosix-kernel/miosix/arch/cortexM3_stm32f2/stm32f205rc_skyward_ciuti", + "${workspaceFolder}/libs/miosix-kernel/miosix/arch/cortexM3_stm32f2/common", + "${workspaceFolder}/libs/miosix-kernel/miosix/arch/common", + "${workspaceFolder}/libs/miosix-kernel/miosix", + "${workspaceFolder}/libs/mavlink-skyward-lib", + "${workspaceFolder}/libs/fmt/include", + "${workspaceFolder}/libs/eigen", + "${workspaceFolder}/libs/tscpp", + "${workspaceFolder}/libs", + "${workspaceFolder}/src/shared", + "${workspaceFolder}/src/tests" + ], + "browse": { + "path": [ + "${workspaceFolder}/libs/miosix-kernel/miosix/config/arch/cortexM3_stm32f2/stm32f205rc_skyward_ciuti", + "${workspaceFolder}/libs/miosix-kernel/miosix/arch/cortexM3_stm32f2/stm32f205rc_skyward_ciuti", + "${workspaceFolder}/libs/miosix-kernel/miosix/arch/cortexM3_stm32f2/common", + "${workspaceFolder}/libs/miosix-kernel/miosix/stdlib_integration", + "${workspaceFolder}/libs/miosix-kernel/miosix/arch/common", + "${workspaceFolder}/libs/miosix-kernel/miosix/interfaces", + "${workspaceFolder}/libs/miosix-kernel/miosix/filesystem", + "${workspaceFolder}/libs/miosix-kernel/miosix/kernel", + "${workspaceFolder}/libs/miosix-kernel/miosix/util", + "${workspaceFolder}/libs/miosix-kernel/miosix/e20", + "${workspaceFolder}/libs/miosix-kernel/miosix/*", + "${workspaceFolder}/libs/mavlink-skyward-lib", + "${workspaceFolder}/libs/eigen", + "${workspaceFolder}/libs/tscpp", + "${workspaceFolder}/libs/mxgui", + "${workspaceFolder}/libs/fmt", + "${workspaceFolder}/src/shared", + "${workspaceFolder}/src/tests" + ], + "limitSymbolsToIncludedHeaders": true + } } ], "version": 4 diff --git a/.vscode/settings.json b/.vscode/settings.json index 43e514f2603ebb9bb2b90fdab6c1c80067e2f17d..68d8988bcafbddb302ab2276396aab2f81057fc8 100644 --- a/.vscode/settings.json +++ b/.vscode/settings.json @@ -1,228 +1,306 @@ { - "cmake.configureSettings": { - "CMAKE_C_COMPILER_LAUNCHER": "ccache", - "CMAKE_CXX_COMPILER_LAUNCHER": "ccache" - }, - "cmake.parallelJobs": 1, - "files.associations": { - "sstream": "cpp", - "format": "cpp", - "any": "cpp", - "array": "cpp", - "atomic": "cpp", - "bit": "cpp", - "*.tcc": "cpp", - "bitset": "cpp", - "cctype": "cpp", - "chrono": "cpp", - "clocale": "cpp", - "cmath": "cpp", - "codecvt": "cpp", - "complex": "cpp", - "condition_variable": "cpp", - "cstdarg": "cpp", - "cstddef": "cpp", - "cstdint": "cpp", - "cstdio": "cpp", - "cstdlib": "cpp", - "cstring": "cpp", - "ctime": "cpp", - "cwchar": "cpp", - "cwctype": "cpp", - "deque": "cpp", - "list": "cpp", - "map": "cpp", - "set": "cpp", - "unordered_map": "cpp", - "vector": "cpp", - "exception": "cpp", - "algorithm": "cpp", - "functional": "cpp", - "iterator": "cpp", - "memory": "cpp", - "memory_resource": "cpp", - "numeric": "cpp", - "optional": "cpp", - "random": "cpp", - "ratio": "cpp", - "regex": "cpp", - "string": "cpp", - "string_view": "cpp", - "system_error": "cpp", - "tuple": "cpp", - "type_traits": "cpp", - "utility": "cpp", - "fstream": "cpp", - "future": "cpp", - "initializer_list": "cpp", - "iomanip": "cpp", - "iosfwd": "cpp", - "iostream": "cpp", - "istream": "cpp", - "limits": "cpp", - "mutex": "cpp", - "new": "cpp", - "ostream": "cpp", - "shared_mutex": "cpp", - "stdexcept": "cpp", - "streambuf": "cpp", - "thread": "cpp", - "cinttypes": "cpp", - "typeindex": "cpp", - "typeinfo": "cpp", - "variant": "cpp", - "__config": "cpp", - "__threading_support": "cpp", - "__mutex_base": "cpp", - "__tree": "cpp", - "locale": "cpp", - "__bit_reference": "cpp", - "__bits": "cpp", - "__debug": "cpp", - "__errc": "cpp", - "__functional_base": "cpp", - "__hash_table": "cpp", - "__locale": "cpp", - "__node_handle": "cpp", - "__nullptr": "cpp", - "__split_buffer": "cpp", - "__string": "cpp", - "__tuple": "cpp", - "ios": "cpp", - "queue": "cpp", - "stack": "cpp", - "__functional_03": "cpp", - "filesystem": "cpp", - "unordered_set": "cpp", - "hash_map": "cpp", - "valarray": "cpp", - "ranges": "cpp", - "compare": "cpp", - "concepts": "cpp", - "core": "cpp", - "iterativelinearsolvers": "cpp", - "pastixsupport": "cpp", - "superlusupport": "cpp", - "adolcforward": "cpp", - "alignedvector3": "cpp", - "bvh": "cpp", - "fft": "cpp", - "iterativesolvers": "cpp", - "mprealsupport": "cpp", - "matrixfunctions": "cpp", - "nonlinearoptimization": "cpp", - "openglsupport": "cpp", - "polynomials": "cpp", - "autodiff": "cpp", - "sparseextra": "cpp", - "specialfunctions": "cpp" - }, - "cSpell.words": [ - "aelf", - "Alessandro", - "AMSL", - "atthr", - "AVDD", - "Baro", - "boardcore", - "Boardcorev", - "Corigliano", - "CORTEXM", - "cpitch", - "cppcheck", - "croll", - "cwise", - "cyaw", - "deleteme", - "DMEIE", - "Doxyfile", - "doxygen", - "DRDY", - "Duca", - "Ecompass", - "Eigen", - "elfs", - "Erbetta", - "Fatt", - "Fatttr", - "fedetft's", - "fiprintf", - "Gatttr", - "getdetahstate", - "Gpio", - "GPIOA", - "GPIOB", - "GPIOC", - "GPIOD", - "GPIOE", - "GPIOF", - "GPIOG", - "GPIOS", - "gpstr", - "Hatt", - "HSCMAND", - "HSCMRNN", - "IDLEIE", - "irqn", - "irqv", - "Kalman", - "Katt", - "kbps", - "ldrex", - "LIFCR", - "logdecoder", - "Luca", - "MEKF", - "MINC", - "miosix", - "mkdir", - "MPXHZ", - "Musso", - "NATT", - "NBAR", - "NDTR", - "NGPS", - "NMAG", - "NMEKF", - "nord", - "NVIC", - "peripehral", - "PINC", - "Pitot", - "Plin", - "Qgbw", - "Qget", - "Qhandle", - "Qput", - "Qwait", - "Qwakeup", - "Riccardo", - "RXNE", - "RXNEIE", - "sats", - "Satt", - "SDRAM", - "spitch", - "sqdip", - "sqtrp", - "sroll", - "SSCDANN", - "SSCDRRN", - "stof", - "syaw", - "TCIE", - "TEIE", - "testsuite", - "TSCPP", - "Ublox", - "Unsync", - "upcounter", - "USART", - "velnord", - "Xbee", - "xnord", - "yned" - ], - "cSpell.language": "en", - "cSpell.enabled": true + "cmake.configureSettings": { + "CMAKE_C_COMPILER_LAUNCHER": "ccache", + "CMAKE_CXX_COMPILER_LAUNCHER": "ccache" + }, + "cmake.parallelJobs": 1, + "files.associations": { + "sstream": "cpp", + "format": "cpp", + "any": "cpp", + "array": "cpp", + "atomic": "cpp", + "bit": "cpp", + "*.tcc": "cpp", + "bitset": "cpp", + "cctype": "cpp", + "chrono": "cpp", + "clocale": "cpp", + "cmath": "cpp", + "codecvt": "cpp", + "complex": "cpp", + "condition_variable": "cpp", + "cstdarg": "cpp", + "cstddef": "cpp", + "cstdint": "cpp", + "cstdio": "cpp", + "cstdlib": "cpp", + "cstring": "cpp", + "ctime": "cpp", + "cwchar": "cpp", + "cwctype": "cpp", + "deque": "cpp", + "list": "cpp", + "map": "cpp", + "set": "cpp", + "unordered_map": "cpp", + "vector": "cpp", + "exception": "cpp", + "algorithm": "cpp", + "functional": "cpp", + "iterator": "cpp", + "memory": "cpp", + "memory_resource": "cpp", + "numeric": "cpp", + "optional": "cpp", + "random": "cpp", + "ratio": "cpp", + "regex": "cpp", + "string": "cpp", + "string_view": "cpp", + "system_error": "cpp", + "tuple": "cpp", + "type_traits": "cpp", + "utility": "cpp", + "fstream": "cpp", + "future": "cpp", + "initializer_list": "cpp", + "iomanip": "cpp", + "iosfwd": "cpp", + "iostream": "cpp", + "istream": "cpp", + "limits": "cpp", + "mutex": "cpp", + "new": "cpp", + "ostream": "cpp", + "shared_mutex": "cpp", + "stdexcept": "cpp", + "streambuf": "cpp", + "thread": "cpp", + "cinttypes": "cpp", + "typeindex": "cpp", + "typeinfo": "cpp", + "variant": "cpp", + "__config": "cpp", + "__threading_support": "cpp", + "__mutex_base": "cpp", + "__tree": "cpp", + "locale": "cpp", + "__bit_reference": "cpp", + "__bits": "cpp", + "__debug": "cpp", + "__errc": "cpp", + "__functional_base": "cpp", + "__hash_table": "cpp", + "__locale": "cpp", + "__node_handle": "cpp", + "__nullptr": "cpp", + "__split_buffer": "cpp", + "__string": "cpp", + "__tuple": "cpp", + "ios": "cpp", + "queue": "cpp", + "stack": "cpp", + "__functional_03": "cpp", + "filesystem": "cpp", + "unordered_set": "cpp", + "hash_map": "cpp", + "valarray": "cpp", + "ranges": "cpp", + "compare": "cpp", + "concepts": "cpp", + "core": "cpp", + "iterativelinearsolvers": "cpp", + "pastixsupport": "cpp", + "superlusupport": "cpp", + "adolcforward": "cpp", + "alignedvector3": "cpp", + "bvh": "cpp", + "fft": "cpp", + "iterativesolvers": "cpp", + "mprealsupport": "cpp", + "matrixfunctions": "cpp", + "nonlinearoptimization": "cpp", + "openglsupport": "cpp", + "polynomials": "cpp", + "autodiff": "cpp", + "sparseextra": "cpp", + "specialfunctions": "cpp" + }, + "cSpell.words": [ + "abom", + "ADCPRE", + "addfilter", + "ADON", + "aelf", + "airbrakes", + "Airbrakes", + "Alain", + "Alessandro", + "ALST", + "AMSL", + "apbclk", + "atthr", + "AVDD", + "awum", + "Baro", + "bittiming", + "boardcore", + "Boardcorev", + "boudrate", + "Canbus", + "canprotocol", + "Carlucci", + "compid", + "Corigliano", + "CORTEXM", + "cpitch", + "cppcheck", + "croll", + "cwise", + "cyaw", + "DATABUS", + "deleteme", + "DMEIE", + "Doxyfile", + "doxygen", + "DRDY", + "Duca", + "Ecompass", + "Eigen", + "elfs", + "Erbetta", + "Fatt", + "Fatttr", + "fedetft's", + "fiprintf", + "FMPIE", + "FOVR", + "Gatttr", + "getdetahstate", + "GNSS", + "Gpio", + "GPIOA", + "GPIOB", + "GPIOC", + "GPIOD", + "GPIOE", + "GPIOF", + "GPIOG", + "GPIOS", + "gpstr", + "Hatt", + "HIFCR", + "HISR", + "hppw", + "HSCMAND", + "HSCMRNN", + "HWMAPPING", + "IDLEIE", + "Impli", + "Implii", + "INAK", + "INRQ", + "irqn", + "irqv", + "JEOC", + "JOFR", + "JSQR", + "JSWSTART", + "Kalman", + "Katt", + "kbps", + "LBKM", + "ldrex", + "leds", + "LIFCR", + "LISR", + "logdecoder", + "Luca", + "Mandelli", + "Matteo", + "Mavlink", + "mavlinkdriver", + "MEKF", + "microcontrollers", + "MINC", + "miosix", + "mkdir", + "mosfet", + "mosi", + "MPXHZ", + "Musso", + "nart", + "NATT", + "NBAR", + "NDTR", + "NGPS", + "Nidasio", + "NMAG", + "NMEA", + "NMEKF", + "nord", + "NVIC", + "peripehral", + "Piazzolla", + "PINC", + "Pitot", + "Plin", + "prescaler", + "Qgbw", + "Qget", + "Qhandle", + "Qput", + "Qwait", + "Qwakeup", + "RDHR", + "RDLR", + "RDTR", + "rflm", + "RFOM", + "Riccardo", + "RQCP", + "RXIRQ", + "RXNE", + "RXNEIE", + "sats", + "Satt", + "sdio", + "SDRAM", + "smpr", + "SMPR", + "spitch", + "sqdip", + "sqtrp", + "sroll", + "SSCDANN", + "SSCDRRN", + "stof", + "SWSTART", + "syaw", + "TCIE", + "TCIF", + "TDHR", + "TDLR", + "TDTR", + "TEIE", + "Terraneo", + "testsuite", + "THID", + "TMEIE", + "tparam", + "TSCPP", + "TSVREFE", + "Tweakable", + "txfp", + "TXIRQ", + "TXOK", + "TXRQ", + "Ublox", + "UBXACK", + "UBXGPS", + "UBXNAV", + "Unsync", + "upcounter", + "USART", + "vbat", + "velnord", + "vout", + "vsense", + "Xbee", + "xnord", + "yned" + ], + "cSpell.language": "en", + "cSpell.enabled": true } diff --git a/CMakeLists.txt b/CMakeLists.txt index 5623c9375bd54d014e1e31f5fe8109ff40650ff2..52b88b00b9d7a740fadcf23a794b230d9d964a49 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -40,19 +40,19 @@ add_executable(config-dsgamma src/entrypoints/config-dsgamma.cpp) sbs_target(config-dsgamma stm32f429zi_stm32f4discovery) add_executable(imu-calibration src/entrypoints/imu-calibration.cpp) -sbs_target(imu-calibration stm32f429zi_parafoil) +sbs_target(imu-calibration stm32f429zi_skyward_parafoil) add_executable(mxgui-helloworld src/entrypoints/examples/mxgui-helloworld.cpp) sbs_target(mxgui-helloworld stm32f429zi_stm32f4discovery) add_executable(kernel-testsuite src/entrypoints/kernel-testsuite.cpp) -sbs_target(kernel-testsuite stm32f429zi_stm32f4discovery) +sbs_target(kernel-testsuite stm32f205rc_skyward_ciuti) add_executable(runcam-settings src/entrypoints/runcam-settings.cpp) sbs_target(runcam-settings stm32f407vg_stm32f4discovery) add_executable(sdcard-benchmark src/entrypoints/sdcard-benchmark.cpp) -sbs_target(sdcard-benchmark stm32f429zi_stm32f4discovery) +sbs_target(sdcard-benchmark stm32f429zi_skyward_death_stack_x) #-----------------------------------------------------------------------------# # Tests # @@ -80,7 +80,7 @@ add_executable(test-sensormanager src/tests/test-sensormanager.cpp) sbs_target(test-sensormanager stm32f429zi_skyward_death_stack_x) add_executable(test-serial src/tests/test-serial.cpp) -sbs_target(test-serial stm32f407vg_stm32f4discovery) +sbs_target(test-serial stm32f429zi_stm32f4discovery) add_executable(test-taskscheduler src/tests/scheduler/test-taskscheduler.cpp) sbs_target(test-taskscheduler stm32f407vg_stm32f4discovery) @@ -100,7 +100,7 @@ add_executable(catch-tests-boardcore src/tests/catch/test-circularbuffer.cpp src/tests/catch/test-eventbroker.cpp src/tests/catch/test-timestamptimer.cpp - src/tests/catch/test-kalman-eigen.cpp + src/tests/catch/test-kalman.cpp src/tests/catch/test-packetqueue.cpp src/tests/catch/test-sensormanager-catch.cpp src/tests/catch/xbee/test-xbee-parser.cpp @@ -129,20 +129,17 @@ sbs_target(test-stepper stm32f429zi_stm32f4discovery) # Tests - Algorithms # #-----------------------------------------------------------------------------# -add_executable(test-kalman-eigen-benchmark src/tests/algorithms/Kalman/test-kalman-eigen-benchmark.cpp) -sbs_target(test-kalman-eigen-benchmark stm32f429zi_stm32f4discovery) - -add_executable(test-tmp src/tests/algorithms/NAS/test-tmp.cpp) -sbs_target(test-tmp stm32f429zi_skyward_death_stack_x) +add_executable(test-kalman-benchmark src/tests/algorithms/Kalman/test-kalman-benchmark.cpp) +sbs_target(test-kalman-benchmark stm32f429zi_stm32f4discovery) add_executable(test-attitude-parafoil src/tests/algorithms/NAS/test-attitude-parafoil.cpp) -sbs_target(test-attitude-parafoil stm32f429zi_parafoil) +sbs_target(test-attitude-parafoil stm32f429zi_skyward_parafoil) add_executable(test-attitude-stack src/tests/algorithms/NAS/test-attitude-stack.cpp) sbs_target(test-attitude-stack stm32f429zi_skyward_death_stack_x) add_executable(test-nas-parafoil src/tests/algorithms/NAS/test-nas-parafoil.cpp) -sbs_target(test-nas-parafoil stm32f429zi_parafoil) +sbs_target(test-nas-parafoil stm32f429zi_skyward_parafoil) add_executable(test-nas-stack src/tests/algorithms/NAS/test-nas-stack.cpp) sbs_target(test-nas-stack stm32f429zi_skyward_death_stack_x) @@ -154,17 +151,26 @@ add_executable(test-triad src/tests/algorithms/NAS/test-triad.cpp) sbs_target(test-triad stm32f429zi_skyward_death_stack_x) add_executable(test-triad-parafoil src/tests/algorithms/NAS/test-triad-parafoil.cpp) -sbs_target(test-triad-parafoil stm32f429zi_parafoil) +sbs_target(test-triad-parafoil stm32f429zi_skyward_parafoil) + +add_executable(test-ada src/tests/algorithms/ADA/test-ada.cpp) +sbs_target(test-ada stm32f429zi_skyward_death_stack_v3) #-----------------------------------------------------------------------------# # Tests - Drivers # #-----------------------------------------------------------------------------# -add_executable(test-canbus-loopback src/tests/drivers/canbus/test-canbus-loopback.cpp) -sbs_target(test-canbus-loopback stm32f429zi_stm32f4discovery) +add_executable(test-can-2way src/tests/drivers/canbus/CanDriver/test-can-2way.cpp) +sbs_target(test-can-2way stm32f429zi_skyward_pyxis_auxiliary) + +add_executable(test-can-filters src/tests/drivers/canbus/CanDriver/test-can-filters.cpp) +sbs_target(test-can-filters stm32f429zi_skyward_pyxis_auxiliary) -add_executable(test-canbus-2way src/tests/drivers/canbus/test-canbus-2way.cpp) -sbs_target(test-canbus-2way stm32f429zi_stm32f4discovery) +add_executable(test-can-loopback src/tests/drivers/canbus/CanDriver/test-can-loopback.cpp) +sbs_target(test-can-loopback stm32f429zi_skyward_death_stack_x) + +add_executable(test-can-protocol src/tests/drivers/canbus/CanProtocol/test-can-protocol.cpp) +sbs_target(test-can-protocol stm32f429zi_skyward_death_stack_x) add_executable(test-dma-spi src/tests/drivers/dma/test-dma-spi.cpp) sbs_target(test-dma-spi stm32f429zi_stm32f4discovery) @@ -176,7 +182,7 @@ add_executable(test-general-purpose-timer src/tests/drivers/timer/test-general-p sbs_target(test-general-purpose-timer stm32f429zi_stm32f4discovery) add_executable(test-internal-adc src/tests/drivers/test-internal-adc.cpp) -sbs_target(test-internal-adc stm32f429zi_skyward_death_stack_x) +sbs_target(test-internal-adc stm32f407vg_stm32f4discovery) add_executable(test-internal-adc-dma src/tests/drivers/test-internal-adc-dma.cpp) sbs_target(test-internal-adc-dma stm32f429zi_stm32f4discovery) @@ -229,6 +235,9 @@ sbs_target(test-xbee-snd stm32f429zi_stm32f4discovery) add_executable(test-usart src/tests/drivers/usart/test-usart.cpp) sbs_target(test-usart stm32f407vg_stm32f4discovery) +add_executable(test-internal-temp src/tests/drivers/test-internal-temp.cpp) +sbs_target(test-internal-temp stm32f407vg_stm32f4discovery) + #-----------------------------------------------------------------------------# # Tests - Events # #-----------------------------------------------------------------------------# @@ -240,29 +249,23 @@ sbs_target(test-fsm stm32f429zi_stm32f4discovery) # Tests - Radio # #-----------------------------------------------------------------------------# -add_executable(test-sx1278-bench - src/tests/drivers/sx1278/test-sx1278-bench.cpp - src/tests/drivers/sx1278/test-sx1278-core.cpp -) -sbs_target(test-sx1278-bench stm32f407vg_stm32f4discovery) +# add_executable(test-sx1278-bench src/tests/drivers/sx1278/test-sx1278-bench.cpp) +# sbs_target(test-sx1278-bench stm32f407vg_stm32f4discovery) -add_executable(test-sx1278-bidir - src/tests/drivers/sx1278/test-sx1278-bidir.cpp - src/tests/drivers/sx1278/test-sx1278-core.cpp -) -sbs_target(test-sx1278-bidir stm32f407vg_stm32f4discovery) +# add_executable(test-sx1278-bidir src/tests/drivers/sx1278/test-sx1278-bidir.cpp) +# sbs_target(test-sx1278-bidir stm32f407vg_stm32f4discovery) -add_executable(test-sx1278-tx - src/tests/drivers/sx1278/test-sx1278-tx.cpp - src/tests/drivers/sx1278/test-sx1278-core.cpp -) -sbs_target(test-sx1278-tx stm32f407vg_stm32f4discovery) +add_executable(test-sx1278-bidir-gs src/tests/drivers/sx1278/test-sx1278-bidir.cpp) +sbs_target(test-sx1278-bidir-gs stm32f429zi_skyward_ground_station) -add_executable(test-sx1278-rx - src/tests/drivers/sx1278/test-sx1278-rx.cpp - src/tests/drivers/sx1278/test-sx1278-core.cpp -) -sbs_target(test-sx1278-rx stm32f407vg_stm32f4discovery) +add_executable(test-sx1278-bidir-v3 src/tests/drivers/sx1278/test-sx1278-bidir.cpp) +sbs_target(test-sx1278-bidir-v3 stm32f429zi_skyward_death_stack_v3) + +add_executable(test-sx1278-tx src/tests/drivers/sx1278/test-sx1278-tx.cpp) +sbs_target(test-sx1278-tx stm32f429zi_skyward_death_stack_v3) + +add_executable(test-sx1278-rx src/tests/drivers/sx1278/test-sx1278-rx.cpp) +sbs_target(test-sx1278-rx stm32f429zi_skyward_ground_station) add_executable(test-sx1278-mavlink src/tests/drivers/sx1278/test-sx1278-mavlink.cpp @@ -279,6 +282,9 @@ sbs_target(test-sx1278-serial stm32f429zi_stm32f4discovery) add_executable(test-cc3135 src/tests/drivers/CC3135/test-cc3135.cpp) sbs_target(test-cc3135 stm32f407vg_stm32f4discovery) +add_executable(test-mavlinkdriver src/tests/radio/test-mavlinkdriver.cpp) +sbs_target(test-mavlinkdriver stm32f407vg_stm32f4discovery) + #-----------------------------------------------------------------------------# # Tests - Sensors # #-----------------------------------------------------------------------------# @@ -347,17 +353,16 @@ add_executable(test-max31855 src/tests/sensors/test-max31855.cpp) sbs_target(test-max31855 stm32f429zi_stm32f4discovery) add_executable(test-mpu9250 src/tests/sensors/test-mpu9250.cpp) -sbs_target(test-mpu9250 stm32f429zi_parafoil) +sbs_target(test-mpu9250 stm32f429zi_skyward_parafoil) add_executable(test-ms5803 src/tests/sensors/test-ms5803.cpp) sbs_target(test-ms5803 stm32f429zi_skyward_death_stack_x) -add_executable(test-ubloxgps-serial src/tests/sensors/test-ubloxgps.cpp) -sbs_target(test-ubloxgps-serial stm32f429zi_skyward_death_stack_x) +add_executable(test-ubxgps-serial src/tests/sensors/test-ubxgps-serial.cpp) +sbs_target(test-ubxgps-serial stm32f429zi_skyward_death_stack_x) -add_executable(test-ubloxgps-spi src/tests/sensors/test-ubloxgps.cpp) -target_compile_definitions(test-ubloxgps-spi PRIVATE USE_SPI) -sbs_target(test-ubloxgps-spi stm32f407vg_stm32f4discovery) +add_executable(test-ubxgps-spi src/tests/sensors/test-ubxgps-spi.cpp) +sbs_target(test-ubxgps-spi stm32f429zi_skyward_death_stack_x) add_executable(test-vn100 src/tests/sensors/test-vn100.cpp) sbs_target(test-vn100 stm32f407vg_stm32f4discovery) @@ -371,3 +376,6 @@ sbs_target(test-csvreader stm32f429zi_stm32f4discovery) add_executable(test-buttonhandler src/tests/utils/test-buttonhandler.cpp) sbs_target(test-buttonhandler stm32f429zi_stm32f4discovery) + +add_executable(test-syncpacketqueue src/tests/utils/test-syncpacketqueue.cpp) +sbs_target(test-syncpacketqueue stm32f407vg_stm32f4discovery) diff --git a/cmake/boardcore-host.cmake b/cmake/boardcore-host.cmake index 85d11ef2498c72e2528591aabf6a092ebb82b0af..355f4c9e69dca277517dd4a4bdc5cc401064433e 100644 --- a/cmake/boardcore-host.cmake +++ b/cmake/boardcore-host.cmake @@ -22,7 +22,7 @@ add_library(boardcore-host STATIC EXCLUDE_FROM_ALL # Debug ${SBS_BASE}/src/shared/utils/Debug.cpp - ${SBS_BASE}/src/shared/diagnostic/CpuMeter.cpp + ${SBS_BASE}/src/shared/diagnostic/CpuMeter/CpuMeter.cpp ${SBS_BASE}/src/shared/diagnostic/PrintLogger.cpp # Actuators diff --git a/cmake/boardcore.cmake b/cmake/boardcore.cmake index 7d521942145deac97f0c9b58b127de8b93b420e8..d5a2e222f0d41f5d77829b239bdccc3b0eb9a070 100644 --- a/cmake/boardcore.cmake +++ b/cmake/boardcore.cmake @@ -26,23 +26,28 @@ include(boardcore-host) foreach(OPT_BOARD ${BOARDS}) set(BOARDCORE_LIBRARY boardcore-${OPT_BOARD}) add_library(${BOARDCORE_LIBRARY} STATIC EXCLUDE_FROM_ALL + # Actuators ${SBS_BASE}/src/shared/actuators/HBridge/HBridge.cpp ${SBS_BASE}/src/shared/actuators/Servo/Servo.cpp - # Algorithms + ${SBS_BASE}/src/shared/algorithms/ADA/ADA.cpp + ${SBS_BASE}/src/shared/algorithms/AirBrakes/AirBrakes.cpp ${SBS_BASE}/src/shared/algorithms/NAS/NAS.cpp + ${SBS_BASE}/src/shared/algorithms/NAS/StateInitializer.cpp # Debug ${SBS_BASE}/src/shared/utils/Debug.cpp - ${SBS_BASE}/src/shared/diagnostic/CpuMeter.cpp + ${SBS_BASE}/src/shared/diagnostic/CpuMeter/CpuMeter.cpp ${SBS_BASE}/src/shared/diagnostic/PrintLogger.cpp # Drivers + ${SBS_BASE}/src/shared/drivers/adc/InternalTemp.cpp ${SBS_BASE}/src/shared/drivers/adc/InternalADC.cpp - ${SBS_BASE}/src/shared/drivers/canbus/Canbus.cpp - ${SBS_BASE}/src/shared/drivers/canbus/CanInterrupt.cpp + ${SBS_BASE}/src/shared/drivers/canbus/CanDriver/CanDriver.cpp + ${SBS_BASE}/src/shared/drivers/canbus/CanDriver/CanInterrupt.cpp + ${SBS_BASE}/src/shared/drivers/canbus/CanProtocol/CanProtocol.cpp ${SBS_BASE}/src/shared/drivers/i2c/stm32f2_f4_i2c.cpp ${SBS_BASE}/src/shared/drivers/interrupt/external_interrupts.cpp ${SBS_BASE}/src/shared/drivers/timer/PWM.cpp @@ -76,6 +81,8 @@ foreach(OPT_BOARD ${BOARDS}) ${SBS_BASE}/src/shared/sensors/BMX160/BMX160.cpp ${SBS_BASE}/src/shared/sensors/BMX160/BMX160WithCorrection.cpp ${SBS_BASE}/src/shared/sensors/HX711/HX711.cpp + ${SBS_BASE}/src/shared/sensors/LIS3MDL/LIS3MDL.cpp + ${SBS_BASE}/src/shared/sensors/LIS331HH/LIS331HH.cpp ${SBS_BASE}/src/shared/sensors/calibration/SensorDataExtra.cpp ${SBS_BASE}/src/shared/sensors/MAX6675/MAX6675.cpp ${SBS_BASE}/src/shared/sensors/MAX31855/MAX31855.cpp @@ -84,7 +91,8 @@ foreach(OPT_BOARD ${BOARDS}) ${SBS_BASE}/src/shared/sensors/MS5803/MS5803.cpp ${SBS_BASE}/src/shared/sensors/SensorManager.cpp ${SBS_BASE}/src/shared/sensors/SensorSampler.cpp - ${SBS_BASE}/src/shared/sensors/UbloxGPS/UbloxGPS.cpp + ${SBS_BASE}/src/shared/sensors/UBXGPS/UBXGPSSerial.cpp + ${SBS_BASE}/src/shared/sensors/UBXGPS/UBXGPSSpi.cpp ${SBS_BASE}/src/shared/sensors/VN100/VN100.cpp # Calibration @@ -93,6 +101,7 @@ foreach(OPT_BOARD ${BOARDS}) # Utils ${SBS_BASE}/src/shared/utils/AeroUtils/AeroUtils.cpp ${SBS_BASE}/src/shared/utils/ButtonHandler/ButtonHandler.cpp + ${SBS_BASE}/src/shared/utils/PinObserver/PinObserver.cpp ${SBS_BASE}/src/shared/utils/SkyQuaternion/SkyQuaternion.cpp ${SBS_BASE}/src/shared/utils/Stats/Stats.cpp ${SBS_BASE}/src/shared/utils/TestUtils/TestHelper.cpp diff --git a/libs/mavlink-skyward-lib b/libs/mavlink-skyward-lib index 94b57a3b5d5c200e69817066d69bc2e37cf963af..be1b8d4f61c546548d8b0c7d128dd304c9c49476 160000 --- a/libs/mavlink-skyward-lib +++ b/libs/mavlink-skyward-lib @@ -1 +1 @@ -Subproject commit 94b57a3b5d5c200e69817066d69bc2e37cf963af +Subproject commit be1b8d4f61c546548d8b0c7d128dd304c9c49476 diff --git a/libs/miosix-kernel b/libs/miosix-kernel index a4d47de3e79207aebb096cc8878e75af24905b07..fd9f506f11661d34b1e42a4af8b12d994fd1fa0e 160000 --- a/libs/miosix-kernel +++ b/libs/miosix-kernel @@ -1 +1 @@ -Subproject commit a4d47de3e79207aebb096cc8878e75af24905b07 +Subproject commit fd9f506f11661d34b1e42a4af8b12d994fd1fa0e diff --git a/libs/mxgui b/libs/mxgui index 0052374bc85c2bf90753faba61ecc08905658c83..537e0d172209024e6cfefbfeb4bf0a61bf8a09d1 160000 --- a/libs/mxgui +++ b/libs/mxgui @@ -1 +1 @@ -Subproject commit 0052374bc85c2bf90753faba61ecc08905658c83 +Subproject commit 537e0d172209024e6cfefbfeb4bf0a61bf8a09d1 diff --git a/scripts/generators/README.md b/scripts/generators/README.md index dfa4189d688093436b7c79293db6ad612aa7513a..a428a0ca26ac4a3e41c37291d33ccd8224219473 100644 --- a/scripts/generators/README.md +++ b/scripts/generators/README.md @@ -21,6 +21,7 @@ optional arguments: ## FSMGen The FSMGen program generates cpp files (`FSMController.h`, `FSMController.cpp`, `FSMData.h` and `test-FMS.cpp`) for each scxml file specified. +DO NOT USE FOR HSM ```shell usage: fsmgen.py [-h] [-q] [-a AUTHORS] [-n MAIN_NAMESPACE] [-f [F [F ...]]] [directory] diff --git a/src/entrypoints/bmx160-calibration-entry.cpp b/src/entrypoints/bmx160-calibration-entry.cpp index d2aa4746b97f41ee1b47c5306c6ea884f1f859ef..92153a60604522fc9ea1b5e99cbd469a489f8810 100644 --- a/src/entrypoints/bmx160-calibration-entry.cpp +++ b/src/entrypoints/bmx160-calibration-entry.cpp @@ -22,6 +22,7 @@ #include <drivers/interrupt/external_interrupts.h> #include <drivers/timer/TimestampTimer.h> +#include <scheduler/TaskScheduler.h> #include <sensors/BMX160/BMX160.h> #include <sensors/BMX160/BMX160WithCorrection.h> #include <sensors/calibration/AxisOrientation.h> @@ -31,8 +32,9 @@ #include <fstream> #include <iostream> -using namespace Boardcore; using namespace std; +using namespace miosix; +using namespace Boardcore; constexpr const char* CORRECTION_PARAMETER_FILE = "/sd/bmx160_params.csv"; constexpr const char* MAG_CALIBRATION_DATA_FILE = @@ -41,15 +43,13 @@ constexpr int ACC_CALIBRATION_SAMPLES = 200; constexpr int ACC_CALIBRATION_SLEEP_TIME = 25; // [us] constexpr int ACC_CALIBRATION_N_ORIENTATIONS = 6; -constexpr int MAG_CALIBRATION_SAMPLES = 500; -constexpr int MAG_CALIBRATION_DURATION = 60; // [s] -constexpr int MAG_CALIBRATION_SLEEP_TIME = - MAG_CALIBRATION_DURATION * 1000 / MAG_CALIBRATION_SAMPLES; // [us] +constexpr int MAG_CALIBRATION_DURATION = 10; // [s] +constexpr uint32_t MAG_CALIBRATION_SAMPLE_PERIOD = 20; // [ms] BMX160* bmx160; /** - * Orientations for accelerometer calibration + * @brief Orientations for accelerometer calibration. * * The BMX160 reference frame view facing the death stack x is: * z x @@ -77,22 +77,16 @@ constexpr const char* testHumanFriendlyDirection[]{ void __attribute__((used)) EXTI5_IRQHandlerImpl() { if (bmx160) - { - bmx160->IRQupdateTimestamp( - TimestampTimer::getInstance().getTimestamp()); - } + bmx160->IRQupdateTimestamp(TimestampTimer::getTimestamp()); } int menu(); -bool askToContinue(); void waitForInput(); BMX160CorrectionParameters calibrateAccelerometer( BMX160CorrectionParameters correctionParameters); BMX160CorrectionParameters calibrateMagnetometer( BMX160CorrectionParameters correctionParameters); -BMX160CorrectionParameters changeMinGyroCorrectionSamples( - BMX160CorrectionParameters correctionParameters); int main() { @@ -102,7 +96,7 @@ int main() // Greet the user printf("\nWelcome to the calibration procedure!\n"); - // Read the current correciton parameters + // Read the current correction parameters BMX160CorrectionParameters correctionParameters; correctionParameters = BMX160WithCorrection::readCorrectionParametersFromFile( @@ -117,10 +111,6 @@ int main() case 2: correctionParameters = calibrateMagnetometer(correctionParameters); break; - case 3: - correctionParameters = - changeMinGyroCorrectionSamples(correctionParameters); - break; default: break; @@ -144,23 +134,12 @@ int menu() printf("\nWhat do you want to do?\n"); printf("1. Calibrate accelerometer\n"); printf("2. Calibrate magnetometer\n"); - printf("3. Set minimum gyroscope samples for calibration\n"); printf("\n>> "); scanf("%d", &choice); return choice; } -bool askToContinue() -{ - string temp; - - cout << "Write 'c' to continue, otherwise stop:\n"; - getline(cin, temp); - - return temp != "c"; -} - void waitForInput() { string temp; @@ -244,10 +223,7 @@ BMX160CorrectionParameters calibrateAccelerometer( printf(" | % 2.5f % 2.5f % 2.5f |\n", 0.f, 0.f, correctionParameters.accelParams(2, 0)); - if (!askToContinue()) - { - return correctionParameters; - } + waitForInput(); printf( "Please note that the BMX axis, viewed facing the death stack x, " @@ -337,16 +313,18 @@ BMX160CorrectionParameters calibrateMagnetometer( SPIBus bus(SPI1); BMX160Config bmxConfig; - bmxConfig.fifoMode = BMX160Config::FifoMode::DISABLED; + bmxConfig.fifoMode = BMX160Config::FifoMode::HEADER; + bmxConfig.fifoWatermark = 20; + bmxConfig.fifoInterrupt = BMX160Config::FifoInterruptPin::PIN_INT1; bmxConfig.temperatureDivider = 0; bmxConfig.accelerometerRange = BMX160Config::AccelerometerRange::G_16; bmxConfig.gyroscopeRange = BMX160Config::GyroscopeRange::DEG_2000; - bmxConfig.accelerometerDataRate = BMX160Config::OutputDataRate::HZ_1600; - bmxConfig.gyroscopeDataRate = BMX160Config::OutputDataRate::HZ_1600; - bmxConfig.magnetometerRate = BMX160Config::OutputDataRate::HZ_50; + bmxConfig.accelerometerDataRate = BMX160Config::OutputDataRate::HZ_100; + bmxConfig.gyroscopeDataRate = BMX160Config::OutputDataRate::HZ_100; + bmxConfig.magnetometerRate = BMX160Config::OutputDataRate::HZ_100; bmxConfig.gyroscopeUnit = BMX160Config::GyroscopeMeasureUnit::RAD; @@ -372,16 +350,16 @@ BMX160CorrectionParameters calibrateMagnetometer( // Show the user the current correction values printf("Current bias vector\n"); - printf("b = [ % 2.5f % 2.5f % 2.5f ]\n\n", + printf("b = |% 2.5f % 2.5f % 2.5f|\n\n", correctionParameters.magnetoParams(0, 1), correctionParameters.magnetoParams(1, 1), correctionParameters.magnetoParams(2, 1)); printf("Matrix to be multiplied to the input vector\n"); - printf(" | % 2.5f % 2.5f % 2.5f |\n", + printf(" |% 2.5f % 2.5f % 2.5f|\n", correctionParameters.magnetoParams(0, 0), 0.f, 0.f); - printf("M = | % 2.5f % 2.5f % 2.5f |\n", 0.f, + printf("M = |% 2.5f % 2.5f % 2.5f|\n", 0.f, correctionParameters.magnetoParams(1, 0), 0.f); - printf(" | % 2.5f % 2.5f % 2.5f |\n", 0.f, 0.f, + printf(" |% 2.5f % 2.5f % 2.5f|\n", 0.f, 0.f, correctionParameters.magnetoParams(2, 0)); printf("Now I will calibrate the magnetometer\n"); @@ -392,56 +370,46 @@ BMX160CorrectionParameters calibrateMagnetometer( printf("The calibration will run for %d seconds\n", MAG_CALIBRATION_DURATION); - if (!askToContinue()) - { - return correctionParameters; - } + waitForInput(); - // Sample the sensor and feed the data to the calibration model - int count = 0; - while (count < MAG_CALIBRATION_SAMPLES) - { - bmx160->sample(); + printf("Calibration started, rotate the stack!\n"); - BMX160Data data = bmx160->getLastSample(); - calibrationModel->feed(data); - count++; + TaskScheduler scheduler; + scheduler.addTask( + [&]() + { + bmx160->sample(); - miosix::Thread::sleep(MAG_CALIBRATION_SLEEP_TIME); - } + uint8_t fifoSize = bmx160->getLastFifoSize(); + auto& fifo = bmx160->getLastFifo(); - printf("Computing the result...."); + for (uint8_t i = 0; i < fifoSize; i++) + { + Logger::getInstance().log(fifo.at(i)); + calibrationModel->feed(fifo.at(i)); + } + }, + 200); + Logger::getInstance().start(); + scheduler.start(); + + Thread::sleep(MAG_CALIBRATION_DURATION * 1000); + + scheduler.stop(); + Logger::getInstance().stop(); + + printf("Computing the result....\n"); auto corrector = calibrationModel->computeResult(); corrector >> m; corrector >> correctionParameters.magnetoParams; printf("b: the bias vector\n"); - printf("b = [ % 2.5f % 2.5f % 2.5f ]\n\n", m(0, 1), m(1, 1), - m(2, 1)); + printf("b = |% 2.5f % 2.5f % 2.5f|\n\n", m(0, 1), m(1, 1), m(2, 1)); printf("M: the matrix to be multiplied to the input vector\n"); - printf(" | % 2.5f % 2.5f % 2.5f |\n", m(0, 0), 0.f, 0.f); - printf("M = | % 2.5f % 2.5f % 2.5f |\n", 0.f, m(1, 0), 0.f); - printf(" | % 2.5f % 2.5f % 2.5f |\n", 0.f, 0.f, m(2, 0)); - - return correctionParameters; -} - -BMX160CorrectionParameters changeMinGyroCorrectionSamples( - BMX160CorrectionParameters correctionParameters) -{ - // Show the user the current parameter - printf( - "The current minimun number of gyroscope samples for calibration " - "is " - "%d\n", - correctionParameters.minGyroSamplesForCalibration); - - if (askToContinue()) - { - printf("Insert the new value: "); - scanf("%d", &correctionParameters.minGyroSamplesForCalibration); - } + printf(" |% 2.5f % 2.5f % 2.5f|\n", m(0, 0), 0.f, 0.f); + printf("M = |% 2.5f % 2.5f % 2.5f|\n", 0.f, m(1, 0), 0.f); + printf(" |% 2.5f % 2.5f % 2.5f|\n", 0.f, 0.f, m(2, 0)); return correctionParameters; } diff --git a/src/entrypoints/sdcard-benchmark.cpp b/src/entrypoints/sdcard-benchmark.cpp index 89aa596440629e7fca70113320d987ad15e63467..9a54a3a63869949c8b7b04e7e1b8a94697107256 100644 --- a/src/entrypoints/sdcard-benchmark.cpp +++ b/src/entrypoints/sdcard-benchmark.cpp @@ -1,5 +1,5 @@ -/* Copyright (c) 2018 Skyward Experimental Rocketry - * Author: Luca Erbetta +/* Copyright (c) 2018-2021 Skyward Experimental Rocketry + * Authors: Luca Erbetta, Alberto Nidasio * * Permission is hereby granted, free of charge, to any person obtaining a copy * of this software and associated documentation files (the "Software"), to deal @@ -20,121 +20,145 @@ * THE SOFTWARE. */ +#include <drivers/timer/TimestampTimer.h> +#include <miosix.h> +#include <stdint.h> +#include <utils/Stats/Stats.h> + #include <array> -// #include <chrono> #include <cstdio> #include <ctime> #include <iostream> -// #include <thread> -#include <miosix.h> -#include <utils/Stats/Stats.h> - #include <vector> using namespace Boardcore; using namespace miosix; using namespace std; -const unsigned int NUM_WRITES = 5000; +///< Number of writes to perform for each buffer size +const unsigned int NUM_WRITES = 1000; -vector<unsigned int> BUF_SIZES{128, 256, 512, 1024, 2048, 4096, 1024 * 8}; +vector<size_t> BUFFER_SIZES = {128, 256, 512, 1024, 2048, + 4096, 8192, 16348, 32768, 65536}; -// Fills a buffer with random bytes -void rndFill(uint8_t* buf, unsigned int size) +array<float, NUM_WRITES> data; + +/** + * @brief Fills a buffer with random bytes. + * + * @param buf Pointer to the buffer to fill. + * @param size Size of the buffer + */ +void rndFill(uint8_t* buf, size_t size); + +/** + * @brief Writes random bufferSize bytes on the SD card and measure the duration + * of each transaction. + * + * @param bufferSize Number of bytes to write. + * @param results Array where to store the duration measured for each write. + * @return True if no error encountered. + */ +bool benchmark(size_t bufferSize, array<float, NUM_WRITES>& results); + +/** + * @brief Prints the test results for the specified buffer size. + * + * @param bufferSize Buffer size of the benchmark. + * @param results Results form the benchmark. + */ +void printResults(size_t bufferSize, array<float, NUM_WRITES>& results); + +int main() { - for (unsigned int i = 0; i < size; i++) + srand(time(NULL)); + + for (size_t bufferSize : BUFFER_SIZES) { - *buf = rand() % 256; - ++buf; + if (benchmark(bufferSize, data)) + printResults(bufferSize, data); + else + printf("Error while performing the benchmark (buffer size: %lu)\n", + (unsigned long)bufferSize); } + + printf("Test completed\n"); + + while (true) + Thread::sleep(1000); } -bool benchmark(unsigned int buf_size, array<float, NUM_WRITES>& results) +void rndFill(uint8_t* buf, size_t size) { - bool success = false; + for (size_t i = 0; i < size; i++) + buf[i] = rand() % 256; +} - uint8_t* buf = new uint8_t[buf_size]; +bool benchmark(size_t bufferSize, array<float, NUM_WRITES>& results) +{ + uint8_t* buffer = new uint8_t[bufferSize]; - FILE* f = fopen("/sd/buf.dat", "w"); + FILE* file = fopen("/sd/buf.dat", "w"); - if (f == NULL) + if (file == nullptr) { printf("Error opening file!\n"); - goto clean; + // cppcheck-suppress nullPointerRedundantCheck + // cppcheck-suppress nullPointer + fclose(file); + // cppcheck-suppress uninitdata + delete[] buffer; + return false; } for (unsigned int i = 0; i < NUM_WRITES; i++) { - rndFill(buf, buf_size); - long long t = getTick(); - int w = fwrite(buf, 1, buf_size, f); - t = getTick() - t; + rndFill(buffer, bufferSize); - if (w != (int)buf_size) - { - printf("fwrite error: %d\n", ferror(f)); - goto clean; - } - results[i] = t; - } + // Time in microseconds (us) + uint64_t duration = TimestampTimer::getTimestamp(); - success = true; + size_t writeResult = fwrite(buffer, 1, bufferSize, file); -clean: - // Cleanup - fclose(f); - remove("buf.dat"); - delete[] buf; + duration = TimestampTimer::getTimestamp() - duration; - return success; -} + if (writeResult != bufferSize) + { + printf("fwrite error: %d\n", ferror(file)); + fclose(file); + delete[] buffer; + return false; + } -void printResults(unsigned int buf_size, array<float, NUM_WRITES>& results) -{ - Stats s; - for (float f : results) - { - s.add(f); + results[i] = duration; } - StatsResult res = s.getStats(); - - cout << "***BUF SIZE: " << buf_size << "\n"; - cout << "Times: \n"; - cout << "- mean: " << res.mean << " ms \n"; - cout << "- stddev: " << res.stdDev << " ms \n"; - cout << "- min: " << res.minValue << " ms \n"; - cout << "- max: " << res.maxValue << " ms \n"; - - cout << "Speeds: \n"; - cout << "- mean: " << buf_size / (res.mean * 1024) << " KiB/s \n"; - cout << "- min: " << buf_size / (res.maxValue * 1024) << " KiB/s \n"; - cout << "- max: " << buf_size / (res.minValue * 1024) << " KiB/s \n"; - cout << "\n\n"; + fclose(file); + delete[] buffer; + return true; } -array<float, NUM_WRITES> data; - -int main() +void printResults(size_t bufferSize, array<float, NUM_WRITES>& results) { - srand(time(NULL)); - - for (unsigned int s : BUF_SIZES) - { - if (benchmark(s, data)) - { - printResults(s, data); - } - else - { - cout << "Error (buf_size: " << s << ").\nAborting.\n"; - } - } - for (;;) - { - Thread::sleep(60000); - cout << "Aborted!\n"; - } - - return 0; + // Compute statistics on the benchmark results + Stats stats; + for (float result : results) + stats.add(result); + StatsResult statsResults = stats.getStats(); + + printf("\tBuffer size: %lu\n", (unsigned long)bufferSize); + printf("Times:\n"); + printf("- mean: % 6.1f us\n", statsResults.mean); + printf("- std dev: % 6.1f us\n", statsResults.stdDev); + printf("- min: % 6.1f us\n", statsResults.minValue); + printf("- max: % 6.1f us\n", statsResults.maxValue); + printf("Speeds:\n"); + printf("- mean: % 6.2fKiB/s\n", + bufferSize / (statsResults.mean / 1e6) / 1024); + printf("- min: % 6.2fKiB/s\n", + bufferSize / (statsResults.maxValue / 1e6) / 1024); + printf("- max: % 6.2fKiB/s\n", + bufferSize / (statsResults.minValue / 1e6) / 1024); + + printf("\n"); } diff --git a/src/shared/ActiveObject.h b/src/shared/ActiveObject.h index ddcb49f60d4bca82b2671d0fd498d013ab850709..c26c6b2d902308ebd9821ee895bc8137f7f133e8 100644 --- a/src/shared/ActiveObject.h +++ b/src/shared/ActiveObject.h @@ -49,7 +49,7 @@ public: virtual ~ActiveObject(){}; /** - * @brief Start the thread associated with this activeobject. + * @brief Start the thread associated with this active object. * * Call stop() to terminate execution of the thread. * @return true if the thread has been started. diff --git a/src/shared/actuators/Servo/Servo.cpp b/src/shared/actuators/Servo/Servo.cpp index ceffefd2963bda1cb9984ea73974b692d62df2ba..2cabb2505381e44168d7fe90c8346173e07f0cde 100644 --- a/src/shared/actuators/Servo/Servo.cpp +++ b/src/shared/actuators/Servo/Servo.cpp @@ -59,8 +59,16 @@ void Servo::disable() {} #endif -void Servo::setPosition(float position) +void Servo::setPosition(float position, bool limited) { + if (limited) + { + if (position < 0) + position = 0; + else if (position > 1) + position = 1; + } + float pulse = minPulse + (maxPulse - minPulse) * position; float dutyCycle = pulse * frequency / 1000000.0f; @@ -101,7 +109,7 @@ float Servo::getPosition360Deg() { return getPosition() * 3600; } ServoData Servo::getState() { - return {TimestampTimer::getInstance().getTimestamp(), + return {TimestampTimer::getTimestamp(), #ifndef COMPILE_FOR_HOST pwm.getTimer().getTimerNumber(), static_cast<uint8_t>(pwmChannel), diff --git a/src/shared/actuators/Servo/Servo.h b/src/shared/actuators/Servo/Servo.h index 2e0a511eb412e5a52f71a4399357d927ded90d62..e4a792cc1380044597d0da1a9c08f7f0c1a3fc76 100644 --- a/src/shared/actuators/Servo/Servo.h +++ b/src/shared/actuators/Servo/Servo.h @@ -98,7 +98,7 @@ public: * * @param position Position in range [0, 1]. */ - void setPosition(float position); + void setPosition(float position, bool limited = true); void setPosition90Deg(float degrees); diff --git a/src/shared/algorithms/ADA/ADA.cpp b/src/shared/algorithms/ADA/ADA.cpp new file mode 100644 index 0000000000000000000000000000000000000000..0b828756a82f859a5ebb3e4d4c983ae71aaed738 --- /dev/null +++ b/src/shared/algorithms/ADA/ADA.cpp @@ -0,0 +1,67 @@ +/* Copyright (c) 2018-2022 Skyward Experimental Rocketry + * Authors: Luca Mozzarelli, Luca Conterio, Alberto Nidasio + * + * 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. + */ + +#include "ADA.h" + +#include <drivers/timer/TimestampTimer.h> +#include <utils/AeroUtils/AeroUtils.h> + +namespace Boardcore +{ + +ADA::ADA(const ReferenceValues reference, + const KalmanFilter::KalmanConfig kalmanConfig) + : reference(reference), filter(kalmanConfig), state() +{ +} + +void ADA::update(const float pressure) +{ + const auto filterState = filter.getState(); + + // Update the Kalman filter + filter.predict(); + filter.correct(KalmanFilter::CVectorP{pressure}); + + // Convert filter data to altitudes and speeds + state.timestamp = TimestampTimer::getTimestamp(); + state.mslAltitude = Aeroutils::relAltitude(pressure, reference.pressure, + reference.temperature); + state.aglAltitude = state.mslAltitude - reference.altitude; + state.verticalSpeed = Aeroutils::verticalSpeed( + filterState(0), filterState(1), reference.mslPressure, + reference.mslTemperature); + state.x0 = filterState(0); + state.x1 = filterState(1); + state.x2 = filterState(2); +} + +ADAState ADA::getState() { return state; } + +void ADA::setReferenceValues(const ReferenceValues reference) +{ + this->reference = reference; +} + +ReferenceValues ADA::getReferenceValues() { return reference; } + +} // namespace Boardcore diff --git a/src/shared/algorithms/ADA/ADA.h b/src/shared/algorithms/ADA/ADA.h new file mode 100644 index 0000000000000000000000000000000000000000..1e0eb0f1d8329e5a4035c76375e610f97fd15dba --- /dev/null +++ b/src/shared/algorithms/ADA/ADA.h @@ -0,0 +1,71 @@ +/* Copyright (c) 2018-2022 Skyward Experimental Rocketry + * Authors: Luca Mozzarelli, Luca Conterio, Alberto Nidasio + * + * 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. + */ + +#pragma once + +#include <algorithms/Kalman/Kalman.h> +#include <algorithms/ReferenceValues.h> + +#include "ADAData.h" + +namespace Boardcore +{ + +class ADA +{ +public: + using KalmanFilter = Kalman<float, 3, 1>; + + ADA(const ReferenceValues reference, + const KalmanFilter::KalmanConfig kalmanConfig); + + /** + * @brief Update the Kalman filter. + * + * @param pressure Measured pressure [Pa]. + */ + void update(const float pressure); + + /** + * @param state ADA state with altitude and Kalman parameters. + */ + ADAState getState(); + + /** + * @brief Changes the reference values. + */ + void setReferenceValues(const ReferenceValues reference); + + /** + * @brief Returns the current reference values. + */ + ReferenceValues getReferenceValues(); + +private: + ReferenceValues reference; + + KalmanFilter filter; + + ADAState state; +}; + +} // namespace Boardcore diff --git a/src/shared/algorithms/ADA/ADAData.h b/src/shared/algorithms/ADA/ADAData.h new file mode 100644 index 0000000000000000000000000000000000000000..a00d7c4cfeebd6c4b7f9fcfda59f0a01c31023c3 --- /dev/null +++ b/src/shared/algorithms/ADA/ADAData.h @@ -0,0 +1,52 @@ +/* Copyright (c) 2018-2022 Skyward Experimental Rocketry + * Author: Luca Mozzarelli, Alberto Nidasio + * + * 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. + */ + +#pragma once + +#include <ostream> + +namespace Boardcore +{ + +struct ADAState +{ + uint64_t timestamp; + float mslAltitude; // Altitude at mean sea level [m]. + float aglAltitude; // Altitude above ground level [m]. + float verticalSpeed; // Vertical speed [m/s]. + float x0; + float x1; + float x2; + + static std::string header() + { + return "timestamp,mslAltitude,aglAltitude,verticalSpeed,x0,x1,x2\n"; + } + + void print(std::ostream& os) const + { + os << timestamp << "," << mslAltitude << "," << aglAltitude << "," + << verticalSpeed << "," << x0 << "," << x1 << "," << x2 << "\n"; + } +}; + +} // namespace Boardcore diff --git a/src/shared/algorithms/AirBrakes/AirBrakes.cpp b/src/shared/algorithms/AirBrakes/AirBrakes.cpp new file mode 100644 index 0000000000000000000000000000000000000000..896815cdba7893328e332a775c895c878602a4c2 --- /dev/null +++ b/src/shared/algorithms/AirBrakes/AirBrakes.cpp @@ -0,0 +1,239 @@ +/* Copyright (c) 2021-2022 Skyward Experimental Rocketry + * Author: Vincenzo Santomarco, Alberto Nidasio + * + * 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. + */ + +#include "AirBrakes.h" + +#include <logger/Logger.h> +#include <utils/Constants.h> + +#include <limits> + +namespace Boardcore +{ + +AirBrakes::AirBrakes(std::function<TimedTrajectoryPoint()> getCurrentPosition, + const TrajectorySet &trajectorySet, + const AirBrakesConfig &config, + std::function<void(float)> setActuator) + : getCurrentPosition(getCurrentPosition), trajectorySet(trajectorySet), + config(config), setActuator(setActuator), + pi(config.KP, config.KI, config.TS) +{ +} + +bool AirBrakes::init() { return true; } + +void AirBrakes::begin() +{ + if (running) + return; + + lastPosition = getCurrentPosition(); + chooseTrajectory(lastPosition); + + Algorithm::begin(); +} + +void AirBrakes::step() +{ + auto currentPosition = getCurrentPosition(); + + // Do nothing if we have no new data + if (lastPosition.timestamp >= currentPosition.timestamp) + return; + lastPosition = currentPosition; + + auto setPoint = getSetpoint(currentPosition); + float rho = getRho(currentPosition.z); + + float targetDrag = piStep(currentPosition, setPoint, rho); + float surface = getSurface(currentPosition, rho, targetDrag); + + setActuator(surface / config.SURFACE); +} + +void AirBrakes::chooseTrajectory(TrajectoryPoint currentPosition) +{ + float minDistance = std::numeric_limits<float>::infinity(); + uint8_t trjIndexMin = trajectorySet.length() / 2; + + for (uint8_t trjIndex = 0; trjIndex < trajectorySet.length(); trjIndex++) + { + Trajectory &trajectory = trajectorySet.trajectories[trjIndex]; + + for (uint32_t ptIndex = 0; ptIndex < trajectory.size(); ptIndex++) + { + TrajectoryPoint point = trajectory.points[ptIndex]; + float distance = + TrajectoryPoint::distanceSquared(point, currentPosition); + + if (distance < minDistance) + { + minDistance = distance; + trjIndexMin = trjIndex; + lastSelectedPointIndex = ptIndex; + chosenTrajectory = &trajectory; + } + } + } + + chosenTrajectory = &(trajectorySet.trajectories[trjIndexMin]); + + Logger::getInstance().log(AirBrakesChosenTrajectory{trjIndexMin}); +} + +TrajectoryPoint AirBrakes::getSetpoint(TrajectoryPoint currentPosition) +{ + if (chosenTrajectory == nullptr) + return {}; + + float minDistance = std::numeric_limits<float>::infinity(); + + uint32_t end = chosenTrajectory->size(); + for (uint32_t ptIndex = lastSelectedPointIndex; ptIndex < end; ptIndex++) + { + float distanceFromCurrentinput = TrajectoryPoint::distanceSquared( + chosenTrajectory->points[ptIndex], currentPosition); + + if (distanceFromCurrentinput < minDistance) + { + minDistance = distanceFromCurrentinput; + lastSelectedPointIndex = ptIndex; + } + } + + return chosenTrajectory->points[lastSelectedPointIndex]; +} + +float AirBrakes::getRho(float z) +{ + return Constants::RHO_0 * expf(-z / Constants::Hn); +} + +float AirBrakes::piStep(TimedTrajectoryPoint currentPosition, + TrajectoryPoint setPoint, float rho) +{ + const float cdMin = getCD(currentPosition, 0); + const float dragMin = getDrag(currentPosition, cdMin, rho); + + const float cdMax = getCD(currentPosition, config.EXTENSION); + const float dragMax = getDrag(currentPosition, cdMax, rho); + + // Get target surface percentage + const float cdRef = getCD(currentPosition, chosenTrajectory->extension); + const float dragRef = getDrag(currentPosition, cdRef, rho); + + // PI update + const float error = currentPosition.vz - setPoint.vz; + const float dragPi = + pi.antiWindUp(pi.update(error) + dragRef, dragMin, dragMax); + + return dragPi; +} + +float AirBrakes::getSurface(const TimedTrajectoryPoint ¤tPosition, + float rho, float targetDrag) +{ + float bestDDrag = std::numeric_limits<float>::infinity(); + float bestSurface = 0; + + // TODO: Drags are monotone, here the algorithm can be more efficient + for (uint8_t step = 0; step < config.DRAG_STEPS; step++) + { + float surface = (step / (config.DRAG_STEPS - 1)) * config.SURFACE; + + float extension = getExtension(surface); + float cd = getCD(currentPosition, extension); + float drag = getDrag(currentPosition, cd, rho); + float dDrag = abs(targetDrag - drag); + + if (dDrag < bestDDrag) + { + bestDDrag = dDrag; + bestSurface = surface; + } + } + + return bestSurface; +} + +float AirBrakes::getMach(TimedTrajectoryPoint currentPosition) +{ + return currentPosition.vMod / + (Constants::CO + Constants::ALPHA * currentPosition.z); +} + +float AirBrakes::getExtension(float surface) +{ + // clang-format off + return + config.EXT_POL_1 * powf(surface, 4) + + config.EXT_POL_2 * powf(surface, 3) + + config.EXT_POL_3 * powf(surface, 2) + + config.EXT_POL_4 * surface; + // clang-format on +} + +float AirBrakes::getCD(TimedTrajectoryPoint currentPosition, float extension) +{ + const float mach1 = currentPosition.getMac(); + const float mach2 = powf(mach1, 2); + const float mach3 = powf(mach1, 3); + const float mach4 = powf(mach1, 4); + const float mach5 = powf(mach1, 5); + const float mach6 = powf(mach1, 6); + + const float extension2 = powf(extension, 2); + + // clang-format off + return + config.N000 + + config.N100 * mach1 + + config.N200 * mach2 + + config.N300 * mach3 + + config.N400 * mach4 + + config.N500 * mach5 + + config.N600 * mach6 + + config.N010 * extension + + config.N020 * extension2 + + config.N110 * extension * mach1 + + config.N120 * extension2 * mach1 + + config.N210 * extension * mach2 + + config.N220 * extension2 * mach2 + + config.N310 * extension * mach3 + + config.N320 * extension2 * mach3 + + config.N410 * extension * mach4 + + config.N420 * extension2 * mach4 + + config.N510 * extension * mach5 + + config.N520 * extension2 * mach5 + + config.N001 * currentPosition.z; + // clang-format on +} + +float AirBrakes::getDrag(TimedTrajectoryPoint currentPosition, float cd, + float rho) +{ + return 0.5 * rho * config.S0 * cd * currentPosition.vz * + currentPosition.vMod; +} + +} // namespace Boardcore diff --git a/src/shared/algorithms/AirBrakes/AirBrakes.h b/src/shared/algorithms/AirBrakes/AirBrakes.h new file mode 100644 index 0000000000000000000000000000000000000000..9af39d4d26638dadceb5536b6026c9ff2414967c --- /dev/null +++ b/src/shared/algorithms/AirBrakes/AirBrakes.h @@ -0,0 +1,153 @@ +/* Copyright (c) 2021-2022 Skyward Experimental Rocketry + * Author: Vincenzo Santomarco, Alberto Nidasio + * + * 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. + */ + +#pragma once + +#include <actuators/Servo/Servo.h> +#include <algorithms/Algorithm.h> +#include <algorithms/PIController.h> + +#include <functional> +#include <vector> + +#include "AirBrakesConfig.h" +#include "AirBrakesData.h" +#include "TrajectorySet.h" + +namespace Boardcore +{ + +class AirBrakes : public Algorithm +{ +public: + AirBrakes(std::function<TimedTrajectoryPoint()> getCurrentPosition, + const TrajectorySet &trajectorySet, const AirBrakesConfig &config, + std::function<void(float)> setActuator); + + bool init() override; + + /** + * @brief This method chooses the trajectory the rocket will follow and + * starts the algorithm. + */ + void begin(); + + /** + * @brief Looks for nearest point in the current chosen trajectory and moves + * the airbraks according to the current rocket speed and the prediction. + */ + void step() override; + +private: + /** + * @brief Searched all the trajectories and find the neares point to the + * given position. The trajectory of this point is the one choosen. + */ + void chooseTrajectory(TrajectoryPoint currentPosition); + + /** + * @brief Searches, in the choosen trajectory, the point neares to the given + * one. This method considers the Euclidean distance between altitude and + * vertical speed. + */ + TrajectoryPoint getSetpoint(TrajectoryPoint currentPosition); + + /** + * @brief Returns the air density at the current altitude using the basic + * atmosphere model. + * + * @param z The current altitude [m]. + * @return The density of air according to current altitude [Kg/m^3] + */ + float getRho(float z); + + /** + * @brief Update PI to compute the target drag froce. + * + * @returns Target drag force to generate [N]. + */ + float piStep(TimedTrajectoryPoint currentPosition, + TrajectoryPoint reference, float rho); + + /** + * @brief Compute the necessary airbrakes surface to match the + * given drag force from the Pid as closely as possible. + * + * @param currentPosition Current rocket position. + * @param rho Air density [kg/m^2]. + * @param drag Target drag force. + * @return AirBrakes surface [m]; + */ + float getSurface(const TimedTrajectoryPoint ¤tPosition, float rho, + float drag); + + /** + * @brief Computes the speed in Mach unit for the given position. + * + * @return Mach speed [M]. + */ + float getMach(TimedTrajectoryPoint currentPosition); + + /** + * @brief Computes the airbrakes extension given the desired area. + * + * @param surface Desired airbrakes surface [m^2]. + * @return The radial extension [m]. + */ + float getExtension(float surface); + + /** + * @brief Returns the coefficient of drag for the airbrakes at the given + * position and with the given extension. + * + * @param currentPosition Current rocket position. + * @param extension AirBrakes extension [m]. + * @return The coefficient drag [1]. + */ + float getCD(TimedTrajectoryPoint currentPosition, float extension); + + /** + * @brief Return the drag generated from the AirBrakes in the given + * conditions. + * + * @param currentPosition Current position of the rocket. + * @param cd Coefficient of drag [1]. + * @param rho Air density [kg/m^2]. + * @return Generated drag [N]. + */ + float getDrag(TimedTrajectoryPoint currentPosition, float cd, float rho); + +private: + std::function<TimedTrajectoryPoint()> getCurrentPosition; + const TrajectorySet &trajectorySet; + const AirBrakesConfig &config; + std::function<void(float)> setActuator; + + TimedTrajectoryPoint lastPosition; + uint32_t lastSelectedPointIndex = 0; + + PIController pi; + + Trajectory *chosenTrajectory = nullptr; +}; + +} // namespace Boardcore diff --git a/src/shared/algorithms/AirBrakes/AirBrakesConfig.h b/src/shared/algorithms/AirBrakes/AirBrakesConfig.h new file mode 100644 index 0000000000000000000000000000000000000000..8294310a556dceaaef69f17e86bd056b5997e6e7 --- /dev/null +++ b/src/shared/algorithms/AirBrakes/AirBrakesConfig.h @@ -0,0 +1,69 @@ +/* Copyright (c) 2022 Skyward Experimental Rocketry + * Author: Alberto Nidasio + * + * 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. + */ + +#pragma once + +namespace Boardcore +{ + +struct AirBrakesConfig +{ + // Coefficient of drag coefficients. + float N000; + float N100; + float N200; + float N300; + float N400; + float N500; + float N600; + float N010; + float N020; + float N110; + float N120; + float N210; + float N220; + float N310; + float N320; + float N410; + float N420; + float N510; + float N520; + float N001; + + // Aibrakes extension. + float EXTENSION; ///< [m] + uint8_t DRAG_STEPS; + float EXT_POL_1; + float EXT_POL_2; + float EXT_POL_3; + float EXT_POL_4; + + float S0; ///< Rocket surface [m^2] + float SURFACE; ///< AirBrakes max surface [m^2] + + // PI parameters + float KP; + float KI; + float TS; +}; + +} // namespace Boardcore diff --git a/src/shared/algorithms/AirBrakes/AirBrakesData.h b/src/shared/algorithms/AirBrakes/AirBrakesData.h new file mode 100644 index 0000000000000000000000000000000000000000..1e9ee5c9f152a46731c4379c55d9f8c33e322cb8 --- /dev/null +++ b/src/shared/algorithms/AirBrakes/AirBrakesData.h @@ -0,0 +1,41 @@ +/* Copyright (c) 2021-2022 Skyward Experimental Rocketry + * Author: Vincenzo Santomarco, Alberto Nidasio + * + * 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. + */ + +#pragma once + +#include <stdint.h> + +#include <iostream> + +namespace Boardcore +{ + +struct AirBrakesChosenTrajectory +{ + uint8_t trajectory; + + static std::string header() { return "trajectory\n"; } + + void print(std::ostream& os) const { os << (int)trajectory << "\n"; } +}; + +} // namespace Boardcore diff --git a/src/shared/algorithms/AirBrakes/Trajectory.h b/src/shared/algorithms/AirBrakes/Trajectory.h new file mode 100644 index 0000000000000000000000000000000000000000..0f8d1774089ad6ca215bba360f633dc31deaab0e --- /dev/null +++ b/src/shared/algorithms/AirBrakes/Trajectory.h @@ -0,0 +1,45 @@ +/* Copyright (c) 2021-2022 Skyward Experimental Rocketry + * Author: Vincenzo Santomarco, Alberto Nidasio + * + * 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. + */ + +#pragma once + +#include "TrajectoryPoint.h" + +namespace Boardcore +{ + +class Trajectory +{ +public: + float extension; ///< AirBrakes target extension for this trajectory [m]. + TrajectoryPoint *points; + uint16_t trjSize; + + Trajectory(float extension, TrajectoryPoint points[], uint16_t trjSize) + : extension(extension), points(points), trjSize(trjSize) + { + } + + uint32_t size() { return trjSize; } +}; + +} // namespace Boardcore diff --git a/src/shared/algorithms/AirBrakes/TrajectoryPoint.h b/src/shared/algorithms/AirBrakes/TrajectoryPoint.h new file mode 100644 index 0000000000000000000000000000000000000000..da4adfb069e08f6d50691a1fd3e148f251ac3da1 --- /dev/null +++ b/src/shared/algorithms/AirBrakes/TrajectoryPoint.h @@ -0,0 +1,89 @@ +/* Copyright (c) 2021-2022 Skyward Experimental Rocketry + * Author: Vincenzo Santomarco, Alberto Nidasio + * + * 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. + */ + +#pragma once + +#include <algorithms/NAS/NASState.h> +#include <math.h> +#include <utils/Constants.h> + +#include <Eigen/Eigen> + +namespace Boardcore +{ + +class TrajectoryPoint +{ +public: + float z; ///< Vertical position [m]. + float vz; ///< Vertical velocity [m/s]. + + TrajectoryPoint() : TrajectoryPoint(0, 0) {} + + TrajectoryPoint(float z, float vz) : z(z), vz(vz) {} + + /** + * @brief Returns the distance squared between the two points. + */ + static float distanceSquared(TrajectoryPoint a, TrajectoryPoint b) + { + return powf(a.z - b.z, 2) + powf(a.vz - b.vz, 2); + } + + /** + * @brief Returns the distance in height between the two given points. + */ + static float zDistance(TrajectoryPoint a, TrajectoryPoint b) + { + return abs(a.z - b.z); + } + + /** + * @brief Returns the distance in vertical speed between the two points. + */ + static float vzDistance(TrajectoryPoint a, TrajectoryPoint b) + { + return abs(a.vz - b.vz); + } +}; + +/** + * @brief Trajectory point with timestamp and velocity module. + */ +class TimedTrajectoryPoint : public TrajectoryPoint +{ +public: + uint64_t timestamp; + float vMod; + + TimedTrajectoryPoint() : TrajectoryPoint(), timestamp(0), vMod(0) {} + + explicit TimedTrajectoryPoint(NASState state) + : TrajectoryPoint(-state.d, -state.vd), timestamp(state.timestamp), + vMod(Eigen::Vector3f{state.vn, state.ve, state.vd}.norm()) + { + } + + float getMac() { return vMod / (Constants::CO + Constants::ALPHA * z); } +}; + +} // namespace Boardcore diff --git a/src/shared/algorithms/AirBrakes/TrajectorySet.h b/src/shared/algorithms/AirBrakes/TrajectorySet.h new file mode 100644 index 0000000000000000000000000000000000000000..64075e6b7f16a6fa1f7667b680032df7fed9a85e --- /dev/null +++ b/src/shared/algorithms/AirBrakes/TrajectorySet.h @@ -0,0 +1,44 @@ +/* Copyright (c) 2021-2022 Skyward Experimental Rocketry + * Author: Vincenzo Santomarco, Alberto Nidasio + * + * 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. + */ + +#pragma once + +#include "Trajectory.h" + +namespace Boardcore +{ + +class TrajectorySet +{ +public: + Trajectory* trajectories; + uint16_t trjSize; + + TrajectorySet(Trajectory trajectories[], uint16_t trjSize) + : trajectories(trajectories), trjSize(trjSize) + { + } + + uint32_t length() const { return trjSize; } +}; + +} // namespace Boardcore diff --git a/src/shared/algorithms/Algorithm.h b/src/shared/algorithms/Algorithm.h index 56d31830cdc7218ecd795ab34e003e57261a13d8..441f9116a221724878630c89760dda8b2ef2c4f6 100644 --- a/src/shared/algorithms/Algorithm.h +++ b/src/shared/algorithms/Algorithm.h @@ -53,9 +53,7 @@ public: void update() { if (running) - { step(); - } } protected: diff --git a/src/shared/algorithms/Kalman/Kalman.h b/src/shared/algorithms/Kalman/Kalman.h index 204311d7532230955459247fcc4ece54e2777785..3488e295362507074be95b223243da2cacf0f56f 100644 --- a/src/shared/algorithms/Kalman/Kalman.h +++ b/src/shared/algorithms/Kalman/Kalman.h @@ -28,24 +28,22 @@ namespace Boardcore { /** - * @brief Class representing a Kalman filter using the Eigen library for - * matrix computations + * @brief Implementation of a generic Kalman filter using the Eigen library. * - * WARNING : This class uses templates in order to know the size of each matrix - * at compile-time. This way we avoid Eigen to allocate memory - * dynamically. + * This class uses templates in order to know the size of each matrix at + * compile-time. This way we avoid Eigen to allocate memory dynamically. */ -template <typename t, uint8_t n, uint8_t p> +template <typename T, int N_size, int P_size> class Kalman { - using MatrixNN = Eigen::Matrix<t, n, n>; - using MatrixPN = Eigen::Matrix<t, p, n>; - using MatrixNP = Eigen::Matrix<t, n, p>; - using MatrixPP = Eigen::Matrix<t, p, p>; - using CVectorN = Eigen::Matrix<t, n, 1>; - using CVectorP = Eigen::Matrix<t, p, 1>; - public: + using MatrixNN = Eigen::Matrix<T, N_size, N_size>; + using MatrixPN = Eigen::Matrix<T, P_size, N_size>; + using MatrixNP = Eigen::Matrix<T, N_size, P_size>; + using MatrixPP = Eigen::Matrix<T, P_size, P_size>; + using CVectorN = Eigen::Vector<T, N_size>; + using CVectorP = Eigen::Vector<T, P_size>; + /** * @brief Configuration struct for the Kalman class. */ @@ -60,52 +58,51 @@ public: }; /** - * @param config configuration object containing all the initialized - * matrices + * @brief Creates a Kalman filter object. + * + * @param config Configuration parameters. */ Kalman(const KalmanConfig& config) : F(config.F), H(config.H), Q(config.Q), R(config.R), P(config.P), - S(MatrixPP::Zero(p, p)), K(MatrixNP::Zero(n, p)), x(config.x) + S(MatrixPP::Zero(P_size, P_size)), K(MatrixNP::Zero(N_size, P_size)), + x(config.x) { I.setIdentity(); } /** - * @brief Prediction step. + * @brief Prediction step with previous F matrix. */ void predict() { - P = F * P * F.transpose() + Q; x = F * x; + P = F * P * F.transpose() + Q; } /** * @brief Prediction step. * - * @param F_new updated F matrix + * @param F_new updated F matrix. */ void predict(const MatrixNN& F_new) { - this->F = F_new; - this->predict(); + F = F_new; + predict(); } /** - * @brief Correction step (correct the estimate). + * @brief Correction step. * - * @param y The measurement vector + * @param y The measurement vector. */ bool correct(const CVectorP& y) { S = H * P * H.transpose() + R; - // here the determinant is computed and - // then the inverse recomputes it, - // this passage could be optimized + // TODO: The determinant is computed here and when S is inverted, it + // could be optimized if (S.determinant() < 1e-3) - { return false; - } K = P * H.transpose() * S.inverse(); P = (I - K * H) * P; @@ -137,24 +134,23 @@ public: const CVectorP getResidual() { return res; } /** - * @brief Predicts k steps ahead the output - */ - const CVectorP predictOutput(uint32_t k) { return H * predictState(k); } - - /** - * @brief Predicts k steps ahead the state + * @brief Predicts k steps ahead the state. */ const CVectorN predictState(uint32_t k) { CVectorN xHat = x; for (uint32_t i = 0; i < k; i++) - { xHat = F * xHat; - } + return xHat; } + /** + * @brief Predicts k steps ahead the output. + */ + const CVectorP predictOutput(uint32_t k) { return H * predictState(k); } + private: MatrixNN F; /**< State propagation matrix (n x n) */ MatrixPN H; /**< Output matrix (p x n) */ diff --git a/src/shared/algorithms/NAS/NAS.cpp b/src/shared/algorithms/NAS/NAS.cpp index 1296b639b48483d3a0309d5136e77c5a97c5fc7e..464ce4c41a69b9365e51cd087598f7d46588446e 100644 --- a/src/shared/algorithms/NAS/NAS.cpp +++ b/src/shared/algorithms/NAS/NAS.cpp @@ -1,4 +1,4 @@ -/* Copyright (c) 2020 Skyward Experimental Rocketry +/* Copyright (c) 2020-2022 Skyward Experimental Rocketry * Authors: Alessandro Del Duca, Luca Conterio, Marco Cella * * Permission is hereby granted, free of charge, to any person obtaining a copy @@ -100,7 +100,7 @@ NAS::NAS(NASConfig config) : config(config) void NAS::predictAcc(const Vector3f& acceleration) { - Matrix3f A = body2ned(x.block<4, 1>(IDX_QUAT, 0)); + Matrix3f A = SkyQuaternion::quat2rotationMatrix(x.block<4, 1>(IDX_QUAT, 0)); Vector3f pos = x.block<3, 1>(IDX_POS, 0); Vector3f vel = x.block<3, 1>(IDX_VEL, 0); @@ -122,6 +122,12 @@ void NAS::predictAcc(const Vector3f& acceleration) P.block<6, 6>(0, 0) = F_lin * Pl * F_lin_tr + Q_lin; } +void NAS::predictAcc(const AccelerometerData& acceleration) +{ + predictAcc(Vector3f{acceleration.accelerationX, acceleration.accelerationY, + acceleration.accelerationZ}); +} + void NAS::predictGyro(const Vector3f& angularVelocity) { Vector3f bias = x.block<3, 1>(IDX_BIAS, 0); @@ -151,17 +157,23 @@ void NAS::predictGyro(const Vector3f& angularVelocity) P.block<6, 6>(IDX_QUAT, IDX_QUAT) = Pq; } -void NAS::correctBaro(const float pressure, const float mslPress, - const float mslTemp) +void NAS::predictGyro(const GyroscopeData& angularVelocity) +{ + predictGyro(Vector3f{angularVelocity.angularVelocityX, + angularVelocity.angularVelocityY, + angularVelocity.angularVelocityZ}); +} + +void NAS::correctBaro(const float pressure) { Matrix<float, 1, 6> H = Matrix<float, 1, 6>::Zero(); // Temperature at current altitude. Since in NED the altitude is negative, // mslTemperature returns temperature at current altitude and not at msl - float temp = Aeroutils::mslTemperature(mslTemp, x(2)); + float temp = Aeroutils::mslTemperature(reference.mslTemperature, x(2)); // Compute gradient of the altitude-pressure function - H[2] = Constants::a * Constants::n * mslPress * + H[2] = Constants::a * Constants::n * reference.mslPressure * powf(1 - Constants::a * x(2) / temp, -Constants::n - 1) / temp; Eigen::Matrix<float, 6, 6> Pl = P.block<6, 6>(0, 0); @@ -170,7 +182,8 @@ void NAS::correctBaro(const float pressure, const float mslPress, Matrix<float, 6, 1> K = Pl * H.transpose() * S.inverse(); P.block<6, 6>(0, 0) = (Matrix<float, 6, 6>::Identity() - K * H) * Pl; - float y_hat = Aeroutils::mslPressure(mslPress, mslTemp, x(2)); + float y_hat = Aeroutils::mslPressure(reference.mslPressure, + reference.mslTemperature, x(2)); // Update the state x.head<6>() = x.head<6>() + K * (pressure - y_hat); @@ -193,10 +206,23 @@ void NAS::correctGPS(const Vector4f& gps) x.head<6>() = x.head<6>() + K * (gps - H); } +void NAS::correctGPS(const GPSData& gps) +{ + if (!gps.fix) + return; + + auto gpsPos = Aeroutils::geodetic2NED( + {gps.latitude, gps.longitude}, + {reference.startLatitude, reference.startLongitude}); + + correctGPS( + Vector4f{gpsPos(0), gpsPos(1), gps.velocityNorth, gps.velocityEast}); +} + void NAS::correctMag(const Vector3f& mag) { Vector4f q = x.block<4, 1>(IDX_QUAT, 0); - Matrix3f A = body2ned(q).transpose(); + Matrix3f A = SkyQuaternion::quat2rotationMatrix(q).transpose(); // Rotate the NED magnetic field in the relative reference frame Vector3f mEst = A * config.NED_MAG; @@ -226,10 +252,17 @@ void NAS::correctMag(const Vector3f& mag) P.block<6, 6>(IDX_QUAT, IDX_QUAT) = Pq; } +void NAS::correctMag(const MagnetometerData& mag) +{ + Vector3f magV = {mag.magneticFieldX, mag.magneticFieldY, + mag.magneticFieldZ}; + correctMag(magV.normalized()); +} + void NAS::correctAcc(const Eigen::Vector3f& acc) { Vector4f q = x.block<4, 1>(IDX_QUAT, 0); - Matrix3f A = body2ned(q).transpose(); + Matrix3f A = SkyQuaternion::quat2rotationMatrix(q).transpose(); // Rotate the NED magnetic field in the relative reference frame Vector3f aEst = A * gravityNed; @@ -264,6 +297,12 @@ void NAS::correctAcc(const Eigen::Vector3f& acc) P.block<6, 6>(IDX_QUAT, IDX_QUAT) = Pq; } +void NAS::correctAcc(const AccelerometerData& acc) +{ + Vector3f accV = {acc.accelerationX, acc.accelerationY, acc.accelerationZ}; + correctAcc(accV.normalized()); +} + void NAS::correctPitot(const float deltaP, const float staticP) { if (deltaP >= 0) @@ -303,7 +342,7 @@ void NAS::correctPitot(const float deltaP, const float staticP) NASState NAS::getState() const { - return NASState(TimestampTimer::getInstance().getTimestamp(), x); + return NASState(TimestampTimer::getTimestamp(), x); } Eigen::Matrix<float, 13, 1> NAS::getX() const { return x; } @@ -312,27 +351,11 @@ void NAS::setState(const NASState& state) { this->x = state.getX(); } void NAS::setX(const Eigen::Matrix<float, 13, 1>& x) { this->x = x; } -Matrix3f NAS::body2ned(const Vector4f& q) +void NAS::setReferenceValues(const ReferenceValues reference) { - // clang-format off - return Matrix3f{ - { - q[0] * q[0] - q[1] * q[1] - q[2] * q[2] + q[3] * q[3], - 2.0f * (q[0] * q[1] - q[2] * q[3]), - 2.0f * (q[0] * q[2] + q[1] * q[3]), - }, - { - 2.0f * (q[0] * q[1] + q[2] * q[3]), - - q[0] * q[0] + q[1] * q[1] - q[2] * q[2] + q[3] * q[3], - 2.0f * (q[1] * q[2] - q[0] * q[3]), - }, - { - 2.0f * (q[0] * q[2] - q[1] * q[3]), - 2.0f * (q[1] * q[2] + q[0] * q[3]), - - q[0] * q[0] - q[1] * q[1] + q[2] * q[2] + q[3] * q[3] - } - }; - // clang-format on + this->reference = reference; } +ReferenceValues NAS::getReferenceValues() { return reference; } + } // namespace Boardcore diff --git a/src/shared/algorithms/NAS/NAS.h b/src/shared/algorithms/NAS/NAS.h index d232f4beb6f6951c1d8ecded27b3aea6c2c9a77f..c515ea41c741736c9b975d3cf686596db567cadd 100644 --- a/src/shared/algorithms/NAS/NAS.h +++ b/src/shared/algorithms/NAS/NAS.h @@ -22,6 +22,8 @@ #pragma once +#include <algorithms/ReferenceValues.h> +#include <sensors/SensorData.h> #include <utils/AeroUtils/AeroUtils.h> #include <utils/Constants.h> @@ -53,56 +55,87 @@ public: /** * @brief Prediction with accelerometer data. * - * @param u Vector with acceleration data [x y z][m/s^2] + * @param acceleration Vector with acceleration data [x y z][m/s^2]. */ void predictAcc(const Eigen::Vector3f& acceleration); + /** + * @brief Prediction with accelerometer data. + * + * @param acceleration Accelerometer data [m/s^2]. + */ + void predictAcc(const AccelerometerData& acceleration); + /** * @brief Prediction with gyroscope data. * - * @param u Vector with angular velocity data [x y z] + * @param angularVelocity Vector with angular velocity data [x y z][rad/s]. */ void predictGyro(const Eigen::Vector3f& angularVelocity); + /** + * @brief Prediction with gyroscope data. + * + * @param angularVelocity Gyroscope data [rad/s]. + */ + void predictGyro(const GyroscopeData& angularVelocity); + /** * @brief Correction with barometer data. * - * @param pressure Pressure read from the barometer [Pa] - * @param mslPress Pressure at sea level [Pa] - * @param mslTemp Temperature at sea level [Kelvin] + * @param pressure Pressure read from the barometer [Pa]. */ - void correctBaro(const float pressure, const float mslPress, - const float mslTemp); + void correctBaro(const float pressure); /** * @brief Correction with gps data. * - * @param gps Vector of the gps readings [n e vn ve][m m m/s m/s] - * @param sats_num Number of satellites available + * @param gps Vector of the gps readings [n e vn ve][m m m/s m/s]. */ void correctGPS(const Eigen::Vector4f& gps); + /** + * @brief Correction with gps data only if fix is acquired. + * + * @param gps GPS data. + */ + void correctGPS(const GPSData& gps); + /** * @brief Correction with magnetometer data. * - * @param mag Normalized vector of the magnetometer readings [x y z] + * @param mag Normalized vector of the magnetometer readings [x y z][uT]. */ void correctMag(const Eigen::Vector3f& mag); + /** + * @brief Correction with magnetometer data. + * + * @param mag Magnetometer data [uT]. + */ + void correctMag(const MagnetometerData& mag); + + /** + * @brief Correction with accelerometer data. + * + * @param u Normalized vector with acceleration data [x y z][m/s^2]. + */ + void correctAcc(const Eigen::Vector3f& acc); + /** * @brief Correction with accelerometer data. * - * @param u Normaliezed vector with acceleration data [x y z] + * @param u Acceleration data [m/s^2]. */ - void correctAcc(const Eigen::Vector3f& acceleration); + void correctAcc(const AccelerometerData& acc); /** * @brief Correction with pitot pressure. * * Do not call this function after apogee! * - * @param deltaP Delta pressure measured by the differential sensor [Pa] - * @param staticP Static pressure [Pa] + * @param deltaP Delta pressure measured by the differential sensor [Pa]. + * @param staticP Static pressure [Pa]. */ void correctPitot(const float deltaP, const float staticP); @@ -126,25 +159,31 @@ public: */ void setX(const Eigen::Matrix<float, 13, 1>& x); -private: /** - * @brief Return a rotation matrix from body from to NED frame; - * - * TODO: Move to SkyQuaternion utilities + * @brief Changes the reference values. */ - Eigen::Matrix3f body2ned(const Eigen::Vector4f& q); + void setReferenceValues(const ReferenceValues reference); - ///< Extended Kalman filter configuration parameters + /** + * @brief Returns the current reference values. + */ + ReferenceValues getReferenceValues(); + +private: + ///< Extended Kalman filter configuration parameters. NASConfig config; - ///< State vector [n e d vn ve vd qx qy qz qw bx by bz] + ///< Reference values used for altitude and gps position. + ReferenceValues reference; + + ///< State vector [n e d vn ve vd qx qy qz qw bx by bz]. Eigen::Matrix<float, 13, 1> x; - ///< Covariance matrix + ///< Covariance matrix. Eigen::Matrix<float, 12, 12> P; - ///< NED gravity vector [m/s^2] - Eigen::Vector3f gravityNed{0.0f, 0.0f, -Constants::g}; + ///< NED gravity vector [m/s^2]. + const Eigen::Vector3f gravityNed{0.0f, 0.0f, -Constants::g}; // Utility matrixes used for the gps Eigen::Matrix<float, 4, 6> H_gps; diff --git a/src/shared/algorithms/NAS/NASConfig.h b/src/shared/algorithms/NAS/NASConfig.h index b73b2f8f8b3bdf6a5eb1d48194d81f9a8ad0ad75..289be22616cd5a6562bccdf36856dd415a1f0e38 100644 --- a/src/shared/algorithms/NAS/NASConfig.h +++ b/src/shared/algorithms/NAS/NASConfig.h @@ -39,11 +39,11 @@ struct NASConfig float SIGMA_VEL; ///< [(m/s)^2] Estimated variance of the velocity noise float SIGMA_PITOT; ///< [Pa^2] Estimated variance of the pitot velocity - float P_POS; ///< Position prediction covariance - float P_POS_VERTICAL; + float P_POS; ///< Position prediction covariance horizontal + float P_POS_VERTICAL; ///< Position prediction covariance vertical - float P_VEL; ///< Velocity prediction covariance - float P_VEL_VERTICAL; + float P_VEL; ///< Velocity prediction covariance horizontal + float P_VEL_VERTICAL; ///< Velocity prediction covariance vertical float P_ATT; ///< Attitude prediction covariance float P_BIAS; ///< Bias prediction covariance diff --git a/src/shared/algorithms/NAS/StateInitializer.cpp b/src/shared/algorithms/NAS/StateInitializer.cpp new file mode 100644 index 0000000000000000000000000000000000000000..d1c590432ee91a55f632725f838c8cae3d048693 --- /dev/null +++ b/src/shared/algorithms/NAS/StateInitializer.cpp @@ -0,0 +1,97 @@ +/* Copyright (c) 2022 Skyward Experimental Rocketry + * Authors: Marco Cella, Alberto Nidasio + * + * 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. + */ + +#include "StateInitializer.h" + +namespace Boardcore +{ +StateInitializer::StateInitializer() { x_init << Eigen::MatrixXf::Zero(13, 1); } + +void StateInitializer::eCompass(const Eigen::Vector3f acc, + const Eigen::Vector3f mag) +{ + // ndr: since this method runs only when the rocket is stationary, there's + // no need to add the gravity vector because the accelerometers already + // measure it. This is not true if we consider the flying rocket. + + Eigen::Vector3f am(acc.cross(mag)); + + Eigen::Matrix3f R; + // cppcheck-suppress constStatement + R << am.cross(acc), am, acc; + R.col(0).normalize(); + R.col(1).normalize(); + R.col(2).normalize(); + + Eigen::Vector4f x_quat = SkyQuaternion::rotationMatrix2quat(R); + + x_init(NAS::IDX_QUAT) = x_quat(0); + x_init(NAS::IDX_QUAT + 1) = x_quat(1); + x_init(NAS::IDX_QUAT + 2) = x_quat(2); + x_init(NAS::IDX_QUAT + 3) = x_quat(3); +} + +void StateInitializer::triad(Eigen::Vector3f& acc, Eigen::Vector3f& mag, + Eigen::Vector3f& nedMag) +{ + // The gravity vector is expected to be read inversely because + // accelerometers read the binding reaction + Eigen::Vector3f nedAcc(0.0f, 0.0f, -1.0f); + + // Compute the reference triad + Eigen::Vector3f R1 = nedAcc; + Eigen::Vector3f R2 = nedAcc.cross(nedMag).normalized(); + Eigen::Vector3f R3 = R1.cross(R2); + + // Compute the measured triad + Eigen::Vector3f r1 = acc; + Eigen::Vector3f r2 = acc.cross(mag).normalized(); + Eigen::Vector3f r3 = r1.cross(r2); + + // Compose the reference and measured matrixes + Eigen::Matrix3f M; + // cppcheck-suppress constStatement + M << R1, R2, R3; + Eigen::Matrix3f m; + // cppcheck-suppress constStatement + m << r1, r2, r3; + + // Compute the rotation matrix and the corresponding quaternion + Eigen::Matrix3f A = M * m.transpose(); + Eigen::Vector4f q = SkyQuaternion::rotationMatrix2quat(A); + + // Save the orientation in the state + x_init.block<4, 1>(NAS::IDX_QUAT, 0) = q; +} + +void StateInitializer::positionInit(const float pressure, + const float pressureRef, + const float temperatureRef) +{ + x_init(0) = 0.0; + x_init(1) = 0.0; + // msl altitude (in NED, so negative) + x_init(2) = -Aeroutils::relAltitude(pressure, pressureRef, temperatureRef); +} + +Eigen::Matrix<float, 13, 1> StateInitializer::getInitX() { return x_init; } +} // namespace Boardcore diff --git a/src/shared/algorithms/NAS/StateInitializer.h b/src/shared/algorithms/NAS/StateInitializer.h index 959597beb70db8e4b2133eacf12df22d90f10add..8b72cad89b4300e623a849bae9a0d6e29d8d5b5e 100644 --- a/src/shared/algorithms/NAS/StateInitializer.h +++ b/src/shared/algorithms/NAS/StateInitializer.h @@ -97,73 +97,4 @@ private: PrintLogger log = Logging::getLogger("initstates"); }; - -StateInitializer::StateInitializer() { x_init << Eigen::MatrixXf::Zero(13, 1); } - -void StateInitializer::eCompass(const Eigen::Vector3f acc, - const Eigen::Vector3f mag) -{ - // ndr: since this method runs only when the rocket is stationary, there's - // no need to add the gravity vector because the accelerometers already - // measure it. This is not true if we consider the flying rocket. - - Eigen::Vector3f am(acc.cross(mag)); - - Eigen::Matrix3f R; - R << am.cross(acc), am, acc; - R.col(0).normalize(); - R.col(1).normalize(); - R.col(2).normalize(); - - Eigen::Vector4f x_quat = SkyQuaternion::rotationMatrix2quat(R); - - x_init(NAS::IDX_QUAT) = x_quat(0); - x_init(NAS::IDX_QUAT + 1) = x_quat(1); - x_init(NAS::IDX_QUAT + 2) = x_quat(2); - x_init(NAS::IDX_QUAT + 3) = x_quat(3); -} - -void StateInitializer::triad(Eigen::Vector3f& acc, Eigen::Vector3f& mag, - Eigen::Vector3f& nedMag) -{ - // The gravity vector is expected to be read inversely because - // accelerometers read the binding reaction - Eigen::Vector3f nedAcc(0.0f, 0.0f, -1.0f); - - // Compute the reference triad - Eigen::Vector3f R1 = nedAcc; - Eigen::Vector3f R2 = nedAcc.cross(nedMag).normalized(); - Eigen::Vector3f R3 = R1.cross(R2); - - // Compute the measured triad - Eigen::Vector3f r1 = acc; - Eigen::Vector3f r2 = acc.cross(mag).normalized(); - Eigen::Vector3f r3 = r1.cross(r2); - - // Compose the reference and measured matrixes - Eigen::Matrix3f M; - M << R1, R2, R3; - Eigen::Matrix3f m; - m << r1, r2, r3; - - // Compute the rotation matrix and the corresponding quaternion - Eigen::Matrix3f A = M * m.transpose(); - Eigen::Vector4f q = SkyQuaternion::rotationMatrix2quat(A); - - // Save the orientation in the state - x_init.block<4, 1>(NAS::IDX_QUAT, 0) = q; -} - -void StateInitializer::positionInit(const float pressure, - const float pressureRef, - const float temperatureRef) -{ - x_init(0) = 0.0; - x_init(1) = 0.0; - // msl altitude (in NED, so negative) - x_init(2) = -Aeroutils::relAltitude(pressure, pressureRef, temperatureRef); -} - -Eigen::Matrix<float, 13, 1> StateInitializer::getInitX() { return x_init; } - } // namespace Boardcore diff --git a/src/shared/algorithms/PID.h b/src/shared/algorithms/PIController.h similarity index 71% rename from src/shared/algorithms/PID.h rename to src/shared/algorithms/PIController.h index 5f460f4381ee7e9e9e9aa16886dda6850ca620b6..c30e3e4099eeb9bf3b0bb55400e91cf394f34dd2 100644 --- a/src/shared/algorithms/PID.h +++ b/src/shared/algorithms/PIController.h @@ -34,9 +34,9 @@ class PIController { public: - PIController(double Kp, double Ki, double Ts = 1, - double uMin = -std::numeric_limits<double>::infinity(), - double uMax = std::numeric_limits<double>::infinity()) + PIController(float Kp, float Ki, float Ts = 1, + float uMin = -std::numeric_limits<float>::infinity(), + float uMax = std::numeric_limits<float>::infinity()) : Kp(Kp), Ki(Ki), Ts(Ts), uMin(uMin), uMax(uMax) { } @@ -44,26 +44,23 @@ public: /** * @brief Update the PI internal state. * */ - double update(double error) + float update(float error) { - - lastP = Kp * error; - if (!saturation) - { i = i + Ki * Ts * error; - } - double u = lastP + i; + float u = Kp * error + i; lastOutput = antiWindUp(u); return lastOutput; } + float antiWindUp(float u) { return antiWindUp(u, uMin, uMax); } + /** * @brief Anti-windup mechanism. */ - double antiWindUp(double u) + float antiWindUp(float u, float uMin, float uMax) { if (u < uMin) { @@ -83,23 +80,20 @@ public: return u; } - double getI() { return i; } - - double getLastP() { return lastP; } + float getI() { return i; } - double getLastOutput() { return lastOutput; } + float getLastOutput() { return lastOutput; } bool isSaturated() { return saturation; } - double Kp; // Proportional factor. - double Ki; // Integral factor. - double Ts; // Sampling period. - double uMin, uMax; // Anti-windup limits. + float Kp; // Proportional factor. + float Ki; // Integral factor. + float Ts; // Sampling period. + float uMin, uMax; // Anti-windup limits. private: - double i = 0; // Integral contribution. - double lastP = 0; // Last computer proportional contribution. - double lastOutput; // Last computed controller output. + float i = 0; // Integral contribution. + float lastOutput; // Last computed controller output. bool saturation = false; }; diff --git a/src/shared/algorithms/ReferenceValues.h b/src/shared/algorithms/ReferenceValues.h new file mode 100644 index 0000000000000000000000000000000000000000..fcd4de5df92ae22adb817d1938c8464fdbf89147 --- /dev/null +++ b/src/shared/algorithms/ReferenceValues.h @@ -0,0 +1,93 @@ +/* Copyright (c) 2018-2021 Skyward Experimental Rocketry + * Authors: Luca Mozzarelli, Luca Conterio, Alberto Nidasio + * + * 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. + */ + +#pragma once + +#include <utils/Constants.h> + +#include <Eigen/Eigen> +#include <ostream> + +namespace Boardcore +{ + +/** + * @brief Reference values for the Apogee Detection Algorithm. + */ +struct ReferenceValues +{ + // Launch site parameters + float altitude; + float pressure; + float temperature; + + // Start position + float startLatitude; + float startLongitude; + + // Pressure and temperature at mean sea level for altitude calculation + float mslPressure = Constants::MSL_PRESSURE; + float mslTemperature = Constants::MSL_TEMPERATURE; + + ReferenceValues(){}; + + ReferenceValues(float altitude, float pressure, float temperature, + float startLatitude = Constants::B21_LATITUDE, + float startLongitude = Constants::B21_LONGITUDE, + float mslPressure = Constants::MSL_PRESSURE, + float mslTemperature = Constants::MSL_TEMPERATURE) + : altitude(altitude), pressure(pressure), temperature(temperature), + startLatitude(startLatitude), startLongitude(startLongitude), + mslPressure(mslPressure), mslTemperature(mslTemperature) + { + } + + static std::string header() + { + return "altitude,pressure,temperature,startLatitude,startLongitude," + "mslPressure,mslTemperature\n"; + } + + void print(std::ostream& os) const + { + os << altitude << "," << pressure << "," << temperature << "," + << startLatitude << "," << startLongitude << "," << mslPressure + << "," << mslTemperature << "\n"; + } + + bool operator==(const ReferenceValues& other) const + { + return altitude == other.altitude && pressure == other.pressure && + temperature == other.temperature && + startLatitude == other.startLatitude && + startLongitude == other.startLongitude && + mslPressure == other.mslPressure && + mslTemperature == other.mslTemperature; + } + + bool operator!=(const ReferenceValues& other) const + { + return !(*this == other); + } +}; + +} // namespace Boardcore diff --git a/src/shared/diagnostic/CpuMeter.cpp b/src/shared/diagnostic/CpuMeter/CpuMeter.cpp similarity index 73% rename from src/shared/diagnostic/CpuMeter.cpp rename to src/shared/diagnostic/CpuMeter/CpuMeter.cpp index e9c5bfcf2791535e95aaf0299bfcf334aa749a45..57990c49ff064d0d5ae08ddf6c703c0c1e87a2c9 100644 --- a/src/shared/diagnostic/CpuMeter.cpp +++ b/src/shared/diagnostic/CpuMeter/CpuMeter.cpp @@ -24,20 +24,35 @@ #include <diagnostic/SkywardStack.h> #include <diagnostic/StackLogger.h> +#include <drivers/timer/TimestampTimer.h> using namespace miosix; namespace Boardcore { +namespace CpuMeter +{ + const int period = 100; const int gap = 100; const int watchdogPeriod = 20 * period; -static volatile float utilization = 0.f; +static FastMutex utilizationMutex; +static Stats utilization; static volatile unsigned int update = 0; -float averageCpuUtilization() { return utilization; } +CpuMeterData getCpuStats() +{ + Lock<FastMutex> l(utilizationMutex); + return CpuMeterData(TimestampTimer::getTimestamp(), utilization.getStats(), + MemoryProfiling::getAbsoluteFreeHeap(), + MemoryProfiling::getCurrentFreeHeap(), + MemoryProfiling::getAbsoluteFreeStack(), + MemoryProfiling::getCurrentFreeStack()); +} + +void resetCpuStats() { utilization.reset(); } #ifdef ENABLE_CPU_METER @@ -51,7 +66,10 @@ static void cpuMeterThread(void*) update++; float delta = t2 - t1; - utilization = 100.f * (1.f - static_cast<float>(period) / delta); + { + Lock<FastMutex> l(utilizationMutex); + utilization.add(100.f * (1.f - static_cast<float>(period) / delta)); + } Thread::sleep(gap); @@ -65,7 +83,10 @@ static void watchdogThread(void*) { Thread::sleep(watchdogPeriod); if (previous == update) - utilization = 100.f; + { + Lock<FastMutex> l(utilizationMutex); + utilization.add(100.0); + } StackLogger::getInstance().updateStack(THID_CPU_WD); } @@ -87,4 +108,6 @@ static CpuMeterLauncher launcher; #endif // ENABLE_CPU_METER +} // namespace CpuMeter + } // namespace Boardcore diff --git a/src/shared/diagnostic/CpuMeter.h b/src/shared/diagnostic/CpuMeter/CpuMeter.h similarity index 85% rename from src/shared/diagnostic/CpuMeter.h rename to src/shared/diagnostic/CpuMeter/CpuMeter.h index 17056473afe6c5fe2cf1a246b0786e9a6bc6ebb1..0787fc156066a5c058b04e22453999624fefcdf8 100644 --- a/src/shared/diagnostic/CpuMeter.h +++ b/src/shared/diagnostic/CpuMeter/CpuMeter.h @@ -22,9 +22,16 @@ #pragma once +#include <utils/Stats/Stats.h> + +#include "CpuMeterData.h" + namespace Boardcore { +namespace CpuMeter +{ + /* * This CPU meter works like this. * It creates a thread with the minimum priority that is (almost) always active @@ -40,16 +47,23 @@ namespace Boardcore * idle thread from running and thus it prevents the CPU from going into deep * sleep. * - * NOTE: for this to work, no other thread with the lowest priority has to be + * NOTE: For this to work, no other thread with the lowest priority has to be * created, otherwise its time will not be accounted. */ -/// If defined, the CPU meter is active +/// If defined, the CPU meter is activated #define ENABLE_CPU_METER /** - * \return the average CPU utilization + * \return The average CPU utilization */ -float averageCpuUtilization(); +CpuMeterData getCpuStats(); + +/** + * @brief Resets the cpu utilization statistics. + */ +void resetCpuStats(); + +} // namespace CpuMeter } // namespace Boardcore diff --git a/src/shared/diagnostic/CpuMeter/CpuMeterData.h b/src/shared/diagnostic/CpuMeter/CpuMeterData.h new file mode 100644 index 0000000000000000000000000000000000000000..a28b62a3a270284e38e808cdaae6f2fe2c1b8af6 --- /dev/null +++ b/src/shared/diagnostic/CpuMeter/CpuMeterData.h @@ -0,0 +1,68 @@ +/* Copyright (c) 2022 Skyward Experimental Rocketry + * Author: Alberto Nidasio + * + * 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. + */ + +#pragma once + +#include <utils/Stats/Stats.h> + +namespace Boardcore +{ + +struct CpuMeterData +{ + uint64_t timestamp = 0; + float minValue = 0; ///< Min value found so far. + float maxValue = 0; ///< Max value found so far. + float mean = 0; ///< Mean of dataset. + float stdDev = 0; ///< Standard deviation of dataset. + uint32_t nSamples = 0; ///< Number of samples. + + uint32_t minFreeHeap = 0; + uint32_t freeHeap = 0; + uint32_t minFreeStack = 0; + uint32_t freeStack = 0; + + CpuMeterData() {} + + explicit CpuMeterData(uint64_t timestamp, StatsResult stats, + uint32_t freeHeap, uint32_t minFreeHeap, + uint32_t minFreeStack, uint32_t freeStack) + : timestamp(timestamp), minValue(stats.minValue), + maxValue(stats.maxValue), mean(stats.mean), stdDev(stats.stdDev), + nSamples(stats.nSamples), minFreeHeap(minFreeHeap), + freeHeap(freeHeap), minFreeStack(minFreeStack), freeStack(freeStack) + { + } + + static std::string header() + { + return "timestamp,minValue,maxValue,mean,stdDev,nSamples\n"; + } + + void print(std::ostream& os) const + { + os << timestamp << "," << minValue << "," << maxValue << "," << mean + << "," << stdDev << "," << nSamples << "\n"; + } +}; + +} // namespace Boardcore diff --git a/src/shared/diagnostic/SkywardStack.h b/src/shared/diagnostic/SkywardStack.h index 8b85e44b0965153080f462b80cd08aaac55c6f5b..6a27d747f85267406a2c73daa1b727e8b70bc77e 100644 --- a/src/shared/diagnostic/SkywardStack.h +++ b/src/shared/diagnostic/SkywardStack.h @@ -27,7 +27,11 @@ namespace Boardcore { +#ifndef _ARCH_CORTEXM3_STM32F2 static const unsigned int STACK_MIN_FOR_SKYWARD = 16 * 1024; +#else +static const unsigned int STACK_MIN_FOR_SKYWARD = 1024; +#endif inline unsigned int skywardStack(unsigned int stack) { diff --git a/src/shared/drivers/adc/InternalADC.cpp b/src/shared/drivers/adc/InternalADC.cpp index f87b6c91c63d6af58b9a9a6e4cfdbfddc222eb54..737b2b6bc040925b2f7268ebc6154edcb17f25b3 100644 --- a/src/shared/drivers/adc/InternalADC.cpp +++ b/src/shared/drivers/adc/InternalADC.cpp @@ -72,9 +72,7 @@ InternalADC::InternalADC(ADC_TypeDef* adc, const float supplyVoltage, // Init indexMap for (auto i = 0; i < CH_NUM; i++) - { indexMap[i] = -1; - } } InternalADC::~InternalADC() @@ -90,13 +88,13 @@ bool InternalADC::init() adc->CR2 |= ADC_CR2_ADON; // Set single conversion mode - adc->CR2 &= ~ADC_CR2_CONT; + // adc->CR2 &= ~ADC_CR2_CONT; // Set scan mode - adc->CR1 |= ADC_CR1_SCAN; + // adc->CR1 |= ADC_CR1_SCAN; // Data alignment - adc->CR2 &= ~ADC_CR2_ALIGN; // right + // adc->CR2 &= ~ADC_CR2_ALIGN; // right if (isUsingDMA) { @@ -130,33 +128,22 @@ bool InternalADC::init() return true; } -bool InternalADC::enableChannel(Channel channel) -{ - return enableChannel(channel, CYCLES_3); -} - bool InternalADC::enableChannel(Channel channel, SampleTime sampleTime) { // Check channel number if (channel < CH0 || channel >= CH_NUM) - { return false; - } // Add channel to the sequence if (!isUsingDMA) { if (!addInjectedChannel(channel)) - { return false; - } } else { if (!addRegularChannel(channel)) - { return false; - } // Update the DMA number of data dmaStream->NDTR = activeChannels; @@ -168,7 +155,53 @@ bool InternalADC::enableChannel(Channel channel, SampleTime sampleTime) return true; } -ADCData InternalADC::getVoltage(Channel channel) +bool InternalADC::addRegularChannel(Channel channel) +{ + // Check active channels number + if (activeChannels >= 16) + return false; + + // Add the channel to the sequence + volatile uint32_t* sqrPtr; + switch (activeChannels / 6) + { + case 1: + sqrPtr = &(adc->SQR2); + break; + case 2: + sqrPtr = &(adc->SQR1); + break; + default: + sqrPtr = &(adc->SQR3); + } + *sqrPtr = channel << ((activeChannels % 6) * 5); + + // Update the channels number in the register + adc->SQR1 &= ~ADC_SQR1_L; + adc->SQR1 |= activeChannels << 20; + + // Save the index of the channel in the ADC's regular sequence + indexMap[channel] = activeChannels; + + // Update the counter + activeChannels++; + + return true; +} + +ADCData InternalADC::readChannel(Channel channel, SampleTime sampleTime) +{ + setChannelSampleTime(channel, sampleTime); + startRegularConversion(); + + while (!(adc->SR & ADC_SR_EOC)) + ; + + return {TimestampTimer::getTimestamp(), channel, + static_cast<uint16_t>(adc->DR) * supplyVoltage / RESOLUTION}; +} + +InternalADCData InternalADC::getVoltage(Channel channel) { float voltage = 0; @@ -177,7 +210,7 @@ ADCData InternalADC::getVoltage(Channel channel) voltage = values[indexMap[channel]] * supplyVoltage / RESOLUTION; } - return ADCData{timestamp, (uint8_t)channel, voltage}; + return InternalADCData{timestamp, (uint8_t)channel, voltage}; } bool InternalADC::selfTest() @@ -193,7 +226,7 @@ bool InternalADC::selfTest() return true; } -ADCData InternalADC::sampleImpl() +InternalADCData InternalADC::sampleImpl() { if (!isUsingDMA) { @@ -219,14 +252,14 @@ ADCData InternalADC::sampleImpl() // This should trigger the DMA stream for each channel's conversion - // Wait for tranfer end + // Wait for transfer end while (!(*statusReg & (transferCompleteMask | transferErrorMask))) ; // Clear the transfer complete flag *clearFlagReg |= transferCompleteMask; - // If and error has occurred (probaly due to a higher priority stream) + // If and error has occurred (probably due to a higher priority stream) // don't update the timestamp, the values should not have been updated if (*statusReg & transferErrorMask) { @@ -239,11 +272,13 @@ ADCData InternalADC::sampleImpl() } } - timestamp = TimestampTimer::getInstance().getTimestamp(); + timestamp = TimestampTimer::getTimestamp(); return lastSample; } +float InternalADC::getSupplyVoltage() { return supplyVoltage; } + inline void InternalADC::resetRegisters() { // Reset the ADC configuration @@ -277,9 +312,7 @@ inline bool InternalADC::addInjectedChannel(Channel channel) { // Check active channels number if (activeChannels >= 4) - { return false; - } // Add the channel to the sequence, starting from position 4 adc->JSQR |= channel << (15 - activeChannels * 5); @@ -292,9 +325,7 @@ inline bool InternalADC::addInjectedChannel(Channel channel) for (auto i = 0; i < CH_NUM; i++) { if (indexMap[i] >= 0) - { indexMap[i]++; - } } // Set this channel index to 0 @@ -306,53 +337,15 @@ inline bool InternalADC::addInjectedChannel(Channel channel) return true; } -inline bool InternalADC::addRegularChannel(Channel channel) -{ - // Check active channels number - if (activeChannels >= 16) - { - return false; - } - - // Add the channel to the sequence - volatile uint32_t* sqrPtr; - switch (activeChannels % 6) - { - case 1: - sqrPtr = &(adc->SQR3); - break; - case 2: - sqrPtr = &(adc->SQR2); - break; - default: - sqrPtr = &(adc->SQR1); - } - *sqrPtr = channel << ((activeChannels % 6) * 5); - - // Update the channels number in the register - adc->SQR1 |= activeChannels << 20; - - // Save the index of the channel in the ADC's regular sequence - indexMap[channel] = activeChannels; - - // Update the counter - activeChannels++; - - return true; -} - inline void InternalADC::setChannelSampleTime(Channel channel, SampleTime sampleTime) { volatile uint32_t* smprPtr; if (channel <= 9) - { smprPtr = &(adc->SMPR2); - } else - { smprPtr = &(adc->SMPR1); - } + *smprPtr = sampleTime << (channel * 3); } diff --git a/src/shared/drivers/adc/InternalADC.h b/src/shared/drivers/adc/InternalADC.h index cc9a4ce025dba27666e020cc3d3cb393b28087c2..ab0498619a7447080ab2efa4c6c6b7c53438e73b 100644 --- a/src/shared/drivers/adc/InternalADC.h +++ b/src/shared/drivers/adc/InternalADC.h @@ -66,7 +66,7 @@ namespace Boardcore * timers and multi adc mode. * This features are not implemented to keep the driver simple. */ -class InternalADC : public Sensor<ADCData> +class InternalADC : public Sensor<InternalADCData> { public: /** @@ -90,6 +90,9 @@ public: CH13, CH14, CH15, + CH16, + CH17, + CH18, CH_NUM }; @@ -127,15 +130,22 @@ public: */ bool init() override; - bool enableChannel(Channel channel); + /** + * @brief Make a regular conversion for the specified channel. + */ + ADCData readChannel(Channel channel, SampleTime sampleTime = CYCLES_3); + + bool enableChannel(Channel channel, SampleTime sampleTime = CYCLES_3); - bool enableChannel(Channel channel, SampleTime sampleTime); + bool addRegularChannel(Channel channel); - ADCData getVoltage(Channel channel); + InternalADCData getVoltage(Channel channel); bool selfTest() override; - ADCData sampleImpl() override; + InternalADCData sampleImpl() override; + + float getSupplyVoltage(); private: inline void resetRegisters(); @@ -146,8 +156,6 @@ private: inline bool addInjectedChannel(Channel channel); - inline bool addRegularChannel(Channel channel); - inline void setChannelSampleTime(Channel channel, SampleTime sampleTime); ADC_TypeDef* adc; @@ -168,7 +176,7 @@ private: * We'll use up to 4 injected channel by default and up to 16 channels when * using DMA. * - * The differentiation is necessary because whitout DMA it is much simplier + * The differentiation is necessary because whiteout DMA it is much simpler * to use injected channel for multichannel readings. Otherwise we would * need to handle each channel's end of conversion interrupt or go through */ @@ -182,7 +190,7 @@ private: volatile uint32_t* clearFlagReg; static constexpr int INJECTED_CHANNEL_N = 4; - static constexpr int RESOLUTION = 4096; ///< 12 bits + static constexpr int RESOLUTION = 4095; ///< 12 bits }; } // namespace Boardcore diff --git a/src/shared/drivers/adc/InternalTemp.cpp b/src/shared/drivers/adc/InternalTemp.cpp new file mode 100644 index 0000000000000000000000000000000000000000..e6c15b2fc9629145d82ac9a6cb4f7fe6c63dcfec --- /dev/null +++ b/src/shared/drivers/adc/InternalTemp.cpp @@ -0,0 +1,84 @@ +/* Copyright (c) 2022 Skyward Experimental Rocketry + * Authors: Giulia Ghirardini + * + * 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. + */ + +#include "InternalTemp.h" + +#ifdef _ARCH_CORTEXM4_STM32F4 +#define TEMP30_CAL_VALUE ((uint16_t*)((uint32_t)0x1FFF7A2C)) +#define TEMP110_CAL_VALUE ((uint16_t*)((uint32_t)0x1FFF7A2E)) +#define TEMP30 30 +#define TEMP110 110 +#endif + +namespace Boardcore +{ + +InternalTemp::InternalTemp(InternalADC::SampleTime sampleTime, + const float supplyVoltage) + : adc(ADC1, supplyVoltage), sampleTime(sampleTime) +{ +} + +bool InternalTemp::init() +{ + bool result = adc.init(); + +#if defined(_BOARD_STM32F4DISCOVERY) || defined(_ARCH_CORTEXM3_STM32F2) + adc.addRegularChannel(InternalADC::CH16); +#else + adc.addRegularChannel(InternalADC::CH18); +#endif + + ADC->CCR &= ~ADC_CCR_VBATE; + ADC->CCR |= ADC_CCR_TSVREFE; + + return result; +} + +bool InternalTemp::selfTest() { return adc.selfTest(); } + +InternalTempData InternalTemp::sampleImpl() +{ +#if defined(_BOARD_STM32F4DISCOVERY) || defined(_ARCH_CORTEXM3_STM32F2) + auto adcData = adc.readChannel(InternalADC::CH16, sampleTime); +#else + auto adcData = adc.readChannel(InternalADC::CH18, sampleTime); +#endif + + InternalTempData data; + data.temperatureTimestamp = adcData.voltageTimestamp; + +#ifdef _ARCH_CORTEXM3_STM32F2 + // Default conversion + data.temperature = ((adcData.voltage - 0.76) / 0.0025) + 25; +#else + // Factory calibration + float voltage30 = static_cast<float>(*TEMP30_CAL_VALUE) * 3.3 / 4095; + float voltage110 = static_cast<float>(*TEMP110_CAL_VALUE) * 3.3 / 4095; + float slope = (voltage110 - voltage30) / (TEMP110 - TEMP30); + data.temperature = ((adcData.voltage - voltage30) / slope) + TEMP30; +#endif + + return data; +} + +} // namespace Boardcore diff --git a/src/shared/drivers/adc/InternalTemp.h b/src/shared/drivers/adc/InternalTemp.h new file mode 100644 index 0000000000000000000000000000000000000000..a66e32cafa0283ee463a82c0d8c7be4b3efa99a3 --- /dev/null +++ b/src/shared/drivers/adc/InternalTemp.h @@ -0,0 +1,51 @@ +/* Copyright (c) 2022 Skyward Experimental Rocketry + * Authors: Giulia Ghirardini + * + * 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. + */ + +#pragma once +#include <drivers/adc/InternalADC.h> + +#include "InternalTempData.h" + +namespace Boardcore +{ + +class InternalTemp : public Sensor<InternalTempData> +{ +public: + explicit InternalTemp( + InternalADC::SampleTime sampleTime = InternalADC::CYCLES_480, + const float supplyVoltage = 5.0); + + bool init() override; + + bool selfTest() override; + + InternalTempData sampleImpl() override; + + // InternalTempData addRegularChannel(InternalADC::Channel channel); + +private: + InternalADC adc; + InternalADC::SampleTime sampleTime; +}; + +} // namespace Boardcore diff --git a/src/shared/drivers/adc/InternalTempData.h b/src/shared/drivers/adc/InternalTempData.h new file mode 100644 index 0000000000000000000000000000000000000000..96f709033d5cdcadb60b4d3e53f19d2da7901b90 --- /dev/null +++ b/src/shared/drivers/adc/InternalTempData.h @@ -0,0 +1,42 @@ +/* Copyright (c) 2021 Skyward Experimental Rocketry + * Author: Alberto Nidasio + * + * 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. + */ + +#pragma once + +#include <sensors/SensorData.h> + +namespace Boardcore +{ + +struct InternalTempData : public TemperatureData +{ + InternalTempData() : TemperatureData{0, 0} {} + + static std::string header() { return "timestamp,temperature\n"; } + + void print(std::ostream& os) const + { + os << temperatureTimestamp << "," << temperature << "\n"; + } +}; + +} // namespace Boardcore diff --git a/src/shared/drivers/canbus/BusLoadEstimation.h b/src/shared/drivers/canbus/CanDriver/BusLoadEstimation.h similarity index 98% rename from src/shared/drivers/canbus/BusLoadEstimation.h rename to src/shared/drivers/canbus/CanDriver/BusLoadEstimation.h index 66bf37394c23a1fc14617028d1b350e0c830a968..d635553acec07638bffa7aa20876123429fbe2de 100644 --- a/src/shared/drivers/canbus/BusLoadEstimation.h +++ b/src/shared/drivers/canbus/CanDriver/BusLoadEstimation.h @@ -27,7 +27,7 @@ #include <cstdint> -#include "CanData.h" +#include "CanDriverData.h" using miosix::FastMutex; using miosix::Lock; diff --git a/src/shared/drivers/canbus/Canbus.cpp b/src/shared/drivers/canbus/CanDriver/CanDriver.cpp similarity index 94% rename from src/shared/drivers/canbus/Canbus.cpp rename to src/shared/drivers/canbus/CanDriver/CanDriver.cpp index b7d70591a2b90d79f7ba675bd98c6858e89192ad..dc9469bddda098bdeac1b050a113bc04e734128c 100644 --- a/src/shared/drivers/canbus/Canbus.cpp +++ b/src/shared/drivers/canbus/CanDriver/CanDriver.cpp @@ -20,7 +20,7 @@ * THE SOFTWARE. */ -#include "Canbus.h" +#include "CanDriver.h" #include <kernel/scheduler/scheduler.h> #include <utils/ClockUtils.h> @@ -53,26 +53,23 @@ CanbusDriver::CanbusDriver(CAN_TypeDef* can, CanbusConfig config, ClockUtils::enablePeripheralClock(can); // Enter init mode - can->MCR &= (~CAN_MCR_SLEEP); + can->MCR &= ~CAN_MCR_SLEEP; can->MCR |= CAN_MCR_INRQ; while ((can->MSR & CAN_MSR_INAK) == 0) ; + // Automatic wakeup when a new packet is available if (config.awum) - { - can->MCR |= - CAN_MCR_AWUM; // Automatic wakeup when a new packet is available - } + can->MCR |= CAN_MCR_AWUM; + // Automatically recover from Bus-Off mode if (config.abom) - { - can->MCR |= CAN_MCR_ABOM; // Automatically recover from Bus-Off mode - } + can->MCR |= CAN_MCR_ABOM; + + // Disable automatic retransmission if (config.nart) - { - can->MCR |= CAN_MCR_NART; // Disable automatic retransmission - } + can->MCR |= CAN_MCR_NART; // Bit timing configuration can->BTR &= ~CAN_BTR_BRP; @@ -86,21 +83,15 @@ CanbusDriver::CanbusDriver(CAN_TypeDef* can, CanbusConfig config, can->BTR |= ((bitTiming.SJW - 1) & 0x3) << 24; if (config.loopback) - { can->BTR |= CAN_BTR_LBKM; - } // Enter filter initialization mode can->FMR |= CAN_FMR_FINIT; if (can == CAN1) - { canDrivers[0] = this; - } else - { canDrivers[1] = this; - } // Enable interrupts can->IER |= CAN_IER_FMPIE0 | CAN_IER_FMPIE1 | CAN_IER_TMEIE; @@ -139,7 +130,7 @@ CanbusDriver::BitTiming CanbusDriver::calcBitTiming(AutoBitTiming autoBt) 1 << 10), 1); - // Given N, calculate BS1 and BS2 that statusult in a sample time as + // Given N, calculate BS1 and BS2 that result in a sample time as // close as possible to the target one cfgIter.BS1 = std::min(std::max((int)roundf(autoBt.samplePoint * N - 1), 1), @@ -190,9 +181,7 @@ CanbusDriver::BitTiming CanbusDriver::calcBitTiming(AutoBitTiming autoBt) void CanbusDriver::init() { if (isInit) - { return; - } PrintLogger ls = l.getChild("init"); @@ -203,9 +192,7 @@ void CanbusDriver::init() LOG_DEBUG(ls, "Waiting for canbus synchronization..."); while ((can->MSR & CAN_MSR_INAK) > 0) - { Thread::sleep(1); - } LOG_INFO(ls, "Canbus synchronized! Init done!"); @@ -221,6 +208,7 @@ bool CanbusDriver::addFilter(FilterBank filter) LOG_ERR(ls, "Cannot add filter: canbus already initialized"); return false; } + if (filterIndex == NUM_FILTER_BANKS) { LOG_ERR(ls, "Cannot add filter: no more filter banks available"); @@ -256,6 +244,7 @@ uint32_t CanbusDriver::send(CanPacket packet) { miosix::FastInterruptDisableLock d; + // Wait until there is an empty mailbox available to use while ((can->TSR & CAN_TSR_TME) == 0) { @@ -312,13 +301,9 @@ uint32_t CanbusDriver::send(CanPacket packet) for (uint8_t i = 0; i < packet.length; ++i) { if (i < 4) - { mailbox->TDLR |= packet.data[i] << i * 8; - } else - { mailbox->TDHR |= packet.data[i] << (i - 4) * 8; - } } // Finally send the packet @@ -336,13 +321,9 @@ void CanbusDriver::handleRXInterrupt(int fifo) mailbox = &can->sFIFOMailBox[fifo]; if (fifo == 0) - { RFR = &can->RF0R; - } else - { RFR = &can->RF1R; - } status.fifoOverrun = (*RFR & CAN_RF0R_FOVR0) > 0; status.fifoFull = (*RFR & CAN_RF0R_FULL0) > 0; @@ -365,25 +346,18 @@ void CanbusDriver::handleRXInterrupt(int fifo) p.rtr = (mailbox->RIR & CAN_RI0R_RTR) > 0; if (p.ext) - { p.id = (mailbox->RIR >> 3) & 0x1FFFFFFF; - } else - { p.id = (mailbox->RIR >> 21) & 0x7FF; - } + p.length = mailbox->RDTR & CAN_RDT0R_DLC; for (uint8_t i = 0; i < p.length; i++) { if (i < 4) // Low register - { p.data[i] = (mailbox->RDLR >> (i * 8)) & 0xFF; - } else // High register - { p.data[i] = (mailbox->RDHR >> ((i - 4) * 8)) & 0xFF; - } } *RFR |= CAN_RF0R_RFOM0; diff --git a/src/shared/drivers/canbus/Canbus.h b/src/shared/drivers/canbus/CanDriver/CanDriver.h similarity index 91% rename from src/shared/drivers/canbus/Canbus.h rename to src/shared/drivers/canbus/CanDriver/CanDriver.h index 96a686b9206069d6fac893ef38efb5c643769acb..ed845f5f52b5f4748e0f2247d876783c8801eb63 100644 --- a/src/shared/drivers/canbus/Canbus.h +++ b/src/shared/drivers/canbus/CanDriver/CanDriver.h @@ -26,7 +26,7 @@ #include <miosix.h> #include <utils/collections/IRQCircularBuffer.h> -#include "CanData.h" +#include "CanDriverData.h" #include "Filters.h" using miosix::Thread; @@ -38,8 +38,8 @@ namespace Canbus { /** - * @brief Low level canbus driver, with support for both peripherals (CAN1 and - * CAN2) on stm32f4 micros. + * @brief Low level CanBus driver, with support for both peripherals (CAN1 and + * CAN2) on stm32f4 microcontrollers. */ class CanbusDriver { @@ -56,7 +56,7 @@ class CanbusDriver public: /** - * @brief Configuration struct for basic canbus operation. + * @brief Configuration struct for basic CanBus operation. */ struct CanbusConfig { @@ -64,13 +64,13 @@ public: uint8_t awum = 1; // Automatic wakeup (1: automatic wakeup upon new // message received) uint8_t nart = - 0; // No auto retransmission (0: packets are retrasmitted until + 0; // No auto retransmission (0: packets are retransmitted until // success, 1: only one transfer attempt) uint8_t abom = 1; // Automatic bus off management (1: automatically // recovers from bus-off state) uint8_t rflm = 1; // Receive fifo locked (0: new messages overwrite // last ones, 1: new message discarded) - uint8_t txfp = 0; // TX Fifo priority (0: identifier, 1: chronological) + uint8_t txfp = 1; // TX Fifo priority (0: identifier, 1: chronological) }; /** @@ -81,7 +81,7 @@ public: { /** * @brief Canbus baud rate in bps (BITS PER SECOND). CANOpen standard - * values are preferred but not mandatory: 1000 kpbs, 500 kbps, 250 + * values are preferred but not mandatory: 1000 kbps, 500 kbps, 250 * kbps, 125 kbps, 100 kbps, 83.333 kbps, 50 kbps, 25 kbps and 10 kbps. */ uint32_t baudRate; @@ -93,7 +93,7 @@ public: }; /** - * @brief Struct specifing exact bit timing registers values. + * @brief Struct specifying exact bit timing registers values. */ struct BitTiming { @@ -133,13 +133,14 @@ public: ~CanbusDriver(); /** - * @brief Exits initialization mode and starts canbus operation. + * @brief Exits initialization mode and starts CanBus operation. */ void init(); /** * @brief Adds a new filter to the bus, or returns false if there are no * more filter banks available. + * * @warning Can only be called before init(). * * @param filter Filter to be added @@ -173,7 +174,7 @@ public: } /** - * @brief Returns the canbus peripheral assigned to this instance. + * @brief Returns the CanBus peripheral assigned to this instance. */ CAN_TypeDef* getCAN() { return can; } diff --git a/src/shared/drivers/canbus/CanData.h b/src/shared/drivers/canbus/CanDriver/CanDriverData.h similarity index 96% rename from src/shared/drivers/canbus/CanData.h rename to src/shared/drivers/canbus/CanDriver/CanDriverData.h index 8123c8514b1e25e58ea88eb04d453bb742c7b509..97e583073d3f823b35b79ea7dde0df4c7e2c599d 100644 --- a/src/shared/drivers/canbus/CanData.h +++ b/src/shared/drivers/canbus/CanDriver/CanDriverData.h @@ -54,7 +54,7 @@ struct CanPacket uint32_t timestamp = 0; uint32_t id; - bool ext = false; + bool ext = false; ///< Whether to use extended packet id bool rtr = false; diff --git a/src/shared/drivers/canbus/CanInterrupt.cpp b/src/shared/drivers/canbus/CanDriver/CanInterrupt.cpp similarity index 99% rename from src/shared/drivers/canbus/CanInterrupt.cpp rename to src/shared/drivers/canbus/CanDriver/CanInterrupt.cpp index e0312b326dc917837e84f4faca875d6f22fa62c8..4ed47a191f8c8afa1a0716b7f1b0bfc08642cf47 100644 --- a/src/shared/drivers/canbus/CanInterrupt.cpp +++ b/src/shared/drivers/canbus/CanDriver/CanInterrupt.cpp @@ -26,7 +26,7 @@ #include <kernel/scheduler/scheduler.h> #include <miosix.h> -#include "Canbus.h" +#include "CanDriver.h" namespace Boardcore { @@ -98,9 +98,7 @@ void __attribute__((used)) CAN_RXIRQHandlerImpl(int canDev, int fifo) (void)canDev; if (canDrivers[canDev]) - { canDrivers[canDev]->handleRXInterrupt(fifo); - } } void __attribute__((used)) CAN_TXIRQHandlerImpl(int canDev) diff --git a/src/shared/drivers/canbus/CanInterrupt.h b/src/shared/drivers/canbus/CanDriver/CanInterrupt.h similarity index 100% rename from src/shared/drivers/canbus/CanInterrupt.h rename to src/shared/drivers/canbus/CanDriver/CanInterrupt.h diff --git a/src/shared/drivers/canbus/Filters.h b/src/shared/drivers/canbus/CanDriver/Filters.h similarity index 100% rename from src/shared/drivers/canbus/Filters.h rename to src/shared/drivers/canbus/CanDriver/Filters.h diff --git a/src/shared/drivers/canbus/CanProtocol/CanProtocol.cpp b/src/shared/drivers/canbus/CanProtocol/CanProtocol.cpp new file mode 100644 index 0000000000000000000000000000000000000000..64c6a27bdaaf0cc92de58915d63f46ac21503ff6 --- /dev/null +++ b/src/shared/drivers/canbus/CanProtocol/CanProtocol.cpp @@ -0,0 +1,318 @@ +/* Copyright (c) 2022 Skyward Experimental Rocketry + * Author: Federico Mandelli + * + * 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. + */ + +#include "CanProtocol.h" + +using namespace miosix; + +namespace Boardcore +{ + +namespace Canbus +{ + +CanProtocol::CanProtocol(CanbusDriver* can, MsgHandler onReceive) + : can(can), onReceive(onReceive) +{ +} + +bool CanProtocol::start() +{ + stopFlag = false; + + if (can == nullptr) + return false; + + // Start sender (joinable thread) + if (!sndStarted) + { + sndThread = miosix::Thread::create( + sndLauncher, skywardStack(4 * 1024), miosix::MAIN_PRIORITY, + reinterpret_cast<void*>(this), miosix::Thread::JOINABLE); + + if (sndThread != nullptr) + sndStarted = true; + else + LOG_ERR(logger, "Could not start sender!"); + } + + // Start receiver + if (!rcvStarted) + { + rcvThread = miosix::Thread::create(rcvLauncher, skywardStack(4 * 1024), + miosix::MAIN_PRIORITY, + reinterpret_cast<void*>(this)); + + if (rcvThread != nullptr) + rcvStarted = true; + else + LOG_ERR(logger, "Could not start receiver!"); + } + + if (sndStarted && rcvStarted) + LOG_DEBUG(logger, "Sender and receiver started"); + + return sndStarted && rcvStarted; +} + +bool CanProtocol::isStarted() { return sndStarted && rcvStarted; } + +void CanProtocol::stop() +{ + stopFlag = true; + + // Wait for sender to stop + sndThread->join(); +} + +bool CanProtocol::enqueueMsg(const CanMessage& msg) +{ + // Append the message to the queue + outQueue.put(msg); + + // Update stats + // updateQueueStats(appended); + + // Return always true because the circular buffer overrides current packets + // and can't get full. + return true; +} + +bool CanProtocol::addFilter(uint8_t src, uint64_t dst) +{ + if (src > 0xF || dst > 0xF) + return false; + + // The filter mask will cover only the source and destination bits + uint32_t mask = static_cast<uint32_t>(CanProtocolIdMask::SOURCE) | + static_cast<uint32_t>(CanProtocolIdMask::DESTINATION); + + uint32_t id = + src << static_cast<uint8_t>(CanProtocolShiftInformation::SOURCE) | + dst << static_cast<uint8_t>(CanProtocolShiftInformation::DESTINATION); + + Mask32FilterBank filterBank(id, mask, 1, 1, 0, 0, 0); + + if (can == nullptr) + return false; + else + return can->addFilter(filterBank); +} + +void CanProtocol::sendMessage(const CanMessage& msg) +{ + CanPacket packet = {}; + uint32_t leftToSend = msg.length - 1; + + // Create the id for the first packet + packet.ext = true; // Use extended packet id + + // The number of left to send packets + packet.id = static_cast<uint32_t>(msg.id) | + ((static_cast<uint32_t>(0x3F) - leftToSend) & + static_cast<uint32_t>(CanProtocolIdMask::LEFT_TO_SEND)); + packet.length = byteForUint64(msg.payload[0]); + + // Splits payload[0] in the right number of uint8_t + for (int i = 0; i < packet.length; i++) + packet.data[i] = msg.payload[0] >> (8 * i); + + // Send the first packet + can->send(packet); + leftToSend--; + + // Prepare the remaining packets + for (int i = 1; i < msg.length; i++) + { + packet.id = + static_cast<uint32_t>(msg.id) | + static_cast<uint32_t>(CanProtocolIdMask::FIRST_PACKET_FLAG) | + ((static_cast<uint32_t>(0x3F) - leftToSend) & + static_cast<uint32_t>(CanProtocolIdMask::LEFT_TO_SEND)); + packet.length = byteForUint64(msg.payload[i]); + + // Splits payload[i] in the right number of uint8_t + for (int k = 0; k < packet.length; k++) + packet.data[k] = msg.payload[i] >> (8 * k); + + can->send(packet); + leftToSend--; + } +} + +bool CanProtocol::enqueueEvent(uint8_t priority, uint8_t primaryType, + uint8_t source, uint8_t destination, + uint8_t secondaryType) +{ + if (priority > 0xF || primaryType > 0x3F || source > 0xF || + destination > 0xF || secondaryType > 0xF) + return false; + + CanMessage msg{}; + + // Length set to a minumum of 1 even if there is no payload + msg.length = 1; + msg.payload[0] = 0xFF; + + // clang-format off + msg.id = priority << static_cast<uint32_t>(CanProtocolShiftInformation::PRIORITY); + msg.id |= primaryType << static_cast<uint32_t>(CanProtocolShiftInformation::PRIMARY_TYPE); + msg.id |= source << static_cast<uint32_t>(CanProtocolShiftInformation::SOURCE); + msg.id |= destination << static_cast<uint32_t>(CanProtocolShiftInformation::DESTINATION); + msg.id |= secondaryType << static_cast<uint32_t>(CanProtocolShiftInformation::SECONDARY_TYPE); + // clang-format off + + LOG_DEBUG(logger, "Sending message with id: {:x}", msg.id); + + return enqueueMsg(msg); +} + +void CanProtocol::runReceiver() +{ + CanMessage msg; + uint8_t nReceived = 0; + + while (!stopFlag) + { + // Wait for the next packet + can->getRXBuffer().waitUntilNotEmpty(); + + // If the buffer is not empty retrieve the packet + if (!can->getRXBuffer().isEmpty()) + { + CanPacket pkt = can->getRXBuffer().pop().packet; + + uint8_t leftToReceive = + static_cast<uint32_t>(0x3F) - + (pkt.id & + static_cast<uint32_t>(CanProtocolIdMask::LEFT_TO_SEND)); + + // Check if the packet is the first in the sequence, if this is the + // case then the previous message is overriden + if ((pkt.id & static_cast<uint32_t>( + CanProtocolIdMask::FIRST_PACKET_FLAG)) == 0) + { + // If it is we save the id (without the sequence number) and the + // message length + msg.id = pkt.id & static_cast<uint32_t>( + CanProtocolIdMask::MESSAGE_INFORMATION); + msg.length = leftToReceive + 1; + + // Reset the number of received packets + nReceived = 0; + } + + // Accept the packet only if it has the expected id + // clang-format off + if (msg.id != -1 && + (pkt.id & static_cast<uint32_t>(CanProtocolIdMask::MESSAGE_INFORMATION)) == + (msg.id & static_cast<uint32_t>(CanProtocolIdMask::MESSAGE_INFORMATION))) + // clang-format on + { + // Check if the packet is expected in the sequence. The received + // packet must have the expected left to send value + + if (msg.length - nReceived - 1 == leftToReceive) + { + uint64_t payload = 0; + + // Assemble the packet data into a uint64_t + for (uint8_t i = 0; i < pkt.length; i++) + payload |= pkt.data[i] << (i * 8); + + // Add the data to the message + msg.payload[pkt.length - leftToReceive - 1] = payload; + nReceived++; + } + } + + // If we have received the right number of packet call onReceive and + // reset the message + if (nReceived == msg.length && nReceived != 0) + { + LOG_DEBUG(logger, "Message ready with id: {:x}", msg.id); + + onReceive(msg); + + // Reset the packet + msg.id = -1; + msg.length = 0; + } + } + } +} + +void CanProtocol::runSender() +{ + LOG_DEBUG(logger, "Sender is running"); + CanMessage msg; + + while (!stopFlag) + { + outQueue.waitUntilNotEmpty(); + + if (!outQueue.isEmpty()) + { + // Get the first packet in the queue, without removing it + msg = outQueue.pop(); + + LOG_DEBUG(logger, "Sending message, length: {}", msg.length); + + sendMessage(msg); + + // updateSenderStats(); + } + else + { + // Wait before sending something else + miosix::Thread::sleep(50); + } + } +} + +void CanProtocol::rcvLauncher(void* arg) +{ + reinterpret_cast<CanProtocol*>(arg)->runReceiver(); +} + +void CanProtocol::sndLauncher(void* arg) +{ + reinterpret_cast<CanProtocol*>(arg)->runSender(); +} + +uint8_t CanProtocol::byteForUint64(uint64_t number) +{ + uint8_t i; + + for (i = 1; i <= 8; i++) + { + number >>= 8; + if (number == 0) + return i; + } + + return i; +} + +} // namespace Canbus + +} // namespace Boardcore diff --git a/src/shared/drivers/canbus/CanProtocol/CanProtocol.h b/src/shared/drivers/canbus/CanProtocol/CanProtocol.h new file mode 100644 index 0000000000000000000000000000000000000000..fc79de55e28f26e80d359a7f1d875f807c6a02dc --- /dev/null +++ b/src/shared/drivers/canbus/CanProtocol/CanProtocol.h @@ -0,0 +1,204 @@ +/* Copyright (c) 2022 Skyward Experimental Rocketry + * Author: Federico Mandelli + * + * 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. + */ + +#pragma once + +#include <diagnostic/PrintLogger.h> +#include <drivers/canbus/CanDriver/CanDriver.h> +#include <utils/Debug.h> +#include <utils/collections/SyncCircularBuffer.h> + +#include "CanProtocolData.h" +#include "CanProtocolTypes.h" + +namespace Boardcore +{ + +namespace Canbus +{ + +/** + * @brief Canbus protocol implementation. + * + * Given a can interface this class takes care of sending messages segmented + * into multiple packets, and receiving single packets that are then reframed + * into messages. + * + * This driver has been implemented following the MavlinkDriver. + */ +class CanProtocol +{ + using MsgHandler = std::function<void(CanMessage data)>; + +public: + /** + * @brief Construct a new CanProtocol object. + * + * @param can Pointer to a CanbusDriver object. + */ + CanProtocol(CanbusDriver* can, MsgHandler onReceive); + + /** + * @brief Start the receiving and sending threads. + * + * @return False if at least one could not start. + */ + bool start(); + + /** + * @brief Tells whether the driver was started. + */ + bool isStarted(); + + /** + * @brief Stops sender and receiver threads. + */ + void stop(); + + /** + * @brief Adds a filter to the can peripheral to receive only messages from + * the given source and targeted to the given destination. + * + * @param src Message source. + * @param dst Message destination. + * @return True if the filter was added successfully. + */ + bool addFilter(uint8_t src, uint64_t dst); + + /** + * @brief Non-blocking send function, puts the messages in a queue. + * Message is discarded if the queue is full. + * + * @param msg Message to send (CanMessage struct). + * @return True if the message could be enqueued. + */ + bool enqueueMsg(const CanMessage& msg); + + /** + * @brief Non-blocking send function for an event (a message without + * payload). + */ + bool enqueueEvent(uint8_t priority, uint8_t primaryType, uint8_t source, + uint8_t destination, uint8_t secondaryType); + + /** + * @brief Non-blocking send function for a generic data type. + * + * @warning There must be a function called with this prototype: + * CanMessage toCanMessage(const T& t); + * + * @param t The class to be logged. + */ + template <typename T> + bool enqueueData(uint8_t priority, uint8_t primaryType, uint8_t source, + uint8_t destination, uint8_t secondaryType, const T& t); + +private: + /** + * @brief Blocking send function, puts the CanMessage object on the bus. + * + * Takes a CanMessage object, splits it into multiple CanPackets with the + * correct sequential id. + * + * @param msg Contains the id and the data of the packet to send. + */ + void sendMessage(const CanMessage& msg); + + /** + * @brief Receiver thread: waits for one packet at a time from the can + * driver and tries to parse a message. + * + * If the message is successfully parsed, the onReceive function is + * executed. + * + * For now if a packet is received in the wrong order or if a packet with a + * different id is received, the current (incomplete) message will be lost. + * Once we receive a new first packet, currently saved data are reset. + */ + void runReceiver(); + + /** + * @brief Sender Thread: Periodically flushes the message queue and sends + * all the enqueued messages. + */ + void runSender(); + + /** + * @brief Calls the run member function. + * + * @param arg The object pointer cast to void*. + */ + static void rcvLauncher(void* arg); + + /** + * @brief Calls the run member function. + * + * @param arg The object pointer cast to void*. + */ + static void sndLauncher(void* arg); + + /** + * @brief Count the number of bytes needed to encode a uint64_t number. + */ + uint8_t byteForUint64(uint64_t number); + + CanbusDriver* can; ///< Device used to send and receive packets. + MsgHandler onReceive; ///< Function executed when a message is ready. + + // Threads + bool stopFlag = false; + bool sndStarted = false; + bool rcvStarted = false; + + miosix::Thread* sndThread = nullptr; + miosix::Thread* rcvThread = nullptr; + + SyncCircularBuffer<CanMessage, 10> outQueue; + + PrintLogger logger = Logging::getLogger("canprotocol"); +}; + +template <typename T> +bool CanProtocol::enqueueData(uint8_t priority, uint8_t primaryType, + uint8_t source, uint8_t destination, + uint8_t secondaryType, const T& t) +{ + if (priority > 0xF || primaryType > 0x3F || source > 0xF || + destination > 0xF || secondaryType > 0xF) + return false; + + CanMessage msg = toCanMessage(t); + + // clang-format off + msg.id = priority << static_cast<uint32_t>(CanProtocolShiftInformation::PRIORITY); + msg.id |= primaryType << static_cast<uint32_t>(CanProtocolShiftInformation::PRIMARY_TYPE); + msg.id |= source << static_cast<uint32_t>(CanProtocolShiftInformation::SOURCE); + msg.id |= destination << static_cast<uint32_t>(CanProtocolShiftInformation::DESTINATION); + msg.id |= secondaryType << static_cast<uint32_t>(CanProtocolShiftInformation::SECONDARY_TYPE); + // clang-format off + + return enqueueMsg(msg); +} + +} // namespace Canbus + +} // namespace Boardcore diff --git a/src/shared/drivers/canbus/CanProtocol/CanProtocolData.h b/src/shared/drivers/canbus/CanProtocol/CanProtocolData.h new file mode 100644 index 0000000000000000000000000000000000000000..b73b40ca8535cf0f5bfacffc48d703ede106ed66 --- /dev/null +++ b/src/shared/drivers/canbus/CanProtocol/CanProtocolData.h @@ -0,0 +1,185 @@ +/* Copyright (c) 2022 Skyward Experimental Rocketry + * Author: Federico Mandelli + * + * 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. + */ + +#pragma once + +#include <stdint.h> + +namespace Boardcore +{ + +namespace Canbus +{ + +/** + * The CanProtocol allows to transmit arbitrarily sized messages over the CanBus + * overcoming the 8 byte limitation of each single packet. + * + * Our CanProtocol uses the extended can packet, the 29 bits id is divided such + * as: + * - Priority 4 bit \ + * - Primary type 6 bit | + * - Source 4 bit | 22 bits - Message informations + * - Destination 4 bit | + * - Secondary type 4 bit / + * - First packet flag 1 bit \ 7 bits - Sequential informations + * - Remaining packets 6 bit / + * shiftNameOfField the number of shift needed to reach that field + * + * The id is split into 2 parts: + * - Message information: Common to every packet of a given message + * - Sequential information: Used to distinguish between packets + * + * The sender splits into multiple packets a message that is then recomposed on + * the receiver end. The message informations are encoded into the packets id, + * therefore they have an effect on packets priorities. + */ +/** + * The CanProtocol allows to transmit arbitrarily sized messages over the CanBus + * overcoming the 8 byte limitation of each single packet. + * + * Our CanProtocol uses the extended can packet, the 29 bits id is divided such + * as: + * - Priority 4 bit \ + * - Primary type 6 bit | + * - Source 4 bit | 22 bits - Message informations + * - Destination 4 bit | + * - Secondary type 4 bit / + * - First packet flag 1 bit \ 7 bits - Sequential informations + * - Remaining packets 6 bit / + * shiftNameOfField the number of shift needed to reach that field + * + * The id is split into 2 parts: + * - Message information: Common to every packet of a given message + * - Sequential information: Used to distinguish between packets + * + * The sender splits into multiple packets a message that is then recomposed on + * the receiver end. The message informations are encoded into the packets id, + * therefore they have an effect on packets priorities. + */ + +/** + * @brief Masks of the elements composing can packets ids. + */ +enum class CanProtocolIdMask : uint32_t +{ + PRIORITY = 0x1E000000, + PRIMARY_TYPE = 0x01F80000, + SOURCE = 0x00078000, + DESTINATION = 0x00007800, + SECONDARY_TYPE = 0x00000780, + + MESSAGE_INFORMATION = 0x1FFFFF80, + + FIRST_PACKET_FLAG = 0x00000040, + LEFT_TO_SEND = 0x0000003F, + + SEQUENTIAL_INFORMATION = 0x0000007F +}; + +enum CanProtocolShiftInformation : uint8_t +{ + // Shift values for message informations + PRIORITY = 25, + PRIMARY_TYPE = 19, + SOURCE = 15, + DESTINATION = 11, + SECONDARY_TYPE = 7, + + // Shift values for sequential informations + FIRST_PACKET_FLAG = 6, + LEFT_TO_SEND = 0, + + // Position of the message infos relative to the entire can packet id + SEQUENTIAL_INFORMATION = 7 +}; + +/** + * @brief Generic struct that contains a can protocol message. + * + * For example an accelerometer message could have: + * - 4 bytes for the timestamp + * - 3x4 bytes for float values + * This message would be divided into 2 can packets. + * + * Note that the maximum size for a message is 520 bytes since the remaining + * packet information is 6 bit wide. + */ +struct CanMessage +{ + int32_t id = -1; ///< Id of the message without sequential infos. + uint8_t length = 0; ///< Length of the message content. + uint64_t payload[65]; + + uint8_t getPriority() const + { + return id >> + static_cast<uint8_t>(CanProtocolShiftInformation::PRIORITY); + } + + uint8_t getPrimaryType() const + { + return (id & static_cast<uint32_t>(CanProtocolIdMask::PRIMARY_TYPE)) >> + static_cast<uint8_t>(CanProtocolShiftInformation::PRIMARY_TYPE); + } + + uint8_t getSource() const + { + return (id & static_cast<uint32_t>(CanProtocolIdMask::SOURCE)) >> + static_cast<uint8_t>(CanProtocolShiftInformation::SOURCE); + } + + uint8_t getDestination() const + { + return (id & static_cast<uint32_t>(CanProtocolIdMask::DESTINATION)) >> + static_cast<uint8_t>(CanProtocolShiftInformation::DESTINATION); + } + + uint8_t getSecondaryType() const + { + return (id & + static_cast<uint32_t>(CanProtocolIdMask::SECONDARY_TYPE)) >> + static_cast<uint8_t>( + CanProtocolShiftInformation::SECONDARY_TYPE); + } +}; + +inline bool operator==(const CanMessage& lhs, const CanMessage& rhs) +{ + if (lhs.id != rhs.id || lhs.length != rhs.length) + return false; + + for (int i = 0; i < lhs.length; i++) + if (lhs.payload[i] != rhs.payload[i]) + return false; + + return true; +} + +inline bool operator!=(const CanMessage& lhs, const CanMessage& rhs) +{ + return !(lhs == rhs); +} + +} // namespace Canbus + +} // namespace Boardcore diff --git a/src/shared/drivers/canbus/CanProtocol/CanProtocolTypes.h b/src/shared/drivers/canbus/CanProtocol/CanProtocolTypes.h new file mode 100644 index 0000000000000000000000000000000000000000..b84db80a9c1e530dc9666af6c2e9951a7e3ed7f6 --- /dev/null +++ b/src/shared/drivers/canbus/CanProtocol/CanProtocolTypes.h @@ -0,0 +1,49 @@ +/* Copyright (c) 2022 Skyward Experimental Rocketry + * Author: Alberto Nidasio + * + * 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. + */ + +#pragma once + +#include <sensors/analog/Pitot/PitotData.h> + +#include <cstring> + +#include "CanProtocolData.h" + +namespace Boardcore +{ + +inline Canbus::CanMessage toCanMessage(const PitotData& data) +{ + Canbus::CanMessage message; + + uint32_t tmp; + memcpy(&tmp, &(data.airspeed), sizeof(tmp)); + + message.id = -1; + message.length = 1; + message.payload[0] = (data.timestamp & ~0x3) << 30; + message.payload[0] |= tmp; + + return message; +} + +} // namespace Boardcore diff --git a/src/shared/drivers/interrupt/external_interrupts.cpp b/src/shared/drivers/interrupt/external_interrupts.cpp index a00631d4624bfd6725933c2d70caec86d8032987..56aad8e2b5d9b7bb85664635f735b7de60b2101e 100644 --- a/src/shared/drivers/interrupt/external_interrupts.cpp +++ b/src/shared/drivers/interrupt/external_interrupts.cpp @@ -23,6 +23,9 @@ #include "external_interrupts.h" #include <miosix.h> + +#include "kernel/logging.h" + using namespace miosix; /** @@ -62,46 +65,95 @@ using namespace miosix; // All unused interrupts call this function. extern void unexpectedInterrupt(); -extern "C" void Default_EXTI_Handler() { unexpectedInterrupt(); } +extern "C" void Default_EXTI_Handler() +{ + IRQerrorLog("\r\n***Unexpected Peripheral interrupt [Boardcore]\r\n"); +} /** * Declaration of a separate IRQHandler for each external - * interrupt. If no further implementatio is provided, the + * interrupt. If no further implementation is provided, the * Default_Handler will be called. */ -void __attribute__((weak)) EXTI0_IRQHandlerImpl(); -void __attribute__((weak)) EXTI1_IRQHandlerImpl(); -void __attribute__((weak)) EXTI2_IRQHandlerImpl(); -void __attribute__((weak)) EXTI3_IRQHandlerImpl(); -void __attribute__((weak)) EXTI4_IRQHandlerImpl(); -void __attribute__((weak)) EXTI5_IRQHandlerImpl(); -void __attribute__((weak)) EXTI6_IRQHandlerImpl(); -void __attribute__((weak)) EXTI7_IRQHandlerImpl(); -void __attribute__((weak)) EXTI8_IRQHandlerImpl(); -void __attribute__((weak)) EXTI9_IRQHandlerImpl(); -void __attribute__((weak)) EXTI10_IRQHandlerImpl(); -void __attribute__((weak)) EXTI11_IRQHandlerImpl(); -void __attribute__((weak)) EXTI12_IRQHandlerImpl(); -void __attribute__((weak)) EXTI13_IRQHandlerImpl(); -void __attribute__((weak)) EXTI14_IRQHandlerImpl(); -void __attribute__((weak)) EXTI15_IRQHandlerImpl(); - -#pragma weak EXTI0_IRQHandlerImpl = Default_EXTI_Handler -#pragma weak EXTI1_IRQHandlerImpl = Default_EXTI_Handler -#pragma weak EXTI2_IRQHandlerImpl = Default_EXTI_Handler -#pragma weak EXTI3_IRQHandlerImpl = Default_EXTI_Handler -#pragma weak EXTI4_IRQHandlerImpl = Default_EXTI_Handler -#pragma weak EXTI5_IRQHandlerImpl = Default_EXTI_Handler -#pragma weak EXTI6_IRQHandlerImpl = Default_EXTI_Handler -#pragma weak EXTI7_IRQHandlerImpl = Default_EXTI_Handler -#pragma weak EXTI8_IRQHandlerImpl = Default_EXTI_Handler -#pragma weak EXTI9_IRQHandlerImpl = Default_EXTI_Handler -#pragma weak EXTI10_IRQHandlerImpl = Default_EXTI_Handler -#pragma weak EXTI11_IRQHandlerImpl = Default_EXTI_Handler -#pragma weak EXTI12_IRQHandlerImpl = Default_EXTI_Handler -#pragma weak EXTI13_IRQHandlerImpl = Default_EXTI_Handler -#pragma weak EXTI14_IRQHandlerImpl = Default_EXTI_Handler -#pragma weak EXTI15_IRQHandlerImpl = Default_EXTI_Handler +void __attribute__((weak)) EXTI0_IRQHandlerImpl() +{ + IRQerrorLog("\r\nUnexpected Peripheral interrupt EXTI0\r\n"); +} + +void __attribute__((weak)) EXTI1_IRQHandlerImpl() +{ + IRQerrorLog("\r\nUnexpected Peripheral interrupt EXTI1\r\n"); +} + +void __attribute__((weak)) EXTI2_IRQHandlerImpl() +{ + IRQerrorLog("\r\nUnexpected Peripheral interrupt EXTI2\r\n"); +} + +void __attribute__((weak)) EXTI3_IRQHandlerImpl() +{ + IRQerrorLog("\r\nUnexpected Peripheral interrupt EXTI3\r\n"); +} + +void __attribute__((weak)) EXTI4_IRQHandlerImpl() +{ + IRQerrorLog("\r\nUnexpected Peripheral interrupt EXTI4\r\n"); +} + +void __attribute__((weak)) EXTI5_IRQHandlerImpl() +{ + IRQerrorLog("\r\nUnexpected Peripheral interrupt EXTI5\r\n"); +} + +void __attribute__((weak)) EXTI6_IRQHandlerImpl() +{ + IRQerrorLog("\r\nUnexpected Peripheral interrupt EXTI6\r\n"); +} + +void __attribute__((weak)) EXTI7_IRQHandlerImpl() +{ + IRQerrorLog("\r\nUnexpected Peripheral interrupt EXTI7\r\n"); +} + +void __attribute__((weak)) EXTI8_IRQHandlerImpl() +{ + IRQerrorLog("\r\nUnexpected Peripheral interrupt EXTI8\r\n"); +} + +void __attribute__((weak)) EXTI9_IRQHandlerImpl() +{ + IRQerrorLog("\r\nUnexpected Peripheral interrupt EXTI9\r\n"); +} + +void __attribute__((weak)) EXTI10_IRQHandlerImpl() +{ + IRQerrorLog("\r\nUnexpected Peripheral interrupt EXTI10\r\n"); +} + +void __attribute__((weak)) EXTI11_IRQHandlerImpl() +{ + IRQerrorLog("\r\nUnexpected Peripheral interrupt EXTI11\r\n"); +} + +void __attribute__((weak)) EXTI12_IRQHandlerImpl() +{ + IRQerrorLog("\r\nUnexpected Peripheral interrupt EXTI12\r\n"); +} + +void __attribute__((weak)) EXTI13_IRQHandlerImpl() +{ + IRQerrorLog("\r\nUnexpected Peripheral interrupt EXTI13\r\n"); +} + +void __attribute__((weak)) EXTI14_IRQHandlerImpl() +{ + IRQerrorLog("\r\nUnexpected Peripheral interrupt EXTI14\r\n"); +} + +void __attribute__((weak)) EXTI15_IRQHandlerImpl() +{ + IRQerrorLog("\r\nUnexpected Peripheral interrupt EXTI15\r\n"); +} /** * Implementation of the IRQHandler that is triggered when @@ -266,7 +318,7 @@ void __attribute__((used)) EXTI15_10_IRQHandlerImpl() } } -constexpr unsigned ConvertGPIO_BASEtoUnsiged(unsigned P) +constexpr unsigned ConvertGPIO_BASEtoUnsigned(unsigned P) { // clang-format off return P == GPIOA_BASE? 0 : @@ -303,7 +355,7 @@ constexpr unsigned GetEXTI_IRQn(unsigned N) constexpr unsigned GetEXTICR_register_value(unsigned P, unsigned N) { - return (ConvertGPIO_BASEtoUnsiged(P) << ((N % 4) * 4)); + return (ConvertGPIO_BASEtoUnsigned(P) << ((N % 4) * 4)); } void enableExternalInterrupt(unsigned int gpioPort, unsigned int gpioNumber, diff --git a/src/shared/drivers/spi/SPI.h b/src/shared/drivers/spi/SPI.h index 8d2077fca048d27085f7f3f64447ac7ca5222663..3d74a7722956f952d1abeec7eb3a8096305549e3 100644 --- a/src/shared/drivers/spi/SPI.h +++ b/src/shared/drivers/spi/SPI.h @@ -30,7 +30,7 @@ using SPIType = SPI_TypeDef; #else #include <utils/TestUtils/FakeSpiTypedef.h> -using SPIType = FakeSpiTypedef; +using SPIType = Boardcore::FakeSpiTypedef; #endif namespace Boardcore @@ -51,7 +51,7 @@ namespace Boardcore * - Full-duplex synchronous transfers on three lines * - 8- or 16-bit transfer frame format selection * - Master or slave operation - * - 8 master mode baud rate prescales (f_PCLK/2 max.) + * - 8 master mode baud rate prescaler (f_PCLK/2 max.) * - Programmable clock polarity and phase * - Programmable data order with MSB-first or LSB-first shifting * - Hardware CRC feature for reliable communication @@ -485,10 +485,12 @@ inline uint16_t SPI::transfer(uint16_t data) inline void SPI::transfer(uint8_t *data, size_t nBytes) { - // Cleaer the RX buffer + miosix::FastInterruptDisableLock lock; + + // Clear the RX buffer (void)spi->DR; - // Write the first data item to transmit + // Write the first data item to transmitted spi->DR = data[0]; for (size_t i = 1; i < nBytes; i++) @@ -508,26 +510,32 @@ inline void SPI::transfer(uint8_t *data, size_t nBytes) data[i - 1] = static_cast<uint8_t>(spi->DR); } - // Wait until data is received - // while ((spi->SR & SPI_SR_RXNE) == 0) - // ; - while (spi->SR & SPI_SR_BSY) + // Wait until the last data item is received + while ((spi->SR & SPI_SR_RXNE) == 0) ; // Read the last received data item data[nBytes - 1] = static_cast<uint8_t>(spi->DR); + + // Wait until TXE=1 and then wait until BSY=0 before concluding + while ((spi->SR & SPI_SR_TXE) == 0) + ; + while (spi->SR & SPI_SR_BSY) + ; } inline void SPI::transfer(uint16_t *data, size_t nBytes) { - // Cleaer the RX buffer + miosix::FastInterruptDisableLock lock; + + // Clear the RX buffer (void)spi->DR; // Set 16 bit frame format set16BitFrameFormat(); - // Write the first data item to transmit - spi->DR = data[0]; + // Write the first data item to transmitted + spi->DR = static_cast<uint16_t>(data[0]); for (size_t i = 1; i < nBytes / 2; i++) { @@ -546,15 +554,19 @@ inline void SPI::transfer(uint16_t *data, size_t nBytes) data[i - 1] = static_cast<uint16_t>(spi->DR); } - // Wait until data is received - // while ((spi->SR & SPI_SR_RXNE) == 0) - // ; - while (spi->SR & SPI_SR_BSY) + // Wait until the last data item is received + while ((spi->SR & SPI_SR_RXNE) == 0) ; // Read the last received data item data[nBytes / 2 - 1] = static_cast<uint16_t>(spi->DR); + // Wait until TXE=1 and then wait until BSY=0 before concluding + while ((spi->SR & SPI_SR_TXE) == 0) + ; + while (spi->SR & SPI_SR_BSY) + ; + // Go back to 8 bit frame format set8BitFrameFormat(); } diff --git a/src/shared/drivers/spi/SPIBus.h b/src/shared/drivers/spi/SPIBus.h index 0d5b0c0b7faeb8c166fd55b8e454a1409ba22aac..e5865b0511bae4e6750b0908eba08074b6e7d2b3 100644 --- a/src/shared/drivers/spi/SPIBus.h +++ b/src/shared/drivers/spi/SPIBus.h @@ -29,8 +29,8 @@ #ifndef USE_MOCK_PERIPHERALS using SPIType = SPI_TypeDef; #else -#include <test/FakeSpiTypedef.h> -using SPIType = FakeSpiTypedef; +#include <utils/TestUtils/FakeSpiTypedef.h> +using SPIType = Boardcore::FakeSpiTypedef; #endif namespace Boardcore diff --git a/src/shared/drivers/spi/SPIBusInterface.h b/src/shared/drivers/spi/SPIBusInterface.h index f10a7e33228d5b43bf701e5e8178cead2abf8411..1cbdd05ffe6c9a8ba86b82307fe776f1d079a645 100644 --- a/src/shared/drivers/spi/SPIBusInterface.h +++ b/src/shared/drivers/spi/SPIBusInterface.h @@ -30,7 +30,7 @@ using GpioType = miosix::GpioPin; #else #include <utils/TestUtils/MockGpioPin.h> -using GpioType = MockGpioPin; +using GpioType = Boardcore::MockGpioPin; #endif namespace Boardcore @@ -46,16 +46,16 @@ struct SPIBusConfig ///< Peripheral clock division SPI::ClockDivider clockDivider; - ///< Clock polarity and phace configuration + ///< Clock polarity and phase configuration SPI::Mode mode; ///< MSB or LSB first SPI::BitOrder bitOrder; - ///< How long to wait before starting a trasmission after CS is set (us) + ///< How long to wait before starting a tranmission after CS is set (us) unsigned int csSetupTimeUs; - ///< How long to hold cs after the end of a trasmission (us) + ///< How long to hold cs after the end of a tranmission (us) unsigned int csHoldTimeUs; SPIBusConfig(SPI::ClockDivider clockDivider = SPI::ClockDivider::DIV_256, @@ -67,9 +67,6 @@ struct SPIBusConfig { } - /** - * @brief Custom comparison operator. - */ bool operator==(const SPIBusConfig& other) const { return clockDivider == other.clockDivider && mode == other.mode && @@ -92,7 +89,7 @@ class SPIBusInterface public: SPIBusInterface() {} - ///< Delete copy/move contructors/operators. + ///< Delete copy/move constructors/operators. SPIBusInterface(const SPIBusInterface&) = delete; SPIBusInterface& operator=(const SPIBusInterface&) = delete; SPIBusInterface(SPIBusInterface&&) = delete; diff --git a/src/shared/drivers/spi/SPITransaction.cpp b/src/shared/drivers/spi/SPITransaction.cpp index 8f557ca944a32909c9be63b803666dc1d455c633..faa330d96f5c8e5cc268863a5b72f51f933ffac0 100644 --- a/src/shared/drivers/spi/SPITransaction.cpp +++ b/src/shared/drivers/spi/SPITransaction.cpp @@ -134,9 +134,7 @@ void SPITransaction::transfer(uint16_t* data, size_t size) uint8_t SPITransaction::readRegister(uint8_t reg) { if (writeBit == WriteBit::NORMAL) - { reg |= 0x80; - } bus.select(cs); bus.write(reg); @@ -148,9 +146,7 @@ uint8_t SPITransaction::readRegister(uint8_t reg) void SPITransaction::readRegisters(uint8_t reg, uint8_t* data, size_t size) { if (writeBit == WriteBit::NORMAL) - { reg |= 0x80; - } bus.select(cs); bus.write(reg); @@ -161,9 +157,7 @@ void SPITransaction::readRegisters(uint8_t reg, uint8_t* data, size_t size) void SPITransaction::writeRegister(uint8_t reg, uint8_t data) { if (writeBit == WriteBit::INVERTED) - { reg |= 0x80; - } bus.select(cs); bus.write(reg); @@ -174,9 +168,7 @@ void SPITransaction::writeRegister(uint8_t reg, uint8_t data) void SPITransaction::writeRegisters(uint8_t reg, uint8_t* data, size_t size) { if (writeBit == WriteBit::INVERTED) - { reg |= 0x80; - } bus.select(cs); bus.write(reg); diff --git a/src/shared/drivers/timer/TimestampTimer.cpp b/src/shared/drivers/timer/TimestampTimer.cpp index 8faa0167753afc9907b8d245aeeda165f5fb4971..993949a8d38d79a077671bec6f9afb1ee4c8726e 100644 --- a/src/shared/drivers/timer/TimestampTimer.cpp +++ b/src/shared/drivers/timer/TimestampTimer.cpp @@ -27,21 +27,21 @@ namespace Boardcore { -TimestampTimer::TimestampTimer() +#ifndef COMPILE_FOR_HOST + +namespace TimestampTimer { - initTimestampTimer(); - enableTimestampTimer(); -} -#ifndef COMPILE_FOR_HOST +GP32bitTimer timestampTimer = initTimestampTimer(); -TIM_TypeDef *TimestampTimer::getTimer() { return timer.getTimer(); } +} // namespace TimestampTimer -void TimestampTimer::resetTimestamp() { timer.setCounter(0); } +void TimestampTimer::resetTimestamp() { timestampTimer.setCounter(0); } // TODO: Keep support for STM32F103 -void TimestampTimer::initTimestampTimer() +GP32bitTimer TimestampTimer::initTimestampTimer() { + GP32bitTimer timer = GP32bitTimer{TIM2}; { miosix::FastInterruptDisableLock dLock; // Enable TIM2 peripheral clock @@ -55,34 +55,18 @@ void TimestampTimer::initTimestampTimer() // Generate an update event to apply the new prescaler value timer.generateUpdate(); + timestampTimer.enable(); + PrintLogger logger = Logging::getLogger("timestamptimer"); LOG_INFO(logger, "Initialized timestamp timer"); -} - -void TimestampTimer::enableTimestampTimer() -{ - timer.enable(); - PrintLogger logger = Logging::getLogger("timestamptimer"); - LOG_INFO(logger, "Enabled timestamp timer"); + return timer; } #else void TimestampTimer::resetTimestamp() {} -void TimestampTimer::initTimestampTimer() -{ - PrintLogger logger = Logging::getLogger("timestamptimer"); - LOG_INFO(logger, "Initialized timestamp timer [COMPILE_FOR_HOST]"); -} - -void TimestampTimer::enableTimestampTimer() -{ - PrintLogger logger = Logging::getLogger("timestamptimer"); - LOG_INFO(logger, "Enabled timestamp timer [COMPILE_FOR_HOST]"); -} - #endif } // namespace Boardcore diff --git a/src/shared/drivers/timer/TimestampTimer.h b/src/shared/drivers/timer/TimestampTimer.h index 8b2bc6f2f445bc0a21f3fd32bd754be102759e25..f3da4e2c861e6631d3e37fc6afba8adeefb37dda 100644 --- a/src/shared/drivers/timer/TimestampTimer.h +++ b/src/shared/drivers/timer/TimestampTimer.h @@ -48,55 +48,44 @@ namespace Boardcore * For timer resolution and duration refer to : * https://docs.google.com/spreadsheets/d/1FiNDVU7Rg98yZzz1dZ4GDAq3-nEg994ziezCawJ-OK4/edit?usp=sharing */ -class TimestampTimer : public Singleton<TimestampTimer> +namespace TimestampTimer { - friend class Singleton<TimestampTimer>; - -public: - /** - * @brief Preferred timer clock frequency. - */ - static constexpr uint32_t TIMER_FREQUENCY = 250000; - - /** - * @brief Resets the timestamp timer to 0. - */ - void resetTimestamp(); - - /** - * @brief Compute the current timer value in microseconds. - * - * @return Current timestamp in microseconds. - */ - uint64_t getTimestamp(); -#ifndef COMPILE_FOR_HOST - TIM_TypeDef *getTimer(); -#endif - -private: - TimestampTimer(); +/** + * @brief Preferred timer clock frequency. + */ +static constexpr uint32_t TIMER_FREQUENCY = 250000; - /** - * @brief Initialize the timer. - * - * Enables the timer clock, resets the timer registers and sets che correct - * timer configuration. - */ - void initTimestampTimer(); +/** + * @brief Resets the timestamp timer to 0. + */ +void resetTimestamp(); - /** - * @brief Starts the timer peripheral. - */ - void enableTimestampTimer(); +/** + * @brief Compute the current timer value in microseconds. + * + * @return Current timestamp in microseconds. + */ +uint64_t getTimestamp(); #ifndef COMPILE_FOR_HOST - /** - * @brief TimestampTimer defaults to TIM2. - */ - GP32bitTimer timer = GP32bitTimer{TIM2}; + +/** + * @brief Initialize the timer. + * + * Enables the timer clock, resets the timer registers and sets che correct + * timer configuration. + */ +GP32bitTimer initTimestampTimer(); + +/** + * @brief TimestampTimer defaults to TIM2. + */ +extern GP32bitTimer timestampTimer; + #endif -}; + +}; // namespace TimestampTimer inline uint64_t TimestampTimer::getTimestamp() { @@ -105,7 +94,7 @@ inline uint64_t TimestampTimer::getTimestamp() #else // With a timer frequency of 250KHz, the conversion from timer ticks to // microseconds only take a 2 byte shift (x4) - return static_cast<uint64_t>(timer.readCounter() << 2); + return static_cast<uint64_t>(timestampTimer.readCounter() << 2); // If the timer frequency is not a multiple of 2 you must compute the value // this way: diff --git a/src/shared/drivers/usart/USART.cpp b/src/shared/drivers/usart/USART.cpp index bc5612a0855997b158c2a1cc5f35c2b01248ce94..765b4dfcc828c6213a8d385822eb789ef40fa9ee 100644 --- a/src/shared/drivers/usart/USART.cpp +++ b/src/shared/drivers/usart/USART.cpp @@ -251,29 +251,6 @@ namespace Boardcore USARTInterface::~USARTInterface() {} -bool USARTInterface::initPins(miosix::GpioPin tx, int nAFtx, miosix::GpioPin rx, - int nAFrx) -{ - if (pinInitialized) - { - return false; - } - - miosix::FastInterruptDisableLock dLock; - - this->tx = tx; - this->rx = rx; - - tx.mode(miosix::Mode::ALTERNATE); - tx.alternateFunction(nAFtx); - - rx.mode(miosix::Mode::ALTERNATE); - rx.alternateFunction(nAFrx); - - pinInitialized = true; - return true; -} - void USART::IRQhandleInterrupt() { char c; @@ -315,112 +292,44 @@ USART::USART(USARTType *usart, Baudrate baudrate, unsigned int queueLen) { case USART1_BASE: this->id = 1; - initPins(u1tx1::getPin(), 7, u1rx1::getPin(), 7); - irqn = USART1_IRQn; + irqn = USART1_IRQn; break; case USART2_BASE: this->id = 2; - initPins(u2tx1::getPin(), 7, u2rx1::getPin(), 7); - irqn = USART2_IRQn; + irqn = USART2_IRQn; break; case USART3_BASE: this->id = 3; - initPins(u3tx1::getPin(), 7, u3rx1::getPin(), 7); - irqn = USART3_IRQn; + irqn = USART3_IRQn; break; case UART4_BASE: this->id = 4; - initPins(u4tx1::getPin(), 8, u4rx1::getPin(), 8); - irqn = UART4_IRQn; + irqn = UART4_IRQn; break; case UART5_BASE: this->id = 5; - initPins(u5tx::getPin(), 8, u5rx::getPin(), 8); - irqn = UART5_IRQn; + irqn = UART5_IRQn; break; case USART6_BASE: this->id = 6; - initPins(u6tx1::getPin(), 8, u6rx1::getPin(), 8); - irqn = USART6_IRQn; + irqn = USART6_IRQn; break; #ifdef STM32F429xx case UART7_BASE: this->id = 7; - initPins(u7tx1::getPin(), 8, u7rx1::getPin(), 8); - irqn = UART7_IRQn; + irqn = UART7_IRQn; break; case UART8_BASE: this->id = 8; - initPins(u8tx::getPin(), 8, u8rx::getPin(), 8); - irqn = UART8_IRQn; + irqn = UART8_IRQn; break; #endif // STM32F429xx } - commonConstructor(usart, baudrate); -} - -USART::USART(USARTType *usart, Baudrate baudrate, miosix::GpioPin tx, - miosix::GpioPin rx, unsigned int queueLen) - : rxQueue(queueLen) -{ - // Setting the id of the serial port - switch (reinterpret_cast<uint32_t>(usart)) - { - case USART1_BASE: - this->id = 1; - initPins(tx, 7, rx, 7); - irqn = USART1_IRQn; - break; - case USART2_BASE: - this->id = 2; - initPins(tx, 7, rx, 7); - irqn = USART2_IRQn; - break; - case USART3_BASE: - this->id = 3; - initPins(tx, 7, rx, 7); - irqn = USART3_IRQn; - break; - case UART4_BASE: - this->id = 4; - initPins(tx, 8, rx, 8); - irqn = UART4_IRQn; - break; - case UART5_BASE: - this->id = 5; - initPins(tx, 8, rx, 8); - irqn = UART5_IRQn; - break; - case USART6_BASE: - this->id = 6; - initPins(tx, 8, rx, 8); - irqn = USART6_IRQn; - break; -#ifdef STM32F429xx - case UART7_BASE: - this->id = 7; - initPins(tx, 8, rx, 8); - irqn = UART7_IRQn; - break; - case UART8_BASE: - this->id = 8; - initPins(tx, 8, rx, 8); - irqn = UART8_IRQn; - break; -#endif // STM32F429xx - } - - commonConstructor(usart, baudrate); -} - -void USART::commonConstructor(USARTType *usart, Baudrate baudrate) -{ this->usart = usart; - // Enabling the peripehral on the right APB + // Enabling the peripheral on the right APB ClockUtils::enablePeripheralClock(usart); - RCC_SYNC(); // Enabling the usart peripheral { @@ -440,25 +349,23 @@ void USART::commonConstructor(USARTType *usart, Baudrate baudrate) USART::~USART() { - { - miosix::FastInterruptDisableLock dLock; + miosix::FastInterruptDisableLock dLock; - // Take out the usart object we are going to destruct - USART::ports[this->id - 1] = nullptr; + // Take out the usart object we are going to destruct + USART::ports[this->id - 1] = nullptr; - // Disabling the usart - usart->CR1 &= ~(USART_CR1_UE | USART_CR1_TE | USART_CR1_RE); + // Disabling the usart + usart->CR1 &= ~(USART_CR1_UE | USART_CR1_TE | USART_CR1_RE); - // Disabling the interrupt of the serial port - NVIC_DisableIRQ(irqn); - } + // Disabling the interrupt of the serial port + NVIC_DisableIRQ(irqn); } bool USART::init() { - if (id < 1 || id > MAX_SERIAL_PORTS || !pinInitialized) + if (id < 1 || id > MAX_SERIAL_PORTS) { - TRACE("Not supported USART id or pins not initialized\n"); + TRACE("Not supported USART id\n"); return false; } @@ -606,7 +513,7 @@ int USART::write(void *buffer, size_t nBytes) // TODO: Use the send complete interrupt in order not to have a busy while // loop waiting const char *buf = reinterpret_cast<const char *>(buffer); - size_t i = 0; + size_t i; for (i = 0; i < nBytes; i++) { while ((usart->SR & USART_SR_TXE) == 0) @@ -663,6 +570,11 @@ STM32SerialWrapper::STM32SerialWrapper(USARTType *usart, Baudrate baudrate) initPins(u3tx1::getPin(), 7, u3rx1::getPin(), 7); this->serialPortName = std::string("usart3"); break; + case UART4_BASE: + this->id = 4; + initPins(u4tx1::getPin(), 8, u4rx1::getPin(), 8); + this->serialPortName = std::string("uart4"); + break; } initialized = false; fd = -1; @@ -687,8 +599,17 @@ STM32SerialWrapper::STM32SerialWrapper(USARTType *usart, Baudrate baudrate, this->id = 3; this->serialPortName = std::string("usart3"); break; + case UART4_BASE: + this->id = 4; + this->serialPortName = std::string("uart4"); + break; } - initPins(tx, 7, rx, 7); + + if (id < 4) + initPins(tx, 7, rx, 7); + else + initPins(tx, 8, rx, 8); + initialized = false; fd = -1; } @@ -703,7 +624,7 @@ STM32SerialWrapper::~STM32SerialWrapper() bool STM32SerialWrapper::init() { - if (id > 3) + if (id > 4) { TRACE( "[STM32SerialWrapper] USART id greater than 3 is not supported\n"); @@ -761,6 +682,27 @@ bool STM32SerialWrapper::serialCommSetup() return true; } +bool STM32SerialWrapper::initPins(miosix::GpioPin tx, int nAFtx, + miosix::GpioPin rx, int nAFrx) +{ + if (pinInitialized) + return false; + + miosix::FastInterruptDisableLock dLock; + + this->tx = tx; + this->rx = rx; + + tx.mode(miosix::Mode::ALTERNATE); + tx.alternateFunction(nAFtx); + + rx.mode(miosix::Mode::ALTERNATE); + rx.alternateFunction(nAFrx); + + pinInitialized = true; + return true; +} + int STM32SerialWrapper::writeString(const char *data) { // strlen + 1 in order to send the '/0' terminated string diff --git a/src/shared/drivers/usart/USART.h b/src/shared/drivers/usart/USART.h index 05cee3a1662984393fc8790c31dab329eb1f201c..b06b19ea903b9ad6abd6d830ca7862e4c411a2e3 100644 --- a/src/shared/drivers/usart/USART.h +++ b/src/shared/drivers/usart/USART.h @@ -34,6 +34,7 @@ using USARTType = USART_TypeDef; #else // TODO: Create test utils +using USARTType = USART_TypeDef; #endif #ifdef STM32F429xx @@ -101,6 +102,7 @@ typedef miosix::Gpio<GPIOE_BASE, 0> u8rx; namespace Boardcore { + /** * @brief Abstract class that implements the interface for the USART/UART serial * communication. @@ -155,24 +157,11 @@ public: int getId() { return id; }; protected: - /** - * @brief Initializes the pins with the appropriate alternate functions. - * - * @param tx Tranmission pin. - * @param nAFtx Tranmission pin alternate function. - * @param rx Reception pin. - * @param nAFrx Reception pin alternate function. - */ - bool initPins(miosix::GpioPin tx, int nAFtx, miosix::GpioPin rx, int nAFrx); - - ///< True if initPins() already called successfully, false otherwise - bool pinInitialized = false; - miosix::GpioPin tx{GPIOA_BASE, 0}; miosix::GpioPin rx{GPIOA_BASE, 0}; USARTType *usart; - int id = 1; ///< Can be 1, 2, 3, 4, 5, 6, 7, 8 + int id = -1; ///< Can be from 1 to 8, -1 is invalid bool initialized = false; Baudrate baudrate; ///< Baudrate of the serial communication }; @@ -214,15 +203,7 @@ public: * * Sets the default values for all the parameters (1 stop bit, 8 bit data, * no control flow and no oversampling). - * Initializes the serial port using the default pins, which are: - * - USART1: tx=PA9 rx=PA10 - * - USART2: tx=PA2 rx=PA3 - * - USART3: tx=PB10 rx=PB11 - * - UART4: tx=PA0 rx=PA1 - * - UART5: tx=PC12 rx=PD2 - * - USART6: tx=PC6 rx=PC7 - * - UART7: tx=PE8 rx=PE7 - * - UART8: tx=PE1 rx=PE0 + * Requires that the gpios are configured for the choosen uart. * * @param usart structure that represents the usart peripheral [accepted * are: USART1, USART2, USART3, UART4, UART5, USART6, UART7, UART8]. @@ -232,30 +213,12 @@ public: USART(USARTType *usart, Baudrate baudrate, unsigned int queueLen = usart_queue_default_capacity); - /** - * @brief Automatically enables the peripheral and timer peripheral clock. - * - * Sets the default values for all the parameters (1 stop bit, 8 bit data, - * no control flow and no oversampling). - * Initializes the serial port using custom pins. - * - * @param usart Structure that represents the usart peripheral [accepted - * are: USART1, USART2, USART3, UART4, UART5, USART6, UART7, UART8]. - * @param baudrate Member of the enum Baudrate that represents the baudrate - * with which the communication will take place. - * @param tx Tranmission pin. - * @param rx Reception pin. - */ - USART(USARTType *usart, Baudrate baudrate, miosix::GpioPin tx, - miosix::GpioPin rx, - unsigned int queueLen = usart_queue_default_capacity); - /** * @brief Disables the flags for the generation of the interrupts, the IRQ * from the NVIC, the peripheral and removes his pointer from the ports * list. */ - ~USART(); + ~USART() override; /** * @brief Initializes the peripheral enabling his interrupts, the interrupts @@ -265,23 +228,23 @@ public: * All the setup phase must be done before the initialization of the * peripheral. The pins must be initialized before calling this function. */ - bool init(); + bool init() override; /** * @brief Blocking read operation to read nBytes or till the data transfer * is complete. */ - int read(void *buffer, size_t nBytes); + int read(void *buffer, size_t nBytes) override; /** * @brief Blocking write operation. */ - int write(void *buf, size_t nChars); + int write(void *buf, size_t nChars) override; /** * @brief Write a string to the serial, comprising the '\0' character. */ - int writeString(const char *buffer); + int writeString(const char *buffer) override; /** * @brief Set the length of the word to 8 or to 9. @@ -326,8 +289,6 @@ public: void clearQueue(); private: - void commonConstructor(USARTType *usart, Baudrate baudrate); - IRQn_Type irqn; miosix::FastMutex rxMutex; ///< mutex for receiving on serial miosix::FastMutex txMutex; ///< mutex for transmitting on serial @@ -408,12 +369,25 @@ public: int writeString(const char *buffer); private: + /** + * @brief Initializes the pins with the appropriate alternate functions. + * + * @param tx Tranmission pin. + * @param nAFtx Tranmission pin alternate function. + * @param rx Reception pin. + * @param nAFrx Reception pin alternate function. + */ + bool initPins(miosix::GpioPin tx, int nAFtx, miosix::GpioPin rx, int nAFrx); + /** * @brief Creates a device that represents the serial port, adds it to the * file system and opens the file that represents the device. */ bool serialCommSetup(); + ///< True if initPins() already called successfully, false otherwise + bool pinInitialized = false; + miosix::STM32Serial *serial; ///< Pointer to the serial object //< Port name of the port that has to be created for the communication diff --git a/src/shared/events/EventBroker.cpp b/src/shared/events/EventBroker.cpp index b748fc1e91393133da2709cab2a761fe341ed442..b7029ee58d1c8d662344995825137b5fd0e791fb 100644 --- a/src/shared/events/EventBroker.cpp +++ b/src/shared/events/EventBroker.cpp @@ -29,6 +29,7 @@ namespace Boardcore { EventBroker::EventBroker() {} + void EventBroker::post(const Event& ev, uint8_t topic) { #ifdef TRACE_EVENTS diff --git a/src/shared/logger/LogTypes.h b/src/shared/logger/LogTypes.h index 4df3ac83cf0921490e029d276f9e26510322d316..309457505c60765b646868eed17381dc376ed5fc 100644 --- a/src/shared/logger/LogTypes.h +++ b/src/shared/logger/LogTypes.h @@ -23,7 +23,9 @@ #pragma once #include <actuators/Servo/ServoData.h> +#include <algorithms/ADA/ADAData.h> #include <algorithms/NAS/NASState.h> +#include <diagnostic/CpuMeter/CpuMeter.h> #include <diagnostic/PrintLoggerData.h> #include <drivers/adc/InternalADCData.h> #include <events/EventData.h> @@ -46,16 +48,19 @@ #include <sensors/MPU9250/MPU9250Data.h> #include <sensors/MS5803/MS5803Data.h> #include <sensors/SensorData.h> -#include <sensors/UbloxGPS/UbloxGPSData.h> +#include <sensors/UBXGPS/UBXGPSData.h> #include <sensors/VN100/VN100Data.h> +#include <sensors/analog/AnalogLoadCellData.h> #include <sensors/analog/BatteryVoltageSensorData.h> #include <sensors/analog/CurrentSensorData.h> -#include <sensors/analog/pressure/MPXHZ6130A/MPXHZ6130AData.h> #include <sensors/analog/pressure/honeywell/HSCMAND015PAData.h> #include <sensors/analog/pressure/honeywell/HSCMRNN030PAData.h> #include <sensors/analog/pressure/honeywell/HSCMRNN160KAData.h> #include <sensors/analog/pressure/honeywell/SSCDANN030PAAData.h> #include <sensors/analog/pressure/honeywell/SSCDRRN015PDAData.h> +#include <sensors/analog/pressure/nxp/MPXH6115AData.h> +#include <sensors/analog/pressure/nxp/MPXH6400AData.h> +#include <sensors/analog/pressure/nxp/MPXHZ6130AData.h> #include <fstream> #include <iostream> @@ -75,7 +80,9 @@ namespace LogTypes void registerTypes(Deserializer& ds) { ds.registerType<ServoData>(); + ds.registerType<ADAState>(); ds.registerType<NASState>(); + ds.registerType<CpuMeterData>(); ds.registerType<LoggingString>(); ds.registerType<InternalADCData>(); ds.registerType<EventData>(); @@ -88,6 +95,8 @@ void registerTypes(Deserializer& ds) ds.registerType<BME280Data>(); ds.registerType<BMP280Data>(); ds.registerType<BMX160Data>(); + ds.registerType<BMX160Temperature>(); + ds.registerType<BMX160FifoStats>(); ds.registerType<BMX160WithCorrectionData>(); ds.registerType<HX711Data>(); ds.registerType<L3GD20Data>(); @@ -97,16 +106,19 @@ void registerTypes(Deserializer& ds) ds.registerType<MPU9250Data>(); ds.registerType<MS5803Data>(); ds.registerType<TemperatureData>(); - ds.registerType<UbloxGPSData>(); + ds.registerType<UBXGPSData>(); ds.registerType<VN100Data>(); + ds.registerType<AnalogLoadCellData>(); ds.registerType<BatteryVoltageSensorData>(); ds.registerType<CurrentSensorData>(); - ds.registerType<MPXHZ6130AData>(); ds.registerType<HSCMAND015PAData>(); ds.registerType<HSCMRNN030PAData>(); ds.registerType<HSCMRNN160KAData>(); ds.registerType<SSCDANN030PAAData>(); ds.registerType<SSCDRRN015PDAData>(); + ds.registerType<MPXH6115AData>(); + ds.registerType<MPXH6400AData>(); + ds.registerType<MPXHZ6130AData>(); } } // namespace LogTypes diff --git a/src/shared/logger/Logger.cpp b/src/shared/logger/Logger.cpp index dbb750e96abf5343305b6592145644a5ede1884b..b8c903a79268e22b4c80814f886027bd1f0826e7 100644 --- a/src/shared/logger/Logger.cpp +++ b/src/shared/logger/Logger.cpp @@ -55,9 +55,7 @@ bool Logger::start() filename = getFileName(fileNumber); struct stat st; if (stat(filename.c_str(), &st) != 0) - { break; - } if (fileNumber == maxFilenameNumber - 1) TRACE("Too many log files, appending data to last\n"); @@ -124,6 +122,8 @@ void Logger::stop() fclose(file); + stats = {}; + fileNumber = -1; // Reset the fileNumber to an invalid value } @@ -138,21 +138,33 @@ int Logger::getCurrentLogNumber() { return fileNumber; } string Logger::getCurrentFileName() { return getFileName(fileNumber); } -LoggerStats Logger::getLoggerStats() +LoggerStats Logger::getStats() { - stats.timestamp = TimestampTimer::getInstance().getTimestamp(); + stats.timestamp = TimestampTimer::getTimestamp(); stats.logNumber = fileNumber; return stats; } +void Logger::resetStats() +{ + // Keep some of the statistics persistent + int buffersWritten = stats.buffersWritten; + int writesFailed = stats.writesFailed; + + // Reset + stats = {}; + + // Put back + stats.buffersWritten = buffersWritten; + stats.writesFailed = writesFailed; +} + bool Logger::isStarted() const { return started; } void Logger::logStats() { - log(getLoggerStats()); - - // Reset the logger stats after they have been logger - stats = LoggerStats(); + log(getStats()); + resetStats(); } Logger::Logger() @@ -290,8 +302,9 @@ void Logger::writeThread() stats.buffersWritten++; timer.stop(); - stats.writeTime = timer.interval(); - stats.maxWriteTime = max(stats.maxWriteTime, stats.writeTime); + stats.averageWriteTime = timer.interval(); + stats.maxWriteTime = + max(stats.maxWriteTime, stats.averageWriteTime); { Lock<FastMutex> l(mutex); diff --git a/src/shared/logger/Logger.h b/src/shared/logger/Logger.h index 33e9067a9b9a04c7d4c7f64d0e31028eef45a4d1..7d404ae83eb064d15f9ef793e0f3cac9867eb11b 100644 --- a/src/shared/logger/Logger.h +++ b/src/shared/logger/Logger.h @@ -59,15 +59,15 @@ public: /** * @brief Call this function to start the logger. * - * The function tryies to start the logger. It first opens the log file and - * then create the pack and write threads. If it fails on one of this - * operation, the logger is not started. + * Tries to start the logger, first opens the log file and then create the + * pack and write threads. If it fails on one of this operation, the logger + * is not started. * * Use getCurrentLogNumber to retrieve the log file number. * * Blocking call. May take a long time. * - * \return true if the logger was started correctly. + * \return True if the logger was started correctly. */ bool start(); @@ -91,7 +91,9 @@ public: std::string getCurrentFileName(); - LoggerStats getLoggerStats(); + LoggerStats getStats(); + + void resetStats(); bool isStarted() const; @@ -117,6 +119,8 @@ public: /** * @brief Log logger stats using the logger itself. + * + * The stats are reset after being logged. */ void logStats(); @@ -149,10 +153,17 @@ private: LoggerResult logImpl(const char *name, const void *data, unsigned int size); static constexpr unsigned int maxFilenameNumber = 100; ///< Limit on files - static constexpr unsigned int maxRecordSize = 512; ///< Limit on data +#ifndef _ARCH_CORTEXM3_STM32F2 + static constexpr unsigned int maxRecordSize = 512; ///< Limit on data static constexpr unsigned int numRecords = 512; ///< Size of record queues static constexpr unsigned int numBuffers = 8; ///< Number of buffers static constexpr unsigned int bufferSize = 64 * 1024; ///< Size of buffers +#else + static constexpr unsigned int maxRecordSize = 512; ///< Limit on data + static constexpr unsigned int numRecords = 64; ///< Size of record queues + static constexpr unsigned int numBuffers = 8; ///< Number of buffers + static constexpr unsigned int bufferSize = 4 * 1024; ///< Size of buffers +#endif /** * A record is a single serialized logged class. Records are used to diff --git a/src/shared/logger/LoggerStats.h b/src/shared/logger/LoggerStats.h index 269cebe36411d28330bce4f13e3b7da2704f7327..3879d894f9c483af6a18ca0f9dfe8462afedd000 100644 --- a/src/shared/logger/LoggerStats.h +++ b/src/shared/logger/LoggerStats.h @@ -40,20 +40,20 @@ struct LoggerStats ///< Number of dropped samples because they where too large. int tooLargeSamples = 0; - int droppedSamples = 0; ///< Number of dropped samples due to fifo full. - int queuedSamples = 0; ///< Number of samples written to buffer. - int buffersFilled = 0; ///< Number of buffers filled. - int buffersWritten = 0; ///< Number of buffers written to disk. - int writesFailed = 0; ///< Number of fwrite() that failed. - int lastWriteError = 0; ///< Error of the last fwrite() that failed. - int writeTime = 0; ///< Time to perform an fwrite() of a buffer. - int maxWriteTime = 0; ///< Max time to perform an fwrite() of a buffer. + int droppedSamples = 0; ///< Number of dropped samples due to fifo full. + int queuedSamples = 0; ///< Number of samples written to buffer. + int buffersFilled = 0; ///< Number of buffers filled. + int buffersWritten = 0; ///< Number of buffers written to disk. + int writesFailed = 0; ///< Number of fwrite() that failed. + int lastWriteError = 0; ///< Error of the last fwrite() that failed. + int averageWriteTime = 0; ///< Average time for an fwrite() of a buffer. + int maxWriteTime = 0; ///< Max time for an fwrite() of a buffer. static std::string header() { - return "timestamp,log_number,too_large_samples,dropped_samples," - "queued_samples,buffers_filled,buffers_written,writes_failed," - "last_write_error,write_time,max_write_time\n"; + return "timestamp,logNumber,tooLargeSamples,droppedSamples," + "queuedSamples,buffersFilled,buffersWritten,writesFailed," + "lastWriteError,averageWriteTime,maxWriteTime\n"; } void print(std::ostream& os) const @@ -61,7 +61,8 @@ struct LoggerStats os << timestamp << "," << logNumber << "," << tooLargeSamples << "," << droppedSamples << "," << queuedSamples << "," << buffersFilled << "," << buffersWritten << "," << writesFailed << "," - << lastWriteError << "," << writeTime << "," << maxWriteTime << "\n"; + << lastWriteError << "," << averageWriteTime << "," << maxWriteTime + << "\n"; } }; diff --git a/src/shared/radio/MavlinkDriver/MavlinkDriver.h b/src/shared/radio/MavlinkDriver/MavlinkDriver.h index af6b337a838ae3d117de774606bebb47f62c016f..81607862cfe14f10b7de94b1faf00bd2fcce23bb 100644 --- a/src/shared/radio/MavlinkDriver/MavlinkDriver.h +++ b/src/shared/radio/MavlinkDriver/MavlinkDriver.h @@ -22,15 +22,12 @@ #pragma once -#include <diagnostic/PrintLogger.h> - #include <vector> /** * This object includes only the protocol header (`protocol.h`). To use this * driver, you should include YOUR OWN implementation of the messages definition - * (`mavlink.h`) before including this header. To create your implementation you - * can use Skyward's *Mavlink Editor*. + * (`mavlink.h`) before including this header. */ #ifndef MAVLINK_H #error \ @@ -38,6 +35,7 @@ implementation before including MavlinkDriver.h" #endif +#include <diagnostic/PrintLogger.h> #include <diagnostic/SkywardStack.h> #include <diagnostic/StackLogger.h> #include <mavlink_lib/mavlink_types.h> @@ -58,14 +56,14 @@ namespace Boardcore * @tparam PktLength Maximum length in bytes of each transceiver packet. * @tparam OutQueueSize Max number of transceiver packets in the output queue. * @tparam MavMsgLength Max length of a mavlink message. By default is 255 the - * maximun possible but can be replaces with MAVLINK_MAX_DIALECT_PAYLOAD_SIZE + * maximum possible but can be replaces with MAVLINK_MAX_DIALECT_PAYLOAD_SIZE * for a specific protocol. */ template <unsigned int PktLength, unsigned int OutQueueSize, unsigned int MavMsgLength = MAVLINK_MAX_PAYLOAD_LEN> class MavlinkDriver { - ///< Alias of the function to be executed on message reception. + /// Alias of the function to be executed on message reception. using MavHandler = std::function<void(MavlinkDriver* channel, const mavlink_message_t& msg)>; @@ -84,10 +82,16 @@ public: /** * @brief Start the receiving and sending threads. - * @return false if at least one could not start. + * + * @return False if at least one could not start. */ bool start(); + /** + * @brief Tells whether the driver was started. + */ + bool isStarted(); + /** * @brief Stops sender and receiver threads. */ @@ -98,10 +102,30 @@ public: * Message is discarded if the queue is full. * * @param msg Message to send (mavlink struct). - * @return true if the message could be enqueued (queue not full). + * @return True if the message could be enqueued. */ bool enqueueMsg(const mavlink_message_t& msg); + /** + * @brief Enqueue a raw packet message into the sync packet queue. + * + * @param msg Message to send. + * @param size Length in bytes. + * @return True if the message was enqueued. + */ + bool enqueueRaw(uint8_t* msg, size_t size); + + /** + * @brief Synchronized status getter. + */ + MavlinkStatus getStatus(); + + /** + * @brief Setter for the sleep after send value. + */ + void setSleepAfterSend(uint16_t newSleepTime); + +private: /** * @brief Receiver thread: reads one char at a time from the transceiver and * tries to parse a mavlink message. @@ -110,28 +134,20 @@ public: * executed. */ void runReceiver(); + /** * @brief Sender Thread: Periodically flushes the message queue and sends * all the enqueued messages. + * * After every send, the thread sleeps to guarantee some silence on the * channel. */ void runSender(); /** - * @brief Synchronized status getter - */ - MavlinkStatus getStatus(); - - /** - * @brief Setter for the sleep after send value. - */ - void setSleepAfterSend(uint16_t newSleepTime); - -private: - /** - * @brief Calls the run member function - * @param arg the object pointer cast to void* + * @brief Calls the run member function. + * + * @param arg The object pointer cast to void*. */ static void rcvLauncher(void* arg) { @@ -139,20 +155,21 @@ private: } /** - * @brief Calls the run member function - * @param arg the object pointer cast to void* + * @brief Calls the run member function. + * + * @param arg The object pointer cast to void*. */ static void sndLauncher(void* arg) { reinterpret_cast<MavlinkDriver*>(arg)->runSender(); } - void updateQueueStats(int dropped); + void updateQueueStats(bool appended); void updateSenderStats(size_t msgCount, bool sent); - Transceiver* device; // transceiver used to send and receive - MavHandler onReceive; // function executed on message rcv + Transceiver* device; ///< Transceiver used to send and receive packets. + MavHandler onReceive; ///< Function executed when a message is ready. // Tweakable params uint16_t sleepAfterSend; @@ -224,9 +241,16 @@ bool MavlinkDriver<PktLength, OutQueueSize, MavMsgLength>::start() } if (sndStarted && rcvStarted) - LOG_DEBUG(logger, "Start ok (sender and receiver)\n"); + LOG_DEBUG(logger, "Sender and receiver started"); + + return sndStarted && rcvStarted; +} - return (sndStarted && rcvStarted); +template <unsigned int PktLength, unsigned int OutQueueSize, + unsigned int MavMsgLength> +bool MavlinkDriver<PktLength, OutQueueSize, MavMsgLength>::isStarted() +{ + return sndStarted && rcvStarted; } template <unsigned int PktLength, unsigned int OutQueueSize, @@ -245,27 +269,42 @@ bool MavlinkDriver<PktLength, OutQueueSize, MavMsgLength>::enqueueMsg( const mavlink_message_t& msg) { // Convert mavlink message to a byte array - uint8_t msgtempBuf[MAVLINK_NUM_NON_PAYLOAD_BYTES + MavMsgLength]; - int msgLen = mavlink_msg_to_send_buffer(msgtempBuf, &msg); + uint8_t msgTempBuf[MAVLINK_NUM_NON_PAYLOAD_BYTES + MavMsgLength]; + int msgLen = mavlink_msg_to_send_buffer(msgTempBuf, &msg); + + // Append the message to the queue + bool appended = outQueue.put(msgTempBuf, msgLen); + + // Update stats + updateQueueStats(appended); + + // Return ok even if a packet was discarded + return appended; +} +template <unsigned int PktLength, unsigned int OutQueueSize, + unsigned int MavMsgLength> +bool MavlinkDriver<PktLength, OutQueueSize, MavMsgLength>::enqueueRaw( + uint8_t* msg, size_t size) +{ // Append message to the queue - int dropped = outQueue.put(msgtempBuf, msgLen); + bool appended = outQueue.put(msg, size); // Update stats - updateQueueStats(dropped); + updateQueueStats(appended); - // return ok even if a packet was discarded - return dropped != -1; + // Return ok even if a packet was discarded + return appended; } template <unsigned int PktLength, unsigned int OutQueueSize, unsigned int MavMsgLength> void MavlinkDriver<PktLength, OutQueueSize, MavMsgLength>::updateQueueStats( - int dropped) + bool appended) { miosix::Lock<miosix::FastMutex> l(mtxStatus); - if (dropped != 0) + if (!appended) { LOG_ERR(logger, "Buffer full, the oldest message has been discarded"); status.nDroppedPackets++; @@ -345,8 +384,7 @@ void MavlinkDriver<PktLength, OutQueueSize, MavMsgLength>::runSender() pkt = outQueue.get(); // If the packet is ready or too old, send it - uint64_t age = TimestampTimer::getInstance().getTimestamp() - - pkt.getTimestamp(); + uint64_t age = TimestampTimer::getTimestamp() - pkt.getTimestamp(); if (pkt.isReady() || age >= outBufferMaxAge * 1e3) { outQueue.pop(); // Remove the packet from queue @@ -392,7 +430,7 @@ template <unsigned int PktLength, unsigned int OutQueueSize, MavlinkStatus MavlinkDriver<PktLength, OutQueueSize, MavMsgLength>::getStatus() { miosix::Lock<miosix::FastMutex> l(mtxStatus); - status.timestamp = miosix::getTick(); + status.timestamp = TimestampTimer::getTimestamp(); return status; } diff --git a/src/shared/radio/MavlinkDriver/MavlinkStatus.h b/src/shared/radio/MavlinkDriver/MavlinkStatus.h index 863aa7daba9c27e61c24fd02ddeb2601670dab09..e10e8cf34fa17451075a3953e6dab4738bde2137 100644 --- a/src/shared/radio/MavlinkDriver/MavlinkStatus.h +++ b/src/shared/radio/MavlinkDriver/MavlinkStatus.h @@ -33,21 +33,19 @@ namespace Boardcore struct MavlinkStatus { uint64_t timestamp; - uint16_t nSendQueue; // current len of the occupied portion of the queue - uint16_t maxSendQueue; // max occupied len of the queue - uint16_t nSendErrors; // Number of failed sends - uint16_t nDroppedPackets; // number of packet drops + uint16_t nSendQueue; ///< Current len of the occupied portion of the queue + uint16_t maxSendQueue; ///< Max occupied len of the queue + uint16_t nSendErrors; ///< Number of failed sends + uint16_t nDroppedPackets; ///< Number of packet drops mavlink_status_t mavStats; static std::string header() { return "timestamp,n_send_queue,max_send_queue,n_send_errors,n_dropped_" - "packets,mav_stats." - "buffer_overrun,mav_stats.msg_received,mav_stats.parse_error," - "mav_stats.parse_state, " - "mav_stats.packet_idx,mav_stats.current_rx_seq,mav_stats." - "current_tx_seq,mav_stats.packet_rx_success_count,mav_stats." - "packet_rx_drop_count\n"; + "packets,mav_stats.buffer_overrun,mav_stats.msg_received,mav_" + "stats.parse_error,mav_stats.parse_state,mav_stats.packet_idx," + "mav_stats.current_rx_seq,mav_stats.current_tx_seq,mav_stats." + "packet_rx_success_count,mav_stats.packet_rx_drop_count\n"; } void print(std::ostream& os) const diff --git a/src/shared/radio/SX1278/SX1278.cpp b/src/shared/radio/SX1278/SX1278.cpp index bed1ae549d6daf57f3b77e8f6f0787c3efa9b5d9..f2765db503a1b78ce70c86e7b1af9d914a8a861f 100644 --- a/src/shared/radio/SX1278/SX1278.cpp +++ b/src/shared/radio/SX1278/SX1278.cpp @@ -156,15 +156,16 @@ SX1278::SX1278(SPIBusInterface &bus, miosix::GpioPin cs) : bus_mgr(bus, cs) {} SX1278::Error SX1278::init(Config config) { - // Lock the bus - bus_mgr.lock(Mode::MODE_STDBY); - bus_mgr.waitForIrq(RegIrqFlags::MODE_READY); - + // Do an early version check to avoid stalling on non-working device if (getVersion() != 0x12) { return Error::BAD_VERSION; } + // Lock the bus + bus_mgr.lock(Mode::MODE_STDBY); + bus_mgr.waitForIrq(RegIrqFlags::MODE_READY); + setBitrate(config.bitrate); setFreqDev(config.freq_dev); setFreqRF(config.freq_rf); @@ -200,7 +201,7 @@ SX1278::Error SX1278::init(Config config) spi.writeRegister(REG_RX_TIMEOUT_3, 0x00); spi.writeRegister(REG_PACKET_CONFIG_1, RegPacketConfig1::PACKET_FORMAT_VARIABLE_LENGTH | - RegPacketConfig1::DC_FREE_NONE | + RegPacketConfig1::DC_FREE_MANCHESTER | RegPacketConfig1::CRC_ON | RegPacketConfig1::ADDRESS_FILTERING_NONE | RegPacketConfig1::CRC_WHITENING_TYPE_CCITT_CRC); diff --git a/src/shared/radio/SX1278/SX1278Defs.h b/src/shared/radio/SX1278/SX1278Defs.h index 06954099644e8a7b6d6b6566e0ad7d2ef1118f3b..e573f1bfff65211a6574c3b03c44903d8e2f0c45 100644 --- a/src/shared/radio/SX1278/SX1278Defs.h +++ b/src/shared/radio/SX1278/SX1278Defs.h @@ -60,7 +60,7 @@ inline SPIBusConfig spiConfig() // FIXME(davide.mor): This depends on the device config.clockDivider = SPI::ClockDivider::DIV_64; - config.mode = SPI::Mode::MODE_1; + config.mode = SPI::Mode::MODE_0; config.bitOrder = SPI::BitOrder::MSB_FIRST; // config.cs_setup_time_us = 30; // config.cs_hold_time_us = 100; diff --git a/src/shared/radio/SerialTransceiver/SerialTransceiver.h b/src/shared/radio/SerialTransceiver/SerialTransceiver.h index 6d49174699d56e0431467c9c09a042be9ba9fcbd..f5e0ae00b22a814f475341a31626bf1548bb6bcf 100644 --- a/src/shared/radio/SerialTransceiver/SerialTransceiver.h +++ b/src/shared/radio/SerialTransceiver/SerialTransceiver.h @@ -22,6 +22,7 @@ #pragma once +#include <drivers/usart/USART.h> #include <radio/Transceiver.h> #include <iostream> @@ -33,19 +34,21 @@ namespace Boardcore class SerialTransceiver : public Transceiver { public: + SerialTransceiver(USARTInterface& usart) : usart(usart) {} + bool send(uint8_t* packet, size_t packetLength) { - for (size_t i = 0; i < packetLength; i++) - std::cout << packet[i]; - std::cout << "\n"; + usart.write(packet, packetLength); return true; } ssize_t receive(uint8_t* packet, size_t packetLength) { - std::cin.read(reinterpret_cast<char*>(packet), packetLength); - return packetLength; + return usart.read(packet, packetLength); } + +private: + USARTInterface& usart; }; -} // namespace Boardcore \ No newline at end of file +} // namespace Boardcore diff --git a/src/shared/radio/Xbee/Xbee.cpp b/src/shared/radio/Xbee/Xbee.cpp index 0c5b04ff9d37ca8a5a9af4012f6f0d254b777ac9..35553d134b2a3598838e5c728cc9f327c08f7e55 100644 --- a/src/shared/radio/Xbee/Xbee.cpp +++ b/src/shared/radio/Xbee/Xbee.cpp @@ -56,18 +56,18 @@ Xbee::Xbee(SPIBusInterface& bus, SPIBusConfig config, GpioType cs, Xbee::~Xbee() { wakeReceiver(true); } -bool Xbee::send(uint8_t* pkt, size_t packeLength) +bool Xbee::send(uint8_t* pkt, size_t packetLength) { - if (packeLength > MAX_PACKET_PAYLOAD_LENGTH || packeLength == 0) + if (packetLength > MAX_PACKET_PAYLOAD_LENGTH || packetLength == 0) { - LOG_ERR(logger, "Invalid packet length (0< {} <= {})", packeLength, + LOG_ERR(logger, "Invalid packet length (0< {} <= {})", packetLength, MAX_PACKET_PAYLOAD_LENGTH); return false; } long long startTick = miosix::getTick(); TXRequestFrame txReq; - uint8_t txFrameId = buildTXRequestFrame(txReq, pkt, packeLength); + uint8_t txFrameId = buildTXRequestFrame(txReq, pkt, packetLength); bool success = false; bool statusTimeout = true; { @@ -99,9 +99,8 @@ bool Xbee::send(uint8_t* pkt, size_t packeLength) // If there is more data to receive, wake the receive() thread if (attn.value() == 0) - { wakeReceiver(); - } + if (statusTimeout) { ++status.txTimeoutCount; @@ -120,9 +119,8 @@ ssize_t Xbee::receive(uint8_t* buf, size_t bufMaxSize) { // We have data in the buffer pending to be returned if (!rxFramesBuffer.isEmpty() || currRxPayloadPointer >= 0) - { return fillReceiveBuf(buf, bufMaxSize); - } + // No data in the buffer, but the xbee has data to return via SPI else if (attn.value() == 0) { @@ -199,9 +197,7 @@ void Xbee::reset() handleFrame(parsingApiFrame); if (parsingApiFrame.frameType == FTYPE_MODEM_STATUS) - { break; - } } miosix::Thread::sleep(5); } while (miosix::getTick() < timeout); @@ -226,9 +222,8 @@ void Xbee::handleATTNInterrupt() receiveThread->IRQwakeup(); if (receiveThread->IRQgetPriority() > miosix::Thread::IRQgetCurrentThread()->IRQgetPriority()) - { miosix::Scheduler::IRQfindNextThread(); - } + receiveThread = 0; } } @@ -290,9 +285,7 @@ bool Xbee::readRXFrame() handleFrame(parsingApiFrame); if (parsingApiFrame.frameType == FTYPE_RX_PACKET_FRAME) - { return true; - } } } return false; @@ -313,9 +306,7 @@ void Xbee::writeFrame(APIFrame& frame) // Pass the frame we just sent to the listener if (frameListener) - { frameListener(frame); - } // Full duplex spi transfer: we may have received valid data while we // were sending the frame. @@ -323,9 +314,7 @@ void Xbee::writeFrame(APIFrame& frame) { ParseResult res = parser.parse(txBuf[i], &parsingApiFrame); if (res == ParseResult::SUCCESS) - { handleFrame(parsingApiFrame); - } } } @@ -341,9 +330,7 @@ bool Xbee::waitForFrame(uint8_t frameType, unsigned int pollInterval, handleFrame(parsingApiFrame); if (parsingApiFrame.frameType == frameType) - { return true; - } } } else @@ -356,10 +343,10 @@ bool Xbee::waitForFrame(uint8_t frameType, unsigned int pollInterval, } uint8_t Xbee::buildTXRequestFrame(TXRequestFrame& txReq, uint8_t* pkt, - size_t packeLength) + size_t packetLength) { - memcpy(txReq.getRFDataPointer(), pkt, packeLength); - txReq.setRFDataLength(packeLength); + memcpy(txReq.getRFDataPointer(), pkt, packetLength); + txReq.setRFDataLength(packetLength); uint8_t txFrameId = getNewFrameID(); @@ -459,14 +446,12 @@ void Xbee::handleFrame(APIFrame& frame) Lock<FastMutex> l(mutexRxFrames); if (rxFramesBuffer.isFull()) - { ++status.rxDroppedBuffers; - } + rxFramesBuffer.put(*pf); + if (rxFramesBuffer.count() > status.frameBufMaxLength) - { status.frameBufMaxLength = rxFramesBuffer.count(); - } } wakeReceiver(); break; @@ -490,10 +475,10 @@ void Xbee::handleFrame(APIFrame& frame) { TXStatusFrame* ts = frame.toFrameType<TXStatusFrame>(); status.lastTxStatus = ts->getDeliveryStatus(); + if (status.lastTxStatus != DELS_SUCCESS) - { status.lastTxStatusError = status.lastTxStatus; - } + switch (status.lastTxStatus) { case DELS_SUCCESS: @@ -513,9 +498,7 @@ void Xbee::handleFrame(APIFrame& frame) // Pass the frame to the listener if (frameListener) - { frameListener(frame); - } } void Xbee::setOnFrameReceivedListener(OnFrameReceivedListener listener) diff --git a/src/shared/radio/Xbee/Xbee.h b/src/shared/radio/Xbee/Xbee.h index abb1be5015ba548258ab5207dd6abccff0bbd00a..fde68bbaccbf98a75a1f6d270a26959fcb2fbf15 100644 --- a/src/shared/radio/Xbee/Xbee.h +++ b/src/shared/radio/Xbee/Xbee.h @@ -94,19 +94,19 @@ public: * not wait for an ACK or send confirmation from the Xbee. Thus, it always * returns true. * - * @param pkt Pointer to the packet (needs to be at least packetLength + * @param pkt Pointer to the packet (needs to be at least packetLength * bytes). - * @param packetLength Lenght of the packet to be sent. - * @return Always true + * @param packetLength Length of the packet to be sent. + * @return Always true */ bool send(uint8_t* pkt, size_t packetLength) override; /** * @brief Waits until a new packet is received. * - * @param buf Buffer to store the received packet into. - * @param bufferMaxSize Maximum length of the received data. - * @return Size of the data received or -1 if failure + * @param buf Buffer to store the received packet into. + * @param bufferMaxSize Maximum length of the received data. + * @return Size of the data received or -1 if failure */ ssize_t receive(uint8_t* buf, size_t bufferMaxSize) override; @@ -117,8 +117,8 @@ public: /** * @brief Signals the receive() function that there is new data available. - * Call this from the ATTN pin interrupt servirce routine, and nowhere else - * plese. + * Call this from the ATTN pin interrupt service routine, and nowhere else + * please. * */ void handleATTNInterrupt(); @@ -231,7 +231,7 @@ private: /** * @brief Waits until an APIFrame with frame type \p frameType is received * on the SPI or until the timeouts expires. The frame is then stored in the - * parsingApiFrame local class varibale. Any frame received by this + * parsingApiFrame local class variable. Any frame received by this * function is automatically passed to the handleFrame() function * @attention mutexXbeeCommunication must be locked before calling this * function. diff --git a/src/shared/scheduler/TaskScheduler.cpp b/src/shared/scheduler/TaskScheduler.cpp index 0518b34d9e8b23c4a65efc67804e1b1edbd87125..06ad343544bc8afedb9ff66dd2d34648743da71d 100644 --- a/src/shared/scheduler/TaskScheduler.cpp +++ b/src/shared/scheduler/TaskScheduler.cpp @@ -46,6 +46,9 @@ bool TaskScheduler::addTask(function_t function, uint32_t period, uint8_t id, Task task = {function, period, id, policy, -1, {}, {}, {}, 0, 0}; auto result = tasks.insert({id, task}); + if (policy == Policy::ONE_SHOT) + startTick += period; + if (result.second) { // Add the task first event in the agenda @@ -66,6 +69,7 @@ bool TaskScheduler::addTask(function_t function, uint32_t period, Policy policy, { uint8_t id = 1; + // Find a suitable id for the new task auto it = tasks.cbegin(), end = tasks.cend(); for (; it != end && id == it->first; ++it, ++id) ; diff --git a/src/shared/scheduler/TaskScheduler.h b/src/shared/scheduler/TaskScheduler.h index 6eb0664158761b6cbc2b1eae124244429d890d94..24808780d2e2d4df751219e7dc9f2c550344a3c1 100644 --- a/src/shared/scheduler/TaskScheduler.h +++ b/src/shared/scheduler/TaskScheduler.h @@ -97,7 +97,8 @@ public: * Therefore, if a task already exists with the same id, the function will * fail and return false. * - * For one shot tasks, the period is useless and not used. + * For one shot tasks, the period is used as a delay. If 0 the task will be + * executed immediately, otherwise after the given period. * * @param function Function to be called periodically. * @param period Inter call period. @@ -117,7 +118,8 @@ public: * Therefore, if a task already exists with the same id, the function will * fail and return false. * - * For one shot tasks, the period is useless and not used. + * For one shot tasks, the period is used as a delay. If 0 the task will be + * executed immediately, otherwise after the given period. * * @param function Function to be called periodically. * @param period Inter call period. @@ -207,6 +209,7 @@ private: const std::pair<const uint8_t, Boardcore::TaskScheduler::Task>& task) { return TaskStatsResult{task.second.id, + task.second.period, task.second.activationStats.getStats(), task.second.periodStats.getStats(), task.second.workloadStats.getStats(), diff --git a/src/shared/scheduler/TaskSchedulerData.h b/src/shared/scheduler/TaskSchedulerData.h index 0cbe3865763d3d144b304ce2af5e26ea62dcb070..f1c43d31f10ff54c1b2a6d26bf9932647a3a4769 100644 --- a/src/shared/scheduler/TaskSchedulerData.h +++ b/src/shared/scheduler/TaskSchedulerData.h @@ -44,6 +44,7 @@ namespace Boardcore struct TaskStatsResult { uint8_t id; + uint32_t period; StatsResult activationStats; StatsResult periodStats; StatsResult workloadStats; @@ -52,7 +53,7 @@ struct TaskStatsResult static std::string header() { - return "id,actMin,actMax,actMean,actStddev,actNsamples," + return "id,period,actMin,actMax,actMean,actStddev,actNSamples," "periodMin,periodMax,periodMean,period_stddev," "periodNSamples,workloadMin,workloadMax,workloadMean," "workload_stddev,workloadNSample,missedEvents,failedEvents\n"; @@ -60,7 +61,7 @@ struct TaskStatsResult void print(std::ostream& os) const { - os << (int)id << "," << activationStats.minValue << "," + os << (int)id << "," << period << "," << activationStats.minValue << "," << activationStats.maxValue << "," << activationStats.mean << "," << activationStats.stdDev << "," << activationStats.nSamples << "," << periodStats.minValue << "," << periodStats.maxValue << "," diff --git a/src/shared/sensors/ADS1118/ADS1118.cpp b/src/shared/sensors/ADS1118/ADS1118.cpp index b49ceb3c61a1da619856134ae200177a034ffb4d..d9778c6f11e21bf7400c388bd123cddfc90805e2 100644 --- a/src/shared/sensors/ADS1118/ADS1118.cpp +++ b/src/shared/sensors/ADS1118/ADS1118.cpp @@ -242,8 +242,7 @@ void ADS1118::readChannel(int8_t nextChannel, int8_t prevChannel) // TODO: the timestamp should be taken when the configuration is // written, now we could be reading the value after some time! - values[prevChannel].voltageTimestamp = - TimestampTimer::getInstance().getTimestamp(); + values[prevChannel].voltageTimestamp = TimestampTimer::getTimestamp(); if (prevChannel != 8) // Voltage value { diff --git a/src/shared/sensors/ADS1118/ADS1118.h b/src/shared/sensors/ADS1118/ADS1118.h index 7a945166bf926962aed19263291d1b4c174e4e8e..dfdb2bab87f1431518c45a121c4540fde5aac831 100644 --- a/src/shared/sensors/ADS1118/ADS1118.h +++ b/src/shared/sensors/ADS1118/ADS1118.h @@ -44,21 +44,21 @@ namespace Boardcore * value while writing the configuration. * * Data rate between 8Hz and 860Hz can be programmed and an internal - * programmable gain aplifier can be set with a sensitivity range from ±0.256V + * programmable gain amplifier can be set with a sensitivity range from ±0.256V * to ±6.144V (note that the inputs must remain between VCC or GND). * * The data rate should be choosen as low as possible to allow the delta-sigma * adc to average the input voltage (this allows a less noisy reading). * * The device can work in two modes: - * - CONTIN_CONV_MODE: Continuosly read the last configured channel, when you - * make a read you'll obtain the lates reading + * - CONTINUOUS_CONV_MODE: Continuously read the last configured channel, when + * you make a read you'll obtain the lates reading * - SINGLE_SHOT_MODE: A single conversion is performed when the configuration * is written * * The ADS1118 is a simple device, it has a single data register where it can * store the reading, therefore it can sample a single input at a time. sample() - * cylces through the enabled channels one at a time and writes it's + * cycles through the enabled channels one at a time and writes it's * configuration while reading the value of the previous written one. * * As an example if you need to read 4 inputs at 50Hz you should set all the @@ -95,9 +95,9 @@ public: enum ADS1118Mode { - CONTIN_CONV_MODE = 0x0, ///< Continuous-conversion mode - SINGLE_SHOT_MODE = 0x1 ///< Power-down and single-shot mode (default) - }; ///< Conversione mode values + CONTINUOUS_CONV_MODE = 0x0, ///< Continuous-conversion mode + SINGLE_SHOT_MODE = 0x1 ///< Power-down and single-shot mode (default) + }; ///< Conversion mode values enum ADS1118DataRate { @@ -115,7 +115,7 @@ public: { ADC_MODE = 0x0, ///< ADC mode (default) TEMP_SENSOR_MODE = 0x1 ///< Temperature sensor mode - }; ///< Temeprature or ADC mode values + }; ///< Temperature or ADC mode values enum ADS1118PullUp { @@ -166,7 +166,7 @@ public: static constexpr int8_t INVALID_CHANNEL = -1; /** - * @brief Construct a new ADS1118 object specifing spi bus, spi config and + * @brief Construct a new ADS1118 object specifying spi bus, spi config and * cs pin as well as device configuration. */ ADS1118(SPIBusInterface &bus, miosix::GpioPin cs, ADS1118Config config_, @@ -302,7 +302,7 @@ private: void readChannel(int8_t nextChannel, int8_t prevChannel); /** - * @brief Reads on the fly the speficied channel. + * @brief Reads on the fly the specified channel. */ void readChannel(int8_t channel); @@ -341,7 +341,7 @@ private: /** * This masks excludes 2 bits from the configuration, the reserved bit and - * the sigle shot bit + * the single shot bit. */ static constexpr uint16_t CONFIG_MASK = 0xFE7F; }; diff --git a/src/shared/sensors/ADS131M04/ADS131M04.cpp b/src/shared/sensors/ADS131M04/ADS131M04.cpp index 32c9c1c5fa430d3607a8ec8a7a0f648d6587b9c5..8c7a46e2dbf5abb3255917fd13b0f450eb69376b 100644 --- a/src/shared/sensors/ADS131M04/ADS131M04.cpp +++ b/src/shared/sensors/ADS131M04/ADS131M04.cpp @@ -227,6 +227,12 @@ void ADS131M04::disableGlobalChopMode() ADS131M04RegisterBitMasks::REG_CFG_GC_EN); } +ADCData ADS131M04::getVoltage(Channel channel) +{ + return {lastSample.timestamp, static_cast<uint8_t>(channel), + lastSample.voltage[static_cast<uint8_t>(channel)]}; +} + bool ADS131M04::selfTest() { // TODO @@ -283,7 +289,7 @@ ADS131M04Data ADS131M04::sampleImpl() // Convert values ADS131M04Data adcData; - adcData.timestamp = TimestampTimer::getInstance().getTimestamp(); + adcData.timestamp = TimestampTimer::getTimestamp(); for (int i = 0; i < 4; i++) { adcData.voltage[i] = diff --git a/src/shared/sensors/ADS131M04/ADS131M04.h b/src/shared/sensors/ADS131M04/ADS131M04.h index 70b97b5f83dcccd4df364ea15d0302fd19ae2ddb..9d948a2886550e06e5ae0e7c37e4261cf80ed9bb 100644 --- a/src/shared/sensors/ADS131M04/ADS131M04.h +++ b/src/shared/sensors/ADS131M04/ADS131M04.h @@ -108,7 +108,7 @@ public: PGA_128 = 0x7 ///< Full scale resolution is ±9.375mV }; - enum class Channel : int + enum class Channel : uint8_t { CHANNEL_0 = 0, CHANNEL_1 = 1, @@ -155,7 +155,7 @@ public: * The ADS131M04 corrects for gain errors by multiplying the ADC conversion * result using the gain calibration registers. * The gain calibration value is interpreted as a 24bit unsigned. The values - * corresponds to n * (1/2^23), rainging from 0 to 2 - (1/2^23). + * corresponds to n * (1/2^23), ranging from 0 to 2 - (1/2^23). * * This function accepts a value between 0 and 2, it then compute the * correct gain register value. @@ -172,6 +172,8 @@ public: void disableGlobalChopMode(); + ADCData getVoltage(Channel channel); + bool selfTest() override; protected: diff --git a/src/shared/sensors/BME280/BME280.cpp b/src/shared/sensors/BME280/BME280.cpp index c8fd6e5400f5209f54a43a2897d990a0505d585a..80ab597f187c771a6e69c4febbef423d0f2b1b66 100644 --- a/src/shared/sensors/BME280/BME280.cpp +++ b/src/shared/sensors/BME280/BME280.cpp @@ -175,7 +175,7 @@ HumidityData BME280::readHumidity() adc_H |= buffer[1]; // Compensate humidity - lastSample.humidityTimestamp = TimestampTimer::getInstance().getTimestamp(); + lastSample.humidityTimestamp = TimestampTimer::getTimestamp(); lastSample.humidity = (float)compensateHumidity(adc_H) / 1024; // Converto to %RH @@ -198,7 +198,7 @@ PressureData BME280::readPressure() adc_P |= (buffer[2] >> 4) & 0x0F; // Compensate pressure - lastSample.pressureTimestamp = TimestampTimer::getInstance().getTimestamp(); + lastSample.pressureTimestamp = TimestampTimer::getTimestamp(); lastSample.pressure = (float)compensatePressure(adc_P) / 256; // Convert to Pa @@ -221,9 +221,8 @@ TemperatureData BME280::readTemperature() adcTemperature |= (buffer[2] >> 4) & 0x0F; // Compensate temperature - fineTemperature = computeFineTemperature(adcTemperature); - lastSample.temperatureTimestamp = - TimestampTimer::getInstance().getTimestamp(); + fineTemperature = computeFineTemperature(adcTemperature); + lastSample.temperatureTimestamp = TimestampTimer::getTimestamp(); lastSample.temperature = (float)compensateTemperature(fineTemperature) / 100; // Converto to DegC @@ -274,16 +273,16 @@ BME280Data BME280::sampleImpl() // Compensate temperature fineTemperature = computeFineTemperature(adcTemperature); - data.temperatureTimestamp = TimestampTimer::getInstance().getTimestamp(); + data.temperatureTimestamp = TimestampTimer::getTimestamp(); data.temperature = (float)compensateTemperature(fineTemperature) / 100; // Converto to DegC // Compensate pressure - data.pressureTimestamp = TimestampTimer::getInstance().getTimestamp(); + data.pressureTimestamp = TimestampTimer::getTimestamp(); data.pressure = (float)compensatePressure(adc_P) / 256; // Convert to Pa // Compensate humidity - data.humidityTimestamp = TimestampTimer::getInstance().getTimestamp(); + data.humidityTimestamp = TimestampTimer::getTimestamp(); data.humidity = (float)compensateHumidity(adc_H) / 1024; // Converto to %RH return data; diff --git a/src/shared/sensors/BMP280/BMP280.cpp b/src/shared/sensors/BMP280/BMP280.cpp index 35ad4ee5fddbd32667e6b361bd80f76d364094dc..45dcc1db2e050fb297e486fcc09e0ea95487e153 100644 --- a/src/shared/sensors/BMP280/BMP280.cpp +++ b/src/shared/sensors/BMP280/BMP280.cpp @@ -140,7 +140,7 @@ PressureData BMP280::readPressure() adc_P |= (buffer[2] >> 4) & 0x0F; // Compensate pressure - lastSample.pressureTimestamp = TimestampTimer::getInstance().getTimestamp(); + lastSample.pressureTimestamp = TimestampTimer::getTimestamp(); lastSample.pressure = (float)compensatePressure(adc_P) / 256; // Convert to Pa @@ -163,9 +163,8 @@ TemperatureData BMP280::readTemperature() adcTemperature |= (buffer[2] >> 4) & 0x0F; // Compensate temperature - fineTemperature = computeFineTemperature(adcTemperature); - lastSample.temperatureTimestamp = - TimestampTimer::getInstance().getTimestamp(); + fineTemperature = computeFineTemperature(adcTemperature); + lastSample.temperatureTimestamp = TimestampTimer::getTimestamp(); lastSample.temperature = (float)compensateTemperature(fineTemperature) / 100; // Converto to DegC @@ -213,12 +212,12 @@ BMP280Data BMP280::sampleImpl() // Compensate temperature fineTemperature = computeFineTemperature(adcTemperature); - data.temperatureTimestamp = TimestampTimer::getInstance().getTimestamp(); + data.temperatureTimestamp = TimestampTimer::getTimestamp(); data.temperature = (float)compensateTemperature(fineTemperature) / 100; // Converto to DegC // Compensate pressure - data.pressureTimestamp = TimestampTimer::getInstance().getTimestamp(); + data.pressureTimestamp = TimestampTimer::getTimestamp(); data.pressure = (float)compensatePressure(adc_P) / 256; // Convert to Pa return data; diff --git a/src/shared/sensors/BMP280/BMP280.h b/src/shared/sensors/BMP280/BMP280.h index 8b3263dfaa376c6108bec7bf03ef154bace53423..5786a0c4854d033077e8f91249c6fec5b740e0d0 100644 --- a/src/shared/sensors/BMP280/BMP280.h +++ b/src/shared/sensors/BMP280/BMP280.h @@ -242,7 +242,7 @@ private: */ bool checkWhoAmI(); - enum BMP280Registers : uint8_t + enum Registers : uint8_t { REG_CALIB_0 = 0x88, // Calibration register 1-25 diff --git a/src/shared/sensors/BMX160/BMX160.cpp b/src/shared/sensors/BMX160/BMX160.cpp index 287f9b5231dc7a08d87240f595a291b75a13089e..7af3062c544d4afe33fb08a6a83ec8ae329701a4 100644 --- a/src/shared/sensors/BMX160/BMX160.cpp +++ b/src/shared/sensors/BMX160/BMX160.cpp @@ -73,6 +73,9 @@ bool BMX160::init() initGyr(); initMag(); + // sleep in order to let the sensors initialize correctly + miosix::Thread::sleep(30); + initFifo(); initInt(); @@ -159,7 +162,7 @@ BMX160Data BMX160::sampleImpl() BMX160Temperature BMX160::getTemperature() { BMX160Temperature t; - t.temperatureTimestamp = TimestampTimer::getInstance().getTimestamp(); + t.temperatureTimestamp = TimestampTimer::getTimestamp(); t.temperature = temperature; return t; } @@ -614,9 +617,10 @@ GyroscopeData BMX160::buildGyrData(BMX160Defs::GyrRaw data, uint64_t timestamp) return GyroscopeData{timestamp, data.x * gyrSensibility, data.y * gyrSensibility, data.z * gyrSensibility}; else - return GyroscopeData{timestamp, data.x * gyrSensibility * g, - data.y * gyrSensibility * g, - data.z * gyrSensibility * g}; + return GyroscopeData{timestamp, + data.x * gyrSensibility * DEGREES_TO_RADIANS, + data.y * gyrSensibility * DEGREES_TO_RADIANS, + data.z * gyrSensibility * DEGREES_TO_RADIANS}; } const char* BMX160::debugErr(SPITransaction& spi) @@ -846,9 +850,9 @@ void BMX160::readFifo(bool headerless) } // Update fifo statistics - stats.timestamp = TimestampTimer::getInstance().getTimestamp(); - stats.watermarkTimestamp = watermarkTimestamp; - stats.fifoDuration = timestamp; + stats.timestamp = TimestampTimer::getTimestamp(); + stats.watermarkTimestamp = watermarkTimestamp; + stats.fifoDuration = timestamp; stats.interruptTimestampDelta = interruptTimestampDelta; stats.len = len; diff --git a/src/shared/sensors/BMX160/BMX160Config.h b/src/shared/sensors/BMX160/BMX160Config.h index 455dc14e6dd09a79c275a312cc57b66ca374a838..514b1cfe753c7bbc147af27282ffa4469427f82d 100644 --- a/src/shared/sensors/BMX160/BMX160Config.h +++ b/src/shared/sensors/BMX160/BMX160Config.h @@ -154,7 +154,7 @@ struct BMX160Config * in the BMX160 datasheet, for more informations consult the BMM150 * datasheet, chapter 4.2.4 Active mode. * - * This are the reccomended presets: + * This are the recommended presets: * - 0x01, RMS Noise (x/y/z) 1.0/1.0/1.4, Current: 0.17mA (Low power) * - 0x04, RMS Noise (x/y/z) 0.6/0.6/0.6, Current: 0.5mA (Regular) * (Default) @@ -168,11 +168,11 @@ struct BMX160Config * @brief Repetitions for the Z axis. * * Repetitions represent how many internal samples are averaged in order to - * get the final outputted sample, these presets are the ones reccomended + * get the final outputted sample, these presets are the ones recommended * in the BMX160 datasheet, for more informations consult the BMM150 * datasheet, chapter 4.2.4 Active mode. * - * This are the reccomended presets: + * This are the recommended presets: * - 0x02, RMS Noise (x/y/z) 1.0/1.0/1.4, Current: 0.17mA (Low power) * - 0x0E, RMS Noise (x/y/z) 0.6/0.6/0.6, Current: 0.5mA (Regular) * (Default) diff --git a/src/shared/sensors/BMX160/BMX160WithCorrection.cpp b/src/shared/sensors/BMX160/BMX160WithCorrection.cpp index f5e1216f8ca9e6533a628f14f70fee8de6cf135b..9ea0958044be239707d47f53a3ea2aab294efc6b 100644 --- a/src/shared/sensors/BMX160/BMX160WithCorrection.cpp +++ b/src/shared/sensors/BMX160/BMX160WithCorrection.cpp @@ -26,20 +26,22 @@ #include <fstream> +using namespace miosix; +using namespace Eigen; + namespace Boardcore { BMX160CorrectionParameters::BMX160CorrectionParameters() { - accelParams << 0, 0, 0, 0, 0, 0; // cppcheck-suppress constStatement + accelParams << 1, 0, 1, 0, 1, 0; // cppcheck-suppress constStatement magnetoParams << 0, 0, 0, 0, 0, 0; // cppcheck-suppress constStatement } std::string BMX160CorrectionParameters::header() { - return "accel_p1,accel_p2,accel_p3,accel_q1,accel_q2,accel_q3,mag_p1," - "mag_p2,mag_p3,mag_q1,mag_q2,mag_q3," - "minGyroSamplesForCalibration"; + return "accAx,accAy,accAz,accbx,accby,accbz," + "magAx,magAy,magAz,magbx,magby,magbz"; } void BMX160CorrectionParameters::read(std::istream& inputStream) @@ -63,9 +65,6 @@ void BMX160CorrectionParameters::read(std::istream& inputStream) inputStream.ignore(1, ','); } } - - // Read gyroscope correction samples - inputStream >> minGyroSamplesForCalibration; } void BMX160CorrectionParameters::print(std::ostream& outputStream) const @@ -79,113 +78,53 @@ void BMX160CorrectionParameters::print(std::ostream& outputStream) const outputStream << magnetoParams(0, 0) << "," << magnetoParams(1, 0) << "," << magnetoParams(2, 0) << "," << magnetoParams(0, 1) << "," << magnetoParams(1, 1) << "," << magnetoParams(2, 1) << ","; - - // Print gyroscope correction samples - outputStream << minGyroSamplesForCalibration << "\n"; } BMX160WithCorrection::BMX160WithCorrection( - BMX160* bmx160_, BMX160CorrectionParameters correctionParameters, - AxisOrthoOrientation rotation_) - : bmx160(bmx160_), minGyroSamplesForCalibration( - correctionParameters.minGyroSamplesForCalibration), - rotation(rotation_) + BMX160* bmx160, BMX160CorrectionParameters correctionParameters, + AxisOrthoOrientation rotation) + : bmx160(bmx160), rotation(rotation) { accelerometerCorrector << correctionParameters.accelParams; magnetometerCorrector << correctionParameters.magnetoParams; } BMX160WithCorrection::BMX160WithCorrection( - BMX160* bmx160_, BMX160CorrectionParameters correctionParameters) - : bmx160(bmx160_), minGyroSamplesForCalibration( - correctionParameters.minGyroSamplesForCalibration) + BMX160* bmx160, BMX160CorrectionParameters correctionParameters) + : bmx160(bmx160) { accelerometerCorrector << correctionParameters.accelParams; magnetometerCorrector << correctionParameters.magnetoParams; } -BMX160WithCorrection::BMX160WithCorrection(BMX160* bmx160_) : bmx160(bmx160_) {} +BMX160WithCorrection::BMX160WithCorrection(BMX160* bmx160) : bmx160(bmx160) {} bool BMX160WithCorrection::init() { return true; } bool BMX160WithCorrection::selfTest() { return true; } -bool BMX160WithCorrection::calibrate() +void BMX160WithCorrection::startCalibration() { - if (!bmx160) - { - LOG_ERR(logger, "Driver doesn't point to valid sensor"); - return false; - } - - int samplesCounter = 0; - BiasCalibration<GyroscopeData> gyroscopeCalibrator; - BMX160Data fifoElement; - uint8_t fifoSize; - uint64_t gyroTimestamp = 0; - - // Set reference vector - gyroscopeCalibrator.setReferenceVector({0, 0, 0}); - - // Read the fifo and feed the gyroscope data to the calibrator - fifoSize = bmx160->getLastFifoSize(); - for (uint8_t i = 0; i < fifoSize; i++) - { - fifoElement = bmx160->getFifoElement(i); - - if (fifoElement.angularVelocityTimestamp > gyroTimestamp) - { - gyroTimestamp = fifoElement.angularVelocityTimestamp; - gyroscopeCalibrator.feed(fifoElement); - - samplesCounter++; - } - } - - // Continues until the averaged samples are at least the amount specified in - // the configuration - while (samplesCounter < minGyroSamplesForCalibration) - { - // Wait for another sample - miosix::Thread::sleep(100); - - // Read the fifo and feed the gyroscope data to the calibrator - fifoSize = bmx160->getLastFifoSize(); - for (uint8_t i = 0; i < fifoSize; i++) - { - fifoElement = bmx160->getFifoElement(i); - - if (fifoElement.angularVelocityTimestamp > gyroTimestamp) - { - gyroTimestamp = fifoElement.angularVelocityTimestamp; - gyroscopeCalibrator.feed(fifoElement); + gyroscopeCalibrator.reset(); + calibrating = true; +} - samplesCounter++; - } - } - } +void BMX160WithCorrection::stopCalibration() +{ + calibrating = false; - // Compute and save the calibration results { - miosix::PauseKernelLock lock; + PauseKernelLock lock; gyroscopeCorrector = gyroscopeCalibrator.computeResult(); } - // Print the calibraton data + // Print the calibrator data + Vector3f gyroscopeCorrectionParameters; gyroscopeCorrector >> gyroscopeCorrectionParameters; LOG_INFO(logger, "Gyroscope bias vector from calibration\n"); LOG_INFO(logger, "b = [ {: >2.5f} {: >2.5f} {: >2.5f} ]\n\n", gyroscopeCorrectionParameters(0), gyroscopeCorrectionParameters(1), gyroscopeCorrectionParameters(2)); - - return true; -} - -BMX160GyroscopeCalibrationBiases BMX160WithCorrection::getGyroscopeBiases() -{ - return BMX160GyroscopeCalibrationBiases{gyroscopeCorrectionParameters(0), - gyroscopeCorrectionParameters(1), - gyroscopeCorrectionParameters(2)}; } BMX160CorrectionParameters @@ -275,22 +214,19 @@ BMX160WithCorrectionData BMX160WithCorrection::sampleImpl() static_cast<GyroscopeData&>(result) << avgGyro; // Correct the averaged measurements - AccelerometerData acc = accelerometerCorrector.correct(result); - result = acc; - MagnetometerData mag = magnetometerCorrector.correct(result); - result = mag; - GyroscopeData gyro; - gyro = gyroscopeCorrector.correct(result); - result = gyro; + result = accelerometerCorrector.correct(result); + result = magnetometerCorrector.correct(result); + result = gyroscopeCorrector.correct(result); // Get the timestamp of the newest value in fifo result.accelerationTimestamp = fifoElement.accelerationTimestamp; result.magneticFieldTimestamp = fifoElement.accelerationTimestamp; result.angularVelocityTimestamp = fifoElement.accelerationTimestamp; - result = rotateAxis(result); + if (calibrating) + gyroscopeCalibrator.feed(result); - return result; + return rotateAxis(result); } BMX160WithCorrectionData BMX160WithCorrection::rotateAxis( diff --git a/src/shared/sensors/BMX160/BMX160WithCorrection.h b/src/shared/sensors/BMX160/BMX160WithCorrection.h index fa139ef6bca95e2b6296a97be26185c050fedfd4..99f05cda17257b92e87d56eac646b4bebbb0979c 100644 --- a/src/shared/sensors/BMX160/BMX160WithCorrection.h +++ b/src/shared/sensors/BMX160/BMX160WithCorrection.h @@ -27,6 +27,7 @@ #include <sensors/calibration/AxisOrientation.h> #include <sensors/calibration/BiasCalibration.h> #include <sensors/calibration/SixParameterCalibration.h> +#include <utils/Stats/Stats.h> #include "BMX160WithCorrectionData.h" @@ -39,7 +40,6 @@ namespace Boardcore struct BMX160CorrectionParameters { Eigen::Matrix<float, 3, 2> accelParams, magnetoParams; - int minGyroSamplesForCalibration = 0; BMX160CorrectionParameters(); @@ -60,44 +60,50 @@ class BMX160WithCorrection : public Sensor<BMX160WithCorrectionData> { public: /** - * @param bmx160_ already initialized bmx. - * @param correctionParameters correction parameter to apply. - * @param rotation_ axis rotation. + * @param bmx160 Already initialized bmx. + * @param correctionParameters Correction parameter to apply. + * @param rotation Axis rotation. */ - BMX160WithCorrection(BMX160* bmx160_, + BMX160WithCorrection(BMX160* bmx160, BMX160CorrectionParameters correctionParameters, - AxisOrthoOrientation rotation_); + AxisOrthoOrientation rotation); /** - * Constructor without rotation, no rotation will be applied. + * @brief Constructor without rotation, no rotation will be applied. * - * @param bmx160_ already initialized bmx. - * @param correctionParameters correction parameter to apply. + * @param bmx160 Already initialized bmx. + * @param correctionParameters Correction parameter to apply. */ - BMX160WithCorrection(BMX160* bmx160_, + BMX160WithCorrection(BMX160* bmx160, BMX160CorrectionParameters correctionParameters); /** - * @brief Constructor without correction nor rotation, no correciton and + * @brief Constructor without correction nor rotation, no correction and * rotation will be applied. * - * @param bmx160_ correction parameter to apply. + * @param bmx160 Correction parameter to apply. */ - explicit BMX160WithCorrection(BMX160* bmx160_); + explicit BMX160WithCorrection(BMX160* bmx160); bool init() override; bool selfTest() override; /** - * @brief Performs the gyroscope calibration. + * @brief Starts collecting calibration data for the gyroscope. * * The gyroscope calibration consists in averaging some samples to measure - * the bias. - * This function is intended to run while another thread samples the bmx at - * at least 10Hz. + * the bias. This function is intended to run while another thread samples + * the bmx. + * + * Call stopCalibration() to end collection and finalizing the offset. */ - bool calibrate(); + void startCalibration(); + + /** + * @brief Stops the data collection and finalizes the calibration. + */ + void stopCalibration(); /** * @brief Utility function to read correction parameters from file. @@ -120,8 +126,6 @@ private: BMX160* bmx160; - int minGyroSamplesForCalibration = 200; - AxisOrthoOrientation rotation = {Direction::POSITIVE_X, Direction::POSITIVE_Y}; @@ -129,7 +133,8 @@ private: SixParameterCorrector<MagnetometerData> magnetometerCorrector; BiasCorrector<GyroscopeData> gyroscopeCorrector{}; - Eigen::Vector3f gyroscopeCorrectionParameters; + bool calibrating = false; + BiasCalibration<GyroscopeData> gyroscopeCalibrator; PrintLogger logger = Logging::getLogger("bmx160withcorrection"); }; diff --git a/src/shared/sensors/HX711/HX711.cpp b/src/shared/sensors/HX711/HX711.cpp index 8e3fa92694daa960e71db8a1463147e11bdd3e9d..0fb1c87653fe972bf2fc43f229ce4bfa67e81e76 100644 --- a/src/shared/sensors/HX711/HX711.cpp +++ b/src/shared/sensors/HX711/HX711.cpp @@ -68,7 +68,7 @@ HX711Data HX711::sampleImpl() if (sample == static_cast<int32_t>(0xFFFFFFFF)) return lastSample; - return {TimestampTimer::getInstance().getTimestamp(), + return {TimestampTimer::getTimestamp(), static_cast<float>(sample - offset) * scale}; } diff --git a/src/shared/sensors/LIS331HH/LIS331HH.cpp b/src/shared/sensors/LIS331HH/LIS331HH.cpp new file mode 100644 index 0000000000000000000000000000000000000000..ad3f18e9690164daf45c85c9288e56ff2495508c --- /dev/null +++ b/src/shared/sensors/LIS331HH/LIS331HH.cpp @@ -0,0 +1,64 @@ +/* Copyright (c) 2022 Skyward Experimental Rocketry + * Author: Alberto Nidasio + * + * 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. + */ + +#include "LIS331HH.h" + +#include <drivers/timer/TimestampTimer.h> + +namespace Boardcore +{ + +LIS331HH::LIS331HH(SPIBusInterface& bus, miosix::GpioPin cs, + SPIBusConfig spiConfig) + : slave(bus, cs, spiConfig) +{ +} + +bool LIS331HH::init() { return true; } + +bool LIS331HH::selfTest() { return true; } + +LIS331HHData LIS331HH::sampleImpl() +{ + uint16_t val; + LIS331HHData data; + + data.accelerationTimestamp = TimestampTimer::getTimestamp(); + + SPITransaction spi(slave); + + val = spi.readRegister(OUT_X_L); + val |= spi.readRegister(OUT_X_H) << 8; + data.accelerationX = 6.0 / 65536.0 * val; + + val = spi.readRegister(OUT_Y_L); + val |= spi.readRegister(OUT_Y_H) << 8; + data.accelerationY = 6.0 / 65536.0 * val; + + val = spi.readRegister(OUT_Z_L); + val |= spi.readRegister(OUT_Z_H) << 8; + data.accelerationZ = 6.0 / 65536.0 * val; + + return data; +} + +} // namespace Boardcore diff --git a/src/shared/sensors/LIS331HH/LIS331HH.h b/src/shared/sensors/LIS331HH/LIS331HH.h new file mode 100644 index 0000000000000000000000000000000000000000..d91cb3d904eae391ce4f3e7ac16a4deb1820104f --- /dev/null +++ b/src/shared/sensors/LIS331HH/LIS331HH.h @@ -0,0 +1,74 @@ +/* Copyright (c) 2022 Skyward Experimental Rocketry + * Author: Alberto Nidasio + * + * 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. + */ + +#pragma once + +#include <drivers/spi/SPIDriver.h> +#include <sensors/Sensor.h> + +#include "LIS331HHData.h" + +namespace Boardcore +{ + +class LIS331HH : public Sensor<LIS331HHData> +{ +public: + LIS331HH(SPIBusInterface& bus, miosix::GpioPin cs, SPIBusConfig spiConfig); + + bool init() override; + + bool selfTest() override; + +private: + LIS331HHData sampleImpl() override; + + SPISlave slave; + + enum Registers : uint8_t + { + CTRL_REG1 = 0x20, + CTRL_REG2 = 0x21, + CTRL_REG3 = 0x22, + CTRL_REG4 = 0x23, + CTRL_REG5 = 0x24, + HP_FILTER_RESET = 0x25, + REFERENCE = 0x26, + STATUS_REG = 0x27, + OUT_X_L = 0x28, + OUT_X_H = 0x29, + OUT_Y_L = 0x2a, + OUT_Y_H = 0x2b, + OUT_Z_L = 0x2c, + OUT_Z_H = 0x2d, + INT1_CFG = 0x30, + INT1_SOURCE = 0x31, + INT1_THS = 0x32, + INT1_DURATION = 0x33, + INT2_CFG = 0x34, + INT2_SOURCE = 0x35, + INT2_THS = 0x36, + INT2_DURATION = 0x37, + }; +}; + +} // namespace Boardcore \ No newline at end of file diff --git a/src/shared/sensors/LIS331HH/LIS331HHData.h b/src/shared/sensors/LIS331HH/LIS331HHData.h new file mode 100644 index 0000000000000000000000000000000000000000..72a57214106d2c3475abe59e9baef9b0701ef2c8 --- /dev/null +++ b/src/shared/sensors/LIS331HH/LIS331HHData.h @@ -0,0 +1,47 @@ +/* Copyright (c) 2022 Skyward Experimental Rocketry + * Author: Alberto Nidasio + * + * 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. + */ + +#pragma once + +#include <sensors/SensorData.h> + +namespace Boardcore +{ + +struct LIS331HHData : public AccelerometerData +{ + static std::string header() + { + return "accelerationTimestamp,accelerationX,accelerationY," + "accelerationZ,temp_" + "timestamp," + "temp\n"; + } + + void print(std::ostream& os) const + { + os << accelerationTimestamp << "," << accelerationX << "," + << accelerationY << "," << accelerationZ << "\n"; + } +}; + +} // namespace Boardcore diff --git a/src/shared/sensors/LIS3DSH/LIS3DSH.h b/src/shared/sensors/LIS3DSH/LIS3DSH.h index 32dd4548fa0d551a33819eef7fe0615ed88e31f8..4c048dc25e2fe3a39db5333368d4e5a8ead6be6c 100644 --- a/src/shared/sensors/LIS3DSH/LIS3DSH.h +++ b/src/shared/sensors/LIS3DSH/LIS3DSH.h @@ -318,9 +318,10 @@ public: private: /** * @brief Read new data from the accelerometer. - * Acceleretions are returned in g. * - * @return boolean value indicating whether the operation succeded or not + * Accelerations are returned in g. + * + * @return boolean value indicating whether the operation succeeded or not */ LIS3DSHData sampleImpl() override { @@ -346,9 +347,9 @@ private: } /** - * @brief Read accelrometer data. + * @brief Read accelerometer data. * - * @return the read accelrometer sample + * @return the read accelerometer sample */ AccelerometerData readAccelData() { @@ -365,7 +366,7 @@ private: { // bit 7 of status set to 1 (some data overwritten) accelData.accelerationTimestamp = - TimestampTimer::getInstance().getTimestamp(); + TimestampTimer::getTimestamp(); // read acceleration on X int8_t accel_L = spi.readRegister(OUT_X_L); @@ -409,7 +410,7 @@ private: int8_t t = spi.readRegister(OUT_T); return TemperatureData{ - TimestampTimer::getInstance().getTimestamp(), + TimestampTimer::getTimestamp(), t + TEMPERATURE_REF}; // add the 'zero' of the temperature sensor } diff --git a/src/shared/sensors/LIS3MDL/LIS3MDL.cpp b/src/shared/sensors/LIS3MDL/LIS3MDL.cpp new file mode 100644 index 0000000000000000000000000000000000000000..095a2fee3cba11eb6134fe4732407432edf60abd --- /dev/null +++ b/src/shared/sensors/LIS3MDL/LIS3MDL.cpp @@ -0,0 +1,315 @@ +/* Copyright (c) 2020 Skyward Experimental Rocketry + * Author: Riccardo Musso + * + * 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. + */ + +#include "LIS3MDL.h" + +#include <drivers/timer/TimestampTimer.h> + +namespace Boardcore +{ + +LIS3MDL::LIS3MDL(SPIBusInterface& bus, miosix::GpioPin pin, + SPIBusConfig spiConfig, Config config) + : mSlave(bus, pin, spiConfig), mConfig(config), currDiv(0), + isInitialized(false) +{ +} + +bool LIS3MDL::init() +{ + if (isInitialized) + { + LOG_ERR(logger, "Attempted to initialized sensor twice but failed"); + lastError = ALREADY_INIT; + return false; + } + + { + SPITransaction spi(mSlave); + uint8_t res = spi.readRegister(WHO_AM_I); + + if (res != WHO_AM_I_VALUE) + { + LOG_ERR(logger, + "WHO_AM_I value differs from expectation: read 0x{02x} " + "but expected 0x{02x}", + res, WHO_AM_I_VALUE); + lastError = INVALID_WHOAMI; + return false; + } + } + + isInitialized = true; + return applyConfig(mConfig); +} + +bool LIS3MDL::selfTest() +{ + if (!isInitialized) + { + LOG_ERR(logger, "Invoked selfTest() but sensor was uninitialized"); + lastError = NOT_INIT; + return false; + } + + constexpr int NUM_SAMPLES = 5; + constexpr int SLEEP_TIME = 50; + + // Absolute value of extra tolerance + constexpr float t = 0.1f; + + // Range which delta must be between, one for axis and expressed as {min, + // max}. The unit is gauss. + constexpr float deltaRange[3][2] = {{1.f, 3.f}, {1.f, 3.f}, {0.1f, 1.f}}; + + float avgX = 0.f, avgY = 0.f, avgZ = 0.f; + + { + SPITransaction spi(mSlave); + spi.writeRegister(CTRL_REG2, FS_12_GAUSS); + } + updateUnit(FS_12_GAUSS); + + for (int i = 0; i < NUM_SAMPLES; ++i) + { + miosix::Thread::sleep(SLEEP_TIME); + + LIS3MDLData lastData = sampleImpl(); + avgX += lastData.magneticFieldX; + avgY += lastData.magneticFieldY; + avgZ += lastData.magneticFieldZ; + } + + avgX /= NUM_SAMPLES; + avgY /= NUM_SAMPLES; + avgZ /= NUM_SAMPLES; + + // Setting up the sensor settings for proper usage of the self test mode. + { + SPITransaction spi(mSlave); + + spi.writeRegister(CTRL_REG1, ODR_20_HZ | ENABLE_SELF_TEST | + (OM_ULTRA_HIGH_POWER << 4)); + spi.writeRegister(CTRL_REG2, FS_12_GAUSS); + spi.writeRegister(CTRL_REG4, OM_ULTRA_HIGH_POWER << 2); + } + + // Deltas: absolute difference between the values measured before and after + float deltas[3]; + + miosix::Thread::sleep(SLEEP_TIME); + + LIS3MDLData lastData = sampleImpl(); + deltas[0] = std::abs(lastData.magneticFieldX - avgX); + deltas[1] = std::abs(lastData.magneticFieldY - avgY); + deltas[2] = std::abs(lastData.magneticFieldZ - avgZ); + + bool passed = true; + for (int j = 0; j < 3; ++j) + if (deltas[j] < (deltaRange[j][0] - t) || + deltas[j] > (deltaRange[j][1] + t)) + passed = false; + + if (!passed) + { + // reset configuration, then return + applyConfig(mConfig); + + lastError = SELF_TEST_FAIL; + return false; + } + + return applyConfig(mConfig); +} + +bool LIS3MDL::applyConfig(Config config) +{ + + SPITransaction spi(mSlave); + uint8_t reg = 0, err = 0; + + mConfig = config; + currDiv = 0; + + // CTRL_REG1 + if (config.enableTemperature) + { + reg = ENABLE_TEMPERATURE; + } + reg |= config.odr; + + // odr <= 80Hz + if (!(config.odr & FAST_ODR_BIT)) + reg |= config.xyMode << 4; + spi.writeRegister(CTRL_REG1, reg); + err |= spi.readRegister(CTRL_REG1) != reg; + + // CTRL_REG2 + reg = config.scale; + spi.writeRegister(CTRL_REG2, reg); + err |= spi.readRegister(CTRL_REG2) != reg; + + // CTRL_REG3 + reg = CONTINUOS_CONVERSION; + spi.writeRegister(CTRL_REG3, reg); + err |= spi.readRegister(CTRL_REG3) != reg; + + // CTRL_REG4 + reg = config.zMode << 2; + spi.writeRegister(CTRL_REG4, reg); + err |= spi.readRegister(CTRL_REG4) != reg; + + // CTRL_REG5 + if (config.doBlockDataUpdate) + reg = ENABLE_BDU; + else + reg = 0; + + spi.writeRegister(CTRL_REG5, reg); + err |= spi.readRegister(CTRL_REG5) != reg; + + // INT_CFG + if (config.enableInterrupt[0]) + reg = ENABLE_INT_X; + else + reg = 0; + + if (config.enableInterrupt[1]) + reg |= ENABLE_INT_Y; + if (config.enableInterrupt[2]) + reg |= ENABLE_INT_Z; + + // The interrupt of at least one axis is enabled + if (reg) + reg |= ENABLE_INT_PIN; + + reg |= 0x08; + spi.writeRegister(INT_CFG, reg); + err |= spi.readRegister(INT_CFG) != reg; + + // INT_THS + uint16_t val = static_cast<uint16_t>(std::abs(config.threshold / mUnit)); + reg = static_cast<uint8_t>(0xff & val); + spi.writeRegister(INT_THS_L, reg); + err |= spi.readRegister(INT_THS_L) != reg; + + reg = static_cast<uint8_t>(val >> 8); + reg &= 0x7f; // Remove MSB (according to the datasheet, it must be zero) + spi.writeRegister(INT_THS_H, reg); + err |= spi.readRegister(INT_THS_H) != reg; + + // Set mUnit according to scale + updateUnit(config.scale); + + if (err) + { + LOG_ERR(logger, "Spi error"); + lastError = BUS_FAULT; + return false; + } + + return true; +} + +LIS3MDLData LIS3MDL::sampleImpl() +{ + if (!isInitialized) + { + LOG_ERR(logger, "Invoked sampleImpl() but sensor was uninitialized"); + lastError = NOT_INIT; + return lastSample; + } + + SPITransaction spi(mSlave); + + if (!spi.readRegister(STATUS_REG)) + { + lastError = NO_NEW_DATA; + return lastSample; + } + + // Reset any error + lastError = SensorErrors::NO_ERRORS; + + int16_t val; + LIS3MDLData newData{}; + + if (mConfig.enableTemperature) + { + if (currDiv == 0) + { + val = spi.readRegister(TEMP_OUT_L); + val |= spi.readRegister(TEMP_OUT_H) << 8; + + newData.temperatureTimestamp = TimestampTimer::getTimestamp(); + newData.temperature = static_cast<float>(val) / LSB_PER_CELSIUS + + REFERENCE_TEMPERATURE; + } + else + { + // Keep old value + newData.temperature = lastSample.temperature; + } + + currDiv = (currDiv + 1) % mConfig.temperatureDivider; + } + + newData.magneticFieldTimestamp = TimestampTimer::getTimestamp(); + + val = spi.readRegister(OUT_X_L); + val |= spi.readRegister(OUT_X_H) << 8; + newData.magneticFieldX = mUnit * val; + + val = spi.readRegister(OUT_Y_L); + val |= spi.readRegister(OUT_Y_H) << 8; + newData.magneticFieldY = mUnit * val; + + val = spi.readRegister(OUT_Z_L); + val |= spi.readRegister(OUT_Z_H) << 8; + newData.magneticFieldZ = mUnit * val; + + return newData; +} + +void LIS3MDL::updateUnit(FullScale fs) +{ + switch (fs) + { + case FS_4_GAUSS: + mUnit = 1.f / LSB_PER_GAUSS_FS_4; + break; + + case FS_8_GAUSS: + mUnit = 1.f / LSB_PER_GAUSS_FS_8; + break; + + case FS_12_GAUSS: + mUnit = 1.f / LSB_PER_GAUSS_FS_12; + break; + + case FS_16_GAUSS: + mUnit = 1.f / LSB_PER_GAUSS_FS_16; + break; + } +}; + +} // namespace Boardcore diff --git a/src/shared/sensors/LIS3MDL/LIS3MDL.h b/src/shared/sensors/LIS3MDL/LIS3MDL.h index 5038c79167cf32e0a4c3f3cf60b1a2182acb6f9f..698432e934826d9c7358fa81adbbcd2b151dbd22 100644 --- a/src/shared/sensors/LIS3MDL/LIS3MDL.h +++ b/src/shared/sensors/LIS3MDL/LIS3MDL.h @@ -24,11 +24,9 @@ #include <diagnostic/PrintLogger.h> #include <drivers/spi/SPIDriver.h> -#include <drivers/timer/TimestampTimer.h> #include <sensors/Sensor.h> #include "LIS3MDLData.h" -#include "miosix.h" namespace Boardcore { @@ -40,12 +38,11 @@ class LIS3MDL : public Sensor<LIS3MDLData> { public: /** - * Constants for Output Data Rate configuration. + * @brief Constants for Output Data Rate configuration. * - * Note: constants values already include - * axis operative mode selection and FAST_ODR - * options, so they are ready to be put inside - * CTRL_REG1 along with TEMP_EN and ST + * Note: constants values already include axis operative mode selection and + * FAST_ODR options, so they are ready to be put inside CTRL_REG1 along with + * TEMP_EN and ST. */ enum ODR : uint8_t { @@ -72,17 +69,17 @@ public: enum FullScale : uint8_t { - FS_4_GAUSS = 0x00, //!< +/- 4 gauss - FS_8_GAUSS = 0x20, //!< +/- 8 gauss - FS_12_GAUSS = 0x40, //!< +/- 12 gauss - FS_16_GAUSS = 0x60, //!< +/- 16 gauss + FS_4_GAUSS = 0x00, ///< +/- 4 gauss + FS_8_GAUSS = 0x20, ///< +/- 8 gauss + FS_12_GAUSS = 0x40, ///< +/- 12 gauss + FS_16_GAUSS = 0x60, ///< +/- 16 gauss }; /** - * @brief Operative mode constants + * @brief Operative mode constants. * - * Operative mode (that is power consumpion) options. - * Higher power implies better performance. + * Operative mode (that is power consumption) options. Higher power implies + * better performance. */ enum OperativeMode : uint8_t { @@ -102,14 +99,11 @@ public: */ struct Config { - /** - * @brief Constructor - * Creates an instance with the default settings. - */ Config() {} /** - * Full scale setting + * @brief Full scale setting. + * * @see LIS3MDL::FullScale */ FullScale scale = FS_8_GAUSS; @@ -119,21 +113,18 @@ public: * * Default: 40 Hz * - * Important: if ODR is set more than 80 Hz, - * operative mode of x and y axis will be set - * accordingly. + * Important: if ODR is set more than 80 Hz, operative mode of x and y + * axis will be set accordingly. * * @see LIS3MDL::ODR */ ODR odr = ODR_40_HZ; /** - * Operative mode for x and y axis. - * Note: if ODR is greater than 80 Hz, - * this setting will be ignored and actual - * operative mode will be set depending of - * the chosen frequency. - * Default: ultra high performance + * @brief Operative mode for x and y axis. + * + * Note: if ODR is greater than 80 Hz, this setting will be ignored and + * actual operative mode will be set depending of the chosen frequency. * * @see LIS3MDL::OperativeMode */ @@ -141,7 +132,6 @@ public: /** * Operative mode for z axis. - * Default: ultra high performance * * @see LIS3MDL::OM */ @@ -162,404 +152,60 @@ public: * to sampleImpl(), so for example: * 2 -> updated half the times, * 1 -> updated every time. - * By default the divider is set to 1 - * */ unsigned temperatureDivider = 1; /** * @brief Enables interrupts * - * Whether are interrupts enabled respectively - * on the x, y and z axis. If it is set to true - * on at least one axis, the interrupts will be - * generated otherwise, they will be completely - * disabled by the driver. - * - * Default: disabled on all axis. + * Whether are interrupts enabled respectively on the x, y and z axis. + * If it is set to true on at least one axis, the interrupts will be + * generated otherwise, they will be completely disabled by the driver. */ bool enableInterrupt[3] = {false, false, false}; /** * Absolute value of the threshold that triggers the interrupt - * (expressed in gauss). Default: 0 + * (expressed in gauss). */ float threshold = 0; /** * @brief BDU setting * - * If set to true, the sensor won't update the data - * until it is read, if false the sensor data will be - * continously updated. Default: false + * If set to true, the sensor won't update the data until it is read, if + * false the sensor data will be continuously updated. */ bool doBlockDataUpdate = false; }; - /** - * Constructs the default config for SPI Bus. - * - * @returns the default SPIBusConfig - */ - static SPIBusConfig getDefaultSPIConfig() - { - SPIBusConfig config{}; - config.clockDivider = SPI::ClockDivider::DIV_32; - return config; - } - - /** - * @brief The constructor. - * - * Takes all relevant SPI info and the settings - * for the sensor. If no SPIBusConfig is given, it will - * be used the default configuration. - * - * @param bus The SPI interface - * @param pin The CS pin - * @param spiConfig SPI configuration, optional - * @param config Driver configuration, optional - * - * @see LIS3MDL::Config - */ LIS3MDL(SPIBusInterface& bus, miosix::GpioPin pin, - SPIBusConfig spiConfig = getDefaultSPIConfig(), Config config = {}) - : mSlave{bus, pin, spiConfig}, mConfig(config), currDiv(0), - isInitialized(false) - { - } - - bool init() override - { - if (isInitialized) - { - LOG_ERR(logger, "Attempted to initialized sensor twice but failed"); - lastError = ALREADY_INIT; - return false; - } - - { - SPITransaction spi(mSlave); - uint8_t res = spi.readRegister(WHO_AM_I); - - if (res != WHO_AM_I_VALUE) - { - LOG_ERR(logger, - "WHO_AM_I value differs from expectation: read 0x{02x} " - "but expected 0x{02x}", - res, WHO_AM_I_VALUE); - lastError = INVALID_WHOAMI; - return false; - } - } - - isInitialized = true; - return applyConfig(mConfig); - } - - /** - * @brief Executes self test - * - * The init() method must have been called before. - * - * @returns false if the sensor failed the self test, true otherwise. - */ - bool selfTest() override - { - if (!isInitialized) - { - LOG_ERR(logger, "Invoked selfTest() but sensor was unitialized"); - lastError = NOT_INIT; - return false; - } - - /* - * NUM_SAMPLES: number of samples used - * to take the average value before tests. - * NUM_TESTS: number of actual tests. - * SLEEP_TIME: millis between samples/tests - */ - constexpr int NUM_SAMPLES = 5, NUM_TESTS = 5, SLEEP_TIME = 50; + SPIBusConfig spiConfig = {}, Config config = {}); - /* - * Absolute value of extra tolerance - */ - constexpr float t = 0.1f; - - /* - * Range which delta must be between, one for - * axis and expressed as {min, max}. The unit is gauss - */ - constexpr float r[3][2] = {{1.f, 3.f}, {1.f, 3.f}, {0.1f, 1.f}}; + bool init() override; - float avgX = 0.f, avgY = 0.f, avgZ = 0.f; - - { - SPITransaction spi(mSlave); - spi.writeRegister(CTRL_REG2, FS_12_GAUSS); - } - updateUnit(FS_12_GAUSS); - - for (int i = 0; i < NUM_SAMPLES; ++i) - { - miosix::Thread::sleep(SLEEP_TIME); - - LIS3MDLData lastData = sampleImpl(); - avgX += lastData.magneticFieldX; - avgY += lastData.magneticFieldY; - avgZ += lastData.magneticFieldZ; - } - - avgX /= NUM_SAMPLES; - avgY /= NUM_SAMPLES; - avgZ /= NUM_SAMPLES; - - /* - * Setting up the sensor settings for - * proper usage of the self test mode. - */ - { - SPITransaction spi(mSlave); - - spi.writeRegister(CTRL_REG1, ODR_20_HZ | ENABLE_SELF_TEST | - (OM_ULTRA_HIGH_POWER << 4)); - spi.writeRegister(CTRL_REG2, FS_12_GAUSS); - spi.writeRegister(CTRL_REG4, OM_ULTRA_HIGH_POWER << 2); - } - - /* - * Deltas: absolute difference between - * the values measured before and during - * selftest - */ - float d[3]; - - for (int i = 0; i < NUM_TESTS; ++i) - { - miosix::Thread::sleep(SLEEP_TIME); - - LIS3MDLData lastData = sampleImpl(); - d[0] = std::abs(lastData.magneticFieldX - avgX); - d[1] = std::abs(lastData.magneticFieldY - avgY); - d[2] = std::abs(lastData.magneticFieldZ - avgZ); - - bool passed = true; - for (int j = 0; j < 3; ++j) - { - if (d[j] < (r[j][0] - t) || d[j] > (r[j][1] + t)) - passed = false; - } - - if (!passed) - { - // reset configuration, then return - applyConfig(mConfig); - - lastError = SELF_TEST_FAIL; - return false; - } - } - - return applyConfig(mConfig); - } + bool selfTest() override; /** * @brief Overwrites the sensor settings. * - * Writes a certain config to the sensor - * registers. This method is automatically - * called in LIS3MDL::init() using as parameter - * the configuration given in the constructor. + * Writes a certain config to the sensor registers. This method is + * automatically called in LIS3MDL::init() using as parameter the + * configuration given in the constructor. * - * This method checks if the values were actually - * written in the sensor's registers and returns false - * if at least one of them was not as expected. + * This method checks if the values were actually written in the sensor's + * registers and returns false if at least one of them was not as expected. * - * @param config The configuration to be applied - * @returns true if the configuration was applied successfully, + * @param config The configuration to be applied. + * @returns True if the configuration was applied successfully, * false otherwise. */ - bool applyConfig(Config config) - { - - SPITransaction spi(mSlave); - uint8_t reg = 0, err = 0; - - mConfig = config; - currDiv = 0; - - /* -- CTRL_REG1 -- */ - if (config.enableTemperature) - { - reg = ENABLE_TEMPERATURE; - } - reg |= config.odr; - - // odr <= 80Hz - if (!(config.odr & FAST_ODR_BIT)) - reg |= config.xyMode << 4; - spi.writeRegister(CTRL_REG1, reg); - err |= spi.readRegister(CTRL_REG1) != reg; - - /* -- CTRL_REG2 -- */ - reg = config.scale; - spi.writeRegister(CTRL_REG2, reg); - err |= spi.readRegister(CTRL_REG2) != reg; - - /* -- CTRL_REG3 -- */ - reg = CONTINOUS_CONVERSION; - spi.writeRegister(CTRL_REG3, reg); - err |= spi.readRegister(CTRL_REG3) != reg; - - /* -- CTRL_REG4 -- */ - reg = config.zMode << 2; - spi.writeRegister(CTRL_REG4, reg); - err |= spi.readRegister(CTRL_REG4) != reg; - - /* -- CTRL_REG5 -- */ - if (config.doBlockDataUpdate) - { - reg = ENABLE_BDU; - } - else - { - reg = 0; - } - - spi.writeRegister(CTRL_REG5, reg); - err |= spi.readRegister(CTRL_REG5) != reg; - - /* -- INT_CFG -- */ - if (config.enableInterrupt[0]) - { - reg = ENABLE_INT_X; - } - else - { - reg = 0; - } - if (config.enableInterrupt[1]) - { - reg |= ENABLE_INT_Y; - } - if (config.enableInterrupt[2]) - { - reg |= ENABLE_INT_Z; - } - - // the interrupt of at least one axis is enabled - if (reg) - { - reg |= ENABLE_INT_PIN; - } - - reg |= 0x08; - spi.writeRegister(INT_CFG, reg); - err |= spi.readRegister(INT_CFG) != reg; - - /** INT_THS */ - uint16_t val = - static_cast<uint16_t>(std::abs(config.threshold / mUnit)); - reg = static_cast<uint8_t>(0xff & val); - spi.writeRegister(INT_THS_L, reg); - err |= spi.readRegister(INT_THS_L) != reg; - - reg = static_cast<uint8_t>(val >> 8); - reg &= - 0x7f; // remove MSB (according to the datasheet, it must be zero) - spi.writeRegister(INT_THS_H, reg); - err |= spi.readRegister(INT_THS_H) != reg; - - /* Set mUnit according to scale */ - updateUnit(config.scale); - - if (err) - { - LOG_ERR(logger, "Spi error"); - lastError = BUS_FAULT; - return false; - } - - return true; - } + bool applyConfig(Config config); private: - /** - * @brief Reads data from the sensor - * - * The init method must have been called before. - * Output data can be fetched with the methods - * compassDataPtr() and tempDataPtr inherited respectevely - * from CompassSensor and TemperatureSensor classes. - * Important: the temperature will be taken only once in a while - * according to the value of `temperatureDivider` - * - * @returns false if the sensor was unitialized, true otherwise. - */ - LIS3MDLData sampleImpl() override - { - if (!isInitialized) - { - LOG_ERR(logger, - "Invoked sampleImpl() but sensor was " - "unitialized"); - lastError = NOT_INIT; - return lastSample; - } - - SPITransaction spi(mSlave); - - if (!spi.readRegister(STATUS_REG)) - { - lastError = NO_NEW_DATA; - return lastSample; - } - - // Reset any error - lastError = SensorErrors::NO_ERRORS; - - int16_t val; - LIS3MDLData newData{}; - - if (mConfig.enableTemperature) - { - if (currDiv == 0) - { - val = spi.readRegister(TEMP_OUT_L); - val |= spi.readRegister(TEMP_OUT_H) << 8; - - newData.temperatureTimestamp = - TimestampTimer::getInstance().getTimestamp(); - newData.temperature = - static_cast<float>(val) / LSB_PER_CELSIUS + - REFERENCE_TEMPERATURE; - } - else - { - // Keep old value - newData.temperature = lastSample.temperature; - } - - currDiv = (currDiv + 1) % mConfig.temperatureDivider; - } - - newData.magneticFieldTimestamp = - TimestampTimer::getInstance().getTimestamp(); - - val = spi.readRegister(OUT_X_L); - val |= spi.readRegister(OUT_X_H) << 8; - newData.magneticFieldX = mUnit * val; - - val = spi.readRegister(OUT_Y_L); - val |= spi.readRegister(OUT_Y_H) << 8; - newData.magneticFieldY = mUnit * val; - - val = spi.readRegister(OUT_Z_L); - val |= spi.readRegister(OUT_Z_H) << 8; - newData.magneticFieldZ = mUnit * val; - - return newData; - } + LIS3MDLData sampleImpl() override; + + void updateUnit(FullScale fs); SPISlave mSlave; Config mConfig; @@ -568,32 +214,7 @@ private: bool isInitialized; float mUnit = 0; - void updateUnit(FullScale fs) - { - switch (fs) - { - case FS_4_GAUSS: - mUnit = 1.f / LSB_PER_GAUSS_FS_4; - break; - - case FS_8_GAUSS: - mUnit = 1.f / LSB_PER_GAUSS_FS_8; - break; - - case FS_12_GAUSS: - mUnit = 1.f / LSB_PER_GAUSS_FS_12; - break; - - case FS_16_GAUSS: - mUnit = 1.f / LSB_PER_GAUSS_FS_16; - break; - } - }; - - /** - * List of addresses of sensor registers - */ - enum Reg : uint8_t + enum Registers : uint8_t { WHO_AM_I = 0x0f, @@ -619,15 +240,11 @@ private: INT_THS_H = 0x33, }; - /** - * Misc. constants used by the driver. They are not - * particularly useful to the user. - */ enum Constants : unsigned { WHO_AM_I_VALUE = 0x3d, - CONTINOUS_CONVERSION = 0x0, + CONTINUOS_CONVERSION = 0x0, REFERENCE_TEMPERATURE = 25, LSB_PER_CELSIUS = 8, diff --git a/src/shared/sensors/MAX31855/MAX31855.cpp b/src/shared/sensors/MAX31855/MAX31855.cpp index b6f820bca946d87f43a41234e4232b8ac6758c03..ee52dd7ab70af2d83e150a60b8b322e490ba1fcd 100644 --- a/src/shared/sensors/MAX31855/MAX31855.cpp +++ b/src/shared/sensors/MAX31855/MAX31855.cpp @@ -76,7 +76,7 @@ TemperatureData MAX31855::sampleImpl() } TemperatureData result{}; - result.temperatureTimestamp = TimestampTimer::getInstance().getTimestamp(); + result.temperatureTimestamp = TimestampTimer::getTimestamp(); // Convert the integer and decimal part separately result.temperature = static_cast<float>(sample >> 2) * 0.25; @@ -94,7 +94,7 @@ TemperatureData MAX31855::readInternalTemperature() } TemperatureData result{}; - result.temperatureTimestamp = TimestampTimer::getInstance().getTimestamp(); + result.temperatureTimestamp = TimestampTimer::getTimestamp(); // Extract data bits sample[1] = sample[1] >> 4; diff --git a/src/shared/sensors/MAX31855/MAX31855.h b/src/shared/sensors/MAX31855/MAX31855.h index 89aa3484f0dc2e589c35f96329bfac0536d22896..4eb7368651024fc5490404ee61a65835559384ee 100644 --- a/src/shared/sensors/MAX31855/MAX31855.h +++ b/src/shared/sensors/MAX31855/MAX31855.h @@ -29,7 +29,7 @@ namespace Boardcore { /** - * @brief MAX31855 termocouple sensor driver. + * @brief MAX31855 thermocouple sensor driver. */ class MAX31855 : public Sensor<TemperatureData> { @@ -54,9 +54,9 @@ public: bool init(); /** - * @brief Checks wheter the termocouple is open. + * @brief Checks whether the thermocouple is open. * - * @return True if the termocouple is connected. + * @return True if the thermocouple is connected. */ bool selfTest(); diff --git a/src/shared/sensors/MAX6675/MAX6675.cpp b/src/shared/sensors/MAX6675/MAX6675.cpp index ae7be61ba8ab3f6bfa4bae88ffce398d4b9eb390..e12ecccb25331a72d0e80ebf420f7083b50833a4 100644 --- a/src/shared/sensors/MAX6675/MAX6675.cpp +++ b/src/shared/sensors/MAX6675/MAX6675.cpp @@ -75,7 +75,7 @@ TemperatureData MAX6675::sampleImpl() } TemperatureData result{}; - result.temperatureTimestamp = TimestampTimer::getInstance().getTimestamp(); + result.temperatureTimestamp = TimestampTimer::getTimestamp(); // Extract bits 14-3 sample &= 0x7FF8; diff --git a/src/shared/sensors/MPU9250/MPU9250.cpp b/src/shared/sensors/MPU9250/MPU9250.cpp index 0348e7afe5ae76c272fc2cbea109439f795dbcea..dba378e31dc922af052f91881fd753fc0016ab3d 100644 --- a/src/shared/sensors/MPU9250/MPU9250.cpp +++ b/src/shared/sensors/MPU9250/MPU9250.cpp @@ -116,9 +116,9 @@ MPU9250Data MPU9250::sampleImpl() spiSlave.config.clockDivider = clockDivider; // Save timestamps - uint64_t timestamp = TimestampTimer::getInstance().getTimestamp(); - data.accelerationTimestamp = timestamp; - data.temperatureTimestamp = timestamp; + uint64_t timestamp = TimestampTimer::getTimestamp(); + data.accelerationTimestamp = timestamp; + data.temperatureTimestamp = timestamp; data.angularVelocityTimestamp = timestamp; data.magneticFieldTimestamp = timestamp; diff --git a/src/shared/sensors/MS5803/MS5803.cpp b/src/shared/sensors/MS5803/MS5803.cpp index 52eec1bb6c3f0c15e833b75eaea66205c26b56e2..7387f6e9981dc87f5fc205ee7955b1631e02cb71 100644 --- a/src/shared/sensors/MS5803/MS5803.cpp +++ b/src/shared/sensors/MS5803/MS5803.cpp @@ -36,25 +36,21 @@ MS5803::MS5803(SPIBusInterface& spiBus, miosix::GpioPin cs, bool MS5803::init() { - SPITransaction transaction{spiSlave}; + SPITransaction transaction{spiSlave, SPITransaction::WriteBit::DISABLED}; // Read calibration data - calibrationData.sens = - readReg(transaction, REG_PROM_READ_MASK | REG_PROM_SENS_MASK); - calibrationData.off = - readReg(transaction, REG_PROM_READ_MASK | REG_PROM_OFF_MASK); - calibrationData.tcs = - readReg(transaction, REG_PROM_READ_MASK | REG_PROM_TCS_MASK); - calibrationData.tco = - readReg(transaction, REG_PROM_READ_MASK | REG_PROM_TCO_MASK); - calibrationData.tref = - readReg(transaction, REG_PROM_READ_MASK | REG_PROM_TREF_MASK); - calibrationData.tempsens = - readReg(transaction, REG_PROM_READ_MASK | REG_PROM_TEMPSENS_MASK); - - LOG_INFO(logger, "Init: off={}, tcs={}, tco={}, tref={}, tsens={}", - calibrationData.off, calibrationData.tcs, calibrationData.tco, - calibrationData.tref, calibrationData.tempsens); + calibrationData.sens = readReg(transaction, REG_PROM_SENS_MASK); + calibrationData.off = readReg(transaction, REG_PROM_OFF_MASK); + calibrationData.tcs = readReg(transaction, REG_PROM_TCS_MASK); + calibrationData.tco = readReg(transaction, REG_PROM_TCO_MASK); + calibrationData.tref = readReg(transaction, REG_PROM_TREF_MASK); + calibrationData.tempsens = readReg(transaction, REG_PROM_TEMPSENS_MASK); + + LOG_INFO( + logger, + "sens={:X}, off={:X}, tcs={:X}, tco={:X}, tref={:X}, tempsens={:X}", + calibrationData.sens, calibrationData.off, calibrationData.tcs, + calibrationData.tco, calibrationData.tref, calibrationData.tempsens); return true; } @@ -63,7 +59,7 @@ bool MS5803::selfTest() { return true; } MS5803Data MS5803::sampleImpl() { - SPITransaction transaction{spiSlave}; + SPITransaction transaction{spiSlave, SPITransaction::WriteBit::DISABLED}; uint8_t buffer[3]; @@ -79,23 +75,18 @@ MS5803Data MS5803::sampleImpl() case STATE_SAMPLED_TEMP: { // Read back the sampled temperature - transaction.writeRegisters(REG_ADC_READ, buffer, 3); + transaction.readRegisters(REG_ADC_READ, buffer, 3); uint32_t tmpRawTemperature = (uint32_t)buffer[2] | ((uint32_t)buffer[1] << 8) | ((uint32_t)buffer[0] << 16); - lastTemperatureTimestamp = - TimestampTimer::getInstance().getTimestamp(); + lastTemperatureTimestamp = TimestampTimer::getTimestamp(); // Check if the value is valid if (tmpRawTemperature != 0) - { rawTemperature = tmpRawTemperature; - } else - { LOG_ERR(logger, "The read raw temperature isn't valid"); - } // Begin pressure sampling transaction.write(static_cast<uint8_t>(REG_CONVERT_D1_4096)); @@ -113,16 +104,11 @@ MS5803Data MS5803::sampleImpl() // Check if the value is valid if (tmpRawPressure != 0) - { rawPressure = tmpRawPressure; - } else - { LOG_ERR(logger, "The read raw pressure isn't valid"); - } lastSample = updateData(); - // Check whether to read the pressure or the temperature tempCounter++; if (tempCounter % temperatureDivider == 0) @@ -166,9 +152,7 @@ MS5803Data MS5803::updateData() sens2 = (7 * (temp - 2000) * (temp - 2000)) >> 3; if (temp < -1500) - { sens2 = sens2 + 2 * (temp + 1500) * (temp + 1500); - } } else if (temp >= 4500) { @@ -185,7 +169,7 @@ MS5803Data MS5803::updateData() // Pressure in Pascal float temp_ = temp / 100.0f; - return MS5803Data(TimestampTimer::getInstance().getTimestamp(), pressure, + return MS5803Data(TimestampTimer::getTimestamp(), pressure, lastTemperatureTimestamp, temp_); } diff --git a/src/shared/sensors/MS5803/MS5803.h b/src/shared/sensors/MS5803/MS5803.h index 6065ebcbab862231cf4fcd37e12d857cb4119198..490d620d1e564e547b4c831ecd30e554709e957d 100644 --- a/src/shared/sensors/MS5803/MS5803.h +++ b/src/shared/sensors/MS5803/MS5803.h @@ -24,9 +24,9 @@ #include <diagnostic/PrintLogger.h> #include <drivers/spi/SPIDriver.h> -#include <sensors/MS5803/MS5803Data.h> #include <sensors/Sensor.h> -#include <utils/Debug.h> + +#include "MS5803Data.h" namespace Boardcore { @@ -62,13 +62,12 @@ public: // Read command for adc output REG_ADC_READ = 0x00, - REG_PROM_READ_MASK = 0xA0, - REG_PROM_SENS_MASK = 0x02, - REG_PROM_OFF_MASK = 0x04, - REG_PROM_TCS_MASK = 0x06, - REG_PROM_TCO_MASK = 0x08, - REG_PROM_TREF_MASK = 0x0A, - REG_PROM_TEMPSENS_MASK = 0x0C, + REG_PROM_SENS_MASK = 0xA2, + REG_PROM_OFF_MASK = 0xA4, + REG_PROM_TCS_MASK = 0xA6, + REG_PROM_TCO_MASK = 0xA8, + REG_PROM_TREF_MASK = 0xAA, + REG_PROM_TEMPSENS_MASK = 0xAC, }; static constexpr uint8_t TIMEOUT = 5; diff --git a/src/shared/sensors/SensorData.h b/src/shared/sensors/SensorData.h index d40024e73622d384aacdd9bddf89b3a76307e217..2a2a2ecb08270a9b4e107871e0480b4bb7b42f79 100644 --- a/src/shared/sensors/SensorData.h +++ b/src/shared/sensors/SensorData.h @@ -134,16 +134,17 @@ struct MagnetometerData struct GPSData { uint64_t gpsTimestamp; - float latitude; /**< [deg] */ - float longitude; /**< [deg] */ - float height; /**< [m] */ - float velocityNorth; /**< [m/s] */ - float velocityEast; /**< [m/s] */ - float velocityDown; /**< [m/s] */ - float speed; /**< [m/s] */ - float track; /**< [deg] */ - uint8_t satellites; /**< [1] */ - bool fix; + float latitude; // [deg] + float longitude; // [deg] + float height; // [m] + float velocityNorth; // [m/s] + float velocityEast; // [m/s] + float velocityDown; // [m/s] + float speed; // [m/s] + float track; // [deg] + float positionDOP; // [?] + uint8_t satellites; // [1] + uint8_t fix; // 0 = no fix }; /** diff --git a/src/shared/sensors/SensorInfo.h b/src/shared/sensors/SensorInfo.h index 2fc741efec5baaf58f12ec0d862dd16fcb11d3a2..804c0b0a863adfd8b97003e5563613e5d3716b6c 100644 --- a/src/shared/sensors/SensorInfo.h +++ b/src/shared/sensors/SensorInfo.h @@ -33,7 +33,7 @@ namespace Boardcore * * This structure contains the sampling period of a sensor, * the function to be called after the sampling (callback) and - * oneboolean indicating if the sensor has to be sampled (is enabled). + * one boolean indicating if the sensor has to be sampled (is enabled). */ struct SensorInfo { diff --git a/src/shared/sensors/SensorManager.h b/src/shared/sensors/SensorManager.h index 3f6cd41900795f9ebcee5c4a26ca9b0891598177..890116fb12216a6115b5e000a8d40efdbe9ca48f 100644 --- a/src/shared/sensors/SensorManager.h +++ b/src/shared/sensors/SensorManager.h @@ -108,7 +108,7 @@ private: * @brief Initializes samplers vector and sensorsMap with the given sensors * map, giving incremental IDs to SensorSampler objects. * - * In case a TaskScheduler was passed in the costructor, the SensorManager + * In case a TaskScheduler was passed in the constructor, the SensorManager * will assign to SensorSamplers incremental IDs starting from the maximum * among the tasks already existing in the TaskScheduler. * diff --git a/src/shared/sensors/UBXGPS/UBXFrame.h b/src/shared/sensors/UBXGPS/UBXFrame.h new file mode 100644 index 0000000000000000000000000000000000000000..9f1593baaa01a1ce8b3d7be31488e9ba12cfd05d --- /dev/null +++ b/src/shared/sensors/UBXGPS/UBXFrame.h @@ -0,0 +1,308 @@ +/* Copyright (c) 2022 Skyward Experimental Rocketry + * Authors: Damiano Amatruda, Alberto Nidasio + * + * 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. + */ + +#pragma once + +#include <stdint.h> + +#include <algorithm> +#include <cstring> + +namespace Boardcore +{ + +/** + * @brief UBX messages enumeration. + */ +enum class UBXMessage : uint16_t +{ + UBX_NAV_PVT = 0x0701, // Navigation position velocity time solution + UBX_ACK_NAK = 0x0005, // Message acknowledged + UBX_ACK_ACK = 0x0105, // Message not acknowledged + UBX_CFG_PRT = 0x0006, // Port configuration + UBX_CFG_MSG = 0x0106, // Set message rate + UBX_CFG_RST = 0x0406, // Reset receiver + UBX_CFG_RATE = 0x0806, // Navigation/measurement rate settings + UBX_CFG_NAV5 = 0x2406, // Navigation engine settings +}; + +/** + * @brief Generic UBX frame. + */ +struct UBXFrame +{ + static constexpr uint16_t MAX_PAYLOAD_LENGTH = 92; + static constexpr uint16_t MAX_FRAME_LENGTH = MAX_PAYLOAD_LENGTH + 8; + static constexpr uint8_t PREAMBLE[] = {0xb5, 0x62}; + static constexpr uint8_t WAIT = 0xff; + + uint8_t preamble[2]; + uint16_t message; + uint16_t payloadLength; + uint8_t payload[MAX_PAYLOAD_LENGTH]; + uint8_t checksum[2]; + + UBXFrame() = default; + + /** + * @brief Construct a new UBXFrame with the specified message and given + * payload. + */ + UBXFrame(UBXMessage message, const uint8_t* payload, + uint16_t payloadLength); + + /** + * @brief Return the total frame length. + */ + uint16_t getLength() const; + + /** + * @brief Return the stored payload length. + */ + uint16_t getRealPayloadLength() const; + + UBXMessage getMessage() const; + + /** + * @brief Tells whether the current frame is valid or not. Checks the + * preamble and the checksum. + */ + bool isValid() const; + + /** + * @brief Writes the current message into the given array. + * + * @param frame Must be an array of the proper length. + */ + void writePacked(uint8_t* frame) const; + + /** + * @brief Reads a raw frame. + * + * Note that the frame bytes are assumed to start with the preamble. + * + * @param frame An array of length at least MAX_FRAME_LENGTH. + */ + void readPacked(const uint8_t* frame); + + /** + * @brief Computes the frame checksum. + * + * @param checksum Array of 2 elements where to store the checksum + */ + void calcChecksum(uint8_t* checksum) const; +}; + +/** + * @brief UBX frames UBX-ACK-ACK and UBX-ACK-NAK. + */ +struct UBXAckFrame : public UBXFrame +{ + /** + * @brief Payload of UBX frames UBX-ACK-ACK and UBX-ACK-NAK. + */ + struct __attribute__((packed)) Payload + { + uint16_t ackMessage; + }; + + Payload& getPayload() const; + + UBXMessage getAckMessage() const; + + /** + * @brief Tells whether the frame is an ack. + */ + bool isAck() const; + + /** + * @brief Tells whether the frame is a nak. + */ + bool isNack() const; + + /** + * @brief Tells whether the frame is an ack frame. + */ + bool isValid() const; +}; + +/** + * @brief UBX frame UBX-NAV-PVT. + */ +struct UBXPvtFrame : public UBXFrame +{ +public: + /** + * @brief Payload of UBX frame UBX-NAV-PVT. + */ + struct __attribute__((packed)) Payload + { + uint32_t iTOW; // GPS time of week of the navigation epoch [ms] + uint16_t year; // Year (UTC) [y] + uint8_t month; // Month, range 1..12 (UTC) [month] + uint8_t day; // Day of month, range 1..31 (UTC) [d] + uint8_t hour; // Hour of day, range 0..23 (UTC) [h] + uint8_t min; // Minute of hour, range 0..59 (UTC) [min] + uint8_t sec; // Seconds of minute, range 0..60 (UTC) [s] + uint8_t valid; // Validity flags + uint32_t tAcc; // Time accuracy estimate (UTC) [ns] + int32_t nano; // Fraction of second, range -1e9 .. 1e9 (UTC) [ns] + uint8_t fixType; // GNSS fix Type + uint8_t flags; // Fix status flags + uint8_t flags2; // Additional flags + uint8_t numSV; // Number of satellites used in Nav Solution + int32_t lon; // Longitude {1e-7} [deg] + int32_t lat; // Latitude {1e-7} [deg] + int32_t height; // Height above ellipsoid [mm] + int32_t hMSL; // Height above mean sea level [mm] + uint32_t hAcc; // Horizontal accuracy estimate [mm] + uint32_t vAcc; // Vertical accuracy estimate [mm] + int32_t velN; // NED north velocity [mm/s] + int32_t velE; // NED east velocity [mm/s] + int32_t velD; // NED down velocity [mm/s] + int32_t gSpeed; // Ground Speed (2-D) [mm/s] + int32_t headMot; // Heading of motion (2-D) {1e-5} [deg] + uint32_t sAcc; // Speed accuracy estimate [mm/s] + uint32_t headAcc; // Heading accuracy estimate (both motion and + // vehicle) {1e-5} [deg] + uint16_t pDOP; // Position DOP {0.01} + uint16_t flags3; // Additional flags + uint8_t reserved0[4]; // Reserved + int32_t headVeh; // Heading of vehicle (2-D) {1e-5} [deg] + int16_t magDec; // Magnetic declination {1e-2} [deg] + uint16_t magAcc; // Magnetic declination accuracy {1e-2} [deg] + }; + + Payload& getPayload() const; + + /** + * @brief Tells whether the frame is an ack frame. + */ + bool isValid() const; +}; + +inline UBXFrame::UBXFrame(UBXMessage message, const uint8_t* payload, + uint16_t payloadLength) + : message(static_cast<uint16_t>(message)), payloadLength(payloadLength) +{ + memcpy(preamble, PREAMBLE, 2); + if (payload != nullptr) + memcpy(this->payload, payload, getRealPayloadLength()); + calcChecksum(checksum); +} + +inline uint16_t UBXFrame::getLength() const { return payloadLength + 8; } + +inline uint16_t UBXFrame::getRealPayloadLength() const +{ + return std::min(payloadLength, MAX_PAYLOAD_LENGTH); +} + +inline UBXMessage UBXFrame::getMessage() const +{ + return static_cast<UBXMessage>(message); +} + +inline bool UBXFrame::isValid() const +{ + if (memcmp(preamble, PREAMBLE, 2) != 0) + return false; + + if (payloadLength > MAX_PAYLOAD_LENGTH) + return false; + + uint8_t validChecksum[2]; + calcChecksum(validChecksum); + return memcmp(checksum, validChecksum, 2) == 0; +} + +inline void UBXFrame::writePacked(uint8_t* frame) const +{ + memcpy(frame, preamble, 2); + memcpy(&frame[2], &message, 2); + memcpy(&frame[4], &payloadLength, 2); + memcpy(&frame[6], payload, getRealPayloadLength()); + memcpy(&frame[6 + payloadLength], checksum, 2); +} + +inline void UBXFrame::readPacked(const uint8_t* frame) +{ + memcpy(preamble, frame, 2); + memcpy(&message, &frame[2], 2); + memcpy(&payloadLength, &frame[4], 2); + memcpy(payload, &frame[6], getRealPayloadLength()); + memcpy(checksum, &frame[6 + payloadLength], 2); +} + +inline void UBXFrame::calcChecksum(uint8_t* checksum) const +{ + uint8_t data[getRealPayloadLength() + 4]; + memcpy(data, &message, 2); + memcpy(&data[2], &payloadLength, 2); + memcpy(&data[4], payload, getRealPayloadLength()); + + checksum[0] = 0; + checksum[1] = 0; + + for (size_t i = 0; i < sizeof(data); ++i) + { + checksum[0] += data[i]; + checksum[1] += checksum[0]; + } +} + +inline UBXAckFrame::Payload& UBXAckFrame::getPayload() const +{ + return (Payload&)payload; +} + +inline UBXMessage UBXAckFrame::getAckMessage() const +{ + return static_cast<UBXMessage>(getPayload().ackMessage); +} + +inline bool UBXAckFrame::isAck() const +{ + return getMessage() == UBXMessage::UBX_ACK_ACK; +} + +inline bool UBXAckFrame::isNack() const +{ + return getMessage() == UBXMessage::UBX_ACK_NAK; +} + +inline bool UBXAckFrame::isValid() const +{ + return UBXFrame::isValid() && (isAck() || isNack()); +} + +inline UBXPvtFrame::Payload& UBXPvtFrame::getPayload() const +{ + return (Payload&)payload; +} + +inline bool UBXPvtFrame::isValid() const +{ + return UBXFrame::isValid() && getMessage() == UBXMessage::UBX_NAV_PVT; +} + +} // namespace Boardcore diff --git a/src/shared/sensors/UbloxGPS/UbloxGPSData.h b/src/shared/sensors/UBXGPS/UBXGPSData.h similarity index 79% rename from src/shared/sensors/UbloxGPS/UbloxGPSData.h rename to src/shared/sensors/UBXGPS/UBXGPSData.h index 7f5570000b78b915a956b96e754d784e08f7611f..ed734d258bd1c0dd79206b8d392562b7009a22bf 100644 --- a/src/shared/sensors/UbloxGPS/UbloxGPSData.h +++ b/src/shared/sensors/UBXGPS/UBXGPSData.h @@ -1,5 +1,5 @@ -/* Copyright (c) 2020 Skyward Experimental Rocketry - * Author: Davide Bonomini +/* Copyright (c) 2020-2022 Skyward Experimental Rocketry + * Authors: Davide Bonomini, Damiano Amatruda * * Permission is hereby granted, free of charge, to any person obtaining a copy * of this software and associated documentation files (the "Software"), to deal @@ -27,20 +27,21 @@ namespace Boardcore { -struct UbloxGPSData : public GPSData +struct UBXGPSData : public GPSData { static std::string header() { - return "gps_timestamp,latitude,longitude,height,velocity_north," - "velocity_east,velocity_down,speed,track,num_satellites,fix\n"; + return "gpsTimestamp,latitude,longitude,height,velocityNorth," + "velocityEast,velocityDown,speed,track,positionDOP,satellites," + "fix\n"; } void print(std::ostream &os) const { os << gpsTimestamp << "," << latitude << "," << longitude << "," << height << "," << velocityNorth << "," << velocityEast << "," - << velocityDown << "," << speed << "," << track << "," - << (int)satellites << "," << (int)fix << "\n"; + << velocityDown << "," << speed << "," << track << "," << positionDOP + << "," << (int)satellites << "," << (int)fix << "\n"; } }; diff --git a/src/shared/sensors/UBXGPS/UBXGPSSerial.cpp b/src/shared/sensors/UBXGPS/UBXGPSSerial.cpp new file mode 100644 index 0000000000000000000000000000000000000000..d8a4502929c73ab4c46462f2a7d36f5004a02942 --- /dev/null +++ b/src/shared/sensors/UBXGPS/UBXGPSSerial.cpp @@ -0,0 +1,430 @@ +/* Copyright (c) 2021 Skyward Experimental Rocketry + * Authors: Davide Bonomini, Davide Mor, Alberto Nidasio + * + * 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. + */ + +#include "UBXGPSSerial.h" + +#include <diagnostic/StackLogger.h> +#include <drivers/serial.h> +#include <drivers/timer/TimestampTimer.h> +#include <fcntl.h> +#include <filesystem/file_access.h> + +using namespace miosix; + +namespace Boardcore +{ + +UBXGPSSerial::UBXGPSSerial(int baudrate, uint8_t sampleRate, int serialPortNum, + const char* serialPortName, int defaultBaudrate) + : baudrate(baudrate), sampleRate(sampleRate), + serialPortNumber(serialPortNum), serialPortName(serialPortName), + defaultBaudrate(defaultBaudrate) +{ + // Prepare the gps file path with the specified name + strcpy(gpsFilePath, "/dev/"); + strcat(gpsFilePath, serialPortName); +} + +bool UBXGPSSerial::init() +{ + LOG_DEBUG(logger, "Changing device baudrate..."); + + if (!setSerialCommunication()) + { + lastError = SensorErrors::INIT_FAIL; + LOG_ERR(logger, "Error while setting serial communication"); + return false; + } + + LOG_DEBUG(logger, "Resetting the device..."); + + // if (!reset()) + // { + // lastError = SensorErrors::INIT_FAIL; + // LOG_ERR(logger, "Could not reset the device"); + // return false; + // } + + LOG_DEBUG(logger, "Setting the UBX protocol..."); + + if (!setBaudrateAndUBX()) + { + lastError = SensorErrors::INIT_FAIL; + LOG_ERR(logger, "Could not set the UBX protocol"); + return false; + } + + LOG_DEBUG(logger, "Setting the dynamic model..."); + + if (!setDynamicModelToAirborne4g()) + { + lastError = SensorErrors::INIT_FAIL; + LOG_ERR(logger, "Could not set the dynamic model"); + return false; + } + + LOG_DEBUG(logger, "Setting the sample rate..."); + + if (!setSampleRate()) + { + lastError = SensorErrors::INIT_FAIL; + LOG_ERR(logger, "Could not set the sample rate"); + return false; + } + + LOG_DEBUG(logger, "Setting the PVT message rate..."); + + if (!setPVTMessageRate()) + { + lastError = SensorErrors::INIT_FAIL; + LOG_ERR(logger, "Could not set the PVT message rate"); + return false; + } + + this->start(); + + return true; +} + +bool UBXGPSSerial::selfTest() { return true; } + +UBXGPSData UBXGPSSerial::sampleImpl() +{ + Lock<FastMutex> l(mutex); + return threadSample; +} + +bool UBXGPSSerial::reset() +{ + uint8_t payload[] = { + 0x00, 0x00, // Hot start + 0x00, // Hardware reset + 0x00 // Reserved + }; + + UBXFrame frame{UBXMessage::UBX_CFG_RST, payload, sizeof(payload)}; + + // The reset message will not be followed by an acknowledgment + if (!writeUBXFrame(frame)) + return false; + + // Do not interact with the module while it is resetting + miosix::Thread::sleep(RESET_SLEEP_TIME); + + return true; +} + +bool UBXGPSSerial::setBaudrateAndUBX(bool safe) +{ + uint8_t payload[] = { + 0x01, // UART port + 0x00, // Reserved + 0x00, 0x00, // txReady + 0xc0, 0x08, 0x00, 0x00, // 8bit, no parity, 1 stop bit + 0x00, 0x00, 0x00, 0x00, // Baudrate + 0x01, 0x00, // inProtoMask = UBX + 0x01, 0x00, // outProtoMask = UBX + 0x00, 0x00, // flags + 0x00, 0x00 // reserved2 + }; + + // Prepare baudrate + payload[8] = baudrate; + payload[9] = baudrate >> 8; + payload[10] = baudrate >> 16; + payload[11] = baudrate >> 24; + + UBXFrame frame{UBXMessage::UBX_CFG_PRT, payload, sizeof(payload)}; + + if (safe) + return safeWriteUBXFrame(frame); + else + return writeUBXFrame(frame); +} + +bool UBXGPSSerial::setSerialCommunication() +{ + intrusive_ref_ptr<DevFs> devFs = FilesystemManager::instance().getDevFs(); + + // Change the baudrate only if it is different than the default + if (baudrate != defaultBaudrate) + { + // Close the gps file if already opened + devFs->remove(serialPortName); + + // Open the serial port device with the default baudrate + if (!devFs->addDevice(serialPortName, + intrusive_ref_ptr<Device>(new STM32Serial( + serialPortNumber, defaultBaudrate)))) + { + LOG_ERR(logger, + "Failed to open serial port {0} with baudrate {1} as " + "file {2}", + serialPortNumber, defaultBaudrate, serialPortName); + return false; + } + + // Open the gps file + if ((gpsFile = open(gpsFilePath, O_RDWR)) < 0) + { + LOG_ERR(logger, "Failed to open gps file {}", gpsFilePath); + return false; + } + + // Change baudrate + if (!setBaudrateAndUBX(false)) + { + return false; + }; + + // Close the gps file + if (close(gpsFile) < 0) + { + LOG_ERR(logger, "Failed to close gps file {}", gpsFilePath); + return false; + } + + // Close the serial port + if (!devFs->remove(serialPortName)) + { + LOG_ERR(logger, "Failed to close serial port {} as file {}", + serialPortNumber, serialPortName); + return false; + } + } + + // Reopen the serial port with the configured baudrate + if (!devFs->addDevice(serialPortName, + intrusive_ref_ptr<Device>( + new STM32Serial(serialPortNumber, baudrate)))) + { + LOG_ERR(logger, + "Failed to open serial port {} with baudrate {} as file {}\n", + serialPortNumber, defaultBaudrate, serialPortName); + return false; + } + + // Reopen the gps file + if ((gpsFile = open(gpsFilePath, O_RDWR)) < 0) + { + LOG_ERR(logger, "Failed to open gps file {}", gpsFilePath); + return false; + } + + return true; +} + +bool UBXGPSSerial::setDynamicModelToAirborne4g() +{ + uint8_t payload[] = { + 0x01, 0x00, // Parameters bitmask, apply dynamic model configuration + 0x08, // Dynamic model = airborne 4g + 0x00, // Fix mode + 0x00, 0x00, 0x00, 0x00, // Fixed altitude for 2D mode + 0x00, 0x00, 0x00, 0x00, // Fixed altitude variance for 2D mode + 0x00, // Minimum elevation for a GNSS satellite to be used + 0x00, // Reserved + 0x00, 0x00, // Position DOP mask to use + 0x00, 0x00, // Time DOP mask to use + 0x00, 0x00, // Position accuracy mask + 0x00, 0x00, // Time accuracy mask + 0x00, // Static hold threshold + 0x00, // DGNSS timeout + 0x00, // C/NO threshold number SVs + 0x00, // C/NO threshold + 0x00, 0x00, // Reserved + 0x00, 0x00, // Static hold distance threshold + 0x00, // UTC standard to be used + 0x00, 0x00, 0x00, 0x00, 0x00 // Reserved + }; + + UBXFrame frame{UBXMessage::UBX_CFG_NAV5, payload, sizeof(payload)}; + + return safeWriteUBXFrame(frame); +} + +bool UBXGPSSerial::setSampleRate() +{ + uint8_t payload[] = { + 0x00, 0x00, // Measurement rate + 0x01, 0x00, // One navigation solution per measurement + 0x01, 0x01 // GPS time + }; + + uint16_t sampleRateMs = 1000 / sampleRate; + payload[0] = sampleRateMs; + payload[1] = sampleRateMs >> 8; + + UBXFrame frame{UBXMessage::UBX_CFG_RATE, payload, sizeof(payload)}; + + return safeWriteUBXFrame(frame); +} + +bool UBXGPSSerial::setPVTMessageRate() +{ + uint8_t payload[] = { + 0x01, 0x07, // PVT message + 0x01 // Rate = 1 navigation solution update + }; + + UBXFrame frame{UBXMessage::UBX_CFG_MSG, payload, sizeof(payload)}; + + return safeWriteUBXFrame(frame); +} + +bool UBXGPSSerial::readUBXFrame(UBXFrame& frame) +{ + // Search UBX frame preamble byte by byte + size_t i = 0; + while (i < 2) + { + uint8_t c; + if (read(gpsFile, &c, 1) <= 0) // No more data available + return false; + + if (c == UBXFrame::PREAMBLE[i]) + { + frame.preamble[i++] = c; + } + else if (c == UBXFrame::PREAMBLE[0]) + { + i = 0; + frame.preamble[i++] = c; + } + else + { + i = 0; + // LOG_DEBUG(logger, "Received unexpected byte: {:02x} {:#c}", c, + // c); + } + } + + if (read(gpsFile, &frame.message, 2) <= 0 || + read(gpsFile, &frame.payloadLength, 2) <= 0 || + read(gpsFile, frame.payload, frame.getRealPayloadLength()) <= 0 || + read(gpsFile, frame.checksum, 2) <= 0) + return false; + + if (!frame.isValid()) + { + LOG_ERR(logger, "Received invalid UBX frame"); + return false; + } + + return true; +} + +bool UBXGPSSerial::writeUBXFrame(const UBXFrame& frame) +{ + if (!frame.isValid()) + { + LOG_ERR(logger, "Trying to send an invalid UBX frame"); + return false; + } + + uint8_t packedFrame[frame.getLength()]; + frame.writePacked(packedFrame); + + if (write(gpsFile, packedFrame, frame.getLength()) < 0) + { + LOG_ERR(logger, "Failed to write ubx message"); + return false; + } + + return true; +} + +bool UBXGPSSerial::safeWriteUBXFrame(const UBXFrame& frame) +{ + for (unsigned int i = 0; i < MAX_TRIES; i++) + { + if (i > 0) + LOG_DEBUG(logger, "Retrying (attempt {:#d} of {:#d})...", i + 1, + MAX_TRIES); + + if (!writeUBXFrame(frame)) + return false; + + UBXAckFrame ack; + + if (!readUBXFrame(ack)) + continue; + + if (ack.isNack()) + { + if (ack.getAckMessage() == frame.getMessage()) + LOG_DEBUG(logger, "Received NAK"); + else + LOG_DEBUG(logger, "Received NAK for different UBX frame {:04x}", + static_cast<uint16_t>(ack.getPayload().ackMessage)); + continue; + } + + if (ack.isAck() && ack.getAckMessage() != frame.getMessage()) + { + LOG_DEBUG(logger, "Received ACK for different UBX frame {:04x}", + static_cast<uint16_t>(ack.getPayload().ackMessage)); + continue; + } + + return true; + } + + LOG_ERR(logger, "Gave up after {:#d} tries", MAX_TRIES); + return false; +} + +void UBXGPSSerial::run() +{ + while (!shouldStop()) + { + UBXPvtFrame pvt; + + // Try to read the message + if (!readUBXFrame(pvt)) + { + LOG_DEBUG(logger, "Unable to read a UBX message"); + continue; + } + + UBXPvtFrame::Payload& pvtP = pvt.getPayload(); + + // Lock the mutex + Lock<FastMutex> l(mutex); + threadSample.gpsTimestamp = TimestampTimer::getTimestamp(); + threadSample.latitude = (float)pvtP.lat / 1e7; + threadSample.longitude = (float)pvtP.lon / 1e7; + threadSample.height = (float)pvtP.height / 1e3; + threadSample.velocityNorth = (float)pvtP.velN / 1e3; + threadSample.velocityEast = (float)pvtP.velE / 1e3; + threadSample.velocityDown = (float)pvtP.velD / 1e3; + threadSample.speed = (float)pvtP.gSpeed / 1e3; + threadSample.track = (float)pvtP.headMot / 1e5; + threadSample.positionDOP = (float)pvtP.pDOP / 1e2; + threadSample.satellites = pvtP.numSV; + threadSample.fix = pvtP.fixType; + + StackLogger::getInstance().updateStack(THID_GPS); + } +} + +} // namespace Boardcore diff --git a/src/shared/sensors/UBXGPS/UBXGPSSerial.h b/src/shared/sensors/UBXGPS/UBXGPSSerial.h new file mode 100644 index 0000000000000000000000000000000000000000..4785778c2beab52185b2b614f06db7ab2c0e4769 --- /dev/null +++ b/src/shared/sensors/UBXGPS/UBXGPSSerial.h @@ -0,0 +1,179 @@ +/* Copyright (c) 2021 Skyward Experimental Rocketry + * Authors: Davide Bonomini, Davide Mor, Alberto Nidasio + * + * 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. + */ + +#pragma once + +#include <ActiveObject.h> +#include <diagnostic/PrintLogger.h> +#include <miosix.h> +#include <sensors/Sensor.h> + +#include "UBXFrame.h" +#include "UBXGPSData.h" + +namespace Boardcore +{ + +/** + * @brief Driver for Ublox GPSs + * + * This driver handles communication and setup with Ublox GPSs. It uses the + * binary UBX protocol to retrieve and parse navigation data quicker than using + * the string based NMEA. + * + * At initialization it configures the device with the specified baudrate, reset + * the configuration and sets up UBX messages and GNSS parameters. + * + * Communication with the device is performed through a file, the driver opens + * the serial port under the filepath /dev/<serialPortName>. + * There is no need for the file to be setted up beforhand. + * + * This driver was written for a NEO-M9N gps with the latest version of UBX. + */ +class UBXGPSSerial : public Sensor<UBXGPSData>, public ActiveObject +{ +public: + /** + * @brief Construct a new UBXGPSSerial object. + * + * @param baudrate Baudrate to communicate with the device (max: 921600, + * min: 4800 for NEO-M9N). + * @param sampleRate GPS sample rate (max: 25 for NEO-M9N). + * @param serialPortNumber Number of the serial port connected to the GPS. + * @param serialPortName Name of the file for the gps device. + * @param defaultBaudrate Startup baudrate (38400 for NEO-M9N). + */ + UBXGPSSerial(int baudrate = 921600, uint8_t sampleRate = 10, + int serialPortNumber = 2, const char *serialPortName = "gps", + int defaultBaudrate = 38400); + + /** + * @brief Sets up the serial port baudrate, disables the NMEA messages, + * configures GNSS options and enables UBX-PVT message. + * + * @return True if the operation succeeded. + */ + bool init() override; + + /** + * @brief Read a single message form the GPS, waits 2 sample cycle. + * + * @return True if a message was sampled. + */ + bool selfTest() override; + +private: + UBXGPSData sampleImpl() override; + + /** + * @brief Resets the device to its default configuration. + * + * @return True if the device reset succeeded. + */ + bool reset(); + + /** + * @brief Sets the UART port baudrate and enables UBX and disables NMEA on + * the UART port. + * + * @param safe Whether to expect an ack after the command. + * @return True if the configuration received an acknowledgement. + */ + bool setBaudrateAndUBX(bool safe = true); + + /** + * @brief Sets up the serial port with the correct baudrate. + * + * Opens the serial port with the default baudrate and changes it to the + * value specified in the constructor, then it reopens the serial port. If + * the device is already using the correct baudrate this won't have effect. + * However if the gps is using a different baudrate the diver won't be able + * to communicate. + */ + bool setSerialCommunication(); + + /** + * @brief Configures the dynamic model to airborn 4g. + * + * @return True if the configuration received an acknowledgement. + */ + bool setDynamicModelToAirborne4g(); + + /** + * @brief Configures the navigation solution sample rate. + * + * @return True if the configuration received an acknowledgement. + */ + bool setSampleRate(); + + /** + * @brief Configures the PVT message output rate. + * + * @return True if the configuration received an acknowledgement. + */ + bool setPVTMessageRate(); + + /** + * @brief Reads a UBX frame. + * + * @param frame The received frame. + * @return True if a valid frame was read. + */ + bool readUBXFrame(UBXFrame &frame); + + /** + * @brief Writes a UBX frame. + * + * @param frame The frame to write. + * @return True if the frame is valid. + */ + bool writeUBXFrame(const UBXFrame &frame); + + /** + * @brief Writes a UBX frame and waits for its acknowledgement. + * + * @param frame The frame to write. + * @return True if the frame is valid and acknowledged. + */ + bool safeWriteUBXFrame(const UBXFrame &frame); + + void run() override; + + const int baudrate; // [baud] + const uint8_t sampleRate; // [Hz] + const int serialPortNumber; + const char *serialPortName; + const int defaultBaudrate; // [baud] + + char gpsFilePath[16]; ///< Allows for a filename of up to 10 characters + int gpsFile = -1; + + mutable miosix::FastMutex mutex; + UBXGPSData threadSample{}; + + PrintLogger logger = Logging::getLogger("ubloxgps"); + + static constexpr unsigned int RESET_SLEEP_TIME = 5000; // [ms] + static constexpr unsigned int MAX_TRIES = 5; // [1] +}; + +} // namespace Boardcore diff --git a/src/shared/sensors/UBXGPS/UBXGPSSpi.cpp b/src/shared/sensors/UBXGPS/UBXGPSSpi.cpp new file mode 100644 index 0000000000000000000000000000000000000000..d5a556b5cfc86f679625cd88ee8007558f23dcea --- /dev/null +++ b/src/shared/sensors/UBXGPS/UBXGPSSpi.cpp @@ -0,0 +1,358 @@ +/* Copyright (c) 2022 Skyward Experimental Rocketry + * Authors: Davide Bonomini, Davide Mor, Alberto Nidasio, Damiano Amatruda + * + * 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. + */ + +#include "UBXGPSSpi.h" + +#include <drivers/timer/TimestampTimer.h> +#include <interfaces/endianness.h> + +namespace Boardcore +{ + +constexpr uint16_t UBXFrame::MAX_PAYLOAD_LENGTH; +constexpr uint16_t UBXFrame::MAX_FRAME_LENGTH; +constexpr uint8_t UBXFrame::PREAMBLE[]; +constexpr uint8_t UBXFrame::WAIT; + +constexpr float UBXGPSSpi::MS_TO_TICK; + +constexpr unsigned int UBXGPSSpi::RESET_SLEEP_TIME; +constexpr unsigned int UBXGPSSpi::READ_TIMEOUT; +constexpr unsigned int UBXGPSSpi::MAX_TRIES; + +UBXGPSSpi::UBXGPSSpi(SPIBusInterface& spiBus, miosix::GpioPin spiCs, + SPIBusConfig spiConfig, uint8_t sampleRate) + : spiSlave(spiBus, spiCs, spiConfig), sampleRate(sampleRate) +{ +} + +SPIBusConfig UBXGPSSpi::getDefaultSPIConfig() +{ + /* From data sheet of series NEO-M8: + * "Minimum initialization time" (setup time): 10 us + * "Minimum deselect time" (hold time): 1 ms */ + return SPIBusConfig{SPI::ClockDivider::DIV_32, SPI::Mode::MODE_0, + SPI::BitOrder::MSB_FIRST, 10, 1000}; +} + +uint8_t UBXGPSSpi::getSampleRate() { return sampleRate; } + +bool UBXGPSSpi::init() +{ + LOG_DEBUG(logger, "Resetting the device..."); + + if (!reset()) + { + lastError = SensorErrors::INIT_FAIL; + LOG_ERR(logger, "Could not reset the device"); + return false; + } + + LOG_DEBUG(logger, "Setting the UBX protocol..."); + + if (!setUBXProtocol()) + { + lastError = SensorErrors::INIT_FAIL; + LOG_ERR(logger, "Could not set the UBX protocol"); + return false; + } + + LOG_DEBUG(logger, "Setting the dynamic model..."); + + if (!setDynamicModelToAirborne4g()) + { + lastError = SensorErrors::INIT_FAIL; + LOG_ERR(logger, "Could not set the dynamic model"); + return false; + } + + LOG_DEBUG(logger, "Setting the sample rate..."); + + if (!setSampleRate()) + { + lastError = SensorErrors::INIT_FAIL; + LOG_ERR(logger, "Could not set the sample rate"); + return false; + } + + LOG_DEBUG(logger, "Setting the PVT message rate..."); + + if (!setPVTMessageRate()) + { + lastError = SensorErrors::INIT_FAIL; + LOG_ERR(logger, "Could not set the PVT message rate"); + return false; + } + + return true; +} + +bool UBXGPSSpi::selfTest() { return true; } + +UBXGPSData UBXGPSSpi::sampleImpl() +{ + UBXPvtFrame pvt; + + if (!readUBXFrame(pvt)) + return lastSample; + + UBXPvtFrame::Payload& pvtP = pvt.getPayload(); + + UBXGPSData sample; + sample.gpsTimestamp = TimestampTimer::getTimestamp(); + sample.latitude = (float)pvtP.lat / 1e7; + sample.longitude = (float)pvtP.lon / 1e7; + sample.height = (float)pvtP.height / 1e3; + sample.velocityNorth = (float)pvtP.velN / 1e3; + sample.velocityEast = (float)pvtP.velE / 1e3; + sample.velocityDown = (float)pvtP.velD / 1e3; + sample.speed = (float)pvtP.gSpeed / 1e3; + sample.track = (float)pvtP.headMot / 1e5; + sample.positionDOP = (float)pvtP.pDOP / 1e2; + sample.satellites = pvtP.numSV; + sample.fix = pvtP.fixType; + + return sample; +} + +bool UBXGPSSpi::reset() +{ + uint8_t payload[] = { + 0x00, 0x00, // Hot start + 0x00, // Hardware reset + 0x00 // Reserved + }; + + UBXFrame frame{UBXMessage::UBX_CFG_RST, payload, sizeof(payload)}; + + // The reset message will not be followed by an acknowledgment + if (!writeUBXFrame(frame)) + return false; + + // Do not interact with the module while it is resetting + miosix::Thread::sleep(RESET_SLEEP_TIME); + + return true; +} + +bool UBXGPSSpi::setUBXProtocol() +{ + uint8_t payload[] = { + 0x04, // SPI port + 0x00, // reserved0 + 0x00, 0x00, // txReady + 0x00, 0x00, 0x00, 0x00, // spiMode = 0, ffCnt = 0 (mechanism off) + 0x00, 0x00, 0x00, 0x00, // reserved1 + 0x01, 0x00, // inProtoMask = UBX + 0x01, 0x00, // outProtoMask = UBX + 0x00, 0x00, // flags + 0x00, 0x00 // reserved2 + }; + + UBXFrame frame{UBXMessage::UBX_CFG_PRT, payload, sizeof(payload)}; + + return safeWriteUBXFrame(frame); +} + +bool UBXGPSSpi::setDynamicModelToAirborne4g() +{ + uint8_t payload[] = { + 0x01, 0x00, // Parameters bitmask, apply dynamic model configuration + 0x08, // Dynamic model = airbone 4g + 0x00, // Fix mode + 0x00, 0x00, 0x00, 0x00, // Fixed altitude for 2D mode + 0x00, 0x00, 0x00, 0x00, // Fixed altitude variance for 2D mode + 0x00, // Minimun elevation for a GNSS satellite to be used + 0x00, // Reserved + 0x00, 0x00, // Position DOP mask to use + 0x00, 0x00, // Time DOP mask to use + 0x00, 0x00, // Position accuracy mask + 0x00, 0x00, // Time accuracy mask + 0x00, // Static hold threshold + 0x00, // DGNSS timeout + 0x00, // C/NO threshold number SVs + 0x00, // C/NO threshold + 0x00, 0x00, // Reserved + 0x00, 0x00, // Static hold distance threshold + 0x00, // UTC standard to be used + 0x00, 0x00, 0x00, 0x00, 0x00 // Reserved + }; + + UBXFrame frame{UBXMessage::UBX_CFG_NAV5, payload, sizeof(payload)}; + + return safeWriteUBXFrame(frame); +} + +bool UBXGPSSpi::setSampleRate() +{ + uint8_t payload[] = { + 0x00, 0x00, // Measurement rate + 0x01, 0x00, // One navigation solution per measurement + 0x01, 0x01 // GPS time + }; + + uint16_t sampleRateMs = 1000 / sampleRate; + payload[0] = sampleRateMs; + payload[1] = sampleRateMs >> 8; + + UBXFrame frame{UBXMessage::UBX_CFG_RATE, payload, sizeof(payload)}; + + return safeWriteUBXFrame(frame); +} + +bool UBXGPSSpi::setPVTMessageRate() +{ + uint8_t payload[] = { + 0x01, 0x07, // PVT message + 0x01 // Rate = 1 navigation solution update + }; + + UBXFrame frame{UBXMessage::UBX_CFG_MSG, payload, sizeof(payload)}; + + return safeWriteUBXFrame(frame); +} + +bool UBXGPSSpi::readUBXFrame(UBXFrame& frame) +{ + long long start = miosix::getTick(); + long long end = start + READ_TIMEOUT * MS_TO_TICK; + + { + SPITransaction spi{spiSlave}; + + // Search UBX frame preamble byte by byte + size_t i = 0; + bool waiting = false; + while (i < 2) + { + if (miosix::getTick() >= end) + { + LOG_ERR(logger, "Timeout for read expired"); + return false; + } + + uint8_t c = spi.read(); + + if (c == UBXFrame::PREAMBLE[i]) + { + waiting = false; + frame.preamble[i++] = c; + } + else if (c == UBXFrame::PREAMBLE[0]) + { + i = 0; + waiting = false; + frame.preamble[i++] = c; + } + else if (c == UBXFrame::WAIT) + { + i = 0; + if (!waiting) + { + waiting = true; + // LOG_DEBUG(logger, "Device is waiting..."); + } + } + else + { + i = 0; + waiting = false; + LOG_DEBUG(logger, "Received unexpected byte: {:02x} {:#c}", c, + c); + } + } + + frame.message = swapBytes16(spi.read16()); + frame.payloadLength = swapBytes16(spi.read16()); + spi.read(frame.payload, frame.getRealPayloadLength()); + spi.read(frame.checksum, 2); + } + + if (!frame.isValid()) + { + LOG_ERR(logger, "Received invalid UBX frame"); + return false; + } + + return true; +} + +bool UBXGPSSpi::writeUBXFrame(const UBXFrame& frame) +{ + if (!frame.isValid()) + { + LOG_ERR(logger, "Trying to send an invalid UBX frame"); + return false; + } + + uint8_t packedFrame[frame.getLength()]; + frame.writePacked(packedFrame); + + { + SPITransaction spi{spiSlave}; + spi.write(packedFrame, frame.getLength()); + } + + return true; +} + +bool UBXGPSSpi::safeWriteUBXFrame(const UBXFrame& frame) +{ + for (unsigned int i = 0; i < MAX_TRIES; i++) + { + if (i > 0) + LOG_DEBUG(logger, "Retrying (attempt {:#d} of {:#d})...", i + 1, + MAX_TRIES); + + if (!writeUBXFrame(frame)) + return false; + + UBXAckFrame ack; + + if (!readUBXFrame(ack)) + continue; + + if (ack.isNack()) + { + if (ack.getAckMessage() == frame.getMessage()) + LOG_DEBUG(logger, "Received NAK"); + else + LOG_DEBUG(logger, "Received NAK for different UBX frame {:04x}", + static_cast<uint16_t>(ack.getPayload().ackMessage)); + continue; + } + + if (ack.isAck() && ack.getAckMessage() != frame.getMessage()) + { + LOG_DEBUG(logger, "Received ACK for different UBX frame {:04x}", + static_cast<uint16_t>(ack.getPayload().ackMessage)); + continue; + } + + return true; + } + + LOG_ERR(logger, "Gave up after {:#d} tries", MAX_TRIES); + return false; +} + +} // namespace Boardcore diff --git a/src/shared/sensors/UBXGPS/UBXGPSSpi.h b/src/shared/sensors/UBXGPS/UBXGPSSpi.h new file mode 100644 index 0000000000000000000000000000000000000000..e20bc3bfcec2c8b36e69093291be5af048d80ce6 --- /dev/null +++ b/src/shared/sensors/UBXGPS/UBXGPSSpi.h @@ -0,0 +1,151 @@ +/* Copyright (c) 2022 Skyward Experimental Rocketry + * Authors: Davide Bonomini, Davide Mor, Alberto Nidasio, Damiano Amatruda + * + * 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. + */ + +#pragma once + +#include <diagnostic/PrintLogger.h> +#include <drivers/spi/SPIDriver.h> +#include <sensors/Sensor.h> + +#include "UBXFrame.h" +#include "UBXGPSData.h" + +namespace Boardcore +{ + +/** + * @brief Sensor for UBlox GPS. + * + * This sensor handles communication and setup with UBlox GPSs. It uses the + * binary UBX protocol to retrieve and parse navigation data faster than using + * the string-based NMEA. + * + * At initialization it resets the device, sets the configuration and sets up + * UBX messages and GNSS parameters. + * + * Communication with the device is performed through SPI. + * + * This sensor is compatible with series NEO-M8 and NEO-M9. + */ +class UBXGPSSpi : public Sensor<UBXGPSData> +{ +public: + /** + * @brief Constructor. + * + * @param spiBus The SPI bus. + * @param spiCs The CS pin to lower when we need to sample. + * @param spiConfig The SPI configuration. + * @param sampleRate The GPS sample rate [kHz]. + */ + UBXGPSSpi(SPIBusInterface& spiBus, miosix::GpioPin spiCs, + SPIBusConfig spiConfig = getDefaultSPIConfig(), + uint8_t sampleRate = 5); + + /** + * @brief Constructs the default config for the SPI bus. + * + * @return The default SPIBusConfig object. + */ + static SPIBusConfig getDefaultSPIConfig(); + + uint8_t getSampleRate(); + + bool init() override; + + bool selfTest() override; + +private: + UBXGPSData sampleImpl() override; + + /** + * @brief Resets the device to its default configuration. + * + * @return True if the device reset succeeded. + */ + bool reset(); + + /** + * @brief Enables UBX and disables NMEA on the SPI port. + * + * @return True if the configuration received an acknowledgement. + */ + bool setUBXProtocol(); + + /** + * @brief Configures the dynamic model to airborn 4g. + * + * @return True if the configuration received an acknowledgement. + */ + bool setDynamicModelToAirborne4g(); + + /** + * @brief Configures the navigation solution sample rate. + * + * @return True if the configuration received an acknowledgement. + */ + bool setSampleRate(); + + /** + * @brief Configures the PVT message output rate. + * + * @return True if the configuration received an acknowledgement. + */ + bool setPVTMessageRate(); + + /** + * @brief Reads a UBX frame. + * + * @param frame The received frame. + * @return True if a valid frame was read. + */ + bool readUBXFrame(UBXFrame& frame); + + /** + * @brief Writes a UBX frame. + * + * @param frame The frame to write. + * @return True if the frame is valid. + */ + bool writeUBXFrame(const UBXFrame& frame); + + /** + * @brief Writes a UBX frame and waits for its acknowledgement. + * + * @param frame The frame to write. + * @return True if the frame is valid and acknowledged. + */ + bool safeWriteUBXFrame(const UBXFrame& frame); + + SPISlave spiSlave; + uint8_t sampleRate; + + PrintLogger logger = Logging::getLogger("ubxgps"); + + static constexpr float MS_TO_TICK = miosix::TICK_FREQ / 1000.f; + + static constexpr unsigned int RESET_SLEEP_TIME = 5000; // [ms] + static constexpr unsigned int READ_TIMEOUT = 5000; // [ms] + static constexpr unsigned int MAX_TRIES = 5; // [1] +}; + +} // namespace Boardcore diff --git a/src/shared/sensors/UbloxGPS/UbloxGPS.cpp b/src/shared/sensors/UbloxGPS/UbloxGPS.cpp deleted file mode 100644 index dff24046dfefeca63f88c4499f1d0b2bf4c9f9ce..0000000000000000000000000000000000000000 --- a/src/shared/sensors/UbloxGPS/UbloxGPS.cpp +++ /dev/null @@ -1,537 +0,0 @@ -/* Copyright (c) 2021 Skyward Experimental Rocketry - * Authors: Davide Bonomini, Davide Mor, Alberto Nidasio - * - * 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. - */ - -#include "UbloxGPS.h" - -#include <diagnostic/StackLogger.h> -#include <drivers/serial.h> -#include <drivers/timer/TimestampTimer.h> -#include <fcntl.h> -#include <filesystem/file_access.h> - -using namespace miosix; - -namespace Boardcore -{ - -UbloxGPS::UbloxGPS(int baudrate_, uint8_t sampleRate_, int serialPortNum_, - const char* serialPortName_, int defaultBaudrate_) - : baudrate(baudrate_), sampleRate(sampleRate_), - serialPortNumber(serialPortNum_), serialPortName(serialPortName_), - defaultBaudrate(defaultBaudrate_) -{ - // Prepare the gps file path with the specified name - strcpy(gpsFilePath, "/dev/"); - strcat(gpsFilePath, serialPortName); -} - -bool UbloxGPS::init() -{ - // Change the baud rate from the default value - if (!serialCommuinicationSetup()) - { - return false; - } - - Thread::sleep(10); - - // Reset configuration to default - // TODO: maybe move this on serial communication setup - if (!resetConfiguration()) - { - return false; - } - - // Disable NMEA messages - if (!disableNMEAMessages()) - { - return false; - } - - Thread::sleep(100); - - // Set GNSS configuration - if (!setGNSSConfiguration()) - { - return false; - } - - Thread::sleep(100); - - // Enable UBX messages - if (!enableUBXMessages()) - { - return false; - } - - Thread::sleep(100); - - // Set rate - if (!setRate()) - { - return false; - } - - return true; -} - -bool UbloxGPS::selfTest() { return true; } - -UbloxGPSData UbloxGPS::sampleImpl() -{ - Lock<FastMutex> l(mutex); - return threadSample; -} - -void UbloxGPS::run() -{ - /** - * UBX message structure: - * - 2B: Preamble - * - 1B: Message class - * - 1B: Message id - * - 2B: Payload length - * - lB: Payload - * - 2B: Checksum - */ - uint8_t message[6 + UBX_MAX_PAYLOAD_LENGTH + 2]; - uint16_t payloadLength; - - while (!shouldStop()) - { - StackLogger::getInstance().updateStack(THID_GPS); - - // Try to read the message - if (!readUBXMessage(message, payloadLength)) - { - LOG_DEBUG(logger, "Unable to read a UBX message"); - continue; - } - - // Parse the message - if (!parseUBXMessage(message)) - { - LOG_DEBUG(logger, - "UBX message not recognized (class:0x{02x}, id: 0x{02x})", - message[2], message[3]); - } - } -} - -void UbloxGPS::ubxChecksum(uint8_t* msg, int len) -{ - uint8_t ck_a = 0, ck_b = 0; - - // The length must be valid, at least 8 bytes (preamble, msg, length, - // checksum) - if (len <= 8) - { - return; - } - - // Checksum calculation from byte 2 to end of payload - for (int i = 2; i < len - 2; i++) - { - ck_a = ck_a + msg[i]; - ck_b = ck_b + ck_a; - } - - msg[len - 2] = ck_a; - msg[len - 1] = ck_b; -} - -bool UbloxGPS::writeUBXMessage(uint8_t* message, int length) -{ - // Compute the checksum - ubxChecksum(message, length); - - // Write configuration - if (write(gpsFile, message, length) < 0) - { - LOG_ERR(logger, - "Failed to write ubx message (class:0x{02x}, id: 0x{02x})", - message[2], message[3]); - return false; - } - - return true; -} - -bool UbloxGPS::serialCommuinicationSetup() -{ - intrusive_ref_ptr<DevFs> devFs = FilesystemManager::instance().getDevFs(); - - // Change the baudrate only if it is different than the default - if (baudrate != defaultBaudrate) - { - // Close the gps file if already opened - devFs->remove(serialPortName); - - // Open the serial port device with the default boudrate - if (!devFs->addDevice(serialPortName, - intrusive_ref_ptr<Device>(new STM32Serial( - serialPortNumber, defaultBaudrate)))) - { - LOG_ERR(logger, - "[gps] Faild to open serial port {0} with baudrate {1} as " - "file {2}", - serialPortNumber, defaultBaudrate, serialPortName); - return false; - } - - // Open the gps file - if ((gpsFile = open(gpsFilePath, O_RDWR)) < 0) - { - LOG_ERR(logger, "Failed to open gps file {}", gpsFilePath); - return false; - } - - // Change boudrate - if (!setBaudrate()) - { - return false; - }; - - // Close the gps file - if (close(gpsFile) < 0) - { - LOG_ERR(logger, "Failed to close gps file {}", gpsFilePath); - return false; - } - - // Close the serial port - if (!devFs->remove(serialPortName)) - { - LOG_ERR(logger, "Failed to close serial port {} as file {}", - serialPortNumber, serialPortName); - return false; - } - } - - // Reopen the serial port with the configured boudrate - if (!devFs->addDevice(serialPortName, - intrusive_ref_ptr<Device>( - new STM32Serial(serialPortNumber, baudrate)))) - { - LOG_ERR(logger, - "Faild to open serial port {} with baudrate {} as file {}\n", - serialPortNumber, defaultBaudrate, serialPortName); - return false; - } - - // Reopen the gps file - if ((gpsFile = open(gpsFilePath, O_RDWR)) < 0) - { - LOG_ERR(logger, "Failed to open gps file {}", gpsFilePath); - return false; - } - - return true; -} - -bool UbloxGPS::resetConfiguration() -{ - uint8_t ubx_cfg_prt[RESET_CONFIG_MSG_LEN] = { - 0Xb5, 0x62, // Preamble - 0x06, 0x04, // Message UBX-CFG-RST - 0x04, 0x00, // Length - 0x00, 0x00, // navBbrMask (Hot start) - 0x00, // Hardware reset immediately - 0x00, // Reserved - 0xff, 0xff // Checksum - }; - - return writeUBXMessage(ubx_cfg_prt, RESET_CONFIG_MSG_LEN); -} - -bool UbloxGPS::setBaudrate() -{ - uint8_t ubx_cfg_prt[SET_BAUDRATE_MSG_LEN] = { - 0Xb5, 0x62, // Preamble - 0x06, 0x8a, // Message UBX-CFG-VALSET - 0x0c, 0x00, // Length - 0x00, // Version - 0xff, // All layers - 0x00, 0x00, // Reserved - 0x01, 0x00, 0x52, 0x40, // Configuration item key ID - 0xff, 0xff, 0xff, 0xff, // Value - 0xff, 0xff // Checksum - }; - - // Prepare boud rate - ubx_cfg_prt[14] = baudrate; - ubx_cfg_prt[15] = baudrate >> 8; - ubx_cfg_prt[16] = baudrate >> 16; - ubx_cfg_prt[17] = baudrate >> 24; - - return writeUBXMessage(ubx_cfg_prt, SET_BAUDRATE_MSG_LEN); -} - -bool UbloxGPS::disableNMEAMessages() -{ - uint8_t ubx_cfg_valset[DISABLE_NMEA_MESSAGES_MSG_LEN] = { - 0Xb5, 0x62, // Preamble - 0x06, 0x8a, // Message UBX-CFG-VALSET - 0x22, 0x00, // Length - 0x00, // Version - 0xff, // All layers - 0x00, 0x00, // Reserved - 0xbb, 0x00, 0x91, 0x20, // CFG-MSGOUT-NMEA_ID_GGA_UART1 key ID - 0x00, // CFG-MSGOUT-NMEA_ID_GGA_UART1 value - 0xca, 0x00, 0x91, 0x20, // CFG-MSGOUT-NMEA_ID_GLL_UART1 key ID - 0x00, // CFG-MSGOUT-NMEA_ID_GLL_UART1 value - 0xc0, 0x00, 0x91, 0x20, // CFG-MSGOUT-NMEA_ID_GSA_UART1 key ID - 0x00, // CFG-MSGOUT-NMEA_ID_GSA_UART1 value - 0xc5, 0x00, 0x91, 0x20, // CFG-MSGOUT-NMEA_ID_GSV_UART1 key ID - 0x00, // CFG-MSGOUT-NMEA_ID_GSV_UART1 value - 0xac, 0x00, 0x91, 0x20, // CFG-MSGOUT-NMEA_ID_RMC_UART1 key ID - 0x00, // CFG-MSGOUT-NMEA_ID_RMC_UART1 value - 0xb1, 0x00, 0x91, 0x20, // CFG-MSGOUT-NMEA_ID_VTG_UART1 key ID - 0x00, // CFG-MSGOUT-NMEA_ID_VTG_UART1 value - 0xff, 0xff // Checksum - }; - - return writeUBXMessage(ubx_cfg_valset, DISABLE_NMEA_MESSAGES_MSG_LEN); -} - -bool UbloxGPS::setGNSSConfiguration() -{ - uint8_t ubx_cfg_valset[SET_GNSS_CONF_LEN] = { - 0Xb5, 0x62, // Preamble - 0x06, 0x8a, // Message UBX-CFG-VALSET - 0x09, 0x00, // Length - 0x00, // Version - 0x07, // All layers - 0x00, 0x00, // Reserved - 0x21, 0x00, 0x11, 0x20, // CFG-NAVSPG-DYNMODEL key ID - 0x08, // CFG-NAVSPG-DYNMODEL value - 0xff, 0xff // Checksum - }; - - return writeUBXMessage(ubx_cfg_valset, SET_GNSS_CONF_LEN); -} - -bool UbloxGPS::enableUBXMessages() -{ - uint8_t ubx_cfg_valset[ENABLE_UBX_MESSAGES_MSG_LEN] = { - 0Xb5, 0x62, // Preamble - 0x06, 0x8a, // Message UBX-CFG-VALSET - 0x09, 0x00, // Length - 0x00, // Version - 0xff, // All layers - 0x00, 0x00, // Reserved - 0x07, 0x00, 0x91, 0x20, // CFG-MSGOUT-UBX_NAV_PVT_UART1 key ID - 0x01, // CFG-MSGOUT-UBX_NAV_PVT_UART1 value - 0xff, 0xff // Checksum - }; - - return writeUBXMessage(ubx_cfg_valset, ENABLE_UBX_MESSAGES_MSG_LEN); -} - -bool UbloxGPS::setRate() -{ - uint16_t rate = 1000 / sampleRate; - LOG_DEBUG(logger, "Rate: {}", rate); - - uint8_t ubx_cfg_valset[SET_RATE_MSG_LEN] = { - 0Xb5, 0x62, // Preamble - 0x06, 0x8a, // Message UBX-CFG-VALSET - 0x0a, 0x00, // Length - 0x00, // Version - 0x07, // All layers - 0x00, 0x00, // Reserved - 0x01, 0x00, 0x21, 0x30, // CFG-RATE-MEAS key ID - 0xff, 0xff, // CFG-RATE-MEAS value - 0xff, 0xff // Checksum - }; - - // Prepare rate - ubx_cfg_valset[14] = rate; - ubx_cfg_valset[15] = rate >> 8; - - return writeUBXMessage(ubx_cfg_valset, SET_RATE_MSG_LEN); -} - -bool UbloxGPS::readUBXMessage(uint8_t* message, uint16_t& payloadLength) -{ - // Read preamble - do - { - // Read util the first byte of the preamble - do - { - if (read(gpsFile, &message[0], 1) <= 0) // No more data available - { - return false; - } - } while (message[0] != PREAMBLE[0]); - - // Read the next byte - if (read(gpsFile, &message[1], 1) <= 0) // No more data available - { - return false; - } - } while (message[1] != PREAMBLE[1]); // Continue - - // Read message class and ID - if (read(gpsFile, &message[2], 1) <= 0) - { - return false; - } - if (read(gpsFile, &message[3], 1) <= 0) - { - return false; - } - - // Read length - if (read(gpsFile, &message[4], 2) <= 0) - { - return false; - } - payloadLength = message[4] | (message[5] << 8); - if (payloadLength > UBX_MAX_PAYLOAD_LENGTH) - { - return false; - } - - // Read paylaod and checksum - for (auto i = 0; i < payloadLength + 2; i++) - { - if (read(gpsFile, &message[6 + i], 1) <= 0) - { - return false; - } - } - - // Verify the checksum - uint8_t msgChecksum1 = message[6 + payloadLength]; - uint8_t msgChecksum2 = message[6 + payloadLength + 1]; - ubxChecksum(message, 6 + payloadLength + 2); - if (msgChecksum1 != message[6 + payloadLength] || - msgChecksum2 != message[6 + payloadLength + 1]) - { - LOG_ERR(logger, "Message checksum verification failed"); - return false; - } - - return true; -} - -bool UbloxGPS::parseUBXMessage(uint8_t* message) -{ - switch (message[2]) // Message class - { - case 0x01: // UBX-NAV - return parseUBXNAVMessage(message); - case 0x05: // UBX-ACK - return parseUBXACKMessage(message); - } - return false; -} - -bool UbloxGPS::parseUBXNAVMessage(uint8_t* message) -{ - switch (message[3]) // Message id - { - case 0x07: // UBX-NAV-PVT - // Lock the threadSample variable - Lock<FastMutex> l(mutex); - - // Latitude - int32_t rawLatitude = message[6 + 28] | message[6 + 29] << 8 | - message[6 + 30] << 16 | message[6 + 31] << 24; - threadSample.latitude = (float)rawLatitude / 1e7; - - // Longitude - int32_t rawLongitude = message[6 + 24] | message[6 + 25] << 8 | - message[6 + 26] << 16 | - message[6 + 27] << 24; - threadSample.longitude = (float)rawLongitude / 1e7; - - // Height - int32_t rawHeight = message[6 + 32] | message[6 + 33] << 8 | - message[6 + 34] << 16 | message[6 + 35] << 24; - threadSample.height = (float)rawHeight / 1e3; - - // Velocity north - int32_t rawVelocityNorth = message[6 + 48] | message[6 + 49] << 8 | - message[6 + 50] << 16 | - message[6 + 51] << 24; - threadSample.velocityNorth = (float)rawVelocityNorth / 1e3; - - // Velocity east - int32_t rawVelocityEast = message[6 + 52] | message[6 + 53] << 8 | - message[6 + 54] << 16 | - message[6 + 55] << 24; - threadSample.velocityEast = (float)rawVelocityEast / 1e3; - - // Velocity down - int32_t rawVelocityDown = message[6 + 56] | message[6 + 57] << 8 | - message[6 + 58] << 16 | - message[6 + 59] << 24; - threadSample.velocityDown = (float)rawVelocityDown / 1e3; - - // Speed - int32_t rawSpeed = message[6 + 60] | message[6 + 61] << 8 | - message[6 + 62] << 16 | message[6 + 63] << 24; - threadSample.speed = (float)rawSpeed / 1e3; - - // Track (heading of motion) - int32_t rawTrack = message[6 + 64] | message[6 + 65] << 8 | - message[6 + 66] << 16 | message[6 + 67] << 24; - threadSample.track = (float)rawTrack / 1e5; - - // Number of satellite - threadSample.satellites = (uint8_t)message[6 + 23]; - - // Fix (every type of fix accepted) - threadSample.fix = message[6 + 20] != 0; - - // Timestamp - threadSample.gpsTimestamp = - TimestampTimer::getInstance().getTimestamp(); - - return true; - } - - return false; -} - -bool UbloxGPS::parseUBXACKMessage(uint8_t* message) -{ - switch (message[3]) // Message id - { - case 0x00: // UBX-ACK-NAC - LOG_DEBUG(logger, - "Received NAC for message (class:0x{02x}, id: 0x{02x})", - message[6], message[7]); - return true; - case 0x01: // UBX-ACK-ACK - LOG_DEBUG(logger, - "Received ACK for message (class:0x{02x}, id: 0x{02x})", - message[6], message[7]); - return true; - } - return false; -} - -} // namespace Boardcore diff --git a/src/shared/sensors/UbloxGPS/UbloxGPS.h b/src/shared/sensors/UbloxGPS/UbloxGPS.h deleted file mode 100644 index 9495bc6f5fe792774f0bb9a59c32f35c6e97e5b8..0000000000000000000000000000000000000000 --- a/src/shared/sensors/UbloxGPS/UbloxGPS.h +++ /dev/null @@ -1,151 +0,0 @@ -/* Copyright (c) 2021 Skyward Experimental Rocketry - * Authors: Davide Bonomini, Davide Mor, Alberto Nidasio - * - * 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. - */ - -#pragma once - -#include <ActiveObject.h> -#include <diagnostic/PrintLogger.h> -#include <miosix.h> -#include <sensors/Sensor.h> - -#include "UbloxGPSData.h" - -namespace Boardcore -{ - -/** - * @brief Driver for Ublox GPSs - * - * This driver handles communication and setup with Ublox GPSs. It uses the - * binary UBX protocol to retrieve and parse navigation data quicker than using - * the string based NMEA. - * - * At initialization it configures the device with the specified baudrate, reset - * the configuration and sets up UBX messages and GNSS parameters. - * - * Communication with the device is performed through a file, the driver opens - * the serial port under the filepath /dev/<serialPortName>. - * There is no need for the file to be setted up beforhand. - * - * This driver was written for a NEO-M9N gps with the latest version of UBX. - */ -class UbloxGPS : public Sensor<UbloxGPSData>, public ActiveObject -{ -public: - /** - * @brief Construct a new UbloxGPS object - * - * @param boudrate_ Baudrate to communicate with the device (max: 921600, - * min: 4800 for NEO-M9N) - * @param sampleRate_ GPS sample rate (max: 25 for NEO-M9N) - * @param serialPortName_ Name of the file for the gps device - * @param defaultBaudrate_ Startup baudrate (38400 for NEO-M9N) - */ - UbloxGPS(int boudrate_ = 921600, uint8_t sampleRate_ = 10, - int serialPortNumber_ = 2, const char *serialPortName_ = "gps", - int defaultBaudrate_ = 38400); - - /** - * @brief Sets up the serial port baudrate, disables the NMEA messages, - * configures GNSS options and enables UBX-PVT message - * - * @return True if the operation succeeded - */ - bool init() override; - - /** - * @brief Read a single message form the GPS, waits 2 sample cycle - * - * @return True if a message was sampled - */ - bool selfTest() override; - -private: - UbloxGPSData sampleImpl() override; - - void run() override; - - void ubxChecksum(uint8_t *msg, int len); - - /** - * @brief Compute the checksum and write the message to the device - */ - bool writeUBXMessage(uint8_t *message, int length); - - /** - * @brief Sets up the serial port with the correct baudrate - * - * Opens the serial port with the defaul baudrate and changes it to - * the value specified in the constructor, then it reopens the serial port. - * If the device is already using the correct baudrate this won't have - * effect. However if the gps is using a different baudrate the diver won't - * be able to communicate. - */ - bool serialCommuinicationSetup(); - - bool resetConfiguration(); - - bool setBaudrate(); - - bool disableNMEAMessages(); - - bool setGNSSConfiguration(); - - bool enableUBXMessages(); - - bool setRate(); - - bool readUBXMessage(uint8_t *message, uint16_t &payloadLength); - - bool parseUBXMessage(uint8_t *message); - - bool parseUBXNAVMessage(uint8_t *message); - - bool parseUBXACKMessage(uint8_t *message); - - const int baudrate; // [baud] - const uint8_t sampleRate; // [Hz] - const int serialPortNumber; - const char *serialPortName; - const int defaultBaudrate; // [baud] - - char gpsFilePath[16]; ///< Allows for a filename of up to 10 characters - int gpsFile = -1; - - mutable miosix::FastMutex mutex; - UbloxGPSData threadSample{}; - - static constexpr int SET_BAUDRATE_MSG_LEN = 20; - static constexpr int RESET_CONFIG_MSG_LEN = 12; - static constexpr int DISABLE_NMEA_MESSAGES_MSG_LEN = 42; - static constexpr int SET_GNSS_CONF_LEN = 17; - static constexpr int ENABLE_UBX_MESSAGES_MSG_LEN = 17; - static constexpr int SET_RATE_MSG_LEN = 18; - - static constexpr uint8_t PREAMBLE[] = {0xb5, 0x62}; - - static constexpr int UBX_MAX_PAYLOAD_LENGTH = 92; - - PrintLogger logger = Logging::getLogger("ubloxgps"); -}; - -} // namespace Boardcore diff --git a/src/shared/sensors/VN100/VN100.cpp b/src/shared/sensors/VN100/VN100.cpp index eb9d3e9043d62522ec566c40e501d139403ee1d4..7adcaac53c171d73c6c87ded7f0b29210d997c19 100644 --- a/src/shared/sensors/VN100/VN100.cpp +++ b/src/shared/sensors/VN100/VN100.cpp @@ -468,7 +468,7 @@ QuaternionData VN100::sampleQuaternion() } // Parse the data - data.quatTimestamp = TimestampTimer::getInstance().getTimestamp(); + data.quatTimestamp = TimestampTimer::getTimestamp(); data.quatX = strtod(recvString + indexStart + 1, &nextNumber); data.quatY = strtod(nextNumber + 1, &nextNumber); data.quatZ = strtod(nextNumber + 1, &nextNumber); @@ -496,7 +496,7 @@ MagnetometerData VN100::sampleMagnetometer() } // Parse the data - data.magneticFieldTimestamp = TimestampTimer::getInstance().getTimestamp(); + data.magneticFieldTimestamp = TimestampTimer::getTimestamp(); data.magneticFieldX = strtod(recvString + indexStart + 1, &nextNumber); data.magneticFieldY = strtod(nextNumber + 1, &nextNumber); data.magneticFieldZ = strtod(nextNumber + 1, NULL); @@ -523,7 +523,7 @@ AccelerometerData VN100::sampleAccelerometer() } // Parse the data - data.accelerationTimestamp = TimestampTimer::getInstance().getTimestamp(); + data.accelerationTimestamp = TimestampTimer::getTimestamp(); data.accelerationX = strtod(recvString + indexStart + 1, &nextNumber); data.accelerationY = strtod(nextNumber + 1, &nextNumber); data.accelerationZ = strtod(nextNumber + 1, NULL); @@ -550,8 +550,7 @@ GyroscopeData VN100::sampleGyroscope() } // Parse the data - data.angularVelocityTimestamp = - TimestampTimer::getInstance().getTimestamp(); + data.angularVelocityTimestamp = TimestampTimer::getTimestamp(); data.angularVelocityX = strtod(recvString + indexStart + 1, &nextNumber); data.angularVelocityY = strtod(nextNumber + 1, &nextNumber); data.angularVelocityZ = strtod(nextNumber + 1, NULL); @@ -577,7 +576,7 @@ TemperatureData VN100::sampleTemperature() } // Parse the data - data.temperatureTimestamp = TimestampTimer::getInstance().getTimestamp(); + data.temperatureTimestamp = TimestampTimer::getTimestamp(); data.temperature = strtod(recvString + indexStart + 1, NULL); return data; @@ -601,7 +600,7 @@ PressureData VN100::samplePressure() } // Parse the data - data.pressureTimestamp = TimestampTimer::getInstance().getTimestamp(); + data.pressureTimestamp = TimestampTimer::getTimestamp(); data.pressure = strtod(recvString + indexStart + 1, NULL); return data; diff --git a/src/shared/sensors/analog/AnalogLoadCell.h b/src/shared/sensors/analog/AnalogLoadCell.h index f554bee330b2595a382b9c5cddc7bb7a44699282..53d0dc42430fc7e4f37528941039c666e15d26a2 100644 --- a/src/shared/sensors/analog/AnalogLoadCell.h +++ b/src/shared/sensors/analog/AnalogLoadCell.h @@ -34,9 +34,8 @@ namespace Boardcore class AnalogLoadCell : public Sensor<AnalogLoadCellData> { public: - AnalogLoadCell(std::function<std::pair<uint64_t, float>()> getVoltage, - const float mVtoV, const unsigned int fullScale, - const float supplyVoltage = 5) + AnalogLoadCell(std::function<ADCData()> getVoltage, const float mVtoV, + const unsigned int fullScale, const float supplyVoltage = 5) : getVoltage(getVoltage), conversionCoeff(mVtoV * supplyVoltage / fullScale / 1e3) { @@ -46,20 +45,33 @@ public: bool selfTest() override { return true; }; + /** + * @brief Sets the offset that will be removed from the measured load. + */ + void setOffset(const float offset) { this->offset = offset; } + AnalogLoadCellData sampleImpl() override { - AnalogLoadCellData data; + ADCData adcData = getVoltage(); - std::tie(data.loadTimestamp, data.voltage) = getVoltage(); + AnalogLoadCellData data; + data.loadTimestamp = adcData.voltageTimestamp; + data.voltage = adcData.voltage; - data.load = data.voltage / conversionCoeff; + if (data.voltage != 0) + data.load = data.voltage / conversionCoeff - offset; + else + data.load = -offset; return data; } private: - std::function<std::pair<uint64_t, float>()> getVoltage; + ///< Function that returns the sensor voltage. + std::function<ADCData()> getVoltage; + const float conversionCoeff; + float offset = 0; }; } // namespace Boardcore diff --git a/src/shared/sensors/analog/Pitot/Pitot.h b/src/shared/sensors/analog/Pitot/Pitot.h new file mode 100644 index 0000000000000000000000000000000000000000..79ab00f76ab5e8ff0e1df0d882c9fc72ba73eb91 --- /dev/null +++ b/src/shared/sensors/analog/Pitot/Pitot.h @@ -0,0 +1,77 @@ +/* Copyright (c) 2022 Skyward Experimental Rocketry + * Authors: Alberto Nidasio, Arturo Benedetti + * + * 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. + */ + +#pragma once + +#include <sensors/Sensor.h> +#include <utils/AeroUtils/AeroUtils.h> + +#include <functional> + +#include "PitotData.h" + +namespace Boardcore +{ + +class Pitot : public Sensor<PitotData> +{ +public: + Pitot(std::function<PressureData()> getPitotPressure, + std::function<float()> getStaticPressure) + : getPitotPressure(getPitotPressure), + getStaticPressure(getStaticPressure) + { + } + + bool init() override { return true; } + + bool selfTest() override { return true; } + + PitotData sampleImpl() override + { + float airDensity = + Aeroutils::relDensity(getStaticPressure(), REFERENCE_PRESSURE, + REFERENCE_ALTITUDE, REFERENCE_TEMPERATURE); + if (airDensity != 0.0) + { + PitotData pitotSpeed; + + pitotSpeed.timestamp = getPitotPressure().pressureTimestamp; + pitotSpeed.airspeed = + sqrtf(2 * fabs(getPitotPressure().pressure) / airDensity); + + return pitotSpeed; + } + + return lastSample; + } + +private: + std::function<PressureData()> getPitotPressure; + std::function<float()> getStaticPressure; + + static constexpr float REFERENCE_PRESSURE = 100000.0; // Milan air pressure + static constexpr float REFERENCE_ALTITUDE = 130.0; // Milan altitude + static constexpr float REFERENCE_TEMPERATURE = 273.15 + 25.0; // 25° +}; + +} // namespace Boardcore diff --git a/src/shared/sensors/analog/Pitot/PitotData.h b/src/shared/sensors/analog/Pitot/PitotData.h new file mode 100644 index 0000000000000000000000000000000000000000..7a3a05a87940a73bf335d7e8a9526cda03d3a3fb --- /dev/null +++ b/src/shared/sensors/analog/Pitot/PitotData.h @@ -0,0 +1,43 @@ +/* Copyright (c) 2022 Skyward Experimental Rocketry + * Authors: Alberto Nidasio, Arturo Benedetti + * + * 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. + */ + +#pragma once + +#include <ostream> + +namespace Boardcore +{ + +struct PitotData +{ + uint64_t timestamp; + float airspeed; + + static std::string header() { return "timestamp,airspeed\n"; } + + void print(std::ostream& os) const + { + os << timestamp << "," << airspeed << "\n"; + } +}; + +} // namespace Boardcore diff --git a/src/shared/sensors/analog/pressure/AnalogPressureSensor.h b/src/shared/sensors/analog/pressure/AnalogPressureSensor.h index 3121fd80cb971e625e558e74ad5e277bea4f8316..7695aeb972f560f06e9a28450d4991596430131c 100644 --- a/src/shared/sensors/analog/pressure/AnalogPressureSensor.h +++ b/src/shared/sensors/analog/pressure/AnalogPressureSensor.h @@ -48,11 +48,15 @@ public: { } - bool init() override { return true; }; + bool init() override { return true; } - bool selfTest() override { return true; }; + bool selfTest() override { return true; } + + /** + * @brief Sets the offset that will be removed from the measured pressure. + */ + void setOffset(const float offset) { this->offset = offset; } - ///< Converts the voltage value to pressure AnalogPressureData sampleImpl() override { AnalogPressureData pressure; @@ -70,19 +74,22 @@ public: else if (pressure.pressure > maxPressure) pressure.pressure = maxPressure; + pressure.pressure -= offset; + return pressure; } protected: - ///< Conversion function from volts to pascals + ///< Conversion function from volts to pascals. virtual float voltageToPressure(float voltage) = 0; - ///< Function that returns the sensor voltage + ///< Function that returns the sensor voltage. std::function<ADCData()> getVoltage; const float supplyVoltage; const float maxPressure; const float minPressure; + float offset = 0; }; } // namespace Boardcore diff --git a/src/shared/sensors/analog/pressure/MPXHZ6130A/MPXHZ6130A.h b/src/shared/sensors/analog/pressure/MPXHZ6130A/MPXHZ6130A.h deleted file mode 100644 index 9ab705349a7685e0acec5d45a4f08f1285de59ee..0000000000000000000000000000000000000000 --- a/src/shared/sensors/analog/pressure/MPXHZ6130A/MPXHZ6130A.h +++ /dev/null @@ -1,112 +0,0 @@ -/* Copyright (c) 2020 Skyward Experimental Rocketry - * Author: Alberto Nidasio - * - * 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. - */ - -#pragma once - -#include "../AnalogPressureSensor.h" -#include "MPXHZ6130AData.h" - -namespace Boardcore -{ - -/** - * @brief Driver for NXP's MPXHZ6130A pressure sensor - */ -class MPXHZ6130A final : public AnalogPressureSensor<MPXHZ6130AData> -{ -public: - MPXHZ6130A(std::function<ADCData()> getSensorVoltage, - const float supplyVoltage = 5.0, - const unsigned int num_calib_samples_ = 200, - const float moving_avg_coeff_ = 1.0, - const float ref_press_ = 101325.0f) - : AnalogPressureSensor(getSensorVoltage, supplyVoltage, 130000), - offset(0.0), num_calib_samples(num_calib_samples_), - moving_avg_coeff(moving_avg_coeff_), ref_press(ref_press_) - { - } - - MPXHZ6130AData sampleImpl() - { - lastSample = AnalogPressureSensor<MPXHZ6130AData>::sampleImpl(); - - if (calibrating) - { - press_stats.add(lastSample.pressure); - - if (press_stats.getStats().nSamples >= num_calib_samples) - { - calibrating = false; - offset = ref_press - press_stats.getStats().mean; - - TRACE("MPXHZ6130A barometer offset : %.2f \n", offset); - } - } - - lastSample.pressure = lastSample.pressure + offset; - - lastSample.pressure = movingAverage(lastSample.pressure); - - return lastSample; - } - - void setReferencePressure(float p) { ref_press = p; } - - void calibrate() - { - press_stats.reset(); - offset = 0.0f; - calibrating = true; - } - - bool isCalibrating() { return calibrating; } - -private: - float voltageToPressure(float voltage) override - { - return (((voltage / supplyVoltage) + CONST_B) / CONST_A) * 1000; - } - - float movingAverage(float new_value) - { - accumulator = (moving_avg_coeff * new_value) + - (1.0 - moving_avg_coeff) * accumulator; - return accumulator; - } - - // Constants from datasheet - static constexpr float CONST_A = 0.007826; - static constexpr float CONST_B = 0.07739; - - bool calibrating = false; - float offset; - Stats press_stats; - unsigned int num_calib_samples; - - // moving average - const float moving_avg_coeff; - float accumulator = 0.0; - - float ref_press; -}; - -} // namespace Boardcore diff --git a/src/shared/sensors/analog/pressure/honeywell/SSCDRRN015PDA.h b/src/shared/sensors/analog/pressure/honeywell/SSCDRRN015PDA.h index 1e2785023c487613b58f094d19113e9d5fe51c6f..b144f93344813b9a9a60f18b6d7cdd2fefc30ba1 100644 --- a/src/shared/sensors/analog/pressure/honeywell/SSCDRRN015PDA.h +++ b/src/shared/sensors/analog/pressure/honeywell/SSCDRRN015PDA.h @@ -37,50 +37,11 @@ class SSCDRRN015PDA final : public HoneywellPressureSensor<SSCDRRN015PDAData> { public: SSCDRRN015PDA(std::function<ADCData()> getSensorVoltage, - const float supplyVoltage = 5.0, - const unsigned int num_calib_samples_ = 200) + const float supplyVoltage = 5.0) : HoneywellPressureSensor(getSensorVoltage, supplyVoltage, 103421.3594, - -103421.3594), - offset(0.0), num_calib_samples(num_calib_samples_) + -103421.3594) { } - - SSCDRRN015PDAData sampleImpl() override - { - lastSample = HoneywellPressureSensor<SSCDRRN015PDAData>::sampleImpl(); - - if (calibrating) - { - press_stats.add(lastSample.pressure); - - if (press_stats.getStats().nSamples >= num_calib_samples) - { - calibrating = false; - offset = press_stats.getStats().mean; - - TRACE("Differential barometer offset : %.2f \n", offset); - } - } - - lastSample.pressure = lastSample.pressure - offset; - - return lastSample; - } - - void calibrate() - { - press_stats.reset(); - offset = 0.0f; - calibrating = true; - } - - bool isCalibrating() { return calibrating; } - -private: - bool calibrating = false; - float offset; - Stats press_stats; - unsigned int num_calib_samples; }; } // namespace Boardcore diff --git a/src/shared/sensors/analog/pressure/nxp/MPXH6115A.h b/src/shared/sensors/analog/pressure/nxp/MPXH6115A.h new file mode 100644 index 0000000000000000000000000000000000000000..d72485d906ec4fbbd8d6d9a882b0ff5355b53e57 --- /dev/null +++ b/src/shared/sensors/analog/pressure/nxp/MPXH6115A.h @@ -0,0 +1,56 @@ +/* Copyright (c) 2022 Skyward Experimental Rocketry + * Author: Alberto Nidasio + * + * 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. + */ + +#pragma once + +#include <sensors/analog/pressure/AnalogPressureSensor.h> +#include <utils/Stats/Stats.h> + +#include "MPXH6115AData.h" + +namespace Boardcore +{ + +/** + * @brief Driver for NXP's MPXH6115A pressure sensor + */ +class MPXH6115A final : public AnalogPressureSensor<MPXH6115AData> +{ +public: + MPXH6115A(std::function<ADCData()> getVoltage, + const float supplyVoltage = 5.0) + : AnalogPressureSensor(getVoltage, supplyVoltage, 115000, 15000) + { + } + +private: + float voltageToPressure(float voltage) override + { + return (((voltage / supplyVoltage) + CONST_B) / CONST_A) * 1000.0; + } + + // Constants from datasheet + static constexpr float CONST_A = 0.009; + static constexpr float CONST_B = 0.095; +}; + +} // namespace Boardcore diff --git a/src/shared/sensors/analog/pressure/nxp/MPXH6115AData.h b/src/shared/sensors/analog/pressure/nxp/MPXH6115AData.h new file mode 100644 index 0000000000000000000000000000000000000000..6737e9e989882f80af268d2c978d6d9ef846b222 --- /dev/null +++ b/src/shared/sensors/analog/pressure/nxp/MPXH6115AData.h @@ -0,0 +1,40 @@ +/* Copyright (c) 2022 Skyward Experimental Rocketry + * Author: Alberto Nidasio + * + * 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. + */ + +#pragma once + +#include <sensors/SensorData.h> + +namespace Boardcore +{ + +struct MPXH6115AData : public PressureData +{ + static std::string header() { return "pressureTimestamp,pressure\n"; } + + void print(std::ostream& os) const + { + os << pressureTimestamp << "," << pressure << "\n"; + } +}; + +} // namespace Boardcore diff --git a/src/shared/sensors/analog/pressure/nxp/MPXH6400A.h b/src/shared/sensors/analog/pressure/nxp/MPXH6400A.h new file mode 100644 index 0000000000000000000000000000000000000000..ab136e27eddc8b19a92af746ec273d8340711aec --- /dev/null +++ b/src/shared/sensors/analog/pressure/nxp/MPXH6400A.h @@ -0,0 +1,56 @@ +/* Copyright (c) 2022 Skyward Experimental Rocketry + * Author: Alberto Nidasio + * + * 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. + */ + +#pragma once + +#include <sensors/analog/pressure/AnalogPressureSensor.h> +#include <utils/Stats/Stats.h> + +#include "MPXH6400AData.h" + +namespace Boardcore +{ + +/** + * @brief Driver for NXP's MPXHZ6130A pressure sensor + */ +class MPXH6400A final : public AnalogPressureSensor<MPXH6400AData> +{ +public: + MPXH6400A(std::function<ADCData()> getVoltage, + const float supplyVoltage = 5.0) + : AnalogPressureSensor(getVoltage, supplyVoltage, 400000, 20000) + { + } + +private: + float voltageToPressure(float voltage) override + { + return (((voltage / supplyVoltage) + CONST_B) / CONST_A) * 1000.0; + } + + // Constants from datasheet + static constexpr float CONST_A = 0.002421; + static constexpr float CONST_B = 0.00842; +}; + +} // namespace Boardcore diff --git a/src/shared/sensors/analog/pressure/nxp/MPXH6400AData.h b/src/shared/sensors/analog/pressure/nxp/MPXH6400AData.h new file mode 100644 index 0000000000000000000000000000000000000000..51416e4e0c7c6580f7913f5d134952656860e044 --- /dev/null +++ b/src/shared/sensors/analog/pressure/nxp/MPXH6400AData.h @@ -0,0 +1,40 @@ +/* Copyright (c) 2022 Skyward Experimental Rocketry + * Author: Alberto Nidasio + * + * 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. + */ + +#pragma once + +#include <sensors/SensorData.h> + +namespace Boardcore +{ + +struct MPXH6400AData : public PressureData +{ + static std::string header() { return "pressureTimestamp,pressure\n"; } + + void print(std::ostream& os) const + { + os << pressureTimestamp << "," << pressure << "\n"; + } +}; + +} // namespace Boardcore diff --git a/src/shared/sensors/analog/pressure/nxp/MPXHZ6130A.h b/src/shared/sensors/analog/pressure/nxp/MPXHZ6130A.h new file mode 100644 index 0000000000000000000000000000000000000000..f2beffc5d4466bfed53d9ec5f2a719ac325a6947 --- /dev/null +++ b/src/shared/sensors/analog/pressure/nxp/MPXHZ6130A.h @@ -0,0 +1,56 @@ +/* Copyright (c) 2020 Skyward Experimental Rocketry + * Author: Alberto Nidasio + * + * 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. + */ + +#pragma once + +#include <sensors/analog/pressure/AnalogPressureSensor.h> +#include <utils/Stats/Stats.h> + +#include "MPXHZ6130AData.h" + +namespace Boardcore +{ + +/** + * @brief Driver for NXP's MPXHZ6130A pressure sensor + */ +class MPXHZ6130A final : public AnalogPressureSensor<MPXHZ6130AData> +{ +public: + MPXHZ6130A(std::function<ADCData()> getVoltage, + const float supplyVoltage = 5.0) + : AnalogPressureSensor(getVoltage, supplyVoltage, 130000, 15000) + { + } + +private: + float voltageToPressure(float voltage) override + { + return (((voltage / supplyVoltage) + CONST_B) / CONST_A) * 1000.0; + } + + // Constants from datasheet + static constexpr float CONST_A = 0.007826; + static constexpr float CONST_B = 0.07739; +}; + +} // namespace Boardcore diff --git a/src/shared/sensors/analog/pressure/MPXHZ6130A/MPXHZ6130AData.h b/src/shared/sensors/analog/pressure/nxp/MPXHZ6130AData.h similarity index 100% rename from src/shared/sensors/analog/pressure/MPXHZ6130A/MPXHZ6130AData.h rename to src/shared/sensors/analog/pressure/nxp/MPXHZ6130AData.h diff --git a/src/shared/sensors/calibration/AxisOrientation.h b/src/shared/sensors/calibration/AxisOrientation.h index 7b6924e7f9ebb9878995dcec88e2cc65345b8fd4..9d6ec3faca36ec73663a2ca972e1cb24fa415cb5 100644 --- a/src/shared/sensors/calibration/AxisOrientation.h +++ b/src/shared/sensors/calibration/AxisOrientation.h @@ -31,13 +31,7 @@ namespace Boardcore { /** - * This enum act like versors towards the chosen axis. - * - * X, Y and Z always set according to the right hand rule, so that: - * X is the index - * Y is the second finger - * Z is the thumb - * + * This enum is used to represent directions relative to X, Y and X. */ enum class Direction : uint8_t { @@ -53,9 +47,9 @@ constexpr const char* humanFriendlyDirection[]{ "North", "South", "East", "West", "Down", "Up", }; -inline Eigen::Vector3f orientationToVector(Direction val) +inline Eigen::Vector3f orientationToVector(Direction direction) { - switch (val) + switch (direction) { case Direction::POSITIVE_X: return {1, 0, 0}; @@ -70,65 +64,43 @@ inline Eigen::Vector3f orientationToVector(Direction val) case Direction::NEGATIVE_Z: return {0, 0, -1}; default: - /* never happens, added just to shut up the warnings */ + // never happens, added just to shut up the warnings return {0, 0, 0}; } } /** - * This struct represents in the most general way any kind of transformation of - * the reference frame (axis X, Y and Z). - * This data type is intended to simplify the code, so you shouldn't instantiate - * this struct directly, but rather use the structures AxisAngleOrientation or - * AxisOrthoOrientation that will be automatically corrected to this one, thanks - * to the implicit cast in favor of AxisOrientation. - * - * For example: - * - * AxisAngleOrientation angles ( PI/2, PI, 0); - * AxisOrthoOrientation ortho ( Direction::NEGATIVE_X, - * Direction::POSITIVE_Z ); - * - * // The implicit cast is supported and recommended - * AxisOrientation converted1 = angles; - * AxisOrientation converted2 = ortho; - * - * // Now we can use the generated matrix: - * Eigen::Vector3f zeta = convertedX.getMatrix() * Eigen::Vector3f { 0, 0, 1 } + * @brief This struct represents in the most general way any kind of + * transformation of the reference frame (axis X, Y and Z). * + * This class is abstract, use AxisAngleOrientation, AxisOrthoOrientation or + * AxisRelativeOrientation. */ struct AxisOrientation { - Eigen::Matrix3f mat; - - AxisOrientation() : mat(Eigen::Matrix3f::Identity()) {} - - AxisOrientation(Eigen::Matrix3f _mat) : mat(_mat) {} - - void setMatrix(Eigen::Matrix3f _mat) { mat = _mat; } - - Eigen::Matrix3f getMatrix() const { return mat; } + virtual Eigen::Matrix3f getMatrix() const = 0; }; /** - * This struct uses the three angles yaw, pitch and roll to define the - * transformation of the reference frame, so according to N.E.D standard we get: + * @brief This struct uses the three angles yaw, pitch and roll to define a + * transformation. + * + * According to N.E.D standard we get: * - * X (north) + * ^ X (north) * / * / * .----> Y (east) * | * | - * v - * Z (down) + * v Z (down) * * Where: - * Yaw is rotation of Z axis - * Pitch is rotation of Y axis - * Roll is rotation of X axis + *- Yaw is rotation of Z axis + * - Pitch is rotation of Y axis + * - Roll is rotation of X axis */ -struct AxisAngleOrientation +struct AxisAngleOrientation : public AxisOrientation { float yaw, pitch, roll; @@ -139,22 +111,21 @@ struct AxisAngleOrientation { } - operator AxisOrientation() const { return AxisOrientation(getMatrix()); } - - Eigen::Matrix3f getMatrix() const + Eigen::Matrix3f getMatrix() const override { - return (Eigen::AngleAxisf(yaw, Eigen::Vector3f{0, 0, 1}) * - Eigen::AngleAxisf(pitch, Eigen::Vector3f{0, 1, 0}) * - Eigen::AngleAxisf(roll, Eigen::Vector3f{1, 0, 0})) + return (Eigen::AngleAxisf(yaw, Eigen::Vector3f::UnitZ()) * + Eigen::AngleAxisf(pitch, Eigen::Vector3f::UnitY()) * + Eigen::AngleAxisf(roll, Eigen::Vector3f::UnitX())) .toRotationMatrix(); } }; /** - * This struct represents the orientation of the reference frame relative - * to X, Y, Z in the start orientation. - * If we know the orientation of the X and Y axis, using the right hand rule - * we can infer the Z axis. + * @brief This struct represents orthogonal rotations. + * + * The orientation is specified by describing the X and Y axis position relative + * to the absolute frame. Then, using the right hand rule, we can infer the Z + * axis. * * For example, if the base reference is: * @@ -169,13 +140,12 @@ struct AxisAngleOrientation * Then if we set x = NEGATIVE_Y, y = POSITIVE_Z, we get: * * y z - * ^ ^ - * | / + * ^ ^ * | / + * |/ * x <----/ - * */ -struct AxisOrthoOrientation +struct AxisOrthoOrientation : public AxisOrientation { Direction xAxis, yAxis; @@ -189,9 +159,7 @@ struct AxisOrthoOrientation { } - operator AxisOrientation() const { return AxisOrientation(getMatrix()); } - - Eigen::Matrix3f getMatrix() const + Eigen::Matrix3f getMatrix() const override { Eigen::Vector3f vx, vy, vz; @@ -208,25 +176,25 @@ struct AxisOrthoOrientation }; /** - * This struct represents axis orientation relative to a reference system. + * @brief This struct represents axis orientation relative to a reference + * system. + * * Operatively it simply combines two transformations. It is particularly useful * to obtain an AxisOrientation from a reference system generally not N.E.D. */ -struct AxisRelativeOrientation +struct AxisRelativeOrientation : public AxisOrientation { - AxisOrientation systemOrientation, orientation; + const AxisOrientation &orientationA, &orientationB; - AxisRelativeOrientation(const AxisOrientation& _systemOrientation, - const AxisOrientation& _orientation) - : systemOrientation(_systemOrientation), orientation(_orientation) + AxisRelativeOrientation(const AxisOrientation& orientationA, + const AxisOrientation& orientationB) + : orientationA(orientationA), orientationB(orientationB) { } - operator AxisOrientation() const { return {getMatrix()}; } - - Eigen::Matrix3f getMatrix() const + Eigen::Matrix3f getMatrix() const override { - return systemOrientation.getMatrix() * orientation.getMatrix(); + return orientationA.getMatrix() * orientationB.getMatrix(); } }; diff --git a/src/shared/sensors/calibration/BiasCalibration.h b/src/shared/sensors/calibration/BiasCalibration.h index be84f860e0118b37dff9bc6e4b6c600ff74aa473..389804703ae186018314d22742b9ff84c922a4de 100644 --- a/src/shared/sensors/calibration/BiasCalibration.h +++ b/src/shared/sensors/calibration/BiasCalibration.h @@ -81,6 +81,8 @@ public: Eigen::Vector3f getReferenceVector(); + void reset(); + bool feed(const T& measured, const AxisOrientation& transform) override; bool feed(const T& measured); @@ -88,7 +90,7 @@ public: BiasCorrector<T> computeResult(); private: - Eigen::Vector3f sum, ref; + Eigen::Vector3f mean, ref; unsigned numSamples; }; @@ -135,7 +137,7 @@ T BiasCorrector<T>::correct(const T& data) const template <typename T> BiasCalibration<T>::BiasCalibration() - : sum(0, 0, 0), ref(0, 0, 0), numSamples(0) + : mean(0, 0, 0), ref(0, 0, 0), numSamples(0) { } @@ -151,6 +153,12 @@ Eigen::Vector3f BiasCalibration<T>::getReferenceVector() return ref; } +template <typename T> +void BiasCalibration<T>::reset() +{ + mean = {0, 0, 0}; +} + /** * BiasCalibration accepts an indefinite number of samples, * so feed(...) never returns false. @@ -162,8 +170,9 @@ bool BiasCalibration<T>::feed(const T& measured, Eigen::Vector3f vec; measured >> vec; - sum += (transform.getMatrix().transpose() * ref) - vec; numSamples++; + mean += + (((transform.getMatrix().transpose() * ref) - vec) - mean) / numSamples; return true; } @@ -178,8 +187,8 @@ template <typename T> BiasCorrector<T> BiasCalibration<T>::computeResult() { if (numSamples == 0) - return {Eigen::Vector3f{0, 0, 0}}; - return {sum / numSamples}; + return {{0, 0, 0}}; + return {mean}; } } // namespace Boardcore diff --git a/src/shared/sensors/calibration/SixParameterCalibration.h b/src/shared/sensors/calibration/SixParameterCalibration.h index 8296a1ac974718cc02c0b174d1cd2c4f56a1482f..ae2c0449c948500f90e3a7d1d11aab97ca7ea2e0 100644 --- a/src/shared/sensors/calibration/SixParameterCalibration.h +++ b/src/shared/sensors/calibration/SixParameterCalibration.h @@ -48,8 +48,8 @@ class SixParameterCorrector : public ValuesCorrector<T> public: SixParameterCorrector() : SixParameterCorrector({1, 1, 1}, {0, 0, 0}) {} - SixParameterCorrector(const Eigen::Vector3f& _p, const Eigen::Vector3f& _q) - : p(_p), q(_q) + SixParameterCorrector(const Eigen::Vector3f& p, const Eigen::Vector3f& q) + : p(p), q(q) { } @@ -110,7 +110,7 @@ public: expected = transform.getMatrix() * ref; /* - * measered and expected are column vectors, we need to traspose them + * Measured and expected are column vectors, we need to transpose them * to be row vectors */ samples.block(numSamples, 0, 1, 3) = measured.transpose(); diff --git a/src/shared/sensors/calibration/SoftAndHardIronCalibration/SoftAndHardIronCalibration.cpp b/src/shared/sensors/calibration/SoftAndHardIronCalibration/SoftAndHardIronCalibration.cpp index c4d49d703425c8ec7d84fb1052e135b0b655ae97..7157af57868288f8e56d1b38c660ee4762b7d320 100644 --- a/src/shared/sensors/calibration/SoftAndHardIronCalibration/SoftAndHardIronCalibration.cpp +++ b/src/shared/sensors/calibration/SoftAndHardIronCalibration/SoftAndHardIronCalibration.cpp @@ -133,15 +133,15 @@ SoftAndHardIronCorrector SoftAndHardIronCalibration::computeResult() void operator<<(Eigen::Matrix<float, 3, 2>& lhs, const SoftAndHardIronCorrector& rhs) { - lhs.col(0) = rhs.getOffset(); lhs.col(0) = rhs.getGain(); + lhs.col(1) = rhs.getOffset(); } void operator<<(SoftAndHardIronCorrector& lhs, const Eigen::Matrix<float, 3, 2>& rhs) { - lhs.setOffset(rhs.col(0)); - lhs.setGain(rhs.col(1)); + lhs.setGain(rhs.col(0)); + lhs.setOffset(rhs.col(1)); } void operator>>(const Eigen::Matrix<float, 3, 2>& lhs, diff --git a/src/shared/utils/AeroUtils/AeroUtils.h b/src/shared/utils/AeroUtils/AeroUtils.h index 80abb8dac650fc6054e359b34e65442bf1402d41..19e3a5a6bdd6f00bef4825bba4cd2b09667bf401 100644 --- a/src/shared/utils/AeroUtils/AeroUtils.h +++ b/src/shared/utils/AeroUtils/AeroUtils.h @@ -36,7 +36,7 @@ namespace Aeroutils * given pressure, using International Standard Atmosphere model. * * @warning This function is valid for altitudes below 11000 meters above sea - * level + * level. * @warning This function provides a relative altitude from the reference * altitude. It does not provide altitude above mean sea level unless the * reference is, in fact, the sea level. diff --git a/src/shared/utils/ButtonHandler/ButtonHandler.cpp b/src/shared/utils/ButtonHandler/ButtonHandler.cpp index 56a0e5df40a5f5e5b2d12d4c3c80e2f0bfb00774..89c20e726514ba2acc90a9f5ea5d1d2266c3365f 100644 --- a/src/shared/utils/ButtonHandler/ButtonHandler.cpp +++ b/src/shared/utils/ButtonHandler/ButtonHandler.cpp @@ -44,6 +44,11 @@ bool ButtonHandler::registerButtonCallback(miosix::GpioPin pin, return false; } +bool ButtonHandler::unregisterButtonCallback(miosix::GpioPin pin) +{ + return callbacks.erase(pin) != 0; +} + bool ButtonHandler::start() { return scheduler.start(); } void ButtonHandler::stop() { scheduler.stop(); } @@ -63,12 +68,12 @@ void ButtonHandler::periodicButtonValueCheck(miosix::GpioPin pin) // Retrieve the pin information const ButtonCallback &callback = std::get<0>(callbacks[pin]); bool &wasPressed = std::get<1>(callbacks[pin]); - int &pressedTicks = std::get<2>(callbacks[pin]); + unsigned int &pressedTicks = std::get<2>(callbacks[pin]); // Read the current button status // Note: The button is assumed to be pressed if the pin value is low // (pulldown) - bool isNowPressed = !pin.value(); + const bool isNowPressed = !pin.value(); if (isNowPressed) { diff --git a/src/shared/utils/ButtonHandler/ButtonHandler.h b/src/shared/utils/ButtonHandler/ButtonHandler.h index 2ff97a9beb9e4acb7e6e98c45ee88550fa3deddf..8ae5b7d583f10ed726f93e12709bb88279d8e0c3 100644 --- a/src/shared/utils/ButtonHandler/ButtonHandler.h +++ b/src/shared/utils/ButtonHandler/ButtonHandler.h @@ -23,8 +23,8 @@ #pragma once #include <Singleton.h> -#include <miosix.h> #include <scheduler/TaskScheduler.h> +#include <utils/GpioPinCompare.h> #include <map> @@ -33,24 +33,10 @@ namespace Boardcore enum class ButtonEvent { - PRESSED, // Called as soon as the button is pressed - SHORT_PRESS, // Called as soon as the button is released - LONG_PRESS, // Called as soon as the button is released - VERY_LONG_PRESS // Called as soon as the button is released -}; - -/** - * @brief Comparison operator between GpioPins used for std::map. - */ -struct GpioPinCompare -{ - bool operator()(const miosix::GpioPin& lhs, - const miosix::GpioPin& rhs) const - { - if (lhs.getPort() == rhs.getPort()) - return lhs.getNumber() < rhs.getNumber(); - return lhs.getPort() < rhs.getPort(); - } + PRESSED, ///< The button is pressed. + SHORT_PRESS, ///< The button is released before LONG_PRESS_TICKS. + LONG_PRESS, ///< The button is released before VERY_LONG_PRESS_TICKS. + VERY_LONG_PRESS ///< The button is released after VERY_LONG_PRESS_TICKS. }; /** @@ -122,17 +108,12 @@ private: /** * @brief Map of all the callbacks registered in the ButtonHandler. * - * The key is the GpioPin for which the callback is registered. To used - * GpioPin as a map key, the GpioPinCompare operator was defined as - * explained here: - * https://stackoverflow.com/questions/1102392/how-can-i-use-stdmaps-with-user-defined-types-as-key - * * The type stored is a tuple containing: * - The button callback function; * - Whether or not the button was pressed in the last check iteration; * - The relative tick of the last pin value change. */ - std::map<miosix::GpioPin, std::tuple<ButtonCallback, bool, int>, + std::map<miosix::GpioPin, std::tuple<ButtonCallback, bool, unsigned int>, GpioPinCompare> callbacks; }; diff --git a/src/shared/utils/CSVReader/CSVReader.h b/src/shared/utils/CSVReader/CSVReader.h index a8f59a5efae736e8de7fb31193163d7fb4964f16..0db89a16b7b00c7dfa804e6d2679668a47b39ddf 100644 --- a/src/shared/utils/CSVReader/CSVReader.h +++ b/src/shared/utils/CSVReader/CSVReader.h @@ -152,6 +152,8 @@ public: CSVIterator<Data> end() { return CSVIterator<Data>(); } + void close() { fileStream.close(); } + std::vector<Data> collect() { std::vector<Data> fileData; diff --git a/src/shared/utils/ClockUtils.h b/src/shared/utils/ClockUtils.h index 3d671d9f48311aae9bae40d24b5f022e6d9d8e8e..addbdafb8c0bc54895f75fea3f8cb7294c257274 100644 --- a/src/shared/utils/ClockUtils.h +++ b/src/shared/utils/ClockUtils.h @@ -79,7 +79,7 @@ inline uint32_t ClockUtils::getAPBFrequency(APB bus) // The position of the PPRE1 bit in RCC->CFGR is different in some stm32 #ifdef _ARCH_CORTEXM3_STM32 const uint32_t ppre1 = 8; -#elif _ARCH_CORTEXM4_STM32F4 +#elif _ARCH_CORTEXM4_STM32F4 | _ARCH_CORTEXM3_STM32F2 const uint32_t ppre1 = 10; #else #error "Architecture not supported by TimerUtils" @@ -95,7 +95,7 @@ inline uint32_t ClockUtils::getAPBFrequency(APB bus) // The position of the PPRE2 bit in RCC->CFGR is different in some stm32 #ifdef _ARCH_CORTEXM3_STM32 const uint32_t ppre2 = 11; -#elif _ARCH_CORTEXM4_STM32F4 +#elif _ARCH_CORTEXM4_STM32F4 | _ARCH_CORTEXM3_STM32F2 const uint32_t ppre2 = 13; #else #error "Architecture not supported by TimerUtils" @@ -159,9 +159,11 @@ inline bool ClockUtils::enablePeripheralClock(void* peripheral) case BKPSRAM_BASE: RCC->AHB1ENR |= RCC_AHB1ENR_BKPSRAMEN; break; +#ifndef _ARCH_CORTEXM3_STM32F2 case CCMDATARAM_BASE: RCC->AHB1ENR |= RCC_AHB1ENR_CCMDATARAMEN; break; +#endif case DMA1_BASE: RCC->AHB1ENR |= RCC_AHB1ENR_DMA1EN; break; @@ -173,9 +175,11 @@ inline bool ClockUtils::enablePeripheralClock(void* peripheral) RCC->AHB1ENR |= RCC_AHB1ENR_DMA2DEN; break; #endif +#ifndef _ARCH_CORTEXM3_STM32F2 case ETH_MAC_BASE: RCC->AHB1ENR |= RCC_AHB1ENR_ETHMACEN; break; +#endif case USB_OTG_HS_PERIPH_BASE: RCC->AHB1ENR |= RCC_AHB1ENR_OTGHSEN; break; @@ -183,9 +187,11 @@ inline bool ClockUtils::enablePeripheralClock(void* peripheral) // AHB2 peripherals { +#ifndef _ARCH_CORTEXM3_STM32F2 case DCMI_BASE: RCC->AHB2ENR |= RCC_AHB2ENR_DCMIEN; break; +#endif case RNG_BASE: RCC->AHB2ENR |= RCC_AHB2ENR_RNGEN; break; @@ -395,9 +401,11 @@ inline bool ClockUtils::disablePeripheralClock(void* peripheral) case BKPSRAM_BASE: RCC->AHB1ENR &= ~RCC_AHB1ENR_BKPSRAMEN; break; +#ifndef _ARCH_CORTEXM3_STM32F2 case CCMDATARAM_BASE: RCC->AHB1ENR &= ~RCC_AHB1ENR_CCMDATARAMEN; break; +#endif case DMA1_BASE: RCC->AHB1ENR &= ~RCC_AHB1ENR_DMA1EN; break; @@ -409,9 +417,11 @@ inline bool ClockUtils::disablePeripheralClock(void* peripheral) RCC->AHB1ENR &= ~RCC_AHB1ENR_DMA2DEN; break; #endif +#ifndef _ARCH_CORTEXM3_STM32F2 case ETH_MAC_BASE: RCC->AHB1ENR &= ~RCC_AHB1ENR_ETHMACEN; break; +#endif case USB_OTG_HS_PERIPH_BASE: RCC->AHB1ENR &= ~RCC_AHB1ENR_OTGHSEN; break; @@ -419,9 +429,11 @@ inline bool ClockUtils::disablePeripheralClock(void* peripheral) // AHB2 peripherals { +#ifndef _ARCH_CORTEXM3_STM32F2 case DCMI_BASE: RCC->AHB2ENR &= ~RCC_AHB2ENR_DCMIEN; break; +#endif case RNG_BASE: RCC->AHB2ENR &= ~RCC_AHB2ENR_RNGEN; break; diff --git a/src/shared/utils/Constants.h b/src/shared/utils/Constants.h index ddc1e810901159f6b92d95041a8a3606dd8ef939..ba2aafcde38ed05ac9a2fda8bae8f46148ded2da 100644 --- a/src/shared/utils/Constants.h +++ b/src/shared/utils/Constants.h @@ -28,19 +28,27 @@ namespace Boardcore namespace Constants { -static constexpr const float PI = 3.14159265f; // [rad] -static constexpr const float DEGREES_TO_RADIANS = PI / 180.0f; -static constexpr const float RADIANS_TO_DEGREES = 180.0f / PI; +static constexpr float PI = 3.14159265f; // [rad] +static constexpr float DEGREES_TO_RADIANS = PI / 180.0f; +static constexpr float RADIANS_TO_DEGREES = 180.0f / PI; -static constexpr const float g = 9.80665f; // [m^s^2] +static constexpr float g = 9.80665f; // [m^s^2] static constexpr float a = 0.0065f; // Troposphere temperature gradient [deg/m] static constexpr float R = 287.05f; // Air gas constant [J/Kg/K] static constexpr float n = g / (R * a); static constexpr float nInv = (R * a) / g; -static constexpr const float MSL_PRESSURE = 101325.0f; // [Pa] -static constexpr const float MSL_TEMPERATURE = 288.15f; // [Kelvin] +static constexpr float CO = 340.3; // Sound speed at ground altitude [m/s] +static constexpr float ALPHA = -3.871e-3; // Sound speed gradient [1/s] +static constexpr float RHO_0 = 1.225; // Air density at sea level [kg/m^3] +static constexpr float Hn = 10400.0; // Scale height [m] + +static constexpr float MSL_PRESSURE = 101325.0f; // [Pa] +static constexpr float MSL_TEMPERATURE = 288.15f; // [Kelvin] + +static constexpr float B21_LATITUDE = 45.501141; +static constexpr float B21_LONGITUDE = 9.156281; } // namespace Constants diff --git a/src/shared/utils/GpioPinCompare.h b/src/shared/utils/GpioPinCompare.h new file mode 100644 index 0000000000000000000000000000000000000000..428c32c0b97ce46eba3ddb52ee4887efd4ab10e9 --- /dev/null +++ b/src/shared/utils/GpioPinCompare.h @@ -0,0 +1,47 @@ +/* Copyright (c) 2022 Skyward Experimental Rocketry + * Authors: Alberto Nidasio + * + * 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. + */ + +#pragma once + +#include <miosix.h> + +namespace Boardcore +{ + +/** + * @brief Comparison operator between GpioPins used for std::map. + * + * This function was implemented to use GpioPin as a map key. Check here for + * more explanation: + * https://stackoverflow.com/questions/1102392/how-can-i-use-stdmaps-with-user-defined-types-as-key + */ +struct GpioPinCompare +{ + bool operator()(const miosix::GpioPin& lhs, + const miosix::GpioPin& rhs) const + { + if (lhs.getPort() == rhs.getPort()) + return lhs.getNumber() < rhs.getNumber(); + return lhs.getPort() < rhs.getPort(); + } +}; +} // namespace Boardcore diff --git a/src/shared/utils/PinObserver.h b/src/shared/utils/PinObserver.h deleted file mode 100644 index a09573f5453f043219bde522004011a3f2a671b7..0000000000000000000000000000000000000000 --- a/src/shared/utils/PinObserver.h +++ /dev/null @@ -1,228 +0,0 @@ -/* Copyright (c) 2018 Skyward Experimental Rocketry - * Author: Luca Erbetta - * - * 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. - */ - -#pragma once - -#include <diagnostic/StackLogger.h> -#include <miosix.h> - -#include <functional> -#include <map> -#include <utility> - -#include "ActiveObject.h" - -using miosix::FastMutex; -using miosix::GpioPin; -using miosix::Lock; -using miosix::Thread; -using miosix::Unlock; - -using std::function; -using std::map; -using std::pair; - -namespace Boardcore -{ - -/** - * Class used to call a callback after a pin performs a specific transition - * (RISING or FALLING edge) and stays in the new state for a specific amount of - * time. Useful if you want to monitor pin transitions but you want to avoid - * spurious state changes. - * - * A callback to monitor each state change no matter the thresold or the - * transition is also available, in order to be able to observe the current - * state of the pin - */ -class PinObserver : public ActiveObject -{ -public: - /** - * @brief Pin transition - * Actual enumaration value represents the stat of the pin after the - * corresponding transition has occured. - */ - enum class Transition : int - { - FALLING_EDGE = 0, - RISING_EDGE = 1 - }; - - using OnStateChangeCallback = - function<void(unsigned int, unsigned char, int)>; - - using OnTransitionCallback = function<void(unsigned int, unsigned char)>; - - /** - * @brief Construct a new Pin Observer object - * - * @param pollIntervalMs Pin transition polling interval - */ - PinObserver(unsigned int pollIntervalMs = 20) : pollInterval(pollIntervalMs) - { - } - - /** - * Observe a pin for a specific transition, and optionally for every - * single state change. - * - * The @param transitionCb function is called only if the two following - * conditions are verified: - * 1. The transition specified in the @param transition is detected - * 2. The pin stays in the new state for at least detection_threshols - * samples. - * - * The @param onstatechangeCb function [optional] is called at each state - * change, both rising and falling edge, regardless of the @param - * detectionThreshold - * - * @param p GPIOA_BASE, GPIOB_BASE ... - * @param n Which pin (0 to 15) - * @param transition What transition to detect (RISING or FALLING edge) - * @param transitionCb Function to call when the transition is detected and - * the pin stays in the new configuration for at least @param - * detectionThreshold samples - * @param detectionThreshold How many times the pin should be observed in - * the post-transition state to trigger the actual transition callback. - * @param onstatechangeCb Function to be called at each pin state change, - * no matter the threshold or the transition - */ - void observePin(unsigned int p, unsigned char n, Transition transition, - OnTransitionCallback transitionCb, - unsigned int detectionThreshold = 1, - OnStateChangeCallback onstatechangeCb = nullptr) - { - Lock<FastMutex> lock(mtxMap); - observedPins.insert( - std::make_pair(pair<unsigned int, unsigned char>({p, n}), - ObserverData{GpioPin{p, n}, transition, transitionCb, - onstatechangeCb, detectionThreshold})); - } - - /** - * @brief Stop monitoring the specified pin - * - * @param p GPIOA_BASE, GPIOB_BASE ... - * @param n Which pin (0 to 15) - */ - void removeObservedPin(unsigned int p, unsigned char n) - { - Lock<FastMutex> lock(mtxMap); - observedPins.erase({p, n}); - } - -protected: - void run() - { - while (true) - { - { - Lock<FastMutex> lock(mtxMap); - - for (auto it = observedPins.begin(); it != observedPins.end(); - it++) - { - pair<int, int> key = it->first; - ObserverData& pinData = it->second; - - int oldState = pinData.state; - int newState = pinData.pin.value(); - - // Save current state in the struct - pinData.state = newState; - - // Are we in a post-transition state? - if (pinData.state == static_cast<int>(pinData.transition)) - { - ++pinData.detectedCount; - } - else - { - pinData.detectedCount = 0; - } - - // Pre-calcualate conditions in order to unlock the mutex - // only one time - - bool stateChange = pinData.onstatechangeCallback && - oldState != pinData.state; - bool pinTriggered = - pinData.detectedCount == pinData.detectionThreshold; - - { - Unlock<FastMutex> unlock(lock); - - if (stateChange) - { - pinData.onstatechangeCallback(key.first, key.second, - newState); - } - - if (pinTriggered) - { - pinData.transitionCallback(key.first, key.second); - } - } - } - } - - StackLogger::getInstance().updateStack(THID_PIN_OBS); - - Thread::sleep(pollInterval); - } - } - -private: - struct ObserverData - { - GpioPin pin; - Transition transition; - OnTransitionCallback transitionCallback; - OnStateChangeCallback onstatechangeCallback; - unsigned int detectionThreshold; - unsigned int detectedCount; - int state; // 1 if HIGH, 0 if LOW - - ObserverData(GpioPin pin, Transition transition, - OnTransitionCallback transitionCallback, - OnStateChangeCallback onstatechangeCallback, - unsigned int detectionThreshold) - : pin(pin), transition(transition), - transitionCallback(transitionCallback), - onstatechangeCallback(onstatechangeCallback), - detectionThreshold(detectionThreshold), - // Set to this value to avoid detection if the pin is already in - // the ending state of the "trigger" transition - detectedCount(detectionThreshold + 1), state(0) - { - } - }; - - map<pair<unsigned int, unsigned char>, ObserverData> observedPins; - FastMutex mtxMap; - - unsigned int pollInterval; - bool stopped = true; -}; - -} // namespace Boardcore diff --git a/src/shared/utils/PinObserver/PinObserver.cpp b/src/shared/utils/PinObserver/PinObserver.cpp new file mode 100644 index 0000000000000000000000000000000000000000..0eb65db1488357178ae8058de54e209b6c59eb3c --- /dev/null +++ b/src/shared/utils/PinObserver/PinObserver.cpp @@ -0,0 +1,107 @@ +/* Copyright (c) 2018-2022 Skyward Experimental Rocketry + * Author: Luca Erbetta, Alberto Nidasio + * + * 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. + */ + +#include "PinObserver.h" + +#include <drivers/timer/TimestampTimer.h> + +#include <functional> + +namespace Boardcore +{ + +bool PinObserver::registerPinCallback(miosix::GpioPin pin, PinCallback callback, + uint32_t detectionThreshold) +{ + // Try to insert the callback + auto result = callbacks.insert( + {pin, {callback, detectionThreshold, 0, 0, pin.value() == 1, 0}}); + + // Check if the insertion took place + if (result.second) + { + if (scheduler.addTask( + std::bind(&PinObserver::periodicPinValueCheck, this, pin), + SAMPLE_PERIOD, TaskScheduler::Policy::SKIP)) + return true; + else + callbacks.erase(pin); + } + + return false; +} + +bool PinObserver::start() { return scheduler.start(); } + +void PinObserver::stop() { scheduler.stop(); } + +bool PinObserver::isRunning() { return scheduler.isRunning(); } + +PinData PinObserver::getPinData(miosix::GpioPin pin) { return callbacks[pin]; } + +void PinObserver::resetPinChangesCount(miosix::GpioPin pin) +{ + callbacks[pin].changesCount = 0; +} + +PinObserver::PinObserver() { scheduler.start(); } + +void PinObserver::periodicPinValueCheck(miosix::GpioPin pin) +{ + // Make sure the pin informations are still present + if (callbacks.find(pin) == callbacks.end()) + return; + + auto &pinData = callbacks[pin]; + + // Retrieve the pin information + uint32_t &count = pinData.periodCount; + + // Read the current pin status + const bool newState = pin.value(); + + // Are we in a transition? + if (pinData.lastState != newState) + { + count = 0; // Yes, reset the counter + pinData.changesCount++; // And register the change + } + else + { + count++; // No, continue to increment + + // If the count reaches the threshold, then trigger the event + if (count > pinData.threshold) + { + if (newState) + pinData.callback(PinTransition::RISING_EDGE); + else + pinData.callback(PinTransition::FALLING_EDGE); + } + } + + // Save the current pin status + pinData.lastStateTimestamp = TimestampTimer::getTimestamp(); + pinData.lastState = newState; +} + +} // namespace Boardcore diff --git a/src/shared/utils/PinObserver/PinObserver.h b/src/shared/utils/PinObserver/PinObserver.h new file mode 100644 index 0000000000000000000000000000000000000000..a81f6e2b84bd21f252e0ef0b1ae720a89ba44528 --- /dev/null +++ b/src/shared/utils/PinObserver/PinObserver.h @@ -0,0 +1,141 @@ +/* Copyright (c) 2018-2022 Skyward Experimental Rocketry + * Author: Luca Erbetta, Alberto Nidasio + * + * 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. + */ + +#pragma once + +#include <Singleton.h> +#include <scheduler/TaskScheduler.h> +#include <utils/GpioPinCompare.h> + +#include <map> + +namespace Boardcore +{ + +/** + * @brief Pin transition. + */ +enum class PinTransition +{ + FALLING_EDGE, ///< The pin goes from high to low. + RISING_EDGE ///< The pin goes from low to high. +}; + +/** + * @brief Pin informations. + */ +struct PinData +{ + std::function<void(PinTransition)> callback; ///< The callback function. + uint32_t threshold; ///< Number of periods to trigger an event. + uint32_t periodCount; ///< Number of periods the value was the same. + uint64_t lastStateTimestamp; ///< Timestamp of the last measurement. + bool lastState; ///< The last measured pin state. + uint32_t changesCount; ///< Incremental count of the pin changes. +}; + +/** + * Class used to call a callback after a pin performs a specific transition + * (RISING or FALLING edge) and stays in the new state for a specific amount of + * time. Useful if you want to monitor pin transitions but you want to avoid + * spurious state changes. + * + * A callback to monitor each state change no matter the threshold or the + * transition is also available, in order to be able to observe the current + * state of the pin. + */ +class PinObserver : public Singleton<PinObserver> +{ + friend Singleton<PinObserver>; + + static constexpr uint32_t SAMPLE_PERIOD = 100; // 10Hz + +public: + using PinCallback = std::function<void(PinTransition)>; + + /** + * Observe a pin for a specific transition, and optionally for every + * single state change. + * + * @param pin Pin to listen to. + * @param callback Function to call on button events. + * @param detectionThreshold How many times the pin should be observed in + * the post-transition state to trigger the actual transition callback, + * defaults to 1. + * @return False if another callback was already registered for the pin. + */ + bool registerPinCallback(miosix::GpioPin pin, PinCallback callback, + uint32_t detectionThreshold = 1); + + /** + * @brief Starts the PinObserver's task scheduler. + * + * Note that the scheduler is started as soon as the PinObserver is first + * used. + * + * @return Whether the task scheduler was started or not. + */ + bool start(); + + /** + * @brief Stops the PinObserver's task scheduler. + */ + void stop(); + + /** + * @brief True if the PinObserver started correctly. + */ + bool isRunning(); + + /** + * @brief Returns the information for the specified pin. + */ + PinData getPinData(miosix::GpioPin pin); + + /** + * @brief Resets the changes counter for the specified pin. + */ + void resetPinChangesCount(miosix::GpioPin pin); + +private: + /** + * @brief Construct a new PinObserver object. + * + * @param pollInterval Pin transition polling interval, defaults to 20 [ms]. + */ + PinObserver(); + + /** + * @brief This function is added to the scheduler for every pin registered + * in the PinObserver. + * + * @param pin Pin whose value need to be checked. + */ + void periodicPinValueCheck(miosix::GpioPin pin); + + TaskScheduler scheduler; + + /// Map of all the callbacks registered in the PinObserver. + std::map<miosix::GpioPin, PinData, GpioPinCompare> callbacks; +}; + +} // namespace Boardcore diff --git a/src/shared/utils/SkyQuaternion/SkyQuaternion.cpp b/src/shared/utils/SkyQuaternion/SkyQuaternion.cpp index 1af74a6b622c2c287b4e602167ac5d0d0e1335af..bdae72473ce712712e2aedcd309e63800110624c 100644 --- a/src/shared/utils/SkyQuaternion/SkyQuaternion.cpp +++ b/src/shared/utils/SkyQuaternion/SkyQuaternion.cpp @@ -35,7 +35,7 @@ namespace Boardcore namespace SkyQuaternion { -Vector4f eul2quat(Vector3f euler) +Vector4f eul2quat(const Vector3f& euler) { // Euler angles are ZYX float yaw = euler(0) * Constants::DEGREES_TO_RADIANS; @@ -57,7 +57,7 @@ Vector4f eul2quat(Vector3f euler) return Vector4f(qx, qy, qz, qw); } -Vector3f quat2eul(Vector4f quat) +Vector3f quat2eul(const Vector4f& quat) { // Euler angles are ZYX float qx = quat(0); @@ -82,7 +82,7 @@ Vector3f quat2eul(Vector4f quat) return Vector3f(roll, pitch, yaw) * Constants::RADIANS_TO_DEGREES; } -Vector4f rotationMatrix2quat(Matrix3f rtm) +Vector4f rotationMatrix2quat(const Matrix3f& rtm) { float r11 = rtm(0, 0); float r12 = rtm(0, 1); @@ -156,6 +156,29 @@ Vector4f rotationMatrix2quat(Matrix3f rtm) return Vector4f(qx, qy, qz, qw); } +Matrix3f quat2rotationMatrix(const Vector4f& q) +{ + // clang-format off + return Matrix3f{ + { + q[0] * q[0] - q[1] * q[1] - q[2] * q[2] + q[3] * q[3], + 2.0f * (q[0] * q[1] - q[2] * q[3]), + 2.0f * (q[0] * q[2] + q[1] * q[3]), + }, + { + 2.0f * (q[0] * q[1] + q[2] * q[3]), + - q[0] * q[0] + q[1] * q[1] - q[2] * q[2] + q[3] * q[3], + 2.0f * (q[1] * q[2] - q[0] * q[3]), + }, + { + 2.0f * (q[0] * q[2] - q[1] * q[3]), + 2.0f * (q[1] * q[2] + q[0] * q[3]), + - q[0] * q[0] - q[1] * q[1] + q[2] * q[2] + q[3] * q[3] + } + }; + // clang-format on +} + bool quatNormalize(Vector4f& quat) { float den = sqrt(powf(quat(0), 2) + powf(quat(1), 2) + powf(quat(2), 2) + @@ -168,7 +191,7 @@ bool quatNormalize(Vector4f& quat) return true; } -Vector4f quatProd(const Vector4f q1, const Vector4f q2) +Vector4f quatProd(const Vector4f& q1, const Vector4f& q2) { Vector3f qv1 = q1.head<3>(); float qs1 = q1(3); diff --git a/src/shared/utils/SkyQuaternion/SkyQuaternion.h b/src/shared/utils/SkyQuaternion/SkyQuaternion.h index fecab90dcc1aa9e9541bc3ac8de59470a354ac18..884f1db3bc0bf1206e002241fe4fe04fde65b5df 100644 --- a/src/shared/utils/SkyQuaternion/SkyQuaternion.h +++ b/src/shared/utils/SkyQuaternion/SkyQuaternion.h @@ -30,7 +30,7 @@ namespace Boardcore /** * @brief Functions for managing quaternions. * - * Convention used: x, y, z, w (scalar element as last element) + * Convention used: [x, y, z, w] (scalar element as last element). */ namespace SkyQuaternion { @@ -38,43 +38,51 @@ namespace SkyQuaternion /** * @brief Transform a vector of euler angles (ZYX) to quaternion. * - * @param euler The vector of euler angles to be transformed [deg] - * @return Transformed quaternion [x, y, z, w] + * @param euler The vector of euler angles to be transformed [deg]. + * @return Transformed quaternion [x, y, z, w]. */ -Eigen::Vector4f eul2quat(Eigen::Vector3f euler); +Eigen::Vector4f eul2quat(const Eigen::Vector3f& euler); /** - * @brief Transform a quaternion to a vector of euler angles (ZYX). + * @brief Transform a quaternion into a vector of euler angles (ZYX). * - * @param quat The quaternion to be transformed [x, y, z, w] - * @return Transformed vector of euler angles [deg] + * @param quat The quaternion to be transformed [x, y, z, w]. + * @return Transformed vector of euler angles [deg]. */ -Eigen::Vector3f quat2eul(Eigen::Vector4f quat); +Eigen::Vector3f quat2eul(const Eigen::Vector4f& quat); /** - * @brief Transform a rotation matrix to a quaternion. + * @brief Transform a rotation matrix into a quaternion. * - * @param rtm The rotation matrix to be transformed (3x3) - * @return Transformed quaternion [x, y, z, w] + * @param rtm The rotation matrix to be transformed (3x3). + * @return Transformed quaternion [x, y, z, w]. */ -Eigen::Vector4f rotationMatrix2quat(Eigen::Matrix3f rtm); +Eigen::Vector4f rotationMatrix2quat(const Eigen::Matrix3f& rtm); + +/** + * @brief Transform a quaternion into a rotation matrix. + * + * @param quat The quaternion to be transformed [x, y, z, w]. + * @return Transformed rotation matrix. + */ +Eigen::Matrix3f quat2rotationMatrix(const Eigen::Vector4f& quat); /** * @brief Normalize a quaternion. * - * @param quat The quaternion to be normalized [x, y, z, w] - * @return True if the operation succeeded or not + * @param quat The quaternion to be normalized [x, y, z, w]. + * @return True if the operation succeeded or not. */ bool quatNormalize(Eigen::Vector4f& quat); /** * @brief Compute the product of two quaternions. * - * @param q1 First factor [x, y, z, w] - * @param q2 Second factor [x, y, z, w] - * @return The resulting quaternions product [x, y, z, w] + * @param q1 First factor [x, y, z, w]. + * @param q2 Second factor [x, y, z, w]. + * @return The resulting quaternions product [x, y, z, w]. */ -Eigen::Vector4f quatProd(const Eigen::Vector4f q1, const Eigen::Vector4f q2); +Eigen::Vector4f quatProd(const Eigen::Vector4f& q1, const Eigen::Vector4f& q2); }; // namespace SkyQuaternion diff --git a/src/shared/utils/Stats/Stats.h b/src/shared/utils/Stats/Stats.h index 3d57492c1c5bdd1a82ef15a217ed5db9d97c23cc..72fa685b976293b14e55b1b098795bf49d59cf32 100644 --- a/src/shared/utils/Stats/Stats.h +++ b/src/shared/utils/Stats/Stats.h @@ -28,15 +28,15 @@ namespace Boardcore { /** - * @brief Statisitics computed by the Stats class. + * @brief Statistics computed by the Stats class. */ struct StatsResult { - float minValue; ///< Min value found so far - float maxValue; ///< Max value found so far - float mean; ///< Mean of datased - float stdDev; ///< Standard deviation of datset - unsigned int nSamples; ///< Number of samples + float minValue; ///< Min value found so far. + float maxValue; ///< Max value found so far. + float mean; ///< Mean of dataset. + float stdDev; ///< Standard deviation of dataset. + uint32_t nSamples; ///< Number of samples. }; /** @@ -45,35 +45,27 @@ struct StatsResult std::ostream& operator<<(std::ostream& os, const StatsResult& sr); /** - * @brief Computes on-line statisitics of a dataset. This class should - * theoretically work with datasets of up to 2^32-1 elements + * @brief Computes on-line statistics of a dataset. + * + * This class should theoretically work with datasets of up to 2^32-1 elements. */ class Stats { public: - /** - * Constructor - */ Stats(); - /** - * Add an element - */ void add(float data); - /** - * Reset all the stats - */ void reset(); /** - * Return statistics of the elements added so far + * @brief Return statistics of the elements added so far. */ StatsResult getStats() const; private: float minValue, maxValue, mean, m2; - unsigned int n; + uint32_t n; }; } // namespace Boardcore diff --git a/src/shared/utils/TestUtils/FakeSpiTypedef.h b/src/shared/utils/TestUtils/FakeSpiTypedef.h index dae48554ab5c4ac85e0d6e642f7e723a77b48be0..eccb4a17b5b5e50ded8434fdfdaf814b467ae1a5 100644 --- a/src/shared/utils/TestUtils/FakeSpiTypedef.h +++ b/src/shared/utils/TestUtils/FakeSpiTypedef.h @@ -86,6 +86,8 @@ struct FakeSpiTypedef MockGpioPin cs; FakeSpiTypedef() : DR(*this) { cs.high(); } + + FakeSpiTypedef(SPI_TypeDef* spi) : DR(*this) { cs.high(); } }; } // namespace Boardcore diff --git a/src/shared/utils/collections/SyncPacketQueue.h b/src/shared/utils/collections/SyncPacketQueue.h index 90d5c8ea266492977a4449fd428c538d04090f2e..4a28254b2d2803c5f79dad9f3feb3a115abde7a3 100644 --- a/src/shared/utils/collections/SyncPacketQueue.h +++ b/src/shared/utils/collections/SyncPacketQueue.h @@ -158,7 +158,7 @@ size_t Packet<len>::append(const uint8_t* msg, size_t msgLen) { // Set the packet's timestamp when the first message is inserted if (content.size() == 0) - timestamp = TimestampTimer::getInstance().getTimestamp(); + timestamp = TimestampTimer::getTimestamp(); // Append the message to the packet content.insert(content.end(), msg, msg + msgLen); diff --git a/src/tests/algorithms/ADA/EuRoC-pressure-logs.h b/src/tests/algorithms/ADA/EuRoC-pressure-logs.h new file mode 100644 index 0000000000000000000000000000000000000000..8ed8d02134d1dca8c42caee9141629f444c41140 --- /dev/null +++ b/src/tests/algorithms/ADA/EuRoC-pressure-logs.h @@ -0,0 +1,10028 @@ +/* Copyright (c) 2022 Skyward Experimental Rocketry + * Author: Alberto Nidasio + * + * 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. + */ + +#pragma once + +#include <sensors/SensorData.h> + +Boardcore::PressureData euRoCLogs[] = { + {0, 99731.2522966667}, {10000, 99731.1802409184}, + {20000, 99730.9645527451}, {30000, 99730.8481615273}, + {40000, 99731.3327877128}, {50000, 99732.3825483349}, + {60000, 99732.7169921083}, {70000, 99732.0158314925}, + {80000, 99731.0029631542}, {90000, 99730.4967793341}, + {100000, 99730.4900197963}, {110000, 99730.349852717}, + {120000, 99729.8954901112}, {130000, 99729.3493423525}, + {140000, 99728.8295248688}, {150000, 99728.4218337112}, + {160000, 99728.3038754502}, {170000, 99728.4640675585}, + {180000, 99728.4733895779}, {190000, 99728.2241972271}, + {200000, 99727.8440420633}, {210000, 99727.477074123}, + {220000, 99727.1283473002}, {230000, 99726.8346342101}, + {240000, 99726.6049849585}, {250000, 99726.4001323631}, + {260000, 99726.1991753255}, {270000, 99726.0389349059}, + {280000, 99725.9956728505}, {290000, 99726.0589666787}, + {300000, 99725.9526860391}, {310000, 99725.6078176906}, + {320000, 99725.1230618576}, {330000, 99724.6100275692}, + {340000, 99724.0809943457}, {350000, 99723.7053579369}, + {360000, 99723.5255693398}, {370000, 99723.3339919326}, + {380000, 99723.0201457638}, {390000, 99722.609034374}, + {400000, 99722.151721952}, {410000, 99721.6486969769}, + {420000, 99721.0313348419}, {430000, 99720.2827530022}, + {440000, 99719.507327987}, {450000, 99718.8231705235}, + {460000, 99718.2277081137}, {470000, 99717.6482524521}, + {480000, 99717.0666866517}, {490000, 99716.4553879552}, + {500000, 99715.7997631179}, {510000, 99715.1283447269}, + {520000, 99714.4999739238}, {530000, 99713.9081813627}, + {540000, 99713.1623309895}, {550000, 99712.2148711858}, + {560000, 99711.2011369129}, {570000, 99710.2742493691}, + {580000, 99709.433458889}, {590000, 99708.5783027319}, + {600000, 99707.680126101}, {610000, 99706.725522843}, + {620000, 99705.7075081367}, {630000, 99704.6289022037}, + {640000, 99703.495204366}, {650000, 99702.3122882901}, + {660000, 99701.1669411549}, {670000, 99700.0809320785}, + {680000, 99698.9751158993}, {690000, 99697.7599057533}, + {700000, 99696.4395041044}, {710000, 99695.0550726795}, + {720000, 99693.6131777077}, {730000, 99692.1294155028}, + {740000, 99690.6121729627}, {750000, 99689.0561620938}, + {760000, 99687.4502425221}, {770000, 99685.7953524483}, + {780000, 99684.1197957055}, {790000, 99682.4307943679}, + {800000, 99680.7461140025}, {810000, 99679.0858804603}, + {820000, 99677.4471470906}, {830000, 99675.7789005816}, + {840000, 99674.0686487432}, {850000, 99672.2618022151}, + {860000, 99670.3295705182}, {870000, 99668.300179447}, + {880000, 99666.2314586285}, {890000, 99664.1304801217}, + {900000, 99662.0295905082}, {910000, 99659.9369551768}, + {920000, 99657.8365722006}, {930000, 99655.7103110199}, + {940000, 99653.5525581954}, {950000, 99651.3225400993}, + {960000, 99649.0141230993}, {970000, 99646.670916497}, + {980000, 99644.3161799847}, {990000, 99641.9335771142}, + {1000000, 99639.4891853757}, {1010000, 99636.9827808274}, + {1020000, 99634.4557241972}, {1030000, 99631.9185713089}, + {1040000, 99629.3813444179}, {1050000, 99626.8554142424}, + {1060000, 99624.3192535655}, {1070000, 99621.6418512615}, + {1080000, 99618.8056960286}, {1090000, 99616.0043047304}, + {1100000, 99613.3404531287}, {1110000, 99610.7542487207}, + {1120000, 99608.1222916632}, {1130000, 99605.4337331701}, + {1140000, 99602.6815120571}, {1150000, 99599.8640810433}, + {1160000, 99596.9925627559}, {1170000, 99594.0795183505}, + {1180000, 99591.1290473315}, {1190000, 99588.2125428165}, + {1200000, 99585.3486920444}, {1210000, 99582.4028913887}, + {1220000, 99579.3036929024}, {1230000, 99576.1153510696}, + {1240000, 99572.9702215699}, {1250000, 99569.8735768534}, + {1260000, 99566.725347408}, {1270000, 99563.5004403384}, + {1280000, 99560.1845593244}, {1290000, 99556.7614482947}, + {1300000, 99553.2362012944}, {1310000, 99549.7531026535}, + {1320000, 99546.3532632064}, {1330000, 99542.8846242695}, + {1340000, 99539.2664175493}, {1350000, 99535.5537993493}, + {1360000, 99531.8604037585}, {1370000, 99528.1946353766}, + {1380000, 99524.534415515}, {1390000, 99520.874139812}, + {1400000, 99517.1738288285}, {1410000, 99513.3880958101}, + {1420000, 99509.5174345398}, {1430000, 99505.5820703515}, + {1440000, 99501.5875697843}, {1450000, 99497.5094483854}, + {1460000, 99493.3348691468}, {1470000, 99489.1041409611}, + {1480000, 99484.9003781868}, {1490000, 99480.7253839781}, + {1500000, 99476.4905300129}, {1510000, 99472.1736247708}, + {1520000, 99467.7441176904}, {1530000, 99463.167326768}, + {1540000, 99458.4680408745}, {1550000, 99453.832095375}, + {1560000, 99449.2879341141}, {1570000, 99444.7003384933}, + {1580000, 99439.9974439209}, {1590000, 99435.2056236899}, + {1600000, 99430.3789767781}, {1610000, 99425.5220872763}, + {1620000, 99420.6311254827}, {1630000, 99415.7052496058}, + {1640000, 99410.7668557683}, {1650000, 99405.84132397}, + {1660000, 99400.9253395719}, {1670000, 99395.9076368835}, + {1680000, 99390.7567332193}, {1690000, 99385.4857086947}, + {1700000, 99380.1018033959}, {1710000, 99374.6403431825}, + {1720000, 99369.1740150516}, {1730000, 99363.7025595615}, + {1740000, 99358.1153868337}, {1750000, 99352.38495903}, + {1760000, 99346.5875237532}, {1770000, 99340.8094702717}, + {1780000, 99335.0529107748}, {1790000, 99329.3312159941}, + {1800000, 99323.6481169232}, {1810000, 99317.9356972582}, + {1820000, 99312.1578789489}, {1830000, 99306.2989371357}, + {1840000, 99300.325893299}, {1850000, 99294.2329185891}, + {1860000, 99287.9611507698}, {1870000, 99281.496354969}, + {1880000, 99274.9584357172}, {1890000, 99268.4833797906}, + {1900000, 99262.0702992972}, {1910000, 99255.6559576145}, + {1920000, 99249.2239188206}, {1930000, 99242.7314252704}, + {1940000, 99236.1558306549}, {1950000, 99229.5196105201}, + {1960000, 99222.8689970571}, {1970000, 99216.205238366}, + {1980000, 99209.4808576049}, {1990000, 99202.6840624341}, + {2000000, 99195.7985995062}, {2010000, 99188.8059665358}, + {2020000, 99181.7073044603}, {2030000, 99174.5324458593}, + {2040000, 99167.2901926923}, {2050000, 99159.9836215406}, + {2060000, 99152.6145209483}, {2070000, 99145.1773250005}, + {2080000, 99137.6601361407}, {2090000, 99130.0639387451}, + {2100000, 99122.4171133819}, {2110000, 99114.7270386922}, + {2120000, 99106.9814443964}, {2130000, 99099.1663586878}, + {2140000, 99091.281321106}, {2150000, 99083.3182876388}, + {2160000, 99075.2755320395}, {2170000, 99067.196930594}, + {2180000, 99059.1059795836}, {2190000, 99051.0065048657}, + {2200000, 99042.9063859203}, {2210000, 99034.8029422703}, + {2220000, 99026.6391792962}, {2230000, 99018.4008943053}, + {2240000, 99010.0745197527}, {2250000, 99001.6446009399}, + {2260000, 98993.1118466435}, {2270000, 98984.4799328481}, + {2280000, 98975.7497940957}, {2290000, 98966.9847825495}, + {2300000, 98958.2187850098}, {2310000, 98949.433011652}, + {2320000, 98940.5884315996}, {2330000, 98931.6805388544}, + {2340000, 98922.6857797486}, {2350000, 98913.5985151913}, + {2360000, 98904.4397176636}, {2370000, 98895.2331507288}, + {2380000, 98885.9829479848}, {2390000, 98876.7557479657}, + {2400000, 98867.5690100051}, {2410000, 98858.3952605819}, + {2420000, 98849.2198091645}, {2430000, 98839.9929017949}, + {2440000, 98830.6110866701}, {2450000, 98821.0632410822}, + {2460000, 98811.3009097897}, {2470000, 98801.3126136604}, + {2480000, 98791.1802633603}, {2490000, 98780.9967657655}, + {2500000, 98770.7671037183}, {2510000, 98760.5394575437}, + {2520000, 98750.3260449254}, {2530000, 98740.0329545286}, + {2540000, 98729.6102574116}, {2550000, 98719.1170349467}, + {2560000, 98708.6754214416}, {2570000, 98698.2872779756}, + {2580000, 98687.8087282108}, {2590000, 98677.2036560969}, + {2600000, 98666.5394018314}, {2610000, 98655.8923875061}, + {2620000, 98645.2577383584}, {2630000, 98634.52677896}, + {2640000, 98623.6723170112}, {2650000, 98612.761911138}, + {2660000, 98601.8317415363}, {2670000, 98590.8745967912}, + {2680000, 98579.875376915}, {2690000, 98568.825311244}, + {2700000, 98557.59443044}, {2710000, 98546.1504779952}, + {2720000, 98534.6688718995}, {2730000, 98523.3487700819}, + {2740000, 98512.1313804392}, {2750000, 98500.6708884015}, + {2760000, 98488.9213364322}, {2770000, 98477.0553684692}, + {2780000, 98465.1653804652}, {2790000, 98453.2439337497}, + {2800000, 98441.275400546}, {2810000, 98429.25480757}, + {2820000, 98417.1168018149}, {2830000, 98404.8452319944}, + {2840000, 98392.5183945307}, {2850000, 98380.2252277405}, + {2860000, 98367.9599655361}, {2870000, 98355.502612125}, + {2880000, 98342.7908875092}, {2890000, 98330.041161163}, + {2900000, 98317.3691329999}, {2910000, 98304.6952253771}, + {2920000, 98291.8542408485}, {2930000, 98278.8464533929}, + {2940000, 98265.9070948846}, {2950000, 98253.0955086808}, + {2960000, 98240.2724460386}, {2970000, 98227.279784061}, + {2980000, 98214.1195546006}, {2990000, 98200.9289958081}, + {3000000, 98187.7476829216}, {3010000, 98174.6536584149}, + {3020000, 98161.6884209621}, {3030000, 98148.8011118061}, + {3040000, 98135.8865805175}, {3050000, 98122.9262324949}, + {3060000, 98109.7560134294}, {3070000, 98096.3351014626}, + {3080000, 98082.816102951}, {3090000, 98069.3723730346}, + {3100000, 98055.9959193391}, {3110000, 98042.4658029569}, + {3120000, 98028.7243200588}, {3130000, 98015.0376325853}, + {3140000, 98001.54801962}, {3150000, 97988.1506978022}, + {3160000, 97974.6284359231}, {3170000, 97960.9681583947}, + {3180000, 97947.2582341531}, {3190000, 97933.521256805}, + {3200000, 97919.748422911}, {3210000, 97905.9297026658}, + {3220000, 97892.0643065395}, {3230000, 97878.146468715}, + {3240000, 97864.1755219932}, {3250000, 97850.0557325388}, + {3260000, 97835.7362908378}, {3270000, 97821.2331687886}, + {3280000, 97806.5785577902}, {3290000, 97791.7768845813}, + {3300000, 97776.8451329286}, {3310000, 97761.7880930983}, + {3320000, 97746.6510624912}, {3330000, 97731.4854612069}, + {3340000, 97716.2759060698}, {3350000, 97700.9215855558}, + {3360000, 97685.4091570097}, {3370000, 97669.78018772}, + {3380000, 97654.0571862609}, {3390000, 97638.1665053796}, + {3400000, 97621.9542012728}, {3410000, 97605.4179962476}, + {3420000, 97588.7227153002}, {3430000, 97571.9107468853}, + {3440000, 97554.9155986339}, {3450000, 97537.6615775601}, + {3460000, 97520.188658313}, {3470000, 97502.7416978312}, + {3480000, 97485.3544602847}, {3490000, 97467.865651867}, + {3500000, 97450.1892092555}, {3510000, 97432.3711763523}, + {3520000, 97414.5067506335}, {3530000, 97396.5854149567}, + {3540000, 97378.2827573139}, {3550000, 97359.5178541172}, + {3560000, 97340.5247175497}, {3570000, 97321.569339217}, + {3580000, 97302.6573759681}, {3590000, 97283.7938335705}, + {3600000, 97264.9798606929}, {3610000, 97246.1140270619}, + {3620000, 97227.1421118973}, {3630000, 97208.0737481632}, + {3640000, 97188.9284289212}, {3650000, 97169.7116165128}, + {3660000, 97150.4822659431}, {3670000, 97131.2553873994}, + {3680000, 97111.9917275239}, {3690000, 97092.6466151515}, + {3700000, 97073.2127999668}, {3710000, 97053.5757171371}, + {3720000, 97033.7070261094}, {3730000, 97013.7385887936}, + {3740000, 96993.7413712545}, {3750000, 96973.6807034334}, + {3760000, 96953.484124524}, {3770000, 96933.1474101544}, + {3780000, 96912.6957009888}, {3790000, 96892.1358053162}, + {3800000, 96871.4715219}, {3810000, 96850.7070998602}, + {3820000, 96829.8601728505}, {3830000, 96809.0578658673}, + {3840000, 96788.3194911903}, {3850000, 96767.4792403301}, + {3860000, 96746.4485177161}, {3870000, 96725.2531813028}, + {3880000, 96703.9461218166}, {3890000, 96682.5380707075}, + {3900000, 96661.1260705153}, {3910000, 96639.7347666651}, + {3920000, 96618.313819275}, {3930000, 96596.8059529814}, + {3940000, 96575.2123979646}, {3950000, 96553.5708986109}, + {3960000, 96531.8914445352}, {3970000, 96510.0623606453}, + {3980000, 96488.0241626863}, {3990000, 96465.8673229178}, + {4000000, 96443.779383562}, {4010000, 96421.767283942}, + {4020000, 96399.6765860557}, {4030000, 96377.468348045}, + {4040000, 96355.1427240336}, {4050000, 96332.699805155}, + {4060000, 96310.1454099487}, {4070000, 96287.5658125883}, + {4080000, 96264.9826963955}, {4090000, 96242.376093007}, + {4100000, 96219.7353586587}, {4110000, 96197.0225748844}, + {4120000, 96174.1584772349}, {4130000, 96151.1433166305}, + {4140000, 96128.0880305427}, {4150000, 96105.0209508105}, + {4160000, 96081.9465977544}, {4170000, 96058.8701115793}, + {4180000, 96035.7833374723}, {4190000, 96012.4359148288}, + {4200000, 95988.75682603}, {4210000, 95965.0196594782}, + {4220000, 95941.3713140665}, {4230000, 95917.7939880106}, + {4240000, 95894.2510388385}, {4250000, 95870.7364983237}, + {4260000, 95847.2049399803}, {4270000, 95823.6448867666}, + {4280000, 95800.0207765479}, {4290000, 95776.2920833514}, + {4300000, 95752.4645018159}, {4310000, 95728.6586827853}, + {4320000, 95704.9064758232}, {4330000, 95681.0885860027}, + {4340000, 95657.1411690174}, {4350000, 95633.108133941}, + {4360000, 95609.0803485059}, {4370000, 95585.0655492435}, + {4380000, 95561.0618666376}, {4390000, 95537.0687844632}, + {4400000, 95513.0474251003}, {4410000, 95488.9535142932}, + {4420000, 95464.7847436571}, {4430000, 95440.4880351168}, + {4440000, 95416.0485405948}, {4450000, 95391.5204280581}, + {4460000, 95366.9329593893}, {4470000, 95342.3160870726}, + {4480000, 95317.7320176654}, {4490000, 95293.1816155576}, + {4500000, 95268.5894225935}, {4510000, 95243.9364071519}, + {4520000, 95219.2353295206}, {4530000, 95194.5006917957}, + {4540000, 95169.7340005753}, {4550000, 95144.9534221312}, + {4560000, 95120.1636423284}, {4570000, 95095.2999228608}, + {4580000, 95070.3276590185}, {4590000, 95045.288925994}, + {4600000, 95020.2709701504}, {4610000, 94995.2732073972}, + {4620000, 94970.1570559632}, {4630000, 94944.887718154}, + {4640000, 94919.5245540186}, {4650000, 94894.1351201844}, + {4660000, 94868.7173546751}, {4670000, 94843.1984639008}, + {4680000, 94817.5594978524}, {4690000, 94791.8870174934}, + {4700000, 94766.2275351391}, {4710000, 94740.568264653}, + {4720000, 94714.8825840109}, {4730000, 94689.1690503271}, + {4740000, 94663.4405940357}, {4750000, 94637.7005583733}, + {4760000, 94611.9666116938}, {4770000, 94586.2588866293}, + {4780000, 94560.5754246828}, {4790000, 94534.8706615847}, + {4800000, 94509.1325822155}, {4810000, 94483.2776256804}, + {4820000, 94457.2612347244}, {4830000, 94431.1713245984}, + {4840000, 94405.190551004}, {4850000, 94379.326527346}, + {4860000, 94353.4459249422}, {4870000, 94327.5149037853}, + {4880000, 94301.5257767352}, {4890000, 94275.4697444066}, + {4900000, 94249.3457669923}, {4910000, 94223.1194004297}, + {4920000, 94196.7811506595}, {4930000, 94170.5001559649}, + {4940000, 94144.3676187119}, {4950000, 94118.2511034936}, + {4960000, 94091.87465898}, {4970000, 94065.2345600732}, + {4980000, 94038.6603959401}, {4990000, 94012.2358019331}, + {5000000, 93985.9325845693}, {5010000, 93959.7186870082}, + {5020000, 93933.587052024}, {5030000, 93907.4181722339}, + {5040000, 93881.1804933384}, {5050000, 93854.8324549371}, + {5060000, 93828.3519859959}, {5070000, 93801.801835988}, + {5080000, 93775.3124149169}, {5090000, 93748.8893609691}, + {5100000, 93722.4395213234}, {5110000, 93695.9393094114}, + {5120000, 93669.3632188584}, {5130000, 93642.682137315}, + {5140000, 93615.9171468051}, {5150000, 93589.2285200258}, + {5160000, 93562.6409557268}, {5170000, 93536.0328843679}, + {5180000, 93509.3389653589}, {5190000, 93482.5625281706}, + {5200000, 93455.7100619453}, {5210000, 93428.7866564617}, + {5220000, 93401.8648136426}, {5230000, 93374.9629793497}, + {5240000, 93348.0667840908}, {5250000, 93321.1598484137}, + {5260000, 93294.2470854443}, {5270000, 93267.4093534475}, + {5280000, 93240.6662546869}, {5290000, 93213.8825950397}, + {5300000, 93186.9854635654}, {5310000, 93160.0381510517}, + {5320000, 93133.1729788963}, {5330000, 93106.3919875062}, + {5340000, 93079.5374671039}, {5350000, 93052.5695536468}, + {5360000, 93025.5699731706}, {5370000, 92998.6318835909}, + {5380000, 92971.7545224862}, {5390000, 92944.8610067278}, + {5400000, 92917.9291941453}, {5410000, 92890.9743305662}, + {5420000, 92864.0046689558}, {5430000, 92837.0002124846}, + {5440000, 92809.9190480455}, {5450000, 92782.7610732611}, + {5460000, 92755.5816626198}, {5470000, 92728.3949884364}, + {5480000, 92701.1960224607}, {5490000, 92673.9790179514}, + {5500000, 92646.7539799038}, {5510000, 92619.5963214051}, + {5520000, 92592.5174650703}, {5530000, 92565.4111371095}, + {5540000, 92538.2202398873}, {5550000, 92510.9513206821}, + {5560000, 92483.6176133272}, {5570000, 92456.2255985513}, + {5580000, 92428.862489761}, {5590000, 92401.550375381}, + {5600000, 92374.3012787365}, {5610000, 92347.1289542208}, + {5620000, 92320.0190467446}, {5630000, 92292.855418972}, + {5640000, 92265.6187380047}, {5650000, 92238.3096030178}, + {5660000, 92210.9285023114}, {5670000, 92183.5073215596}, + {5680000, 92156.1123699275}, {5690000, 92128.7437035142}, + {5700000, 92101.3046026817}, {5710000, 92073.7706916591}, + {5720000, 92046.2050394028}, {5730000, 92018.6795907076}, + {5740000, 91991.1989654965}, {5750000, 91963.7814486832}, + {5760000, 91936.4292634479}, {5770000, 91909.0942662946}, + {5780000, 91881.7505233015}, {5790000, 91854.3739417661}, + {5800000, 91826.914073376}, {5810000, 91799.3758713937}, + {5820000, 91771.9146932026}, {5830000, 91744.5698267563}, + {5840000, 91717.2340976951}, {5850000, 91689.7852159593}, + {5860000, 91662.2292449079}, {5870000, 91634.7310333194}, + {5880000, 91607.3341596452}, {5890000, 91579.9929670843}, + {5900000, 91552.6827388444}, {5910000, 91525.3590816977}, + {5920000, 91497.9292018251}, {5930000, 91470.3897678345}, + {5940000, 91442.8148440484}, {5950000, 91415.2234283629}, + {5960000, 91387.6478855606}, {5970000, 91360.1251892215}, + {5980000, 91332.6523898659}, {5990000, 91305.1057026996}, + {6000000, 91277.4490342899}, {6010000, 91249.8360921561}, + {6020000, 91222.3497770652}, {6030000, 91194.9408940572}, + {6040000, 91167.5072230457}, {6050000, 91140.0359183291}, + {6060000, 91112.4564561741}, {6070000, 91084.7512736006}, + {6080000, 91057.0012606906}, {6090000, 91029.2986883559}, + {6100000, 91001.6452916967}, {6110000, 90974.0404211991}, + {6120000, 90946.4837173411}, {6130000, 90918.920253773}, + {6140000, 90891.3204252682}, {6150000, 90863.7232231736}, + {6160000, 90836.2100996617}, {6170000, 90808.7809968227}, + {6180000, 90781.3182743743}, {6190000, 90753.7920639732}, + {6200000, 90726.258564155}, {6210000, 90698.7819505323}, + {6220000, 90671.359653539}, {6230000, 90643.9307382547}, + {6240000, 90616.4799347019}, {6250000, 90588.9953892367}, + {6260000, 90561.4707950372}, {6270000, 90534.0553475359}, + {6280000, 90507.0612563368}, {6290000, 90480.5152161613}, + {6300000, 90454.4407941598}, {6310000, 90428.8422494195}, + {6320000, 90403.5975245431}, {6330000, 90378.567485837}, + {6340000, 90353.7419700754}, {6350000, 90329.0193470905}, + {6360000, 90304.3737470509}, {6370000, 90279.63151831}, + {6380000, 90254.6992347864}, {6390000, 90229.7029575442}, + {6400000, 90204.9058983077}, {6410000, 90180.304547974}, + {6420000, 90155.4540272898}, {6430000, 90130.2417341836}, + {6440000, 90104.7535685937}, {6450000, 90079.0875078595}, + {6460000, 90053.2661713656}, {6470000, 90027.5858530945}, + {6480000, 90002.1181199373}, {6490000, 89976.7362286851}, + {6500000, 89951.3716331972}, {6510000, 89925.9265927838}, + {6520000, 89900.1963134543}, {6530000, 89874.1747513236}, + {6540000, 89848.0450888399}, {6550000, 89821.8544304102}, + {6560000, 89795.6084649763}, {6570000, 89769.3136487784}, + {6580000, 89742.9694467886}, {6590000, 89716.5443840494}, + {6600000, 89690.0295234001}, {6610000, 89663.3606626211}, + {6620000, 89636.5035305489}, {6630000, 89609.5921912179}, + {6640000, 89582.9066423804}, {6650000, 89556.4579669357}, + {6660000, 89530.0318543301}, {6670000, 89503.5735322531}, + {6680000, 89477.0746663614}, {6690000, 89450.5257005922}, + {6700000, 89423.9395369792}, {6710000, 89397.4128180503}, + {6720000, 89370.9602739146}, {6730000, 89344.6296445462}, + {6740000, 89318.446396648}, {6750000, 89292.2672844309}, + {6760000, 89265.7928382981}, {6770000, 89239.0154814873}, + {6780000, 89212.234880596}, {6790000, 89185.5275177951}, + {6800000, 89158.7312454584}, {6810000, 89131.6606660719}, + {6820000, 89104.3353020094}, {6830000, 89077.1454248859}, + {6840000, 89050.1903019645}, {6850000, 89023.3768595061}, + {6860000, 88996.6545154913}, {6870000, 88969.9633745974}, + {6880000, 88943.178253128}, {6890000, 88916.2977411626}, + {6900000, 88889.4800614968}, {6910000, 88862.7653570592}, + {6920000, 88836.0361374852}, {6930000, 88809.1579921599}, + {6940000, 88782.1701852366}, {6950000, 88755.3956139772}, + {6960000, 88728.8854531044}, {6970000, 88702.4659170134}, + {6980000, 88676.042956546}, {6990000, 88649.5753172281}, + {7000000, 88622.9764113534}, {7010000, 88596.2434971152}, + {7020000, 88569.4510091517}, {7030000, 88542.6182137257}, + {7040000, 88515.7913107293}, {7050000, 88489.0231971789}, + {7060000, 88462.3019971634}, {7070000, 88435.5492141128}, + {7080000, 88408.7540927923}, {7090000, 88382.0190457411}, + {7100000, 88355.3992376716}, {7110000, 88328.8534042391}, + {7120000, 88302.2955900558}, {7130000, 88275.7188987707}, + {7140000, 88249.1327040641}, {7150000, 88222.5394353224}, + {7160000, 88195.92855482}, {7170000, 88169.2879950781}, + {7180000, 88142.6208360579}, {7190000, 88115.9885169778}, + {7200000, 88089.4070143835}, {7210000, 88062.8656503532}, + {7220000, 88036.3585673693}, {7230000, 88009.9053294456}, + {7240000, 87983.5471785902}, {7250000, 87957.2771368902}, + {7260000, 87930.9177496979}, {7270000, 87904.4240241083}, + {7280000, 87877.8739460823}, {7290000, 87851.3566833925}, + {7300000, 87824.8768961636}, {7310000, 87798.5275285781}, + {7320000, 87772.3350929276}, {7330000, 87746.0751844973}, + {7340000, 87719.62662118}, {7350000, 87693.0711713152}, + {7360000, 87666.5795552338}, {7370000, 87640.1661153468}, + {7380000, 87613.8262027538}, {7390000, 87587.5583545494}, + {7400000, 87561.2727360067}, {7410000, 87534.8664852392}, + {7420000, 87508.3558721491}, {7430000, 87482.103735009}, + {7440000, 87456.2055114054}, {7450000, 87430.2340869766}, + {7460000, 87403.9589912652}, {7470000, 87377.4781404337}, + {7480000, 87350.9955403331}, {7490000, 87324.5378896901}, + {7500000, 87298.2607881328}, {7510000, 87272.2033084057}, + {7520000, 87246.2274704689}, {7530000, 87220.1754968958}, + {7540000, 87194.0655667158}, {7550000, 87168.1417416831}, + {7560000, 87142.4560028844}, {7570000, 87116.9094205027}, + {7580000, 87091.4481862353}, {7590000, 87066.0524803707}, + {7600000, 87040.6811407179}, {7610000, 87015.3229536773}, + {7620000, 86989.8461792366}, {7630000, 86964.2175787571}, + {7640000, 86938.5208299139}, {7650000, 86912.8516810709}, + {7660000, 86887.2136701877}, {7670000, 86861.6527880827}, + {7680000, 86836.1819125132}, {7690000, 86810.6709995332}, + {7700000, 86785.0498254812}, {7710000, 86759.370240042}, + {7720000, 86733.7407719657}, {7730000, 86708.1661401226}, + {7740000, 86682.5662889874}, {7750000, 86656.9208099206}, + {7760000, 86631.2273780723}, {7770000, 86605.4832957868}, + {7780000, 86579.6921932241}, {7790000, 86553.9732218861}, + {7800000, 86528.3610099168}, {7810000, 86502.721643264}, + {7820000, 86476.9827763602}, {7830000, 86451.2048247747}, + {7840000, 86425.5141473309}, {7850000, 86399.9324413806}, + {7860000, 86374.6533573199}, {7870000, 86349.7252785617}, + {7880000, 86324.8408593166}, {7890000, 86299.6482632685}, + {7900000, 86274.1542646208}, {7910000, 86248.6273562705}, + {7920000, 86223.1392873827}, {7930000, 86197.8362192736}, + {7940000, 86172.7968647979}, {7950000, 86147.8827830316}, + {7960000, 86122.8043252596}, {7970000, 86097.5458396082}, + {7980000, 86072.2634392505}, {7990000, 86046.9971217319}, + {8000000, 86021.7753844732}, {8010000, 85996.6309137179}, + {8020000, 85971.5609136657}, {8030000, 85946.4639107814}, + {8040000, 85921.3105756534}, {8050000, 85896.0729528854}, + {8060000, 85870.7360785275}, {8070000, 85845.4282483872}, + {8080000, 85820.4192425115}, {8090000, 85795.7086237806}, + {8100000, 85770.8944945672}, {8110000, 85745.8742211893}, + {8120000, 85720.7277516844}, {8130000, 85695.5465956946}, + {8140000, 85670.3331001743}, {8150000, 85645.1101821781}, + {8160000, 85619.8852443731}, {8170000, 85594.7924266559}, + {8180000, 85569.9040535742}, {8190000, 85545.1503760283}, + {8200000, 85520.3858591071}, {8210000, 85495.5949183249}, + {8220000, 85470.7259917026}, {8230000, 85445.7661750439}, + {8240000, 85420.7584411514}, {8250000, 85395.7519923482}, + {8260000, 85370.7610812594}, {8270000, 85345.8675259543}, + {8280000, 85321.0822878854}, {8290000, 85296.3351668762}, + {8300000, 85271.5880191935}, {8310000, 85246.836347649}, + {8320000, 85222.0706956638}, {8330000, 85197.2910875413}, + {8340000, 85172.5113934863}, {8350000, 85147.7351627777}, + {8360000, 85122.9831980472}, {8370000, 85098.2793534399}, + {8380000, 85073.621535701}, {8390000, 85048.9606645584}, + {8400000, 85024.2836686936}, {8410000, 84999.6826915104}, + {8420000, 84975.2075135923}, {8430000, 84950.8078908157}, + {8440000, 84926.3788677201}, {8450000, 84901.9102557375}, + {8460000, 84877.3817056922}, {8470000, 84852.7882329221}, + {8480000, 84828.2121946075}, {8490000, 84803.7479693681}, + {8500000, 84779.3889656965}, {8510000, 84755.0001733068}, + {8520000, 84730.5477848986}, {8530000, 84706.1098807513}, + {8540000, 84681.7287571802}, {8550000, 84657.388536082}, + {8560000, 84633.056109735}, {8570000, 84608.7378123228}, + {8580000, 84584.596777798}, {8590000, 84560.6741278638}, + {8600000, 84536.8099001033}, {8610000, 84512.8207018538}, + {8620000, 84488.7091575251}, {8630000, 84464.5830306905}, + {8640000, 84440.4699733799}, {8650000, 84416.4422626713}, + {8660000, 84392.5388879596}, {8670000, 84368.7207124037}, + {8680000, 84344.9060446085}, {8690000, 84321.0842049956}, + {8700000, 84297.1929622344}, {8710000, 84273.2166360723}, + {8720000, 84249.2076009606}, {8730000, 84225.2258924876}, + {8740000, 84201.2791790289}, {8750000, 84177.4260786483}, + {8760000, 84153.6771000802}, {8770000, 84129.9126535663}, + {8780000, 84106.0678564484}, {8790000, 84082.1775440011}, + {8800000, 84058.3145966813}, {8810000, 84034.4859035839}, + {8820000, 84010.7027837755}, {8830000, 83986.9679672492}, + {8840000, 83963.2962753181}, {8850000, 83939.7047523533}, + {8860000, 83916.1896794717}, {8870000, 83892.6425324908}, + {8880000, 83869.0324161239}, {8890000, 83845.391773906}, + {8900000, 83821.7382635547}, {8910000, 83798.1211088545}, + {8920000, 83774.6438503954}, {8930000, 83751.3075009719}, + {8940000, 83727.9811288778}, {8950000, 83704.6311658307}, + {8960000, 83681.2876486296}, {8970000, 83657.9850553309}, + {8980000, 83634.7234356082}, {8990000, 83611.4839784492}, + {9000000, 83588.2610728479}, {9010000, 83565.1038363255}, + {9020000, 83542.0387828365}, {9030000, 83519.0006356284}, + {9040000, 83495.8523621374}, {9050000, 83472.5930266834}, + {9060000, 83449.4088823225}, {9070000, 83426.3473495665}, + {9080000, 83403.3540676474}, {9090000, 83380.3666991465}, + {9100000, 83357.3830240577}, {9110000, 83334.3609967621}, + {9120000, 83311.287894011}, {9130000, 83288.2909529129}, + {9140000, 83265.4390698238}, {9150000, 83242.6941649755}, + {9160000, 83219.9768055125}, {9170000, 83197.2748226904}, + {9180000, 83174.4972663176}, {9190000, 83151.6210545897}, + {9200000, 83128.7477694261}, {9210000, 83105.9939982613}, + {9220000, 83083.3320199366}, {9230000, 83060.5373036514}, + {9240000, 83037.5754060389}, {9250000, 83014.6933129313}, + {9260000, 82992.0249164369}, {9270000, 82969.4918222579}, + {9280000, 82946.9300319846}, {9290000, 82924.3312963147}, + {9300000, 82901.8009696567}, {9310000, 82879.3658038238}, + {9320000, 82856.9943716039}, {9330000, 82834.6506528788}, + {9340000, 82812.3259355755}, {9350000, 82789.9715925901}, + {9360000, 82767.5809825767}, {9370000, 82745.1902443216}, + {9380000, 82722.8189955768}, {9390000, 82700.4851050607}, + {9400000, 82678.2263318326}, {9410000, 82656.040484208}, + {9420000, 82633.836168098}, {9430000, 82611.5900251729}, + {9440000, 82589.3687773528}, {9450000, 82567.249104527}, + {9460000, 82545.2227258094}, {9470000, 82523.2282498465}, + {9480000, 82501.2569525479}, {9490000, 82479.3191957533}, + {9500000, 82457.4205382465}, {9510000, 82435.5524384467}, + {9520000, 82413.6970911173}, {9530000, 82391.8491672635}, + {9540000, 82369.9429788999}, {9550000, 82347.9619042003}, + {9560000, 82325.9789341601}, {9570000, 82304.0779308992}, + {9580000, 82282.257820619}, {9590000, 82260.4658352725}, + {9600000, 82238.6878067105}, {9610000, 82216.9333324838}, + {9620000, 82195.2075783516}, {9630000, 82173.4990531558}, + {9640000, 82151.7836703569}, {9650000, 82130.0673967687}, + {9660000, 82108.4924260893}, {9670000, 82087.0946831098}, + {9680000, 82065.7230285663}, {9690000, 82044.203829935}, + {9700000, 82022.5438564581}, {9710000, 82000.9207330906}, + {9720000, 81979.3799346104}, {9730000, 81957.8940871258}, + {9740000, 81936.4481613987}, {9750000, 81915.0270186558}, + {9760000, 81893.5989382121}, {9770000, 81872.1634958079}, + {9780000, 81850.7618954746}, {9790000, 81829.4045861908}, + {9800000, 81808.1353626179}, {9810000, 81787.0046528576}, + {9820000, 81765.9886583129}, {9830000, 81744.8962384076}, + {9840000, 81723.6965540609}, {9850000, 81702.4354647516}, + {9860000, 81681.1380472016}, {9870000, 81659.8483108659}, + {9880000, 81638.6589133199}, {9890000, 81617.5733651565}, + {9900000, 81596.5176831077}, {9910000, 81575.4727702322}, + {9920000, 81554.4320164853}, {9930000, 81533.3878304135}, + {9940000, 81512.3424772468}, {9950000, 81491.3421738297}, + {9960000, 81470.3988584557}, {9970000, 81449.5051134303}, + {9980000, 81428.656787862}, {9990000, 81407.8391422942}, + {10000000, 81387.0212975025}, {10010000, 81366.2024635993}, + {10020000, 81345.416708658}, {10030000, 81324.6726609969}, + {10040000, 81303.9290089204}, {10050000, 81283.1382873336}, + {10060000, 81262.3065420413}, {10070000, 81241.5427736233}, + {10080000, 81220.8737056187}, {10090000, 81200.2311287078}, + {10100000, 81179.5778429343}, {10110000, 81158.9580206216}, + {10120000, 81138.4649017305}, {10130000, 81118.0999337636}, + {10140000, 81097.753142577}, {10150000, 81077.396213005}, + {10160000, 81057.0270141928}, {10170000, 81036.6430863331}, + {10180000, 81016.2452603957}, {10190000, 80995.8606029148}, + {10200000, 80975.4969473841}, {10210000, 80955.2100923113}, + {10220000, 80935.0302466846}, {10230000, 80914.929487483}, + {10240000, 80894.8494326728}, {10250000, 80874.7782345368}, + {10260000, 80854.5975825486}, {10270000, 80834.2774924968}, + {10280000, 80813.9355602389}, {10290000, 80793.7069929116}, + {10300000, 80773.5903269345}, {10310000, 80753.5035679596}, + {10320000, 80733.424732213}, {10330000, 80713.3862762697}, + {10340000, 80693.4058049746}, {10350000, 80673.5065228314}, + {10360000, 80653.7377648701}, {10370000, 80634.0945536547}, + {10380000, 80614.4212840824}, {10390000, 80594.6780987094}, + {10400000, 80574.8996260982}, {10410000, 80555.1256584179}, + {10420000, 80535.357874189}, {10430000, 80515.6226966555}, + {10440000, 80495.9276972916}, {10450000, 80476.2598477206}, + {10460000, 80456.6119834345}, {10470000, 80437.0093055078}, + {10480000, 80417.5052096381}, {10490000, 80398.0996836534}, + {10500000, 80378.7164422782}, {10510000, 80359.3357910457}, + {10520000, 80339.9410389725}, {10530000, 80320.512966166}, + {10540000, 80301.051279612}, {10550000, 80281.55121111}, + {10560000, 80262.011336457}, {10570000, 80242.5774627951}, + {10580000, 80223.3288477057}, {10590000, 80204.159203326}, + {10600000, 80184.8450634415}, {10610000, 80165.3788688876}, + {10620000, 80145.963482546}, {10630000, 80126.6508236988}, + {10640000, 80107.429845234}, {10650000, 80088.2879051601}, + {10660000, 80069.2225473681}, {10670000, 80050.1984922718}, + {10680000, 80031.2062924026}, {10690000, 80012.2237121161}, + {10700000, 79993.2386064663}, {10710000, 79974.2589436305}, + {10720000, 79955.3015570988}, {10730000, 79936.3642600348}, + {10740000, 79917.3833502627}, {10750000, 79898.3426120267}, + {10760000, 79879.317793302}, {10770000, 79860.3960813515}, + {10780000, 79841.5733639773}, {10790000, 79822.7317643851}, + {10800000, 79803.8397416897}, {10810000, 79784.986581606}, + {10820000, 79766.2208766283}, {10830000, 79747.5126763078}, + {10840000, 79728.7991428787}, {10850000, 79710.0749906317}, + {10860000, 79691.3437926815}, {10870000, 79672.6064936947}, + {10880000, 79653.8674233859}, {10890000, 79635.131563239}, + {10900000, 79616.4009293422}, {10910000, 79597.7394547936}, + {10920000, 79579.1655234859}, {10930000, 79560.6150923745}, + {10940000, 79542.0531453575}, {10950000, 79523.5039112669}, + {10960000, 79505.0186071703}, {10970000, 79486.5947734846}, + {10980000, 79468.1131160679}, {10990000, 79449.5431796941}, + {11000000, 79430.9920564255}, {11010000, 79412.5830082392}, + {11020000, 79394.3140248614}, {11030000, 79376.0998477159}, + {11040000, 79357.9175313033}, {11050000, 79339.7301337877}, + {11060000, 79321.5175252978}, {11070000, 79303.2846185639}, + {11080000, 79285.0416601156}, {11090000, 79266.7908257526}, + {11100000, 79248.5542303101}, {11110000, 79230.3375116532}, + {11120000, 79212.1715895695}, {11130000, 79194.0921174796}, + {11140000, 79176.0938434761}, {11150000, 79158.1093449814}, + {11160000, 79140.123744619}, {11170000, 79122.1259322812}, + {11180000, 79104.1098700842}, {11190000, 79086.0952528848}, + {11200000, 79068.1236637062}, {11210000, 79050.2002951798}, + {11220000, 79032.35609476}, {11230000, 79014.5987330029}, + {11240000, 78996.848445922}, {11250000, 78979.013442376}, + {11260000, 78961.0982150615}, {11270000, 78943.1979012368}, + {11280000, 78925.3357680441}, {11290000, 78907.4760786936}, + {11300000, 78889.5993177958}, {11310000, 78871.7446063155}, + {11320000, 78853.9946501556}, {11330000, 78836.3524962225}, + {11340000, 78818.7507467303}, {11350000, 78801.1719096986}, + {11360000, 78783.624615656}, {11370000, 78766.1188300601}, + {11380000, 78748.6541181812}, {11390000, 78731.2151329755}, + {11400000, 78713.7973191691}, {11410000, 78696.3863156943}, + {11420000, 78678.9742567802}, {11430000, 78661.5721280537}, + {11440000, 78644.2031752162}, {11450000, 78626.8693630243}, + {11460000, 78609.5718874394}, {11470000, 78592.3109218399}, + {11480000, 78575.0617383834}, {11490000, 78557.795864731}, + {11500000, 78540.5227042142}, {11510000, 78523.3181913066}, + {11520000, 78506.1940088208}, {11530000, 78489.0739227238}, + {11540000, 78471.9163051306}, {11550000, 78454.7594907205}, + {11560000, 78437.6844067388}, {11570000, 78420.6936550896}, + {11580000, 78403.7126709475}, {11590000, 78386.7222143852}, + {11600000, 78369.721316694}, {11610000, 78352.7088529365}, + {11620000, 78335.6931624447}, {11630000, 78318.7375069155}, + {11640000, 78301.8516074686}, {11650000, 78284.9893796015}, + {11660000, 78268.1255780612}, {11670000, 78251.2648492588}, + {11680000, 78234.4170289116}, {11690000, 78217.5849511094}, + {11700000, 78200.8050084472}, {11710000, 78184.0863809457}, + {11720000, 78167.380452935}, {11730000, 78150.6312387294}, + {11740000, 78133.8447771019}, {11750000, 78117.0842206002}, + {11760000, 78100.3609651003}, {11770000, 78083.7032669941}, + {11780000, 78067.1264252778}, {11790000, 78050.6078786886}, + {11800000, 78034.1002789465}, {11810000, 78017.600860864}, + {11820000, 78001.1354966881}, {11830000, 77984.7107238122}, + {11840000, 77968.2928488274}, {11850000, 77951.8430370078}, + {11860000, 77935.3627075496}, {11870000, 77918.8947086892}, + {11880000, 77902.4503248758}, {11890000, 77886.0350502466}, + {11900000, 77869.651826789}, {11910000, 77853.3119135926}, + {11920000, 77837.039395553}, {11930000, 77820.8333711166}, + {11940000, 77804.6447359077}, {11950000, 77788.4607790442}, + {11960000, 77772.2512755865}, {11970000, 77755.9813634435}, + {11980000, 77739.6564437872}, {11990000, 77723.401789272}, + {12000000, 77707.2507945121}, {12010000, 77691.109846848}, + {12020000, 77674.9277504213}, {12030000, 77658.731075462}, + {12040000, 77642.5758867551}, {12050000, 77626.466302664}, + {12060000, 77610.3910338171}, {12070000, 77594.347045841}, + {12080000, 77578.3359435057}, {12090000, 77562.3596043998}, + {12100000, 77546.4169506464}, {12110000, 77530.4762740915}, + {12120000, 77514.5283364763}, {12130000, 77498.5840269416}, + {12140000, 77482.6492976922}, {12150000, 77466.7299118046}, + {12160000, 77450.8381461905}, {12170000, 77434.9749959431}, + {12180000, 77419.1410716381}, {12190000, 77403.3364226638}, + {12200000, 77387.5547867233}, {12210000, 77371.7889572834}, + {12220000, 77356.038589049}, {12230000, 77340.3015965426}, + {12240000, 77324.5773807418}, {12250000, 77308.8454796267}, + {12260000, 77293.0947102271}, {12270000, 77277.3502178656}, + {12280000, 77261.665228192}, {12290000, 77246.0415367643}, + {12300000, 77230.4317568118}, {12310000, 77214.8236218514}, + {12320000, 77199.2344107919}, {12330000, 77183.6840734366}, + {12340000, 77168.1735750157}, {12350000, 77152.7145959108}, + {12360000, 77137.3099084492}, {12370000, 77121.9306797999}, + {12380000, 77106.5610707249}, {12390000, 77091.1946393394}, + {12400000, 77075.8177768408}, {12410000, 77060.4296881965}, + {12420000, 77045.0368024504}, {12430000, 77029.6407945699}, + {12440000, 77014.2725170361}, {12450000, 76998.9675865461}, + {12460000, 76983.7250680228}, {12470000, 76968.522464929}, + {12480000, 76953.3541172118}, {12490000, 76938.2210828841}, + {12500000, 76923.1238618288}, {12510000, 76908.0480226842}, + {12520000, 76892.963158576}, {12530000, 76877.8657416658}, + {12540000, 76862.739667718}, {12550000, 76847.5808913805}, + {12560000, 76832.4251215009}, {12570000, 76817.3135579202}, + {12580000, 76802.2472151823}, {12590000, 76787.2394285848}, + {12600000, 76772.2940435889}, {12610000, 76757.3697512321}, + {12620000, 76742.4438634956}, {12630000, 76727.5267869267}, + {12640000, 76712.6406070469}, {12650000, 76697.7871995706}, + {12660000, 76682.9677308445}, {12670000, 76668.1823764099}, + {12680000, 76653.4188853794}, {12690000, 76638.6631412434}, + {12700000, 76623.9172069861}, {12710000, 76609.199569335}, + {12720000, 76594.5130362262}, {12730000, 76579.8408114302}, + {12740000, 76565.1736571547}, {12750000, 76550.5282130894}, + {12760000, 76535.9398360596}, {12770000, 76521.4075245508}, + {12780000, 76506.8613315038}, {12790000, 76492.2832616803}, + {12800000, 76477.7030394327}, {12810000, 76463.1549844537}, + {12820000, 76448.6404942841}, {12830000, 76434.1722714986}, + {12840000, 76419.7533584512}, {12850000, 76405.3428111888}, + {12860000, 76390.9181702595}, {12870000, 76376.4899093715}, + {12880000, 76362.0801863152}, {12890000, 76347.6905407747}, + {12900000, 76333.3149938411}, {12910000, 76318.9519508563}, + {12920000, 76304.6105060577}, {12930000, 76290.3011774486}, + {12940000, 76276.022977295}, {12950000, 76261.7664463853}, + {12960000, 76247.529806918}, {12970000, 76233.3018143172}, + {12980000, 76219.0762781984}, {12990000, 76204.8699714309}, + {13000000, 76190.7185188901}, {13010000, 76176.6221429446}, + {13020000, 76162.5324278773}, {13030000, 76148.4368577019}, + {13040000, 76134.3387501885}, {13050000, 76120.2419341914}, + {13060000, 76106.1486234203}, {13070000, 76092.0723435893}, + {13080000, 76078.0149106247}, {13090000, 76064.0076893615}, + {13100000, 76050.0677805752}, {13110000, 76036.1671566627}, + {13120000, 76022.2466290096}, {13130000, 76008.3036601687}, + {13140000, 75994.3850793667}, {13150000, 75980.5028785681}, + {13160000, 75966.643559637}, {13170000, 75952.7915551743}, + {13180000, 75938.9474543361}, {13190000, 75925.1319922242}, + {13200000, 75911.3506295859}, {13210000, 75897.594215769}, + {13220000, 75883.8576795593}, {13230000, 75870.1463452117}, + {13240000, 75856.4716406197}, {13250000, 75842.8320692109}, + {13260000, 75829.18507155}, {13270000, 75815.5196848882}, + {13280000, 75801.8659190211}, {13290000, 75788.2584629111}, + {13300000, 75774.6972867942}, {13310000, 75761.1572073872}, + {13320000, 75747.6306306032}, {13330000, 75734.1082046178}, + {13340000, 75720.58478114}, {13350000, 75707.0714234403}, + {13360000, 75693.5916390686}, {13370000, 75680.1450483515}, + {13380000, 75666.6898180844}, {13390000, 75653.2151775347}, + {13400000, 75639.7550028509}, {13410000, 75626.3484532798}, + {13420000, 75612.9951352872}, {13430000, 75599.6722862519}, + {13440000, 75586.3736548338}, {13450000, 75573.1007749237}, + {13460000, 75559.8544307271}, {13470000, 75546.620254381}, + {13480000, 75533.3678589362}, {13490000, 75520.0961365264}, + {13500000, 75506.8321182233}, {13510000, 75493.5827558415}, + {13520000, 75480.3704033084}, {13530000, 75467.2209228296}, + {13540000, 75454.132799759}, {13550000, 75441.0843626359}, + {13560000, 75428.070706988}, {13570000, 75415.0251515382}, + {13580000, 75401.9111247695}, {13590000, 75388.7671645244}, + {13600000, 75375.6748749291}, {13610000, 75362.6387320877}, + {13620000, 75349.6130319936}, {13630000, 75336.5859025574}, + {13640000, 75323.5667084798}, {13650000, 75310.5662780867}, + {13660000, 75297.5850573785}, {13670000, 75284.6317788194}, + {13680000, 75271.7088608108}, {13690000, 75258.8250712842}, + {13700000, 75245.9851345808}, {13710000, 75233.1747876124}, + {13720000, 75220.3639327597}, {13730000, 75207.5517928255}, + {13740000, 75194.7724578302}, {13750000, 75182.0346175618}, + {13760000, 75169.3086705212}, {13770000, 75156.5603903194}, + {13780000, 75143.7901677733}, {13790000, 75131.0357290657}, + {13800000, 75118.3080718763}, {13810000, 75105.5993290609}, + {13820000, 75092.9051352236}, {13830000, 75080.236543227}, + {13840000, 75067.6171506836}, {13850000, 75055.0461311633}, + {13860000, 75042.4744271377}, {13870000, 75029.8893617301}, + {13880000, 75017.3003982135}, {13890000, 75004.7184783095}, + {13900000, 74992.1434652157}, {13910000, 74979.567767987}, + {13920000, 74966.989351795}, {13930000, 74954.4484739687}, + {13940000, 74941.9671729242}, {13950000, 74929.5261197006}, + {13960000, 74917.0845276377}, {13970000, 74904.6398456063}, + {13980000, 74892.2112088742}, {13990000, 74879.8035170864}, + {14000000, 74867.4071886084}, {14010000, 74855.0111235517}, + {14020000, 74842.6163271346}, {14030000, 74830.2666642787}, + {14040000, 74817.9748177317}, {14050000, 74805.7124367083}, + {14060000, 74793.4638557696}, {14070000, 74781.2226685261}, + {14080000, 74768.975309064}, {14090000, 74756.7221434173}, + {14100000, 74744.4911285026}, {14110000, 74732.2894082814}, + {14120000, 74720.1075880568}, {14130000, 74707.9348183774}, + {14140000, 74695.770933746}, {14150000, 74683.652435692}, + {14160000, 74671.5910774941}, {14170000, 74659.5400041754}, + {14180000, 74647.4734113044}, {14190000, 74635.4101468003}, + {14200000, 74623.3902642106}, {14210000, 74611.4156578145}, + {14220000, 74599.4597868219}, {14230000, 74587.5157162836}, + {14240000, 74575.5828829913}, {14250000, 74563.6606441743}, + {14260000, 74551.7499302274}, {14270000, 74539.8569923437}, + {14280000, 74527.9826266174}, {14290000, 74516.1030906604}, + {14300000, 74504.2053319777}, {14310000, 74492.2973828033}, + {14320000, 74480.3962818345}, {14330000, 74468.5063010841}, + {14340000, 74456.678623554}, {14350000, 74444.9262715299}, + {14360000, 74433.2101134058}, {14370000, 74421.4848830941}, + {14380000, 74409.7511118791}, {14390000, 74398.0420332045}, + {14400000, 74386.3665072301}, {14410000, 74374.7214331294}, + {14420000, 74363.1050368117}, {14430000, 74351.5113872425}, + {14440000, 74339.9280150952}, {14450000, 74328.3537332601}, + {14460000, 74316.787755562}, {14470000, 74305.229847977}, + {14480000, 74293.6816958854}, {14490000, 74282.1452580929}, + {14500000, 74270.6206045422}, {14510000, 74259.1091624286}, + {14520000, 74247.6112527593}, {14530000, 74236.1416091513}, + {14540000, 74224.7082756191}, {14550000, 74213.2886617209}, + {14560000, 74201.8348609317}, {14570000, 74190.3469716047}, + {14580000, 74178.9012681451}, {14590000, 74167.5173261708}, + {14600000, 74156.1688929445}, {14610000, 74144.8256093533}, + {14620000, 74133.4880093027}, {14630000, 74122.1778046924}, + {14640000, 74110.9004028618}, {14650000, 74099.6397680798}, + {14660000, 74088.3870279687}, {14670000, 74077.1332498589}, + {14680000, 74065.859434389}, {14690000, 74054.567037342}, + {14700000, 74043.3124032353}, {14710000, 74032.1100201039}, + {14720000, 74020.9406443143}, {14730000, 74009.7820096458}, + {14740000, 73998.6347019815}, {14750000, 73987.5090650882}, + {14760000, 73976.4069068749}, {14770000, 73965.3295172638}, + {14780000, 73954.2775518208}, {14790000, 73943.2423796778}, + {14800000, 73932.2057443049}, {14810000, 73921.1671618125}, + {14820000, 73910.1471118624}, {14830000, 73899.1508239093}, + {14840000, 73888.179997747}, {14850000, 73877.2366234063}, + {14860000, 73866.3196401296}, {14870000, 73855.4007772958}, + {14880000, 73844.4719767054}, {14890000, 73833.5546608519}, + {14900000, 73822.6606071241}, {14910000, 73811.7815880025}, + {14920000, 73800.9001946228}, {14930000, 73790.0179792385}, + {14940000, 73779.1913272938}, {14950000, 73768.4346329444}, + {14960000, 73757.7054256043}, {14970000, 73746.954526688}, + {14980000, 73736.1820029905}, {14990000, 73725.4262769666}, + {15000000, 73714.6985199677}, {15010000, 73703.9900943794}, + {15020000, 73693.2961981873}, {15030000, 73682.6165088369}, + {15040000, 73671.9504204888}, {15050000, 73661.2982080714}, + {15060000, 73650.6669731652}, {15070000, 73640.0584787402}, + {15080000, 73629.462083016}, {15090000, 73618.8654676705}, + {15100000, 73608.2690152669}, {15110000, 73597.6872242462}, + {15120000, 73587.1239524928}, {15130000, 73576.5758703596}, + {15140000, 73566.041107187}, {15150000, 73555.5194746975}, + {15160000, 73545.0106467462}, {15170000, 73534.515315857}, + {15180000, 73524.0477377052}, {15190000, 73513.6115042258}, + {15200000, 73503.1903943786}, {15210000, 73492.765613436}, + {15220000, 73482.3391517241}, {15230000, 73471.9296161244}, + {15240000, 73461.5399018627}, {15250000, 73451.1713507694}, + {15260000, 73440.8246560784}, {15270000, 73430.4997272}, + {15280000, 73420.1964949793}, {15290000, 73409.9140714425}, + {15300000, 73399.6380070582}, {15310000, 73389.3645371294}, + {15320000, 73379.09775257}, {15330000, 73368.8423980791}, + {15340000, 73358.6007716869}, {15350000, 73348.3870487127}, + {15360000, 73338.2030891884}, {15370000, 73328.0435058189}, + {15380000, 73317.9052723638}, {15390000, 73307.7768073175}, + {15400000, 73297.6335149659}, {15410000, 73287.475944512}, + {15420000, 73277.3529523318}, {15430000, 73267.2770718187}, + {15440000, 73257.2198076002}, {15450000, 73247.1481365739}, + {15460000, 73237.0688057041}, {15470000, 73227.0296680716}, + {15480000, 73217.0372450202}, {15490000, 73207.0569425848}, + {15500000, 73197.0696489762}, {15510000, 73187.0859168194}, + {15520000, 73177.1282509363}, {15530000, 73167.1982075261}, + {15540000, 73157.2898476596}, {15550000, 73147.4015523063}, + {15560000, 73137.5262401592}, {15570000, 73127.6557116254}, + {15580000, 73117.7897674876}, {15590000, 73107.9287909992}, + {15600000, 73098.0728677089}, {15610000, 73088.2369520556}, + {15620000, 73078.4292496674}, {15630000, 73068.6413965192}, + {15640000, 73058.8556843233}, {15650000, 73049.071262539}, + {15660000, 73039.3014521774}, {15670000, 73029.5496514312}, + {15680000, 73019.8174152366}, {15690000, 73010.106562561}, + {15700000, 73000.416895292}, {15710000, 72990.7437619206}, + {15720000, 72981.0857499047}, {15730000, 72971.4388710988}, + {15740000, 72961.8008977381}, {15750000, 72952.1744595571}, + {15760000, 72942.5652254149}, {15770000, 72932.9736389653}, + {15780000, 72923.3999882117}, {15790000, 72913.8442816323}, + {15800000, 72904.2942481282}, {15810000, 72894.7356531416}, + {15820000, 72885.1706555235}, {15830000, 72875.6182116013}, + {15840000, 72866.0812962053}, {15850000, 72856.5552388821}, + {15860000, 72847.0374355683}, {15870000, 72837.5305399074}, + {15880000, 72828.0402681289}, {15890000, 72818.5674581847}, + {15900000, 72809.1195422948}, {15910000, 72799.6983563955}, + {15920000, 72790.296799734}, {15930000, 72780.9066489399}, + {15940000, 72771.5281388766}, {15950000, 72762.1710044468}, + {15960000, 72752.8377511759}, {15970000, 72743.5240484066}, + {15980000, 72734.227460495}, {15990000, 72724.9421129534}, + {16000000, 72715.65555296}, {16010000, 72706.3685903922}, + {16020000, 72697.1163545694}, {16030000, 72687.9078291007}, + {16040000, 72678.7162283121}, {16050000, 72669.5104844062}, + {16060000, 72660.2911896148}, {16070000, 72651.0860208806}, + {16080000, 72641.9024143873}, {16090000, 72632.7491243565}, + {16100000, 72623.6309322605}, {16110000, 72614.5336867191}, + {16120000, 72605.4273234677}, {16130000, 72596.3099067864}, + {16140000, 72587.1941035975}, {16150000, 72578.0831934317}, + {16160000, 72568.9909059028}, {16170000, 72559.9331881543}, + {16180000, 72550.9098427056}, {16190000, 72541.9042146916}, + {16200000, 72532.9112763409}, {16210000, 72523.9143572193}, + {16220000, 72514.9042453014}, {16230000, 72505.8947357317}, + {16240000, 72496.9152253441}, {16250000, 72487.9678810022}, + {16260000, 72479.0470726097}, {16270000, 72470.1512420128}, + {16280000, 72461.2690178733}, {16290000, 72452.3872162839}, + {16300000, 72443.5055246426}, {16310000, 72434.6240269582}, + {16320000, 72425.7427452337}, {16330000, 72416.8826636737}, + {16340000, 72408.0553422199}, {16350000, 72399.2525541073}, + {16360000, 72390.4568922504}, {16370000, 72381.6663402638}, + {16380000, 72372.8726792637}, {16390000, 72364.073787059}, + {16400000, 72355.291036562}, {16410000, 72346.5492832368}, + {16420000, 72337.8485348983}, {16430000, 72329.1581230162}, + {16440000, 72320.4683825616}, {16450000, 72311.7751959179}, + {16460000, 72303.076293159}, {16470000, 72294.3828471746}, + {16480000, 72285.7187447612}, {16490000, 72277.0848820966}, + {16500000, 72268.4610091782}, {16510000, 72259.8418322081}, + {16520000, 72251.2363236857}, {16530000, 72242.6549152108}, + {16540000, 72234.0976993226}, {16550000, 72225.553454995}, + {16560000, 72217.0184788573}, {16570000, 72208.4950196285}, + {16580000, 72199.984295623}, {16590000, 72191.4834191642}, + {16600000, 72182.9862872415}, {16610000, 72174.4927086353}, + {16620000, 72166.0094344544}, {16630000, 72157.5381793259}, + {16640000, 72149.0682994556}, {16650000, 72140.5874246187}, + {16660000, 72132.0972670357}, {16670000, 72123.6361424886}, + {16680000, 72115.2140405675}, {16690000, 72106.8145429651}, + {16700000, 72098.4285064404}, {16710000, 72090.058299422}, + {16720000, 72081.709063862}, {16730000, 72073.3815649936}, + {16740000, 72065.083189891}, {16750000, 72056.8157489078}, + {16760000, 72048.567815682}, {16770000, 72040.3261256093}, + {16780000, 72032.090022651}, {16790000, 72023.8532502415}, + {16800000, 72015.6141459936}, {16810000, 72007.3872186288}, + {16820000, 71999.1804768533}, {16830000, 71990.9912754116}, + {16840000, 71982.814066571}, {16850000, 71974.6478990069}, + {16860000, 71966.4851989856}, {16870000, 71958.3239858275}, + {16880000, 71950.1812990645}, {16890000, 71942.0769594335}, + {16900000, 71934.0101861298}, {16910000, 71925.942375488}, + {16920000, 71917.8621761164}, {16930000, 71909.7898056385}, + {16940000, 71901.7364442426}, {16950000, 71893.69391561}, + {16960000, 71885.6448241164}, {16970000, 71877.5887623767}, + {16980000, 71869.5462473467}, {16990000, 71861.5225600751}, + {17000000, 71853.5189708988}, {17010000, 71845.5369731959}, + {17020000, 71837.5763761724}, {17030000, 71829.6344058502}, + {17040000, 71821.710243523}, {17050000, 71813.8111012694}, + {17060000, 71805.9409181604}, {17070000, 71798.0883853337}, + {17080000, 71790.2294328325}, {17090000, 71782.3626537471}, + {17100000, 71774.5010452916}, {17110000, 71766.6479655087}, + {17120000, 71758.808582449}, {17130000, 71750.9889195019}, + {17140000, 71743.1876050144}, {17150000, 71735.3876665524}, + {17160000, 71727.5853671284}, {17170000, 71719.7938478301}, + {17180000, 71712.0203725389}, {17190000, 71704.2622976828}, + {17200000, 71696.5140668942}, {17210000, 71688.775897829}, + {17220000, 71681.0617406535}, {17230000, 71673.3751315863}, + {17240000, 71665.700787691}, {17250000, 71658.0209557583}, + {17260000, 71650.336197736}, {17270000, 71642.6626091844}, + {17280000, 71635.0042031683}, {17290000, 71627.3689851854}, + {17300000, 71619.7613436689}, {17310000, 71612.1784818047}, + {17320000, 71604.6145637039}, {17330000, 71597.0689658611}, + {17340000, 71589.5412265014}, {17350000, 71582.0311597454}, + {17360000, 71574.5239904274}, {17370000, 71567.0025334848}, + {17380000, 71559.4671627864}, {17390000, 71551.9469369316}, + {17400000, 71544.4504672545}, {17410000, 71536.9739446687}, + {17420000, 71529.5152100368}, {17430000, 71522.0769039537}, + {17440000, 71514.6647872746}, {17450000, 71507.2781246371}, + {17460000, 71499.8956041921}, {17470000, 71492.5116536776}, + {17480000, 71485.1261208183}, {17490000, 71477.73882668}, + {17500000, 71470.3524766202}, {17510000, 71462.9878739289}, + {17520000, 71455.6482499094}, {17530000, 71448.3224802162}, + {17540000, 71441.0043650111}, {17550000, 71433.6992577253}, + {17560000, 71426.4186750112}, {17570000, 71419.1635632562}, + {17580000, 71411.9344742832}, {17590000, 71404.7314557332}, + {17600000, 71397.5419935466}, {17610000, 71390.3515419272}, + {17620000, 71383.161340901}, {17630000, 71375.9836635028}, + {17640000, 71368.8204254967}, {17650000, 71361.6603677839}, + {17660000, 71354.497239361}, {17670000, 71347.3392536637}, + {17680000, 71340.2040134536}, {17690000, 71333.0918781169}, + {17700000, 71325.9822648293}, {17710000, 71318.8698115059}, + {17720000, 71311.7587504762}, {17730000, 71304.6540062568}, + {17740000, 71297.5571875621}, {17750000, 71290.481838373}, + {17760000, 71283.4303540378}, {17770000, 71276.3914203875}, + {17780000, 71269.3587270419}, {17790000, 71262.337635476}, + {17800000, 71255.3396835268}, {17810000, 71248.3654421932}, + {17820000, 71241.4082742064}, {17830000, 71234.4663875745}, + {17840000, 71227.5283475784}, {17850000, 71220.5808338233}, + {17860000, 71213.6248066263}, {17870000, 71206.6842306155}, + {17880000, 71199.7653416835}, {17890000, 71192.8698902041}, + {17900000, 71185.9987964953}, {17910000, 71179.1434961382}, + {17920000, 71172.2857555292}, {17930000, 71165.424679383}, + {17940000, 71158.5735800012}, {17950000, 71151.7358857009}, + {17960000, 71144.9087230346}, {17970000, 71138.0887555763}, + {17980000, 71131.2760258567}, {17990000, 71124.4739892988}, + {18000000, 71117.6835434837}, {18010000, 71110.9062006074}, + {18020000, 71104.1427715071}, {18030000, 71097.3932013378}, + {18040000, 71090.6574522648}, {18050000, 71083.935456826}, + {18060000, 71077.2271217745}, {18070000, 71070.5323725306}, + {18080000, 71063.8441461763}, {18090000, 71057.1542253699}, + {18100000, 71050.4629530566}, {18110000, 71043.7874527065}, + {18120000, 71037.1326299875}, {18130000, 71030.5000588821}, + {18140000, 71023.8905655946}, {18150000, 71017.2984084116}, + {18160000, 71010.7114019693}, {18170000, 71004.1291647249}, + {18180000, 70997.5653133903}, {18190000, 70991.0233339608}, + {18200000, 70984.4919890351}, {18210000, 70977.9582046922}, + {18220000, 70971.422194178}, {18230000, 70964.8935919685}, + {18240000, 70958.3748733744}, {18250000, 70951.8798707659}, + {18260000, 70945.4162230513}, {18270000, 70938.9756093875}, + {18280000, 70932.5403405983}, {18290000, 70926.1087648378}, + {18300000, 70919.6798143571}, {18310000, 70913.2532013221}, + {18320000, 70906.8338776996}, {18330000, 70900.4276197147}, + {18340000, 70894.0352230755}, {18350000, 70887.6700707185}, + {18360000, 70881.335548847}, {18370000, 70875.0079841606}, + {18380000, 70868.6741984881}, {18390000, 70862.3421393623}, + {18400000, 70856.0288387344}, {18410000, 70849.7346239676}, + {18420000, 70843.4388503631}, {18430000, 70837.1361500522}, + {18440000, 70830.8352174623}, {18450000, 70824.5461848037}, + {18460000, 70818.269136787}, {18470000, 70812.0022512866}, + {18480000, 70805.745030625}, {18490000, 70799.504602468}, + {18500000, 70793.2848929994}, {18510000, 70787.0802934668}, + {18520000, 70780.8788655674}, {18530000, 70774.6798773852}, + {18540000, 70768.4897829086}, {18550000, 70762.3102322669}, + {18560000, 70756.1461143804}, {18570000, 70750.0031389588}, + {18580000, 70743.8809134033}, {18590000, 70737.7621784103}, + {18600000, 70731.6417796822}, {18610000, 70725.5454933989}, + {18620000, 70719.4876174028}, {18630000, 70713.4572228054}, + {18640000, 70707.4310600833}, {18650000, 70701.4069719689}, + {18660000, 70695.3835900376}, {18670000, 70689.3605551892}, + {18680000, 70683.346546948}, {18690000, 70677.3516863513}, + {18700000, 70671.3732533539}, {18710000, 70665.3888529946}, + {18720000, 70659.3949040573}, {18730000, 70653.4215250721}, + {18740000, 70647.4854392547}, {18750000, 70641.5787043758}, + {18760000, 70635.68446111}, {18770000, 70629.8007162184}, + {18780000, 70623.9192252176}, {18790000, 70618.0378319659}, + {18800000, 70612.1612954475}, {18810000, 70606.29516956}, + {18820000, 70600.4398366575}, {18830000, 70594.6008359332}, + {18840000, 70588.7795528951}, {18850000, 70582.9768174082}, + {18860000, 70577.1930520933}, {18870000, 70571.419718854}, + {18880000, 70565.6385718463}, {18890000, 70559.8491117376}, + {18900000, 70554.071820137}, {18910000, 70548.3119927919}, + {18920000, 70542.5661232688}, {18930000, 70536.8301377961}, + {18940000, 70531.1046793379}, {18950000, 70525.3960077654}, + {18960000, 70519.7050907575}, {18970000, 70514.0262819029}, + {18980000, 70508.3564109792}, {18990000, 70502.6981156446}, + {19000000, 70497.0571177845}, {19010000, 70491.4334837598}, + {19020000, 70485.8202885254}, {19030000, 70480.2156879708}, + {19040000, 70474.6153332632}, {19050000, 70469.0141566148}, + {19060000, 70463.4118842033}, {19070000, 70457.8075233094}, + {19080000, 70452.2009436346}, {19090000, 70446.610544445}, + {19100000, 70441.0465339332}, {19110000, 70435.5035712821}, + {19120000, 70429.9703268488}, {19130000, 70424.4457129098}, + {19140000, 70418.9290074899}, {19150000, 70413.4199932282}, + {19160000, 70407.9155249704}, {19170000, 70402.4119388668}, + {19180000, 70396.9099996237}, {19190000, 70391.4365509635}, + {19200000, 70385.9992429244}, {19210000, 70380.5803870179}, + {19220000, 70375.1700819129}, {19230000, 70369.7622496658}, + {19240000, 70364.3438596889}, {19250000, 70358.9156696722}, + {19260000, 70353.5128620389}, {19270000, 70348.1445171069}, + {19280000, 70342.7916474975}, {19290000, 70337.4321059402}, + {19300000, 70332.0660452992}, {19310000, 70326.7175533965}, + {19320000, 70321.3936594027}, {19330000, 70316.0894747237}, + {19340000, 70310.8022308726}, {19350000, 70305.5260846691}, + {19360000, 70300.2485591601}, {19370000, 70294.9692767923}, + {19380000, 70289.7019024917}, {19390000, 70284.4499555295}, + {19400000, 70279.2062407962}, {19410000, 70273.9623678105}, + {19420000, 70268.7189801749}, {19430000, 70263.4949925158}, + {19440000, 70258.2954732256}, {19450000, 70253.1152401707}, + {19460000, 70247.9513621511}, {19470000, 70242.8008109548}, + {19480000, 70237.6571641504}, {19490000, 70232.5197991298}, + {19500000, 70227.3883142241}, {19510000, 70222.2625829718}, + {19520000, 70217.1511640037}, {19530000, 70212.0640586488}, + {19540000, 70206.9996270407}, {19550000, 70201.9352628788}, + {19560000, 70196.8658289012}, {19570000, 70191.7977814788}, + {19580000, 70186.7347168264}, {19590000, 70181.6795518944}, + {19600000, 70176.6385928092}, {19610000, 70171.6123559493}, + {19620000, 70166.6011380677}, {19630000, 70161.6049613496}, + {19640000, 70156.6202702486}, {19650000, 70151.6429249105}, + {19660000, 70146.6729269433}, {19670000, 70141.7148081393}, + {19680000, 70136.7698438141}, {19690000, 70131.8329637174}, + {19700000, 70126.9013235893}, {19710000, 70121.9775843494}, + {19720000, 70117.0675086596}, {19730000, 70112.1715654291}, + {19740000, 70107.2900172097}, {19750000, 70102.4228796331}, + {19760000, 70097.5627132983}, {19770000, 70092.7008343653}, + {19780000, 70087.8375360138}, {19790000, 70082.9913772857}, + {19800000, 70078.1677800497}, {19810000, 70073.3555336959}, + {19820000, 70068.5483556035}, {19830000, 70063.7487704486}, + {19840000, 70058.9622406634}, {19850000, 70054.1892114614}, + {19860000, 70049.4299611996}, {19870000, 70044.6845118249}, + {19880000, 70039.9452823146}, {19890000, 70035.2034300426}, + {19900000, 70030.4592671867}, {19910000, 70025.7238412679}, + {19920000, 70021.0000931272}, {19930000, 70016.2892275961}, + {19940000, 70011.5918890056}, {19950000, 70006.9080196216}, + {19960000, 70002.2375732795}, {19970000, 69997.5804849048}, + {19980000, 69992.9366877164}, {19990000, 69988.3061153825}, + {20000000, 69983.6852440269}, {20010000, 69979.0699658618}, + {20020000, 69974.4602754998}, {20030000, 69969.8606433141}, + {20040000, 69965.2723513474}, {20050000, 69960.6903457861}, + {20060000, 69956.1117918248}, {20070000, 69951.5421686128}, + {20080000, 69946.993299727}, {20090000, 69942.4650441013}, + {20100000, 69937.9364891343}, {20110000, 69933.4021734394}, + {20120000, 69928.8705930188}, {20130000, 69924.3516743387}, + {20140000, 69919.8455985236}, {20150000, 69915.351084505}, + {20160000, 69910.8676742488}, {20170000, 69906.4022327189}, + {20180000, 69901.9585593476}, {20190000, 69897.5310635957}, + {20200000, 69893.1078112821}, {20210000, 69888.6884405406}, + {20220000, 69884.2865857485}, {20230000, 69879.9057438534}, + {20240000, 69875.5335518406}, {20250000, 69871.1555602183}, + {20260000, 69866.7745411642}, {20270000, 69862.4110380659}, + {20280000, 69858.0678658299}, {20290000, 69853.7397364235}, + {20300000, 69849.4236651276}, {20310000, 69845.116668423}, + {20320000, 69840.8123799179}, {20330000, 69836.510957605}, + {20340000, 69832.226349377}, {20350000, 69827.962136655}, + {20360000, 69823.7029203217}, {20370000, 69819.4306973369}, + {20380000, 69815.1465528468}, {20390000, 69810.883162498}, + {20400000, 69806.6493208378}, {20410000, 69802.4337763635}, + {20420000, 69798.2301975891}, {20430000, 69794.0382829706}, + {20440000, 69789.8574513559}, {20450000, 69785.6868425127}, + {20460000, 69781.5120022473}, {20470000, 69777.3291661893}, + {20480000, 69773.1508472783}, {20490000, 69768.9916818336}, + {20500000, 69764.8511709338}, {20510000, 69760.7144953489}, + {20520000, 69756.5777599408}, {20530000, 69752.4536092514}, + {20540000, 69748.349086247}, {20550000, 69744.2587398777}, + {20560000, 69740.1709244719}, {20570000, 69736.0853014842}, + {20580000, 69732.0155153234}, {20590000, 69727.9650853503}, + {20600000, 69723.9303732701}, {20610000, 69719.9071382743}, + {20620000, 69715.8947281648}, {20630000, 69711.8837157385}, + {20640000, 69707.8716269461}, {20650000, 69703.8653011352}, + {20660000, 69699.86855008}, {20670000, 69695.8842721207}, + {20680000, 69691.9187752973}, {20690000, 69687.9718009443}, + {20700000, 69684.0292730637}, {20710000, 69680.0874942816}, + {20720000, 69676.1587438664}, {20730000, 69672.2573923261}, + {20740000, 69668.3812961941}, {20750000, 69664.5092083569}, + {20760000, 69660.6372240603}, {20770000, 69656.7710089066}, + {20780000, 69652.913718332}, {20790000, 69649.0654239275}, + {20800000, 69645.2263318695}, {20810000, 69641.3964207177}, + {20820000, 69637.5756818071}, {20830000, 69633.764079148}, + {20840000, 69629.9619610402}, {20850000, 69626.1697430677}, + {20860000, 69622.3875968015}, {20870000, 69618.621910574}, + {20880000, 69614.8744662014}, {20890000, 69611.1394610124}, + {20900000, 69607.4136189641}, {20910000, 69603.6883490223}, + {20920000, 69599.9451517501}, {20930000, 69596.1846252453}, + {20940000, 69592.4487401146}, {20950000, 69588.7484297242}, + {20960000, 69585.0684280039}, {20970000, 69581.3908861962}, + {20980000, 69577.7156535083}, {20990000, 69574.0543104961}, + {21000000, 69570.4102345211}, {21010000, 69566.7778976757}, + {21020000, 69563.1541792839}, {21030000, 69559.536107176}, + {21040000, 69555.9173128984}, {21050000, 69552.2979634559}, + {21060000, 69548.6920196741}, {21070000, 69545.1030863828}, + {21080000, 69541.5236240302}, {21090000, 69537.9448170443}, + {21100000, 69534.3666596382}, {21110000, 69530.7937351168}, + {21120000, 69527.2272534677}, {21130000, 69523.6801710367}, + {21140000, 69520.1597092859}, {21150000, 69516.6575961391}, + {21160000, 69513.1561039699}, {21170000, 69509.6539685508}, + {21180000, 69506.157341043}, {21190000, 69502.6678112055}, + {21200000, 69499.1898028816}, {21210000, 69495.7285036312}, + {21220000, 69492.2830475545}, {21230000, 69488.8462180099}, + {21240000, 69485.416810546}, {21250000, 69481.9946620341}, + {21260000, 69478.5796653067}, {21270000, 69475.1745855169}, + {21280000, 69471.7854546649}, {21290000, 69468.4123856939}, + {21300000, 69465.0484716702}, {21310000, 69461.6918664114}, + {21320000, 69458.3466081078}, {21330000, 69455.0174328174}, + {21340000, 69451.7033083387}, {21350000, 69448.397118192}, + {21360000, 69445.0978286024}, {21370000, 69441.805214414}, + {21380000, 69438.5191348629}, {21390000, 69435.2423539204}, + {21400000, 69431.9808847557}, {21410000, 69428.7340885134}, + {21420000, 69425.4807272518}, {21430000, 69422.2152614165}, + {21440000, 69418.9499562455}, {21450000, 69415.6991783589}, + {21460000, 69412.4633743257}, {21470000, 69409.2434838067}, + {21480000, 69406.0395704822}, {21490000, 69402.8455633928}, + {21500000, 69399.6580374142}, {21510000, 69396.4796312193}, + {21520000, 69393.3160867966}, {21530000, 69390.1674922435}, + {21540000, 69387.0269361213}, {21550000, 69383.8925783128}, + {21560000, 69380.7606340968}, {21570000, 69377.6266724994}, + {21580000, 69374.4908028323}, {21590000, 69371.3578444977}, + {21600000, 69368.2291029441}, {21610000, 69365.1296103433}, + {21620000, 69362.0733551471}, {21630000, 69359.0466662495}, + {21640000, 69356.0202106764}, {21650000, 69352.9920220607}, + {21660000, 69349.9747331272}, {21670000, 69346.971616111}, + {21680000, 69343.975096747}, {21690000, 69340.9763090026}, + {21700000, 69337.975684852}, {21710000, 69334.9857047968}, + {21720000, 69332.0096097531}, {21730000, 69329.0419249955}, + {21740000, 69326.0795589572}, {21750000, 69323.1279723749}, + {21760000, 69320.1990011992}, {21770000, 69317.2925123867}, + {21780000, 69314.3875869945}, {21790000, 69311.4787391684}, + {21800000, 69308.5739223368}, {21810000, 69305.6824560451}, + {21820000, 69302.8045948135}, {21830000, 69299.9409301379}, + {21840000, 69297.0914980632}, {21850000, 69294.24417769}, + {21860000, 69291.3921602545}, {21870000, 69288.5436207531}, + {21880000, 69285.7162229714}, {21890000, 69282.9107547445}, + {21900000, 69280.1137541891}, {21910000, 69277.3216605257}, + {21920000, 69274.5344382828}, {21930000, 69271.7520502062}, + {21940000, 69268.9740807388}, {21950000, 69266.1912505367}, + {21960000, 69263.401023401}, {21970000, 69260.6164159024}, + {21980000, 69257.8447227922}, {21990000, 69255.0889566476}, + {22000000, 69252.3557191347}, {22010000, 69249.6447721646}, + {22020000, 69246.942058977}, {22030000, 69244.2438636762}, + {22040000, 69241.538224781}, {22050000, 69238.811113389}, + {22060000, 69236.0645437541}, {22070000, 69233.3395281502}, + {22080000, 69230.6465650887}, {22090000, 69227.9802614224}, + {22100000, 69225.3375317113}, {22110000, 69222.7125582808}, + {22120000, 69220.0928758764}, {22130000, 69217.4776804954}, + {22140000, 69214.8733924507}, {22150000, 69212.2816550685}, + {22160000, 69209.6948247522}, {22170000, 69207.1039453735}, + {22180000, 69204.5093597278}, {22190000, 69201.931213239}, + {22200000, 69199.375389439}, {22210000, 69196.82393525}, + {22220000, 69194.2667630555}, {22230000, 69191.7119080797}, + {22240000, 69189.1767256797}, {22250000, 69186.6623596395}, + {22260000, 69184.1625854208}, {22270000, 69181.6757173643}, + {22280000, 69179.1936563766}, {22290000, 69176.7069122678}, + {22300000, 69174.2158071162}, {22310000, 69171.7327031102}, + {22320000, 69169.2609497614}, {22330000, 69166.8071469071}, + {22340000, 69164.3749652932}, {22350000, 69161.9616520439}, + {22360000, 69159.5613638423}, {22370000, 69157.17350078}, + {22380000, 69154.7976675644}, {22390000, 69152.4337162853}, + {22400000, 69150.0776908044}, {22410000, 69147.7249566312}, + {22420000, 69145.3753314585}, {22430000, 69143.0269496395}, + {22440000, 69140.6792540139}, {22450000, 69138.3450089531}, + {22460000, 69136.0313506121}, {22470000, 69133.7356496689}, + {22480000, 69131.4523304242}, {22490000, 69129.1804479098}, + {22500000, 69126.9124668354}, {22510000, 69124.646397134}, + {22520000, 69122.3862896881}, {22530000, 69120.1368985922}, + {22540000, 69117.8979081203}, {22550000, 69115.6617584739}, + {22560000, 69113.4264472614}, {22570000, 69111.192232844}, + {22580000, 69108.9592580637}, {22590000, 69106.7359125816}, + {22600000, 69104.5403783712}, {22610000, 69102.3734676349}, + {22620000, 69100.2217722345}, {22630000, 69098.0817176431}, + {22640000, 69095.9528544719}, {22650000, 69093.8346654704}, + {22660000, 69091.7267427421}, {22670000, 69089.6211580192}, + {22680000, 69087.5157343106}, {22690000, 69085.4167777237}, + {22700000, 69083.3278188215}, {22710000, 69081.2489379861}, + {22720000, 69079.1803677574}, {22730000, 69077.1217129043}, + {22740000, 69075.0657907775}, {22750000, 69073.0107047808}, + {22760000, 69070.9565919246}, {22770000, 69068.903613827}, + {22780000, 69066.852394011}, {22790000, 69064.8172805317}, + {22800000, 69062.8021396137}, {22810000, 69060.8008882178}, + {22820000, 69058.8100725927}, {22830000, 69056.832310273}, + {22840000, 69054.8733387132}, {22850000, 69052.932862293}, + {22860000, 69050.9967958354}, {22870000, 69049.0614235981}, + {22880000, 69047.1306165757}, {22890000, 69045.208924309}, + {22900000, 69043.2960063793}, {22910000, 69041.3762205946}, + {22920000, 69039.4449597376}, {22930000, 69037.5452489149}, + {22940000, 69035.7012352046}, {22950000, 69033.8940112831}, + {22960000, 69032.0829008414}, {22970000, 69030.2645256313}, + {22980000, 69028.4436999307}, {22990000, 69026.6216961336}, + {23000000, 69024.7951530238}, {23010000, 69022.960119681}, + {23020000, 69021.1175403271}, {23030000, 69019.2958279435}, + {23040000, 69017.5029852516}, {23050000, 69015.7207930759}, + {23060000, 69013.9389476028}, {23070000, 69012.159852286}, + {23080000, 69010.3887212721}, {23090000, 69008.6219192848}, + {23100000, 69006.7808720006}, {23110000, 69004.845213968}, + {23120000, 69002.893281313}, {23130000, 69001.0170440793}, + {23140000, 68999.2178518326}, {23150000, 68997.4903405508}, + {23160000, 68995.8333313844}, {23170000, 68994.1907992198}, + {23180000, 68992.5311805927}, {23190000, 68990.858887924}, + {23200000, 68989.1833899538}, {23210000, 68987.5063204584}, + {23220000, 68985.842580807}, {23230000, 68984.1960359978}, + {23240000, 68982.5627660116}, {23250000, 68980.9381797679}, + {23260000, 68979.3216403743}, {23270000, 68977.7049964431}, + {23280000, 68976.0861837685}, {23290000, 68974.483499182}, + {23300000, 68972.9072190357}, {23310000, 68971.3520260343}, + {23320000, 68969.8065318833}, {23330000, 68968.2692652759}, + {23340000, 68966.732339088}, {23350000, 68965.1936804711}, + {23360000, 68963.6535243179}, {23370000, 68962.1121455441}, + {23380000, 68960.5698477715}, {23390000, 68959.0569187962}, + {23400000, 68957.5828989409}, {23410000, 68956.1224399837}, + {23420000, 68954.6612275327}, {23430000, 68953.2043300313}, + {23440000, 68951.762734468}, {23450000, 68950.3366473638}, + {23460000, 68948.9123079142}, {23470000, 68947.4860953486}, + {23480000, 68946.0618853931}, {23490000, 68944.6442346247}, + {23500000, 68943.2332667503}, {23510000, 68941.8292528854}, + {23520000, 68940.4322082233}, {23530000, 68939.0360972102}, + {23540000, 68937.6375164734}, {23550000, 68936.2475236555}, + {23560000, 68934.8901089544}, {23570000, 68933.5669796288}, + {23580000, 68932.2722271198}, {23590000, 68931.0041940194}, + {23600000, 68929.7706431956}, {23610000, 68928.5807287445}, + {23620000, 68927.4232394396}, {23630000, 68926.210232904}, + {23640000, 68924.9276830096}, {23650000, 68923.6338877601}, + {23660000, 68922.3617254843}, {23670000, 68921.1096101459}, + {23680000, 68919.8742255376}, {23690000, 68918.6537094312}, + {23700000, 68917.4191269282}, {23710000, 68916.1629231026}, + {23720000, 68914.9013718209}, {23730000, 68913.6535933613}, + {23740000, 68912.4202538943}, {23750000, 68911.2027601396}, + {23760000, 68910.0012389239}, {23770000, 68908.7855375024}, + {23780000, 68907.5386717304}, {23790000, 68906.2517063423}, + {23800000, 68904.9050405926}, {23810000, 68903.501933942}, + {23820000, 68902.1346926251}, {23830000, 68900.8274509351}, + {23840000, 68899.5335013686}, {23850000, 68898.1979196599}, + {23860000, 68896.8223857969}, {23870000, 68895.4738103903}, + {23880000, 68894.1704127226}, {23890000, 68892.8945598469}, + {23900000, 68891.6362550938}, {23910000, 68890.3950546122}, + {23920000, 68889.1700969607}, {23930000, 68887.9604971074}, + {23940000, 68886.7518056523}, {23950000, 68885.5402108055}, + {23960000, 68884.3178243271}, {23970000, 68883.0753584434}, + {23980000, 68881.8158866884}, {23990000, 68880.6133573826}, + {24000000, 68879.4877909025}, {24010000, 68878.3895516081}, + {24020000, 68877.2905718214}, {24030000, 68876.1981968349}, + {24040000, 68875.1283846819}, {24050000, 68874.0795648415}, + {24060000, 68872.9952254571}, {24070000, 68871.8606277803}, + {24080000, 68870.6845484711}, {24090000, 68869.4772978709}, + {24100000, 68868.2399576949}, {24110000, 68866.9987379902}, + {24120000, 68865.7614489712}, {24130000, 68864.4933149919}, + {24140000, 68863.1747792499}, {24150000, 68861.8192659069}, + {24160000, 68860.4556514504}, {24170000, 68859.0844395545}, + {24180000, 68857.6643469157}, {24190000, 68856.1846906479}, + {24200000, 68854.7257996495}, {24210000, 68853.3821738574}, + {24220000, 68852.1508626807}, {24230000, 68850.9444183161}, + {24240000, 68849.7402137611}, {24250000, 68848.4863753611}, + {24260000, 68847.1537004915}, {24270000, 68845.7832829126}, + {24280000, 68844.46405489}, {24290000, 68843.2018284221}, + {24300000, 68841.9585093735}, {24310000, 68840.7240052811}, + {24320000, 68839.5050419569}, {24330000, 68838.3095442652}, + {24340000, 68837.13776887}, {24350000, 68835.9926164197}, + {24360000, 68834.8747373989}, {24370000, 68833.831081461}, + {24380000, 68832.8879813709}, {24390000, 68832.034854373}, + {24400000, 68831.2492934699}, {24410000, 68830.527093456}, + {24420000, 68829.8308493569}, {24430000, 68829.1505985583}, + {24440000, 68828.4886670073}, {24450000, 68827.8478094255}, + {24460000, 68827.2268672484}, {24470000, 68826.5972923005}, + {24480000, 68825.9511603241}, {24490000, 68825.3065638522}, + {24500000, 68824.6737222011}, {24510000, 68824.0445870124}, + {24520000, 68823.4017188885}, {24530000, 68822.7424589473}, + {24540000, 68822.0443553962}, {24550000, 68821.301638171}, + {24560000, 68820.5082486902}, {24570000, 68819.6570149684}, + {24580000, 68818.7472393589}, {24590000, 68817.7436433964}, + {24600000, 68816.635917009}, {24610000, 68815.5151573905}, + {24620000, 68814.4328642823}, {24630000, 68813.3767939175}, + {24640000, 68812.3205373629}, {24650000, 68811.2612781974}, + {24660000, 68810.1903457289}, {24670000, 68809.105499403}, + {24680000, 68808.0109380363}, {24690000, 68806.9115954097}, + {24700000, 68805.8114406395}, {24710000, 68804.740430688}, + {24720000, 68803.7033206512}, {24730000, 68802.742778665}, + {24740000, 68801.8827796131}, {24750000, 68801.0958877147}, + {24760000, 68800.3230104102}, {24770000, 68799.5622492169}, + {24780000, 68798.8817825059}, {24790000, 68798.2993015237}, + {24800000, 68797.7618333641}, {24810000, 68797.2069072476}, + {24820000, 68796.6361551397}, {24830000, 68796.112162832}, + {24840000, 68795.6512643547}, {24850000, 68795.2283713561}, + {24860000, 68794.8292265245}, {24870000, 68794.456008304}, + {24880000, 68794.113600797}, {24890000, 68793.8008535497}, + {24900000, 68793.4892306253}, {24910000, 68793.1712066232}, + {24920000, 68792.8460962816}, {24930000, 68792.5130857693}, + {24940000, 68792.1711997164}, {24950000, 68791.8123912242}, + {24960000, 68791.4353694627}, {24970000, 68791.0824448062}, + {24980000, 68790.7775026337}, {24990000, 68790.5101009662}, + {25000000, 68790.2577832451}, {25010000, 68790.0180292475}, + {25020000, 68789.7823007315}, {25030000, 68789.5483324953}, + {25040000, 68789.3074537739}, {25050000, 68789.0494429398}, + {25060000, 68788.7784171783}, {25070000, 68788.522873487}, + {25080000, 68788.2867543472}, {25090000, 68788.0770018887}, + {25100000, 68787.8974869109}, {25110000, 68787.7370642221}, + {25120000, 68787.5716411973}, {25130000, 68787.4000901551}, + {25140000, 68787.2425344595}, {25150000, 68787.1042406394}, + {25160000, 68786.9849762196}, {25170000, 68786.8844843789}, + {25180000, 68786.8034548104}, {25190000, 68786.7602543277}, + {25200000, 68786.759791147}, {25210000, 68786.7880232067}, + {25220000, 68786.8369444236}, {25230000, 68786.8866324142}, + {25240000, 68786.8938240587}, {25250000, 68786.8579893132}, + {25260000, 68786.8413499531}, {25270000, 68786.8602355286}, + {25280000, 68786.8991928996}, {25290000, 68786.940034689}, + {25300000, 68786.9814451224}, {25310000, 68786.9905508865}, + {25320000, 68786.9576861752}, {25330000, 68786.8965644146}, + {25340000, 68786.8150147915}, {25350000, 68786.7301157593}, + {25360000, 68786.6789775624}, {25370000, 68786.6627080406}, + {25380000, 68786.6402987297}, {25390000, 68786.6009540473}, + {25400000, 68786.5638349276}, {25410000, 68786.5515362118}, + {25420000, 68786.5623937769}, {25430000, 68786.5468864267}, + {25440000, 68786.4915416556}, {25450000, 68786.4508976549}, + {25460000, 68786.4558180768}, {25470000, 68786.4710212867}, + {25480000, 68786.4198627211}, {25490000, 68786.2944272947}, + {25500000, 68786.0690738185}, {25510000, 68785.7373983439}, + {25520000, 68785.3501775038}, {25530000, 68784.9672805171}, + {25540000, 68784.5898897166}, {25550000, 68784.2150649972}, + {25560000, 68783.8423103627}, {25570000, 68783.4654768747}, + {25580000, 68783.0810899951}, {25590000, 68782.7113668823}, + {25600000, 68782.4046962327}, {25610000, 68782.1627363543}, + {25620000, 68781.9378161357}, {25630000, 68781.7172974219}, + {25640000, 68781.5113085312}, {25650000, 68781.3318052399}, + {25660000, 68781.1789201355}, {25670000, 68781.050168518}, + {25680000, 68780.9447151751}, {25690000, 68780.9027655225}, + {25700000, 68780.9469590395}, {25710000, 68781.0499445775}, + {25720000, 68781.1526058335}, {25730000, 68781.2538260083}, + {25740000, 68781.436157489}, {25750000, 68781.7210804122}, + {25760000, 68782.0326356079}, {25770000, 68782.281283678}, + {25780000, 68782.4669014777}, {25790000, 68782.6746319339}, + {25800000, 68782.9300483785}, {25810000, 68783.2212850098}, + {25820000, 68783.5415430524}, {25830000, 68783.862597}, + {25840000, 68784.1230868557}, {25850000, 68784.3223102873}, + {25860000, 68784.5501647885}, {25870000, 68784.830281129}, + {25880000, 68785.1628549263}, {25890000, 68785.5481656892}, + {25900000, 68785.9846451243}, {25910000, 68786.4411043713}, + {25920000, 68786.9089046545}, {25930000, 68787.3736908428}, + {25940000, 68787.8273268322}, {25950000, 68788.2918647365}, + {25960000, 68788.8153625974}, {25970000, 68789.3976453462}, + {25980000, 68789.9551939861}, {25990000, 68790.4660667534}, + {26000000, 68790.9841527895}, {26010000, 68791.5730525583}, + {26020000, 68792.2317828041}, {26030000, 68792.8671480535}, + {26040000, 68793.4514423637}, {26050000, 68794.0501021323}, + {26060000, 68794.7002136158}, {26070000, 68795.3750993843}, + {26080000, 68796.0168462712}, {26090000, 68796.6220337939}, + {26100000, 68797.223276299}, {26110000, 68797.829199422}, + {26120000, 68798.4325460351}, {26130000, 68799.0247497199}, + {26140000, 68799.6051555894}, {26150000, 68800.1641841601}, + {26160000, 68800.6993785642}, {26170000, 68801.2476397958}, + {26180000, 68801.8298981602}, {26190000, 68802.4440453695}, + {26200000, 68803.085668479}, {26210000, 68803.7531481512}, + {26220000, 68804.4245936906}, {26230000, 68805.0942007309}, + {26240000, 68805.7697392851}, {26250000, 68806.4603841324}, + {26260000, 68807.15763596}, {26270000, 68807.803252991}, + {26280000, 68808.3892406401}, {26290000, 68808.9740875872}, + {26300000, 68809.5909724298}, {26310000, 68810.2327141499}, + {26320000, 68810.8838314109}, {26330000, 68811.542477539}, + {26340000, 68812.2005347342}, {26350000, 68812.8558618076}, + {26360000, 68813.504324518}, {26370000, 68814.1410377407}, + {26380000, 68814.7676231553}, {26390000, 68815.4216656917}, + {26400000, 68816.1132682134}, {26410000, 68816.8174440017}, + {26420000, 68817.519974694}, {26430000, 68818.2147770571}, + {26440000, 68818.8885520027}, {26450000, 68819.5412467674}, + {26460000, 68820.1936806629}, {26470000, 68820.8513515771}, + {26480000, 68821.5223905984}, {26490000, 68822.2164055041}, + {26500000, 68822.9324997016}, {26510000, 68823.6515314057}, + {26520000, 68824.3685307219}, {26530000, 68825.0945789109}, + {26540000, 68825.8359503118}, {26550000, 68826.5900409536}, + {26560000, 68827.3512473486}, {26570000, 68828.1186544917}, + {26580000, 68828.8847440389}, {26590000, 68829.6475322968}, + {26600000, 68830.4107411514}, {26610000, 68831.1787667818}, + {26620000, 68831.9542944621}, {26630000, 68832.7856996117}, + {26640000, 68833.6853680835}, {26650000, 68834.6029758618}, + {26660000, 68835.5099025345}, {26670000, 68836.402343685}, + {26680000, 68837.271924878}, {26690000, 68838.1208676272}, + {26700000, 68839.0061056102}, {26710000, 68839.9425511529}, + {26720000, 68840.8976939745}, {26730000, 68841.8331547763}, + {26740000, 68842.7558425466}, {26750000, 68843.713950953}, + {26760000, 68844.7140171807}, {26770000, 68845.7215414391}, + {26780000, 68846.7169132743}, {26790000, 68847.7021916078}, + {26800000, 68848.6818022245}, {26810000, 68849.6576326435}, + {26820000, 68850.658641387}, {26830000, 68851.692388797}, + {26840000, 68852.7347606204}, {26850000, 68853.7572844138}, + {26860000, 68854.7603729537}, {26870000, 68855.7867337645}, + {26880000, 68856.8490094731}, {26890000, 68857.916076278}, + {26900000, 68858.9702239421}, {26910000, 68860.013645694}, + {26920000, 68861.0510659678}, {26930000, 68862.0833133369}, + {26940000, 68863.1178525787}, {26950000, 68864.156649651}, + {26960000, 68865.1956303379}, {26970000, 68866.2299828994}, + {26980000, 68867.2601076746}, {26990000, 68868.3095598433}, + {27000000, 68869.3854014342}, {27010000, 68870.4682781901}, + {27020000, 68871.547182614}, {27030000, 68872.6217323805}, + {27040000, 68873.691067776}, {27050000, 68874.7558544402}, + {27060000, 68875.8303990668}, {27070000, 68876.9184498851}, + {27080000, 68878.0118292787}, {27090000, 68879.1008759348}, + {27100000, 68880.1853294994}, {27110000, 68881.2645981279}, + {27120000, 68882.3385375059}, {27130000, 68883.419144507}, + {27140000, 68884.5132274635}, {27150000, 68885.6154328345}, + {27160000, 68886.7141331667}, {27170000, 68887.8089831866}, + {27180000, 68888.9136572279}, {27190000, 68890.031736026}, + {27200000, 68891.159195187}, {27210000, 68892.2912864917}, + {27220000, 68893.42787166}, {27230000, 68894.569005486}, + {27240000, 68895.7146779832}, {27250000, 68896.858669824}, + {27260000, 68897.9974430961}, {27270000, 68899.1420153281}, + {27280000, 68900.3164748336}, {27290000, 68901.5218469898}, + {27300000, 68902.7378430355}, {27310000, 68903.9590579181}, + {27320000, 68905.1764540165}, {27330000, 68906.3793448786}, + {27340000, 68907.5684688657}, {27350000, 68908.7503079242}, + {27360000, 68909.9258082928}, {27370000, 68911.0892426943}, + {27380000, 68912.2373755608}, {27390000, 68913.3868608139}, + {27400000, 68914.57402765}, {27410000, 68915.7988411333}, + {27420000, 68916.9987468878}, {27430000, 68918.1572911864}, + {27440000, 68919.2982148032}, {27450000, 68920.4495638755}, + {27460000, 68921.6101927885}, {27470000, 68922.7676630743}, + {27480000, 68923.9202323059}, {27490000, 68925.0493825244}, + {27500000, 68926.1446189302}, {27510000, 68927.2446215223}, + {27520000, 68928.4338659408}, {27530000, 68929.7126256517}, + {27540000, 68930.9420103734}, {27550000, 68932.085434086}, + {27560000, 68933.2088597407}, {27570000, 68934.3903043825}, + {27580000, 68935.6305648019}, {27590000, 68936.9060457869}, + {27600000, 68938.210139276}, {27610000, 68939.5274596061}, + {27620000, 68940.84921744}, {27630000, 68942.1889978813}, + {27640000, 68943.5765676494}, {27650000, 68945.0116059452}, + {27660000, 68946.4382590754}, {27670000, 68947.8417722544}, + {27680000, 68949.2369931073}, {27690000, 68950.6414789463}, + {27700000, 68952.0546661684}, {27710000, 68953.4567532399}, + {27720000, 68954.8425298669}, {27730000, 68956.2237295646}, + {27740000, 68957.6070522063}, {27750000, 68958.9899654664}, + {27760000, 68960.3669382628}, {27770000, 68961.7374813505}, + {27780000, 68963.1012936641}, {27790000, 68964.4583201448}, + {27800000, 68965.8251179435}, {27810000, 68967.2212838103}, + {27820000, 68968.6438074894}, {27830000, 68970.0656482818}, + {27840000, 68971.4823514084}, {27850000, 68972.9047487788}, + {27860000, 68974.3389963051}, {27870000, 68975.7797385013}, + {27880000, 68977.2153095906}, {27890000, 68978.6446439981}, + {27900000, 68980.0670821567}, {27910000, 68981.4824747115}, + {27920000, 68982.8908348112}, {27930000, 68984.2921713836}, + {27940000, 68985.6868820038}, {27950000, 68987.0828325648}, + {27960000, 68988.4821405074}, {27970000, 68989.8965108998}, + {27980000, 68991.3325855731}, {27990000, 68992.7905488556}, + {28000000, 68994.2709362509}, {28010000, 68995.7726205469}, + {28020000, 68997.2740256215}, {28030000, 68998.7694359616}, + {28040000, 69000.2582430791}, {28050000, 69001.7397202632}, + {28060000, 69003.2142946329}, {28070000, 69004.6897485029}, + {28080000, 69006.1681096397}, {28090000, 69007.6371399554}, + {28100000, 69009.0898815002}, {28110000, 69010.5372545058}, + {28120000, 69012.0030933442}, {28130000, 69013.4888199784}, + {28140000, 69014.9814181868}, {28150000, 69016.4774171869}, + {28160000, 69017.9836992385}, {28170000, 69019.5084159255}, + {28180000, 69021.0516298803}, {28190000, 69022.6105805741}, + {28200000, 69024.1843874577}, {28210000, 69025.759239491}, + {28220000, 69027.3272597744}, {28230000, 69028.8854130859}, + {28240000, 69030.4270069995}, {28250000, 69031.9504171157}, + {28260000, 69033.4338535373}, {28270000, 69034.8716893731}, + {28280000, 69036.2688871669}, {28290000, 69037.6312841143}, + {28300000, 69038.9596526561}, {28310000, 69040.2660010868}, + {28320000, 69041.5537830572}, {28330000, 69042.8124143423}, + {28340000, 69044.0359142567}, {28350000, 69045.2380884315}, + {28360000, 69046.4489821204}, {28370000, 69047.6702856568}, + {28380000, 69048.88217698}, {28390000, 69050.0794341775}, + {28400000, 69051.2735358974}, {28410000, 69052.4780699665}, + {28420000, 69053.6938241129}, {28430000, 69054.9405986638}, + {28440000, 69056.2242121801}, {28450000, 69057.5363202291}, + {28460000, 69058.8720983053}, {28470000, 69060.2451955749}, + {28480000, 69061.6856970897}, {28490000, 69063.1943197952}, + {28500000, 69064.7366461619}, {28510000, 69066.3034261702}, + {28520000, 69067.8885817902}, {28530000, 69069.4849281051}, + {28540000, 69071.0911165474}, {28550000, 69072.6857666301}, + {28560000, 69074.2633017274}, {28570000, 69075.8233769725}, + {28580000, 69077.3658325938}, {28590000, 69078.8824001755}, + {28600000, 69080.3548351267}, {28610000, 69081.778766193}, + {28620000, 69083.0960478288}, {28630000, 69084.2916648104}, + {28640000, 69085.4311021932}, {28650000, 69086.591905734}, + {28660000, 69087.7780478164}, {28670000, 69089.055623901}, + {28680000, 69090.4435539437}, {28690000, 69091.8465699798}, + {28700000, 69093.2101094858}, {28710000, 69094.5628759463}, + {28720000, 69095.9676030131}, {28730000, 69097.4320584468}, + {28740000, 69099.0026519096}, {28750000, 69100.691301868}, + {28760000, 69102.4589874396}, {28770000, 69104.2595064398}, + {28780000, 69106.0918904569}, {28790000, 69107.9664303164}, + {28800000, 69109.8858156901}, {28810000, 69111.8349462636}, + {28820000, 69113.805137863}, {28830000, 69115.7765804703}, + {28840000, 69117.7059408085}, {28850000, 69119.5911487186}, + {28860000, 69121.4657002067}, {28870000, 69123.338516612}, + {28880000, 69125.2101905071}, {28890000, 69127.0814229977}, + {28900000, 69128.9518991512}, {28910000, 69130.8073636318}, + {28920000, 69132.6435940432}, {28930000, 69134.4907304937}, + {28940000, 69136.3659794638}, {28950000, 69138.2643185901}, + {28960000, 69140.1748866065}, {28970000, 69142.0958993814}, + {28980000, 69144.0123543802}, {28990000, 69145.9202899568}, + {29000000, 69147.8115403994}, {29010000, 69149.6764053969}, + {29020000, 69151.5158052831}, {29030000, 69153.3578437923}, + {29040000, 69155.2104163205}, {29050000, 69157.0794952398}, + {29060000, 69158.9684596345}, {29070000, 69160.8773736921}, + {29080000, 69162.8064974998}, {29090000, 69164.7554062094}, + {29100000, 69166.7168447632}, {29110000, 69168.688843452}, + {29120000, 69170.6626387301}, {29130000, 69172.6278475784}, + {29140000, 69174.5888204715}, {29150000, 69176.5824493591}, + {29160000, 69178.6147535755}, {29170000, 69180.650186697}, + {29180000, 69182.6684219334}, {29190000, 69184.6631871485}, + {29200000, 69186.6206050031}, {29210000, 69188.5388372215}, + {29220000, 69190.4029589663}, {29230000, 69192.2092069902}, + {29240000, 69193.9708444603}, {29250000, 69195.7035584756}, + {29260000, 69197.4082453354}, {29270000, 69199.0913593189}, + {29280000, 69200.7546656694}, {29290000, 69202.4051715365}, + {29300000, 69204.0469097283}, {29310000, 69205.6662010333}, + {29320000, 69207.2329518436}, {29330000, 69208.747792408}, + {29340000, 69210.27371666}, {29350000, 69211.8274030201}, + {29360000, 69213.3935393477}, {29370000, 69214.9539626982}, + {29380000, 69216.5074170867}, {29390000, 69218.0210946355}, + {29400000, 69219.4853214977}, {29410000, 69220.9557092904}, + {29420000, 69222.4640765749}, {29430000, 69223.9948097233}, + {29440000, 69225.5138112363}, {29450000, 69227.0207860823}, + {29460000, 69228.5711734453}, {29470000, 69230.1795412014}, + {29480000, 69231.8174894296}, {29490000, 69233.4513648139}, + {29500000, 69235.0818700942}, {29510000, 69236.7217058633}, + {29520000, 69238.3729382257}, {29530000, 69240.0236757829}, + {29540000, 69241.6671218546}, {29550000, 69243.3335652283}, + {29560000, 69245.0894798041}, {29570000, 69246.9367555565}, + {29580000, 69248.8000008105}, {29590000, 69250.6591477748}, + {29600000, 69252.5161202037}, {29610000, 69254.3731994275}, + {29620000, 69256.2305215853}, {29630000, 69258.0886843301}, + {29640000, 69259.9477832177}, {29650000, 69261.8196095378}, + {29660000, 69263.7108855615}, {29670000, 69265.6245762188}, + {29680000, 69267.5673164359}, {29690000, 69269.5399474131}, + {29700000, 69271.5498273278}, {29710000, 69273.5987745874}, + {29720000, 69275.6782538487}, {29730000, 69277.7781357675}, + {29740000, 69279.8991497291}, {29750000, 69282.0482329593}, + {29760000, 69284.2262343304}, {29770000, 69286.4270589039}, + {29780000, 69288.6471696408}, {29790000, 69290.8808043415}, + {29800000, 69293.1154109756}, {29810000, 69295.348745696}, + {29820000, 69297.5585545943}, {29830000, 69299.7390122621}, + {29840000, 69301.8981203158}, {29850000, 69304.0453558256}, + {29860000, 69306.1813788779}, {29870000, 69308.3146875263}, + {29880000, 69310.4476439565}, {29890000, 69312.586004476}, + {29900000, 69314.7330524978}, {29910000, 69316.8750326473}, + {29920000, 69318.9817568515}, {29930000, 69321.051979739}, + {29940000, 69323.1127560141}, {29950000, 69325.1713068925}, + {29960000, 69327.2280902998}, {29970000, 69329.2836480751}, + {29980000, 69331.3383818593}, {29990000, 69333.4015440027}, + {30000000, 69335.47566324}, {30010000, 69337.5657793753}, + {30020000, 69339.6747470555}, {30030000, 69341.8081563616}, + {30040000, 69343.9784098388}, {30050000, 69346.1847267426}, + {30060000, 69348.391828364}, {30070000, 69350.5903405709}, + {30080000, 69352.7907124982}, {30090000, 69355.0053693018}, + {30100000, 69357.2343396304}, {30110000, 69359.4515059789}, + {30120000, 69361.6485835104}, {30130000, 69363.8251494051}, + {30140000, 69365.9810047064}, {30150000, 69368.1273089108}, + {30160000, 69370.2884967297}, {30170000, 69372.466080478}, + {30180000, 69374.6470790831}, {30190000, 69376.828028859}, + {30200000, 69378.9925642739}, {30210000, 69381.121228051}, + {30220000, 69383.2134126393}, {30230000, 69385.264142952}, + {30240000, 69387.2722466121}, {30250000, 69389.2216344447}, + {30260000, 69391.1032093863}, {30270000, 69392.9362767293}, + {30280000, 69394.7629147874}, {30290000, 69396.5860297254}, + {30300000, 69398.3865985277}, {30310000, 69400.1596460548}, + {30320000, 69401.8936457938}, {30330000, 69403.5748670831}, + {30340000, 69405.2090575398}, {30350000, 69406.9063001513}, + {30360000, 69408.6950414778}, {30370000, 69410.4664196707}, + {30380000, 69412.158079185}, {30390000, 69413.8123406622}, + {30400000, 69415.5218618412}, {30410000, 69417.2869350222}, + {30420000, 69418.9479365552}, {30430000, 69420.462808561}, + {30440000, 69421.9225148686}, {30450000, 69423.4354511648}, + {30460000, 69425.0044263069}, {30470000, 69426.6304971649}, + {30480000, 69428.3137291735}, {30490000, 69430.0382687772}, + {30500000, 69431.7949308299}, {30510000, 69433.591593147}, + {30520000, 69435.4457860006}, {30530000, 69437.3578278575}, + {30540000, 69439.306942958}, {30550000, 69441.2874722691}, + {30560000, 69443.3200647537}, {30570000, 69445.429321306}, + {30580000, 69447.6137486264}, {30590000, 69449.7951499713}, + {30600000, 69451.9500327656}, {30610000, 69454.0999697079}, + {30620000, 69456.2573512551}, {30630000, 69458.3783363371}, + {30640000, 69460.3663846927}, {30650000, 69462.2197501541}, + {30660000, 69464.069595964}, {30670000, 69465.9508367006}, + {30680000, 69467.8665659523}, {30690000, 69469.8204953205}, + {30700000, 69471.8184779648}, {30710000, 69473.9078268758}, + {30720000, 69476.0960246172}, {30730000, 69478.2747679499}, + {30740000, 69480.3819243902}, {30750000, 69482.423701945}, + {30760000, 69484.4133459842}, {30770000, 69486.3519827923}, + {30780000, 69488.233459745}, {30790000, 69490.0563450672}, + {30800000, 69491.8459073076}, {30810000, 69493.6321567512}, + {30820000, 69495.4140358618}, {30830000, 69497.1557851946}, + {30840000, 69498.8482117898}, {30850000, 69500.5161493805}, + {30860000, 69502.1739011024}, {30870000, 69503.8137321528}, + {30880000, 69505.4185408177}, {30890000, 69506.9875881175}, + {30900000, 69508.5343703855}, {30910000, 69510.0625602618}, + {30920000, 69511.6015602381}, {30930000, 69513.1863384905}, + {30940000, 69514.8137221952}, {30950000, 69516.4511910064}, + {30960000, 69518.0931243581}, {30970000, 69519.7737570895}, + {30980000, 69521.5126540007}, {30990000, 69523.31309112}, + {31000000, 69525.1826368344}, {31010000, 69527.1202783067}, + {31020000, 69529.0974685726}, {31030000, 69531.1064669636}, + {31040000, 69533.1042800153}, {31050000, 69535.0397236469}, + {31060000, 69536.9271951214}, {31070000, 69538.8734026621}, + {31080000, 69540.8932060202}, {31090000, 69543.0257227395}, + {31100000, 69545.2932027282}, {31110000, 69547.6682616966}, + {31120000, 69550.0913002858}, {31130000, 69552.5481338438}, + {31140000, 69554.8632013274}, {31150000, 69556.9902106765}, + {31160000, 69559.040565211}, {31170000, 69561.1468980329}, + {31180000, 69563.3066560708}, {31190000, 69565.3755984517}, + {31200000, 69567.3141569605}, {31210000, 69569.3032594995}, + {31220000, 69571.44680863}, {31230000, 69573.7065745701}, + {31240000, 69575.9991485618}, {31250000, 69578.3148108436}, + {31260000, 69580.6127548692}, {31270000, 69582.8821745033}, + {31280000, 69585.0997994261}, {31290000, 69587.2378813619}, + {31300000, 69589.2964446657}, {31310000, 69591.2932185546}, + {31320000, 69593.2337468744}, {31330000, 69595.11645451}, + {31340000, 69596.940556368}, {31350000, 69598.714504372}, + {31360000, 69600.4565909539}, {31370000, 69602.1697275677}, + {31380000, 69603.8766362231}, {31390000, 69605.5833927991}, + {31400000, 69607.3369252856}, {31410000, 69609.1931356784}, + {31420000, 69611.1513950562}, {31430000, 69613.1699565448}, + {31440000, 69615.237008594}, {31450000, 69617.310913519}, + {31460000, 69619.3677208655}, {31470000, 69621.4425602118}, + {31480000, 69623.6128303992}, {31490000, 69625.8853538093}, + {31500000, 69628.2641668939}, {31510000, 69630.7499588686}, + {31520000, 69633.2133812636}, {31530000, 69635.5001982463}, + {31540000, 69637.6186232502}, {31550000, 69639.6630236953}, + {31560000, 69641.6494715027}, {31570000, 69643.7385378679}, + {31580000, 69646.022433091}, {31590000, 69648.423769922}, + {31600000, 69650.7728169063}, {31610000, 69653.0605475173}, + {31620000, 69655.4134798539}, {31630000, 69657.8650801522}, + {31640000, 69660.336894266}, {31650000, 69662.7354840723}, + {31660000, 69665.0618338843}, {31670000, 69667.456390822}, + {31680000, 69669.9611634858}, {31690000, 69672.4598380255}, + {31700000, 69674.8854761021}, {31710000, 69677.2525297657}, + {31720000, 69679.5924744917}, {31730000, 69681.9101313502}, + {31740000, 69684.2432557192}, {31750000, 69686.6018578025}, + {31760000, 69688.9699228998}, {31770000, 69691.3283829087}, + {31780000, 69693.6785301407}, {31790000, 69696.098494899}, + {31800000, 69698.6115537596}, {31810000, 69701.123712965}, + {31820000, 69703.5808708669}, {31830000, 69705.9951178439}, + {31840000, 69708.3928227486}, {31850000, 69710.7779203661}, + {31860000, 69713.1806636896}, {31870000, 69715.6090685385}, + {31880000, 69718.0546898089}, {31890000, 69720.5074593839}, + {31900000, 69722.96747369}, {31910000, 69725.4446454631}, + {31920000, 69727.9416523559}, {31930000, 69730.4628386641}, + {31940000, 69733.0106541664}, {31950000, 69735.5685536895}, + {31960000, 69738.1001198493}, {31970000, 69740.6044966716}, + {31980000, 69743.129818574}, {31990000, 69745.6888431135}, + {32000000, 69748.2654420143}, {32010000, 69750.8404039616}, + {32020000, 69753.413034289}, {32030000, 69755.9757746326}, + {32040000, 69758.5263841134}, {32050000, 69761.0764775617}, + {32060000, 69763.6327502901}, {32070000, 69766.1871593509}, + {32080000, 69768.7219604803}, {32090000, 69771.2369735665}, + {32100000, 69773.7599151527}, {32110000, 69776.2981463241}, + {32120000, 69778.8435762158}, {32130000, 69781.3865657356}, + {32140000, 69783.9276354516}, {32150000, 69786.4831416747}, + {32160000, 69789.0574216645}, {32170000, 69791.6373009233}, + {32180000, 69794.2151745541}, {32190000, 69796.7963098823}, + {32200000, 69799.3923400018}, {32210000, 69802.0022020429}, + {32220000, 69804.5835361478}, {32230000, 69807.1251423596}, + {32240000, 69809.6678939174}, {32250000, 69812.260522443}, + {32260000, 69814.8939984482}, {32270000, 69817.4988103365}, + {32280000, 69820.0652448026}, {32290000, 69822.6266954302}, + {32300000, 69825.202419134}, {32310000, 69827.7903547204}, + {32320000, 69830.3860317558}, {32330000, 69832.988298427}, + {32340000, 69835.5825113649}, {32350000, 69838.1647922597}, + {32360000, 69840.7270013563}, {32370000, 69843.2594143149}, + {32380000, 69845.7611363589}, {32390000, 69848.2132156009}, + {32400000, 69850.610566842}, {32410000, 69852.9791503207}, + {32420000, 69855.3339886406}, {32430000, 69857.7005080267}, + {32440000, 69860.134897993}, {32450000, 69862.6393457387}, + {32460000, 69865.1594639232}, {32470000, 69867.6806816362}, + {32480000, 69870.2205602932}, {32490000, 69872.8000731818}, + {32500000, 69875.4174003867}, {32510000, 69878.0267547861}, + {32520000, 69880.6159397957}, {32530000, 69883.1953478191}, + {32540000, 69885.770996759}, {32550000, 69888.3431334434}, + {32560000, 69890.91228238}, {32570000, 69893.4791961679}, + {32580000, 69896.0582687647}, {32590000, 69898.6533068894}, + {32600000, 69901.240162446}, {32610000, 69903.7900371503}, + {32620000, 69906.3040638556}, {32630000, 69908.8158442734}, + {32640000, 69911.334186692}, {32650000, 69913.8415431403}, + {32660000, 69916.327822866}, {32670000, 69918.8065412027}, + {32680000, 69921.3074820738}, {32690000, 69923.8316084699}, + {32700000, 69926.3447144139}, {32710000, 69928.8377041188}, + {32720000, 69931.3390665871}, {32730000, 69933.8828039707}, + {32740000, 69936.4585531965}, {32750000, 69938.996065507}, + {32760000, 69941.485705974}, {32770000, 69943.978763645}, + {32780000, 69946.5048301039}, {32790000, 69949.0483656452}, + {32800000, 69951.5751785251}, {32810000, 69954.0828258673}, + {32820000, 69956.5837324184}, {32830000, 69959.0812412714}, + {32840000, 69961.5714895196}, {32850000, 69964.0498606265}, + {32860000, 69966.5170798524}, {32870000, 69969.0045670395}, + {32880000, 69971.5215977191}, {32890000, 69974.0366871784}, + {32900000, 69976.5316697593}, {32910000, 69979.0114972853}, + {32920000, 69981.4870410838}, {32930000, 69983.9600293556}, + {32940000, 69986.4454212383}, {32950000, 69988.9471772171}, + {32960000, 69991.4567471331}, {32970000, 69993.9639280226}, + {32980000, 69996.4686250866}, {32990000, 69998.9797613708}, + {33000000, 70001.5000324936}, {33010000, 70004.0103392283}, + {33020000, 70006.4996660709}, {33030000, 70008.9897711734}, + {33040000, 70011.5286819577}, {33050000, 70014.1175683953}, + {33060000, 70016.6945137809}, {33070000, 70019.2430244907}, + {33080000, 70021.7853880367}, {33090000, 70024.3482365858}, + {33100000, 70026.9325064227}, {33110000, 70029.545353116}, + {33120000, 70032.1886646664}, {33130000, 70034.8181133366}, + {33140000, 70037.4081136745}, {33150000, 70039.977188719}, + {33160000, 70042.5661367265}, {33170000, 70045.1749028326}, + {33180000, 70047.7269754781}, {33190000, 70050.2021086025}, + {33200000, 70052.6321392624}, {33210000, 70055.0550428556}, + {33220000, 70057.4722917734}, {33230000, 70059.8869733638}, + {33240000, 70062.2996147229}, {33250000, 70064.698250395}, + {33260000, 70067.0759955209}, {33270000, 70069.4436830175}, + {33280000, 70071.825236813}, {33290000, 70074.2225010695}, + {33300000, 70076.6296222637}, {33310000, 70079.0449996942}, + {33320000, 70081.4683074696}, {33330000, 70083.8991643227}, + {33340000, 70086.3408202693}, {33350000, 70088.8158735098}, + {33360000, 70091.3273813234}, {33370000, 70093.8398332953}, + {33380000, 70096.3327080328}, {33390000, 70098.8273503556}, + {33400000, 70101.3709312295}, {33410000, 70103.9659352504}, + {33420000, 70106.5790261933}, {33430000, 70109.201226739}, + {33440000, 70111.8230718544}, {33450000, 70114.4332484479}, + {33460000, 70117.0345931614}, {33470000, 70119.6486361382}, + {33480000, 70122.278377086}, {33490000, 70124.9303322987}, + {33500000, 70127.6082256607}, {33510000, 70130.2983084294}, + {33520000, 70132.9702777155}, {33530000, 70135.6217119609}, + {33540000, 70138.2581014118}, {33550000, 70140.8809685825}, + {33560000, 70143.4982880837}, {33570000, 70146.1195778114}, + {33580000, 70148.7452187422}, {33590000, 70151.3785654031}, + {33600000, 70154.0205233363}, {33610000, 70156.669850316}, + {33620000, 70159.3258122229}, {33630000, 70161.9856426244}, + {33640000, 70164.6432270576}, {33650000, 70167.29696443}, + {33660000, 70169.9249887158}, {33670000, 70172.5215434944}, + {33680000, 70175.0750902714}, {33690000, 70177.5717949236}, + {33700000, 70180.0135998227}, {33710000, 70182.4404132163}, + {33720000, 70184.8627692293}, {33730000, 70187.2403042934}, + {33740000, 70189.5497580686}, {33750000, 70191.8153155208}, + {33760000, 70194.0902007744}, {33770000, 70196.3786886429}, + {33780000, 70198.6694557499}, {33790000, 70200.9594642527}, + {33800000, 70203.2647201781}, {33810000, 70205.6043694462}, + {33820000, 70207.9736270631}, {33830000, 70210.3308049576}, + {33840000, 70212.6689797687}, {33850000, 70215.0283997783}, + {33860000, 70217.4323078336}, {33870000, 70219.884158593}, + {33880000, 70222.3918854113}, {33890000, 70224.9556381687}, + {33900000, 70227.5684555666}, {33910000, 70230.2282962216}, + {33920000, 70232.9015177767}, {33930000, 70235.5479238604}, + {33940000, 70238.1679907761}, {33950000, 70240.7957821611}, + {33960000, 70243.4405949926}, {33970000, 70246.0960901405}, + {33980000, 70248.7585728645}, {33990000, 70251.4279127894}, + {34000000, 70254.1038633761}, {34010000, 70256.7863709927}, + {34020000, 70259.4753783191}, {34030000, 70262.1708463188}, + {34040000, 70264.8525630338}, {34050000, 70267.4963570593}, + {34060000, 70270.1029881779}, {34070000, 70272.69848294}, + {34080000, 70275.2898313661}, {34090000, 70277.895606532}, + {34100000, 70280.5265384198}, {34110000, 70283.1719305518}, + {34120000, 70285.8081879968}, {34130000, 70288.4338170539}, + {34140000, 70291.0618269463}, {34150000, 70293.6956925544}, + {34160000, 70296.3234712061}, {34170000, 70298.9308708365}, + {34180000, 70301.5175406161}, {34190000, 70304.0810673059}, + {34200000, 70306.620792998}, {34210000, 70309.1554137069}, + {34220000, 70311.6957713329}, {34230000, 70314.2449996217}, + {34240000, 70316.8100912716}, {34250000, 70319.392318615}, + {34260000, 70322.0063277284}, {34270000, 70324.6559246278}, + {34280000, 70327.3124412219}, {34290000, 70329.9415914731}, + {34300000, 70332.5432818949}, {34310000, 70335.1362512142}, + {34320000, 70337.7257524938}, {34330000, 70340.3239697347}, + {34340000, 70342.9379525423}, {34350000, 70345.5624184474}, + {34360000, 70348.1857354847}, {34370000, 70350.8057843457}, + {34380000, 70353.4004041755}, {34390000, 70355.9637535223}, + {34400000, 70358.496179767}, {34410000, 70360.9980672636}, + {34420000, 70363.4702325036}, {34430000, 70365.9493018173}, + {34440000, 70368.4465013313}, {34450000, 70370.9254596387}, + {34460000, 70373.3651162398}, {34470000, 70375.773128896}, + {34480000, 70378.1662594475}, {34490000, 70380.5461531813}, + {34500000, 70382.9138501716}, {34510000, 70385.2696733861}, + {34520000, 70387.6137110406}, {34530000, 70389.9460567742}, + {34540000, 70392.2671332185}, {34550000, 70394.5848020685}, + {34560000, 70396.9011947268}, {34570000, 70399.2160871896}, + {34580000, 70401.5293528092}, {34590000, 70403.8437489942}, + {34600000, 70406.1653943647}, {34610000, 70408.4955194564}, + {34620000, 70410.8487832324}, {34630000, 70413.2290266659}, + {34640000, 70415.6157343383}, {34650000, 70417.9843516468}, + {34660000, 70420.3361081985}, {34670000, 70422.7232081252}, + {34680000, 70425.1603778681}, {34690000, 70427.621907084}, + {34700000, 70430.0928309736}, {34710000, 70432.5835956285}, + {34720000, 70435.1175006709}, {34730000, 70437.6951747843}, + {34740000, 70440.289081228}, {34750000, 70442.8917871486}, + {34760000, 70445.505621059}, {34770000, 70448.1333819438}, + {34780000, 70450.7732334261}, {34790000, 70453.3823209658}, + {34800000, 70455.9490144836}, {34810000, 70458.4852656124}, + {34820000, 70460.998070608}, {34830000, 70463.4795523271}, + {34840000, 70465.9120595826}, {34850000, 70468.2948319485}, + {34860000, 70470.6413566764}, {34870000, 70472.9553805172}, + {34880000, 70475.2382811937}, {34890000, 70477.4916765791}, + {34900000, 70479.7153466734}, {34910000, 70481.8905360325}, + {34920000, 70484.0117408863}, {34930000, 70486.1112280097}, + {34940000, 70488.207759983}, {34950000, 70490.2992721964}, + {34960000, 70492.3811528762}, {34970000, 70494.4536946445}, + {34980000, 70496.531009094}, {34990000, 70498.6168608186}, + {35000000, 70500.7185709197}, {35010000, 70502.8449203258}, + {35020000, 70504.9957128392}, {35030000, 70507.161404445}, + {35040000, 70509.3392172874}, {35050000, 70511.5272058394}, + {35060000, 70513.7242189518}, {35070000, 70515.9494198261}, + {35080000, 70518.2455009153}, {35090000, 70520.6141233346}, + {35100000, 70523.014435901}, {35110000, 70525.4353654448}, + {35120000, 70527.912163339}, {35130000, 70530.487089313}, + {35140000, 70533.151711177}, {35150000, 70535.8312414385}, + {35160000, 70538.5130089105}, {35170000, 70541.1995468041}, + {35180000, 70543.8923165838}, {35190000, 70546.5831126079}, + {35200000, 70549.2537352772}, {35210000, 70551.9025596558}, + {35220000, 70554.5285983132}, {35230000, 70557.1316696469}, + {35240000, 70559.7044030718}, {35250000, 70562.237936241}, + {35260000, 70564.7339608388}, {35270000, 70567.2272991504}, + {35280000, 70569.7271604802}, {35290000, 70572.2399528061}, + {35300000, 70574.7693712373}, {35310000, 70577.3072695506}, + {35320000, 70579.8356248278}, {35330000, 70582.3524407837}, + {35340000, 70584.8495655571}, {35350000, 70587.3248842671}, + {35360000, 70589.8015303635}, {35370000, 70592.3072237385}, + {35380000, 70594.8425318665}, {35390000, 70597.4013964625}, + {35400000, 70599.9818362339}, {35410000, 70602.5808976882}, + {35420000, 70605.1968245411}, {35430000, 70607.8295220925}, + {35440000, 70610.4788830972}, {35450000, 70613.1438009928}, + {35460000, 70615.8027132267}, {35470000, 70618.4498578429}, + {35480000, 70621.088763458}, {35490000, 70623.7236496756}, + {35500000, 70626.3528801297}, {35510000, 70628.9621739496}, + {35520000, 70631.5492249833}, {35530000, 70634.1375536579}, + {35540000, 70636.7408363479}, {35550000, 70639.3732666311}, + {35560000, 70642.0665161874}, {35570000, 70644.8195499477}, + {35580000, 70647.5551177406}, {35590000, 70650.2525619836}, + {35600000, 70652.9265722378}, {35610000, 70655.5947402392}, + {35620000, 70658.255944761}, {35630000, 70660.8968509446}, + {35640000, 70663.5153005096}, {35650000, 70666.1229364233}, + {35660000, 70668.7265437373}, {35670000, 70671.3154356218}, + {35680000, 70673.8657844431}, {35690000, 70676.3755151072}, + {35700000, 70678.8434143165}, {35710000, 70681.2693090134}, + {35720000, 70683.6785114586}, {35730000, 70686.1014347343}, + {35740000, 70688.5381457264}, {35750000, 70690.983757739}, + {35760000, 70693.4375474598}, {35770000, 70695.8813072825}, + {35780000, 70698.3044688029}, {35790000, 70700.7341577744}, + {35800000, 70703.2306650354}, {35810000, 70705.7973413021}, + {35820000, 70708.3943813335}, {35830000, 70711.0109882486}, + {35840000, 70713.6525867321}, {35850000, 70716.325707644}, + {35860000, 70719.0273642227}, {35870000, 70721.6862333898}, + {35880000, 70724.2828574052}, {35890000, 70726.7875052348}, + {35900000, 70729.1830764934}, {35910000, 70731.5022954517}, + {35920000, 70733.8173787806}, {35930000, 70736.1331234405}, + {35940000, 70738.4107606428}, {35950000, 70740.640021118}, + {35960000, 70742.7750502428}, {35970000, 70744.7607627106}, + {35980000, 70746.5959261654}, {35990000, 70748.2712955157}, + {36000000, 70749.7848590335}, {36010000, 70751.307192351}, + {36020000, 70752.9376086904}, {36030000, 70754.6545866989}, + {36040000, 70756.4108559607}, {36050000, 70758.2038139697}, + {36060000, 70760.073497419}, {36070000, 70762.0303753254}, + {36080000, 70764.0442462611}, {36090000, 70766.0789510082}, + {36100000, 70768.1351745452}, {36110000, 70770.383011792}, + {36120000, 70772.8757103268}, {36130000, 70775.5172566714}, + {36140000, 70778.2514313627}, {36150000, 70781.0348066401}, + {36160000, 70783.7712247597}, {36170000, 70786.4525043068}, + {36180000, 70789.0876375791}, {36190000, 70791.6792067479}, + {36200000, 70794.1820681918}, {36210000, 70796.5419493386}, + {36220000, 70798.7639932902}, {36230000, 70800.9745013018}, + {36240000, 70803.2073552011}, {36250000, 70805.4482852397}, + {36260000, 70807.6889650043}, {36270000, 70809.9071887761}, + {36280000, 70812.0534434595}, {36290000, 70814.1264201466}, + {36300000, 70816.188025243}, {36310000, 70818.2549340436}, + {36320000, 70820.3204856342}, {36330000, 70822.3766841955}, + {36340000, 70824.4247951562}, {36350000, 70826.4956303219}, + {36360000, 70828.597390649}, {36370000, 70830.7169668396}, + {36380000, 70832.8466880989}, {36390000, 70835.0027225319}, + {36400000, 70837.2211822439}, {36410000, 70839.4991125366}, + {36420000, 70841.7094372264}, {36430000, 70843.8182578057}, + {36440000, 70845.9581167833}, {36450000, 70848.2881234878}, + {36460000, 70850.8031331828}, {36470000, 70853.3319110341}, + {36480000, 70855.829365329}, {36490000, 70858.372379043}, + {36500000, 70861.005629221}, {36510000, 70863.6755983958}, + {36520000, 70866.263389837}, {36530000, 70868.7649019983}, + {36540000, 70871.3169293547}, {36550000, 70873.9560438837}, + {36560000, 70876.6507569605}, {36570000, 70879.3633331478}, + {36580000, 70882.0931732615}, {36590000, 70884.8663224017}, + {36600000, 70887.6905068522}, {36610000, 70890.5918379751}, + {36620000, 70893.5853815115}, {36630000, 70896.6248027202}, + {36640000, 70899.6072492389}, {36650000, 70902.5273156445}, + {36660000, 70905.46526814}, {36670000, 70908.442608674}, + {36680000, 70911.4157316674}, {36690000, 70914.3322537659}, + {36700000, 70917.185619977}, {36710000, 70919.9327977646}, + {36720000, 70922.5669619386}, {36730000, 70925.2255815389}, + {36740000, 70927.988761631}, {36750000, 70930.8207355458}, + {36760000, 70933.6423155314}, {36770000, 70936.4464034958}, + {36780000, 70939.2356378511}, {36790000, 70942.0107821896}, + {36800000, 70944.7486492701}, {36810000, 70947.4212777786}, + {36820000, 70950.030839925}, {36830000, 70952.6307251166}, + {36840000, 70955.2350978405}, {36850000, 70957.744208936}, + {36860000, 70960.1000932781}, {36870000, 70962.3121955962}, + {36880000, 70964.4006515964}, {36890000, 70966.3753303219}, + {36900000, 70968.395519537}, {36910000, 70970.5038898783}, + {36920000, 70972.6908762095}, {36930000, 70974.9450701452}, + {36940000, 70977.2670868504}, {36950000, 70979.6675260558}, + {36960000, 70982.1479539144}, {36970000, 70984.6885083442}, + {36980000, 70987.2774693017}, {36990000, 70989.9278756844}, + {37000000, 70992.6691611027}, {37010000, 70995.4993204708}, + {37020000, 70998.3265234284}, {37030000, 71001.1260853645}, + {37040000, 71003.8997369072}, {37050000, 71006.649530107}, + {37060000, 71009.3745664847}, {37070000, 71012.0674504669}, + {37080000, 71014.7272638891}, {37090000, 71017.3897410649}, + {37100000, 71020.0757124871}, {37110000, 71022.7803899723}, + {37120000, 71025.4932310272}, {37130000, 71028.2132041283}, + {37140000, 71030.9396834264}, {37150000, 71033.6724763914}, + {37160000, 71036.4185301577}, {37170000, 71039.186210347}, + {37180000, 71041.9746729979}, {37190000, 71044.7584907238}, + {37200000, 71047.5305633047}, {37210000, 71050.3193858586}, + {37220000, 71053.1415602258}, {37230000, 71055.9756722669}, + {37240000, 71058.7740799531}, {37250000, 71061.5334471158}, + {37260000, 71064.272689073}, {37270000, 71066.9969701703}, + {37280000, 71069.7183788475}, {37290000, 71072.4514448523}, + {37300000, 71075.1963084386}, {37310000, 71077.9426643092}, + {37320000, 71080.6873907249}, {37330000, 71083.4232383176}, + {37340000, 71086.1459929734}, {37350000, 71088.8555644686}, + {37360000, 71091.55167027}, {37370000, 71094.2336740499}, + {37380000, 71096.887312942}, {37390000, 71099.5088512495}, + {37400000, 71102.0910340804}, {37410000, 71104.6250987263}, + {37420000, 71107.1116941771}, {37430000, 71109.5684799956}, + {37440000, 71112.0005138448}, {37450000, 71114.4273273226}, + {37460000, 71116.8603343613}, {37470000, 71119.3026773416}, + {37480000, 71121.76141595}, {37490000, 71124.2368101151}, + {37500000, 71126.722020766}, {37510000, 71129.215168309}, + {37520000, 71131.7362032097}, {37530000, 71134.3091388943}, + {37540000, 71136.9322644163}, {37550000, 71139.5876526448}, + {37560000, 71142.2721146238}, {37570000, 71144.9720249566}, + {37580000, 71147.67939686}, {37590000, 71150.3939010646}, + {37600000, 71153.1148479688}, {37610000, 71155.8404653848}, + {37620000, 71158.5348686116}, {37630000, 71161.1885127283}, + {37640000, 71163.8055965405}, {37650000, 71166.3911339109}, + {37660000, 71168.94298438}, {37670000, 71171.3475983388}, + {37680000, 71173.571120357}, {37690000, 71175.8350327525}, + {37700000, 71178.2687274441}, {37710000, 71180.8078017005}, + {37720000, 71183.3092511074}, {37730000, 71185.7633922125}, + {37740000, 71188.2409341564}, {37750000, 71190.7608396675}, + {37760000, 71193.3186934108}, {37770000, 71195.9092266779}, + {37780000, 71198.5334360159}, {37790000, 71201.2541617158}, + {37800000, 71204.0901466799}, {37810000, 71206.9573636422}, + {37820000, 71209.8066273569}, {37830000, 71212.6472415416}, + {37840000, 71215.4999055489}, {37850000, 71218.3655316441}, + {37860000, 71221.2237809902}, {37870000, 71224.0691874422}, + {37880000, 71226.8857462057}, {37890000, 71229.6541377331}, + {37900000, 71232.3747348635}, {37910000, 71235.0646780648}, + {37920000, 71237.7288107467}, {37930000, 71240.404440832}, + {37940000, 71243.1133542809}, {37950000, 71245.8398032622}, + {37960000, 71248.5487691843}, {37970000, 71251.2390233607}, + {37980000, 71253.9515990798}, {37990000, 71256.6974688243}, + {38000000, 71259.4603642772}, {38010000, 71262.2207291171}, + {38020000, 71264.9786806507}, {38030000, 71267.7662789984}, + {38040000, 71270.5931469108}, {38050000, 71273.4033199201}, + {38060000, 71276.1641164414}, {38070000, 71278.8855225147}, + {38080000, 71281.5895690911}, {38090000, 71284.277082177}, + {38100000, 71286.9207730513}, {38110000, 71289.513449987}, + {38120000, 71292.0753374051}, {38130000, 71294.6307372601}, + {38140000, 71297.1793875091}, {38150000, 71299.7007019634}, + {38160000, 71302.1892788755}, {38170000, 71304.663332409}, + {38180000, 71307.1335538048}, {38190000, 71309.6112887632}, + {38200000, 71312.1219185781}, {38210000, 71314.6673649877}, + {38220000, 71317.2417770387}, {38230000, 71319.8434719186}, + {38240000, 71322.4262741992}, {38250000, 71324.9346057483}, + {38260000, 71327.3812448059}, {38270000, 71329.8651252658}, + {38280000, 71332.4002733208}, {38290000, 71334.9602258634}, + {38300000, 71337.5294421313}, {38310000, 71340.107273847}, + {38320000, 71342.6923268843}, {38330000, 71345.2847697448}, + {38340000, 71347.8916513448}, {38350000, 71350.5148196613}, + {38360000, 71353.1263172588}, {38370000, 71355.6924653753}, + {38380000, 71358.2122109344}, {38390000, 71360.6781463878}, + {38400000, 71363.0883913231}, {38410000, 71365.5049408625}, + {38420000, 71367.9640700748}, {38430000, 71370.4259284139}, + {38440000, 71372.8015475248}, {38450000, 71375.0828932477}, + {38460000, 71377.2652477522}, {38470000, 71379.3476989917}, + {38480000, 71381.3452833265}, {38490000, 71383.2760186491}, + {38500000, 71385.1492025805}, {38510000, 71387.1460031394}, + {38520000, 71389.314760379}, {38530000, 71391.6641143289}, + {38540000, 71394.1987514576}, {38550000, 71396.8908574674}, + {38560000, 71399.6793008587}, {38570000, 71402.5492370644}, + {38580000, 71405.3105724733}, {38590000, 71407.9124065399}, + {38600000, 71410.398021492}, {38610000, 71412.8194590921}, + {38620000, 71415.1769583506}, {38630000, 71417.4364358408}, + {38640000, 71419.5890427728}, {38650000, 71421.7342703684}, + {38660000, 71423.930444562}, {38670000, 71426.2067949963}, + {38680000, 71428.6291586062}, {38690000, 71431.199785908}, + {38700000, 71433.850193089}, {38710000, 71436.5616259597}, + {38720000, 71439.2814986988}, {38730000, 71441.94649597}, + {38740000, 71444.5485497916}, {38750000, 71447.0462454468}, + {38760000, 71449.4342348838}, {38770000, 71451.7593722693}, + {38780000, 71454.0492121301}, {38790000, 71456.3131791539}, + {38800000, 71458.572179953}, {38810000, 71460.8308715364}, + {38820000, 71463.1477639925}, {38830000, 71465.5384342636}, + {38840000, 71468.0119843713}, {38850000, 71470.5794714959}, + {38860000, 71473.2398785777}, {38870000, 71475.9489778195}, + {38880000, 71478.6931428488}, {38890000, 71481.4370616742}, + {38900000, 71484.1600387959}, {38910000, 71486.8860046252}, + {38920000, 71489.6685275077}, {38930000, 71492.510773711}, + {38940000, 71495.379770412}, {38950000, 71498.2665229115}, + {38960000, 71501.1496931709}, {38970000, 71504.0035605789}, + {38980000, 71506.8279019623}, {38990000, 71509.6418718096}, + {39000000, 71512.4513344236}, {39010000, 71515.2565285392}, + {39020000, 71518.0576028257}, {39030000, 71520.8573273354}, + {39040000, 71523.6618857107}, {39050000, 71526.4718424394}, + {39060000, 71529.2875400049}, {39070000, 71532.1090499563}, + {39080000, 71534.9317727549}, {39090000, 71537.7501662644}, + {39100000, 71540.5650348046}, {39110000, 71543.400920034}, + {39120000, 71546.2646212631}, {39130000, 71549.1070853142}, + {39140000, 71551.8995690714}, {39150000, 71554.6603519021}, + {39160000, 71557.4300974865}, {39170000, 71560.2126194319}, + {39180000, 71563.0102449139}, {39190000, 71565.8235470028}, + {39200000, 71568.6521605757}, {39210000, 71571.4956617155}, + {39220000, 71574.3522904011}, {39230000, 71577.2082662749}, + {39240000, 71580.0612523728}, {39250000, 71582.9045315596}, + {39260000, 71585.7341817846}, {39270000, 71588.5419291387}, + {39280000, 71591.3091224362}, {39290000, 71594.0348298946}, + {39300000, 71596.7324794885}, {39310000, 71599.4058088507}, + {39320000, 71602.0471114393}, {39330000, 71604.6470575911}, + {39340000, 71607.2085482901}, {39350000, 71609.7527614835}, + {39360000, 71612.2828212792}, {39370000, 71614.8056015011}, + {39380000, 71617.3251509057}, {39390000, 71619.8525637803}, + {39400000, 71622.4127150951}, {39410000, 71625.0064943024}, + {39420000, 71627.6065507297}, {39430000, 71630.2054749161}, + {39440000, 71632.8024005434}, {39450000, 71635.3962805284}, + {39460000, 71637.9913444138}, {39470000, 71640.6174437015}, + {39480000, 71643.2787260235}, {39490000, 71645.9461477158}, + {39500000, 71648.6026521156}, {39510000, 71651.2503694068}, + {39520000, 71653.8940116235}, {39530000, 71656.5350348924}, + {39540000, 71659.1952009719}, {39550000, 71661.8803175428}, + {39560000, 71664.5894481123}, {39570000, 71667.3214884897}, + {39580000, 71670.0753197479}, {39590000, 71672.8249173048}, + {39600000, 71675.5629762815}, {39610000, 71678.3179247478}, + {39620000, 71681.1064325144}, {39630000, 71683.9235122809}, + {39640000, 71686.7581818093}, {39650000, 71689.6083307305}, + {39660000, 71692.4518001869}, {39670000, 71695.2826299631}, + {39680000, 71698.1157207787}, {39690000, 71700.9690485202}, + {39700000, 71703.8408270802}, {39710000, 71706.6826233629}, + {39720000, 71709.4814435744}, {39730000, 71712.2725755079}, + {39740000, 71715.0767699317}, {39750000, 71717.894732281}, + {39760000, 71720.7281287339}, {39770000, 71723.576056483}, + {39780000, 71726.417061111}, {39790000, 71729.2453735377}, + {39800000, 71732.064517796}, {39810000, 71734.8787384274}, + {39820000, 71737.6864330182}, {39830000, 71740.4733426342}, + {39840000, 71743.2371386851}, {39850000, 71745.9775231707}, + {39860000, 71748.6943687965}, {39870000, 71751.387769479}, + {39880000, 71754.0577892795}, {39890000, 71756.7051997765}, + {39900000, 71759.3444686127}, {39910000, 71761.9795359922}, + {39920000, 71764.6104767669}, {39930000, 71767.2373769108}, + {39940000, 71769.8596694544}, {39950000, 71772.4630808966}, + {39960000, 71775.0437313555}, {39970000, 71777.613520856}, + {39980000, 71780.1794729691}, {39990000, 71782.7554989582}, + {40000000, 71785.3728244365}, {40010000, 71788.0332500882}, + {40020000, 71790.7169354901}, {40030000, 71793.4184196541}, + {40040000, 71796.1243895985}, {40050000, 71798.8187783565}, + {40060000, 71801.5026471315}, {40070000, 71804.2061957152}, + {40080000, 71806.9373951277}, {40090000, 71809.7010923295}, + {40100000, 71812.5000690233}, {40110000, 71815.3206775404}, + {40120000, 71818.1324806264}, {40130000, 71820.9336181757}, + {40140000, 71823.743870458}, {40150000, 71826.5685510032}, + {40160000, 71829.3802780598}, {40170000, 71832.1459819682}, + {40180000, 71834.8658913154}, {40190000, 71837.5873281979}, + {40200000, 71840.3246536291}, {40210000, 71843.0778836532}, + {40220000, 71845.84699529}, {40230000, 71848.629236872}, + {40240000, 71851.4185199024}, {40250000, 71854.2139058407}, + {40260000, 71857.0078358949}, {40270000, 71859.7982704615}, + {40280000, 71862.5846546611}, {40290000, 71865.3663137426}, + {40300000, 71868.1438895627}, {40310000, 71870.9344502724}, + {40320000, 71873.7427541872}, {40330000, 71876.5556390384}, + {40340000, 71879.3653514099}, {40350000, 71882.1770845343}, + {40360000, 71885.0025383607}, {40370000, 71887.8417781769}, + {40380000, 71890.6739487531}, {40390000, 71893.4934385653}, + {40400000, 71896.3110256708}, {40410000, 71899.1397304153}, + {40420000, 71901.9801091435}, {40430000, 71904.8619613707}, + {40440000, 71907.7947105188}, {40450000, 71910.70332549}, + {40460000, 71913.5437106029}, {40470000, 71916.3336663413}, + {40480000, 71919.1127948487}, {40490000, 71921.885561277}, + {40500000, 71924.6686187189}, {40510000, 71927.4664349876}, + {40520000, 71930.2474567356}, {40530000, 71932.9735422927}, + {40540000, 71935.6458967467}, {40550000, 71938.3105356038}, + {40560000, 71940.9799777786}, {40570000, 71943.6018556213}, + {40580000, 71946.1454553495}, {40590000, 71948.6345069582}, + {40600000, 71951.1218837301}, {40610000, 71953.6119573699}, + {40620000, 71956.0934528872}, {40630000, 71958.563351194}, + {40640000, 71960.9982835255}, {40650000, 71963.3699776539}, + {40660000, 71965.6787008928}, {40670000, 71967.9460624679}, + {40680000, 71970.1782983323}, {40690000, 71972.4076429884}, + {40700000, 71974.6530920071}, {40710000, 71976.8880624533}, + {40720000, 71979.0527493472}, {40730000, 71981.146372973}, + {40740000, 71983.2660525417}, {40750000, 71985.4379672291}, + {40760000, 71987.6236910927}, {40770000, 71989.7767728006}, + {40780000, 71991.8969069608}, {40790000, 71994.0085579541}, + {40800000, 71996.1186429456}, {40810000, 71998.2158777294}, + {40820000, 72000.2936408047}, {40830000, 72002.3735687911}, + {40840000, 72004.5041952167}, {40850000, 72006.6908839194}, + {40860000, 72008.9576802636}, {40870000, 72011.3107983667}, + {40880000, 72013.7160234129}, {40890000, 72016.1320374549}, + {40900000, 72018.5585379017}, {40910000, 72021.0435665888}, + {40920000, 72023.6015392093}, {40930000, 72026.2164356139}, + {40940000, 72028.8787023456}, {40950000, 72031.5742689971}, + {40960000, 72034.2717577698}, {40970000, 72036.9714434141}, + {40980000, 72039.7430622012}, {40990000, 72042.6052348632}, + {41000000, 72045.5094445213}, {41010000, 72048.3970677979}, + {41020000, 72051.2662447821}, {41030000, 72054.111956399}, + {41040000, 72056.9328930211}, {41050000, 72059.7236742814}, + {41060000, 72062.4811919024}, {41070000, 72065.2027490421}, + {41080000, 72067.8820433178}, {41090000, 72070.5196363576}, + {41100000, 72073.1368419285}, {41110000, 72075.7395163559}, + {41120000, 72078.3446674755}, {41130000, 72080.9728644908}, + {41140000, 72083.6195611674}, {41150000, 72086.242812229}, + {41160000, 72088.8355000263}, {41170000, 72091.4555974545}, + {41180000, 72094.1372451835}, {41190000, 72096.8678544596}, + {41200000, 72099.6194422036}, {41210000, 72102.3895809721}, + {41220000, 72105.1837565278}, {41230000, 72108.0033669406}, + {41240000, 72110.8277163274}, {41250000, 72113.6317835011}, + {41260000, 72116.4151855824}, {41270000, 72119.182991814}, + {41280000, 72121.9365882464}, {41290000, 72124.6881485691}, + {41300000, 72127.4448485749}, {41310000, 72130.2123708421}, + {41320000, 72133.0035536271}, {41330000, 72135.8139598893}, + {41340000, 72138.5225618123}, {41350000, 72141.0969593484}, + {41360000, 72143.6154929286}, {41370000, 72146.1729137157}, + {41380000, 72148.771219738}, {41390000, 72151.3639208976}, + {41400000, 72153.9364821385}, {41410000, 72156.5466167015}, + {41420000, 72159.2283499592}, {41430000, 72161.9744725393}, + {41440000, 72164.7691871605}, {41450000, 72167.609144488}, + {41460000, 72170.4573924699}, {41470000, 72173.3038873483}, + {41480000, 72176.1719018715}, {41490000, 72179.0896250785}, + {41500000, 72182.0509784107}, {41510000, 72185.0007309117}, + {41520000, 72187.9294921693}, {41530000, 72190.8411154998}, + {41540000, 72193.7379086533}, {41550000, 72196.620029838}, + {41560000, 72199.4877424957}, {41570000, 72202.3414620214}, + {41580000, 72205.1884284105}, {41590000, 72208.0306281442}, + {41600000, 72210.8722671852}, {41610000, 72213.7184351912}, + {41620000, 72216.5694070581}, {41630000, 72219.4263528901}, + {41640000, 72222.2894469048}, {41650000, 72225.146474429}, + {41660000, 72227.9902427423}, {41670000, 72230.8123906188}, + {41680000, 72233.5939652836}, {41690000, 72236.3356241244}, + {41700000, 72239.0865917418}, {41710000, 72241.8601737714}, + {41720000, 72244.6284653579}, {41730000, 72247.3576889687}, + {41740000, 72250.0499664152}, {41750000, 72252.7247531208}, + {41760000, 72255.3848572836}, {41770000, 72258.0252215465}, + {41780000, 72260.642902826}, {41790000, 72263.2351776313}, + {41800000, 72265.7957660489}, {41810000, 72268.3248646642}, + {41820000, 72270.836577013}, {41830000, 72273.3347881228}, + {41840000, 72275.8122893935}, {41850000, 72278.2603342799}, + {41860000, 72280.6795558667}, {41870000, 72283.0903068368}, + {41880000, 72285.4983562214}, {41890000, 72287.8862868025}, + {41900000, 72290.2438478843}, {41910000, 72292.5735335322}, + {41920000, 72294.8807811534}, {41930000, 72297.1665319314}, + {41940000, 72299.4383340996}, {41950000, 72301.6982860738}, + {41960000, 72303.9581945602}, {41970000, 72306.232364482}, + {41980000, 72308.5222297295}, {41990000, 72310.8562900148}, + {42000000, 72313.2424034385}, {42010000, 72315.6244060126}, + {42020000, 72317.9691199977}, {42030000, 72320.2891178081}, + {42040000, 72322.612537788}, {42050000, 72324.942689523}, + {42060000, 72327.2954809842}, {42070000, 72329.6751458322}, + {42080000, 72332.072754945}, {42090000, 72334.4775093059}, + {42100000, 72336.8887514246}, {42110000, 72339.2772759448}, + {42120000, 72341.6338919198}, {42130000, 72343.9943777793}, + {42140000, 72346.3799751615}, {42150000, 72348.7777529689}, + {42160000, 72351.1586558456}, {42170000, 72353.5199935151}, + {42180000, 72355.8602009806}, {42190000, 72358.1789303154}, + {42200000, 72360.5152886551}, {42210000, 72362.9166772284}, + {42220000, 72365.3811016572}, {42230000, 72367.8446240506}, + {42240000, 72370.2901902317}, {42250000, 72372.7745481899}, + {42260000, 72375.331193684}, {42270000, 72377.9556155839}, + {42280000, 72380.6380882305}, {42290000, 72383.3748348948}, + {42300000, 72386.1077702786}, {42310000, 72388.8211498249}, + {42320000, 72391.5098311182}, {42330000, 72394.1675514791}, + {42340000, 72396.7964142049}, {42350000, 72399.4404297532}, + {42360000, 72402.1112738908}, {42370000, 72404.8026050277}, + {42380000, 72407.5106298234}, {42390000, 72410.2351855993}, + {42400000, 72412.9760100895}, {42410000, 72415.7320366708}, + {42420000, 72418.481680597}, {42430000, 72421.2191041714}, + {42440000, 72423.9553110442}, {42450000, 72426.7036430166}, + {42460000, 72429.463236873}, {42470000, 72432.2075376595}, + {42480000, 72434.9294047267}, {42490000, 72437.6401060117}, + {42500000, 72440.3463306164}, {42510000, 72443.0402003234}, + {42520000, 72445.7038885904}, {42530000, 72448.3364781961}, + {42540000, 72450.9513917651}, {42550000, 72453.5523380052}, + {42560000, 72456.15493562}, {42570000, 72458.778125795}, + {42580000, 72461.4218678167}, {42590000, 72464.0539764743}, + {42600000, 72466.6645133937}, {42610000, 72469.2527316428}, + {42620000, 72471.8182337842}, {42630000, 72474.3665297523}, + {42640000, 72476.9099242581}, {42650000, 72479.4492885373}, + {42660000, 72481.9781875058}, {42670000, 72484.4949118164}, + {42680000, 72487.007490398}, {42690000, 72489.5256546824}, + {42700000, 72492.0498545344}, {42710000, 72494.5815853556}, + {42720000, 72497.1210712437}, {42730000, 72499.6797846911}, + {42740000, 72502.2644743683}, {42750000, 72504.8725624341}, + {42760000, 72507.4983888606}, {42770000, 72510.1416563329}, + {42780000, 72512.8090989351}, {42790000, 72515.5024574824}, + {42800000, 72518.220465787}, {42810000, 72520.9616141853}, + {42820000, 72523.7280694847}, {42830000, 72526.5716428136}, + {42840000, 72529.5061426226}, {42850000, 72532.4800690093}, + {42860000, 72535.4628340656}, {42870000, 72538.4425081358}, + {42880000, 72541.3921669584}, {42890000, 72544.3113065526}, + {42900000, 72547.2414565725}, {42910000, 72550.1938630715}, + {42920000, 72553.1488093079}, {42930000, 72556.0823693819}, + {42940000, 72558.9945572493}, {42950000, 72561.8908757938}, + {42960000, 72564.7723637824}, {42970000, 72567.6629564795}, + {42980000, 72570.5768146678}, {42990000, 72573.5062459979}, + {43000000, 72576.4340004322}, {43010000, 72579.3594076847}, + {43020000, 72582.3029365147}, {43030000, 72585.2700790267}, + {43040000, 72588.2445784641}, {43050000, 72591.2067133214}, + {43060000, 72594.1547089686}, {43070000, 72597.0798438271}, + {43080000, 72599.9809533742}, {43090000, 72602.8756157149}, + {43100000, 72605.7742703975}, {43110000, 72608.6745673099}, + {43120000, 72611.5712166612}, {43130000, 72614.4630901916}, + {43140000, 72617.3356269231}, {43150000, 72620.1849399118}, + {43160000, 72623.0225911235}, {43170000, 72625.8625996416}, + {43180000, 72628.7058241747}, {43190000, 72631.5636673242}, + {43200000, 72634.4392593453}, {43210000, 72637.3429514583}, + {43220000, 72640.2808189762}, {43230000, 72643.2421082897}, + {43240000, 72646.2027149378}, {43250000, 72649.1613092473}, + {43260000, 72652.1380048415}, {43270000, 72655.138202113}, + {43280000, 72658.1417614033}, {43290000, 72661.1242444525}, + {43300000, 72664.0846100754}, {43310000, 72667.0040827574}, + {43320000, 72669.8771263166}, {43330000, 72672.7230329703}, + {43340000, 72675.5533006789}, {43350000, 72678.3629837014}, + {43360000, 72681.1407857939}, {43370000, 72683.887052608}, + {43380000, 72686.6299029716}, {43390000, 72689.376997215}, + {43400000, 72692.1360055617}, {43410000, 72694.9162576649}, + {43420000, 72697.7165488807}, {43430000, 72700.4880979498}, + {43440000, 72703.2166911449}, {43450000, 72705.961339349}, + {43460000, 72708.7570128928}, {43470000, 72711.5993442665}, + {43480000, 72714.4787682867}, {43490000, 72717.3929363641}, + {43500000, 72720.3125084398}, {43510000, 72723.2294713458}, + {43520000, 72726.1428648974}, {43530000, 72729.0515188898}, + {43540000, 72731.9563638822}, {43550000, 72734.8652993752}, + {43560000, 72737.7796759336}, {43570000, 72740.6757682447}, + {43580000, 72743.5395040635}, {43590000, 72746.3759298445}, + {43600000, 72749.1962660758}, {43610000, 72752.002935706}, + {43620000, 72754.8252986908}, {43630000, 72757.6712836733}, + {43640000, 72760.5324072472}, {43650000, 72763.3983818199}, + {43660000, 72766.2686626304}, {43670000, 72769.1299306461}, + {43680000, 72771.9780875391}, {43690000, 72774.8184023924}, + {43700000, 72777.6540163917}, {43710000, 72780.4932185916}, + {43720000, 72783.3547458333}, {43730000, 72786.2383640831}, + {43740000, 72789.1020839436}, {43750000, 72791.9345569709}, + {43760000, 72794.7582511876}, {43770000, 72797.6004701893}, + {43780000, 72800.4611911793}, {43790000, 72803.2928754127}, + {43800000, 72806.0808953599}, {43810000, 72808.8845033645}, + {43820000, 72811.7388590628}, {43830000, 72814.6233422364}, + {43840000, 72817.4915400591}, {43850000, 72820.3397306772}, + {43860000, 72823.1796655679}, {43870000, 72826.014578973}, + {43880000, 72828.8444739713}, {43890000, 72831.6693487552}, + {43900000, 72834.4892766293}, {43910000, 72837.3056297547}, + {43920000, 72840.1188090601}, {43930000, 72842.9223367172}, + {43940000, 72845.7123848378}, {43950000, 72848.4915934497}, + {43960000, 72851.2658605584}, {43970000, 72854.0370464278}, + {43980000, 72856.8341490448}, {43990000, 72859.6649682455}, + {44000000, 72862.5167654034}, {44010000, 72865.374077978}, + {44020000, 72868.2355776242}, {44030000, 72871.055917995}, + {44040000, 72873.8213338981}, {44050000, 72876.5565363236}, + {44060000, 72879.2762622936}, {44070000, 72881.9865128288}, + {44080000, 72884.7007907836}, {44090000, 72887.4203658788}, + {44100000, 72890.14597525}, {44110000, 72892.8777976955}, + {44120000, 72895.6074384891}, {44130000, 72898.3246901494}, + {44140000, 72901.0309880029}, {44150000, 72903.7647819294}, + {44160000, 72906.5364715344}, {44170000, 72909.3387106672}, + {44180000, 72912.1670749039}, {44190000, 72915.0132073331}, + {44200000, 72917.8583331242}, {44210000, 72920.7009820635}, + {44220000, 72923.5472275259}, {44230000, 72926.3987111546}, + {44240000, 72929.2513539195}, {44250000, 72932.1001942796}, + {44260000, 72934.9419552047}, {44270000, 72937.7542337803}, + {44280000, 72940.5338828096}, {44290000, 72943.3157665993}, + {44300000, 72946.1206137223}, {44310000, 72948.9409753788}, + {44320000, 72951.7600970536}, {44330000, 72954.5770220261}, + {44340000, 72957.405124528}, {44350000, 72960.2480047508}, + {44360000, 72963.0972227326}, {44370000, 72965.9425254234}, + {44380000, 72968.7836472871}, {44390000, 72971.6213382069}, + {44400000, 72974.4558230705}, {44410000, 72977.2746768445}, + {44420000, 72980.0705419939}, {44430000, 72982.8459641575}, + {44440000, 72985.6065730199}, {44450000, 72988.3532908535}, + {44460000, 72991.0936753865}, {44470000, 72993.8298086339}, + {44480000, 72996.5693194917}, {44490000, 72999.3214935526}, + {44500000, 73002.0845059093}, {44510000, 73004.8159310583}, + {44520000, 73007.504546407}, {44530000, 73010.1975111233}, + {44540000, 73012.9228610275}, {44550000, 73015.6706536729}, + {44560000, 73018.4185366275}, {44570000, 73021.1653176211}, + {44580000, 73023.9312133104}, {44590000, 73026.7216764318}, + {44600000, 73029.5126823823}, {44610000, 73032.2750017782}, + {44620000, 73035.0107964424}, {44630000, 73037.7860425844}, + {44640000, 73040.6185824435}, {44650000, 73043.4656481075}, + {44660000, 73046.3017772655}, {44670000, 73049.1180132214}, + {44680000, 73051.8939648485}, {44690000, 73054.627866114}, + {44700000, 73057.3187320368}, {44710000, 73059.9664501308}, + {44720000, 73062.571318639}, {44730000, 73065.1336528158}, + {44740000, 73067.6569280012}, {44750000, 73070.1630410591}, + {44760000, 73072.6551494161}, {44770000, 73075.1519199987}, + {44780000, 73077.6644585204}, {44790000, 73080.1958287583}, + {44800000, 73082.7530822256}, {44810000, 73085.3364568969}, + {44820000, 73087.9390483796}, {44830000, 73090.5589059953}, + {44840000, 73093.1983352304}, {44850000, 73095.8601628434}, + {44860000, 73098.5441901626}, {44870000, 73101.2408945745}, + {44880000, 73103.9473162692}, {44890000, 73106.6613631246}, + {44900000, 73109.3817756993}, {44910000, 73112.1085129537}, + {44920000, 73114.8415221958}, {44930000, 73117.5810851672}, + {44940000, 73120.334329338}, {44950000, 73123.1031503196}, + {44960000, 73125.9205271538}, {44970000, 73128.8266721683}, + {44980000, 73131.8204855149}, {44990000, 73134.7962509362}, + {45000000, 73137.7215594672}, {45010000, 73140.6238400221}, + {45020000, 73143.5194710203}, {45030000, 73146.4117620951}, + {45040000, 73149.308188125}, {45050000, 73152.2100797801}, + {45060000, 73155.1321598499}, {45070000, 73158.0783663868}, + {45080000, 73161.0169262949}, {45090000, 73163.9091413715}, + {45100000, 73166.7554513732}, {45110000, 73169.5951862752}, + {45120000, 73172.4395318313}, {45130000, 73175.2831391137}, + {45140000, 73178.1228246305}, {45150000, 73180.9585241398}, + {45160000, 73183.7900667637}, {45170000, 73186.6177703781}, + {45180000, 73189.4487854966}, {45190000, 73192.2850499053}, + {45200000, 73195.1183844093}, {45210000, 73197.9388260433}, + {45220000, 73200.7469565419}, {45230000, 73203.5496526427}, + {45240000, 73206.3481164967}, {45250000, 73209.1247837361}, + {45260000, 73211.8692259882}, {45270000, 73214.5946956432}, + {45280000, 73217.3311517557}, {45290000, 73220.0798383702}, + {45300000, 73222.8066494953}, {45310000, 73225.502356571}, + {45320000, 73228.1415329491}, {45330000, 73230.6931538476}, + {45340000, 73233.1613462625}, {45350000, 73235.5797908383}, + {45360000, 73237.9536340409}, {45370000, 73240.2670262741}, + {45380000, 73242.5106511147}, {45390000, 73244.6925957307}, + {45400000, 73246.8308033536}, {45410000, 73248.9309657592}, + {45420000, 73251.080184733}, {45430000, 73253.3020533368}, + {45440000, 73255.5982242559}, {45450000, 73257.9707949385}, + {45460000, 73260.4020937697}, {45470000, 73262.7676119119}, + {45480000, 73265.0493861161}, {45490000, 73267.3200816719}, + {45500000, 73269.6230440574}, {45510000, 73271.9813870881}, + {45520000, 73274.4478715657}, {45530000, 73277.022313624}, + {45540000, 73279.5998699136}, {45550000, 73282.1519408541}, + {45560000, 73284.7222803598}, {45570000, 73287.364232033}, + {45580000, 73290.0782835588}, {45590000, 73292.8419954065}, + {45600000, 73295.6488373037}, {45610000, 73298.4823048338}, + {45620000, 73301.3325047729}, {45630000, 73304.1802127352}, + {45640000, 73306.9816365886}, {45650000, 73309.7358955871}, + {45660000, 73312.5122524603}, {45670000, 73315.3295773178}, + {45680000, 73318.1645576307}, {45690000, 73320.9888020977}, + {45700000, 73323.800048967}, {45710000, 73326.5653255949}, + {45720000, 73329.2757872069}, {45730000, 73331.932574437}, + {45740000, 73334.5364752982}, {45750000, 73337.1120433928}, + {45760000, 73339.7147701529}, {45770000, 73342.3466931716}, + {45780000, 73344.9393433806}, {45790000, 73347.4741772908}, + {45800000, 73349.9987315729}, {45810000, 73352.570976305}, + {45820000, 73355.1843105206}, {45830000, 73357.7705835094}, + {45840000, 73360.3181399924}, {45850000, 73362.8956150153}, + {45860000, 73365.5438692542}, {45870000, 73368.2560209591}, + {45880000, 73371.0168582262}, {45890000, 73373.8218818777}, + {45900000, 73376.6055642069}, {45910000, 73379.3500844443}, + {45920000, 73382.0893135576}, {45930000, 73384.8645588467}, + {45940000, 73387.6767160345}, {45950000, 73390.5205671041}, + {45960000, 73393.3945453608}, {45970000, 73396.2543891128}, + {45980000, 73399.0737037611}, {45990000, 73401.8706138608}, + {46000000, 73404.686159217}, {46010000, 73407.524187944}, + {46020000, 73410.3869894513}, {46030000, 73413.2750994214}, + {46040000, 73416.1717046517}, {46050000, 73419.056324332}, + {46060000, 73421.9294244756}, {46070000, 73424.8131438509}, + {46080000, 73427.7134008476}, {46090000, 73430.6116701952}, + {46100000, 73433.4968968716}, {46110000, 73436.3687650029}, + {46120000, 73439.2264722589}, {46130000, 73442.0706311784}, + {46140000, 73444.9155333219}, {46150000, 73447.7650795433}, + {46160000, 73450.6075297836}, {46170000, 73453.4285564091}, + {46180000, 73456.2281984587}, {46190000, 73459.027837299}, + {46200000, 73461.8340502771}, {46210000, 73464.6463380324}, + {46220000, 73467.4643903423}, {46230000, 73470.2882017061}, + {46240000, 73473.1177964387}, {46250000, 73475.953150123}, + {46260000, 73478.7942217409}, {46270000, 73481.6409793988}, + {46280000, 73484.473523884}, {46290000, 73487.2675676236}, + {46300000, 73490.0223324905}, {46310000, 73492.7324307008}, + {46320000, 73495.3965161034}, {46330000, 73498.0282948386}, + {46340000, 73500.6360238421}, {46350000, 73503.2174064723}, + {46360000, 73505.7670436978}, {46370000, 73508.2842469663}, + {46380000, 73510.7616696576}, {46390000, 73513.1974473512}, + {46400000, 73515.6304475074}, {46410000, 73518.1081142659}, + {46420000, 73520.6315429125}, {46430000, 73523.1832788595}, + {46440000, 73525.7576544719}, {46450000, 73528.4100632005}, + {46460000, 73531.173460101}, {46470000, 73534.0351423529}, + {46480000, 73536.9668754002}, {46490000, 73539.962501657}, + {46500000, 73542.948493046}, {46510000, 73545.9048012476}, + {46520000, 73548.7954272484}, {46530000, 73551.5763881753}, + {46540000, 73554.248934674}, {46550000, 73556.8592234813}, + {46560000, 73559.4199885967}, {46570000, 73561.9473344784}, + {46580000, 73564.4509538296}, {46590000, 73566.9609650152}, + {46600000, 73569.5458449477}, {46610000, 73572.2102526572}, + {46620000, 73574.9219828635}, {46630000, 73577.6720605538}, + {46640000, 73580.4537378674}, {46650000, 73583.2588131377}, + {46660000, 73586.0870995176}, {46670000, 73588.9434770714}, + {46680000, 73591.8292295176}, {46690000, 73594.7064126414}, + {46700000, 73597.5523630286}, {46710000, 73600.3772082536}, + {46720000, 73603.2038498535}, {46730000, 73606.0344756454}, + {46740000, 73608.8704062489}, {46750000, 73611.7119834877}, + {46760000, 73614.5470256983}, {46770000, 73617.3606547739}, + {46780000, 73620.1538180319}, {46790000, 73622.9634509427}, + {46800000, 73625.799994613}, {46810000, 73628.6448282646}, + {46820000, 73631.4867909329}, {46830000, 73634.3390095802}, + {46840000, 73637.2313774045}, {46850000, 73640.1631404899}, + {46860000, 73643.0571152091}, {46870000, 73645.8923388579}, + {46880000, 73648.7179959012}, {46890000, 73651.5941674464}, + {46900000, 73654.5216559214}, {46910000, 73657.4531875774}, + {46920000, 73660.3741841162}, {46930000, 73663.2822582115}, + {46940000, 73666.1760067383}, {46950000, 73669.055454781}, + {46960000, 73671.9205676701}, {46970000, 73674.7714064238}, + {46980000, 73677.6080299381}, {46990000, 73680.4305057335}, + {47000000, 73683.2427419112}, {47010000, 73686.0494976826}, + {47020000, 73688.8512843522}, {47030000, 73691.6575859375}, + {47040000, 73694.4710780201}, {47050000, 73697.3026543494}, + {47060000, 73700.1587988637}, {47070000, 73703.0262248948}, + {47080000, 73705.8746849217}, {47090000, 73708.7035362513}, + {47100000, 73711.5612241363}, {47110000, 73714.460898736}, + {47120000, 73717.3747051287}, {47130000, 73720.2686271379}, + {47140000, 73723.1413713724}, {47150000, 73725.9902077493}, + {47160000, 73728.8147575542}, {47170000, 73731.621130579}, + {47180000, 73734.4130196453}, {47190000, 73737.19333086}, + {47200000, 73739.9686003999}, {47210000, 73742.7382320239}, + {47220000, 73745.4739804478}, {47230000, 73748.1682403953}, + {47240000, 73750.8290791604}, {47250000, 73753.4663151138}, + {47260000, 73756.081062928}, {47270000, 73758.688397494}, + {47280000, 73761.2924089974}, {47290000, 73763.9050272521}, + {47300000, 73766.5333842859}, {47310000, 73769.1857545418}, + {47320000, 73771.8811341914}, {47330000, 73774.62146275}, + {47340000, 73777.4147854707}, {47350000, 73780.2631118709}, + {47360000, 73783.1409121695}, {47370000, 73786.0170284097}, + {47380000, 73788.8902114935}, {47390000, 73791.7442740727}, + {47400000, 73794.5743100606}, {47410000, 73797.4098255417}, + {47420000, 73800.2684915626}, {47430000, 73803.1373926583}, + {47440000, 73805.9871846197}, {47450000, 73808.8154494289}, + {47460000, 73811.6277379755}, {47470000, 73814.4256267339}, + {47480000, 73817.1850345235}, {47490000, 73819.8764960027}, + {47500000, 73822.5024516284}, {47510000, 73825.0885782474}, + {47520000, 73827.6394959378}, {47530000, 73830.1627386384}, + {47540000, 73832.6628760617}, {47550000, 73835.1482677208}, + {47560000, 73837.6378544152}, {47570000, 73840.1331219994}, + {47580000, 73842.6279347514}, {47590000, 73845.120614194}, + {47600000, 73847.6028124332}, {47610000, 73850.0643097771}, + {47620000, 73852.5056450959}, {47630000, 73854.9332505424}, + {47640000, 73857.3482975071}, {47650000, 73859.7569765423}, + {47660000, 73862.1630100516}, {47670000, 73864.5557988551}, + {47680000, 73866.911122294}, {47690000, 73869.2283752296}, + {47700000, 73871.54211482}, {47710000, 73873.8618164199}, + {47720000, 73876.1842300352}, {47730000, 73878.5053846999}, + {47740000, 73880.8273433434}, {47750000, 73883.1646806926}, + {47760000, 73885.5193852195}, {47770000, 73887.8976906144}, + {47780000, 73890.303300307}, {47790000, 73892.7228245412}, + {47800000, 73895.1256993232}, {47810000, 73897.5112244688}, + {47820000, 73899.9277909116}, {47830000, 73902.3885371426}, + {47840000, 73904.8657739673}, {47850000, 73907.3256338598}, + {47860000, 73909.7670211046}, {47870000, 73912.1864930509}, + {47880000, 73914.5831463842}, {47890000, 73916.9752855454}, + {47900000, 73919.3738886708}, {47910000, 73921.7793220206}, + {47920000, 73924.192463506}, {47930000, 73926.6155303269}, + {47940000, 73929.0985936866}, {47950000, 73931.6551475062}, + {47960000, 73934.2334436975}, {47970000, 73936.7701771348}, + {47980000, 73939.2651429749}, {47990000, 73941.7638889911}, + {48000000, 73944.2793953515}, {48010000, 73946.8765798843}, + {48020000, 73949.5942335296}, {48030000, 73952.4009908207}, + {48040000, 73955.2259260295}, {48050000, 73958.062766056}, + {48060000, 73960.9216468261}, {48070000, 73963.8052665019}, + {48080000, 73966.7046389105}, {48090000, 73969.6087847089}, + {48100000, 73972.5168326035}, {48110000, 73975.3995725441}, + {48120000, 73978.2480924665}, {48130000, 73981.0802672143}, + {48140000, 73983.9068682475}, {48150000, 73986.7336628296}, + {48160000, 73989.5738699105}, {48170000, 73992.4283923223}, + {48180000, 73995.2907494465}, {48190000, 73998.1591383982}, + {48200000, 74001.0326700745}, {48210000, 74003.9102622767}, + {48220000, 74006.7909587922}, {48230000, 74009.6538355273}, + {48240000, 74012.4932241131}, {48250000, 74015.3147234289}, + {48260000, 74018.1217283891}, {48270000, 74020.925192778}, + {48280000, 74023.7500636025}, {48290000, 74026.5970954905}, + {48300000, 74029.4318368576}, {48310000, 74032.2448904489}, + {48320000, 74035.0279937822}, {48330000, 74037.7710007619}, + {48340000, 74040.4743060339}, {48350000, 74043.1492667536}, + {48360000, 74045.7990497342}, {48370000, 74048.4484828553}, + {48380000, 74051.1124642848}, {48390000, 74053.7941628607}, + {48400000, 74056.5009162158}, {48410000, 74059.2333160407}, + {48420000, 74061.9916736931}, {48430000, 74064.7759806958}, + {48440000, 74067.5963836509}, {48450000, 74070.4653521019}, + {48460000, 74073.3804350776}, {48470000, 74076.2885600249}, + {48480000, 74079.1756422716}, {48490000, 74082.033908316}, + {48500000, 74084.8587447986}, {48510000, 74087.6286286461}, + {48520000, 74090.2940895015}, {48530000, 74092.8536113461}, + {48540000, 74095.3692114979}, {48550000, 74097.8580591275}, + {48560000, 74100.3111753408}, {48570000, 74102.7175212692}, + {48580000, 74105.0777901619}, {48590000, 74107.4406232988}, + {48600000, 74109.8210315532}, {48610000, 74112.2602658496}, + {48620000, 74114.7829934011}, {48630000, 74117.3763428659}, + {48640000, 74120.0113973114}, {48650000, 74122.6833484918}, + {48660000, 74125.3474410661}, {48670000, 74127.991427651}, + {48680000, 74130.6384834935}, {48690000, 74133.3169980913}, + {48700000, 74136.0344476609}, {48710000, 74138.8473035559}, + {48720000, 74141.7650026553}, {48730000, 74144.6988644147}, + {48740000, 74147.5955778433}, {48750000, 74150.4667926888}, + {48760000, 74153.3389575612}, {48770000, 74156.2143026034}, + {48780000, 74159.0871713256}, {48790000, 74161.9560211763}, + {48800000, 74164.8127035776}, {48810000, 74167.6472238109}, + {48820000, 74170.4599715189}, {48830000, 74173.2647371566}, + {48840000, 74176.0653215496}, {48850000, 74178.8500222409}, + {48860000, 74181.611839809}, {48870000, 74184.3533266371}, + {48880000, 74187.0801761313}, {48890000, 74189.7942292532}, + {48900000, 74192.5244718838}, {48910000, 74195.2787959643}, + {48920000, 74198.0775693516}, {48930000, 74200.9457906108}, + {48940000, 74203.8734002939}, {48950000, 74206.7684771302}, + {48960000, 74209.6146377945}, {48970000, 74212.4384493261}, + {48980000, 74215.2559376212}, {48990000, 74218.0596636715}, + {49000000, 74220.8325443874}, {49010000, 74223.5733832383}, + {49020000, 74226.2885072717}, {49030000, 74228.9797462345}, + {49040000, 74231.6228310999}, {49050000, 74234.1879807273}, + {49060000, 74236.6854546406}, {49070000, 74239.1936927178}, + {49080000, 74241.7242798563}, {49090000, 74244.2976031062}, + {49100000, 74246.9258423358}, {49110000, 74249.6253288439}, + {49120000, 74252.4338313763}, {49130000, 74255.3504931978}, + {49140000, 74258.2839448578}, {49150000, 74261.209064318}, + {49160000, 74264.1118019743}, {49170000, 74266.9749089969}, + {49180000, 74269.7967620373}, {49190000, 74272.5409863384}, + {49200000, 74275.1974897737}, {49210000, 74277.804865839}, + {49220000, 74280.3864279459}, {49230000, 74282.9457719444}, + {49240000, 74285.4909688162}, {49250000, 74288.0225523026}, + {49260000, 74290.5339048594}, {49270000, 74293.0232829269}, + {49280000, 74295.5173877965}, {49290000, 74298.0489571396}, + {49300000, 74300.61836693}, {49310000, 74303.1973294336}, + {49320000, 74305.777076966}, {49330000, 74308.4082710891}, + {49340000, 74311.1212866015}, {49350000, 74313.9088367162}, + {49360000, 74316.7547567858}, {49370000, 74319.6535584816}, + {49380000, 74322.5182192777}, {49390000, 74325.324973373}, + {49400000, 74328.1191549581}, {49410000, 74330.9563696299}, + {49420000, 74333.8363200569}, {49430000, 74336.7091454245}, + {49440000, 74339.5608121668}, {49450000, 74342.4131159314}, + {49460000, 74345.2791837386}, {49470000, 74348.1513808837}, + {49480000, 74351.0122870956}, {49490000, 74353.860582998}, + {49500000, 74356.702487146}, {49510000, 74359.5397311417}, + {49520000, 74362.3723906555}, {49530000, 74365.2005531983}, + {49540000, 74368.024297308}, {49550000, 74370.8441021587}, + {49560000, 74373.6600677734}, {49570000, 74376.4661547202}, + {49580000, 74379.2587493661}, {49590000, 74382.0458323967}, + {49600000, 74384.8455997687}, {49610000, 74387.6591344005}, + {49620000, 74390.473135528}, {49630000, 74393.2839471303}, + {49640000, 74396.083262085}, {49650000, 74398.8608750777}, + {49660000, 74401.6169496084}, {49670000, 74404.3731217057}, + {49680000, 74407.1360467091}, {49690000, 74409.893487904}, + {49700000, 74412.6380854869}, {49710000, 74415.3911374156}, + {49720000, 74418.2014051763}, {49730000, 74421.0699679614}, + {49740000, 74423.9206592749}, {49750000, 74426.7326171709}, + {49760000, 74429.5426527662}, {49770000, 74432.395927135}, + {49780000, 74435.2929952858}, {49790000, 74438.1842578278}, + {49800000, 74441.0541954101}, {49810000, 74443.9011474763}, + {49820000, 74446.7241590581}, {49830000, 74449.5420825233}, + {49840000, 74452.3979987912}, {49850000, 74455.293452344}, + {49860000, 74458.1735277125}, {49870000, 74461.023179938}, + {49880000, 74463.8607418798}, {49890000, 74466.7086919462}, + {49900000, 74469.5684192343}, {49910000, 74472.4610701383}, + {49920000, 74475.3925649791}, {49930000, 74478.3134298085}, + {49940000, 74481.1938475573}, {49950000, 74484.0436981974}, + {49960000, 74486.8854024417}, {49970000, 74489.7214568611}, + {49980000, 74492.5602997787}, {49990000, 74495.4042414708}, + {50000000, 74498.2489309155}, {50010000, 74501.0890307429}, + {50020000, 74503.9244157111}, {50030000, 74506.7563820129}, + {50040000, 74509.5853422488}, {50050000, 74512.4164391136}, + {50060000, 74515.2527660248}, {50070000, 74518.0863870046}, + {50080000, 74520.8991160087}, {50090000, 74523.6902080914}, + {50100000, 74526.4801949735}, {50110000, 74529.2747263836}, + {50120000, 74532.0622017589}, {50130000, 74534.8283682795}, + {50140000, 74537.573748621}, {50150000, 74540.3196730502}, + {50160000, 74543.0720442098}, {50170000, 74545.8071193751}, + {50180000, 74548.5106131837}, {50190000, 74551.1928914864}, + {50200000, 74553.8775480323}, {50210000, 74556.5677501589}, + {50220000, 74559.2863124737}, {50230000, 74562.0394113823}, + {50240000, 74564.8067619047}, {50250000, 74567.5634723143}, + {50260000, 74570.3085630529}, {50270000, 74573.0403386369}, + {50280000, 74575.7586045704}, {50290000, 74578.4927215074}, + {50300000, 74581.2603658465}, {50310000, 74584.0700932987}, + {50320000, 74586.9417641952}, {50330000, 74589.8736716925}, + {50340000, 74592.7879685908}, {50350000, 74595.6633123017}, + {50360000, 74598.5215793028}, {50370000, 74601.3896122566}, + {50380000, 74604.2678790405}, {50390000, 74607.1464648456}, + {50400000, 74610.0225309337}, {50410000, 74612.8949269569}, + {50420000, 74615.7629654446}, {50430000, 74618.6320184853}, + {50440000, 74621.5144046853}, {50450000, 74624.4106439752}, + {50460000, 74627.3070845029}, {50470000, 74630.1999716039}, + {50480000, 74633.0885885812}, {50490000, 74635.9720496419}, + {50500000, 74638.8504066002}, {50510000, 74641.7248917337}, + {50520000, 74644.5958527513}, {50530000, 74647.4803745806}, + {50540000, 74650.3887345758}, {50550000, 74653.3158586955}, + {50560000, 74656.2502276826}, {50570000, 74659.1906991968}, + {50580000, 74662.1365922049}, {50590000, 74665.087699571}, + {50600000, 74668.0433277813}, {50610000, 74671.002629843}, + {50620000, 74673.9663902324}, {50630000, 74676.9526235279}, + {50640000, 74679.9661174651}, {50650000, 74682.9875750745}, + {50660000, 74686.0053277907}, {50670000, 74689.0136479006}, + {50680000, 74691.9993470393}, {50690000, 74694.9621672596}, + {50700000, 74697.9229164508}, {50710000, 74700.8873237676}, + {50720000, 74703.8558893882}, {50730000, 74706.8292328831}, + {50740000, 74709.8063180348}, {50750000, 74712.7800788784}, + {50760000, 74715.7495301865}, {50770000, 74718.7025883617}, + {50780000, 74721.6319885652}, {50790000, 74724.5456237844}, + {50800000, 74727.4614810693}, {50810000, 74730.3803755126}, + {50820000, 74733.2818567493}, {50830000, 74736.1603595321}, + {50840000, 74739.0308600973}, {50850000, 74741.9117541236}, + {50860000, 74744.8030351698}, {50870000, 74747.6709248457}, + {50880000, 74750.5050391198}, {50890000, 74753.352346587}, + {50900000, 74756.2411845276}, {50910000, 74759.1483235489}, + {50920000, 74762.0204726533}, {50930000, 74764.8532431478}, + {50940000, 74767.6580538802}, {50950000, 74770.4381560601}, + {50960000, 74773.2207186883}, {50970000, 74776.0391340231}, + {50980000, 74778.8940144419}, {50990000, 74781.765136895}, + {51000000, 74784.6461195242}, {51010000, 74787.5284118707}, + {51020000, 74790.406847961}, {51030000, 74793.2812907542}, + {51040000, 74796.1513998273}, {51050000, 74799.0171617303}, + {51060000, 74801.8785734068}, {51070000, 74804.7356497056}, + {51080000, 74807.5728259788}, {51090000, 74810.3709345564}, + {51100000, 74813.129637036}, {51110000, 74815.8516052964}, + {51120000, 74818.5377345404}, {51130000, 74821.2190374934}, + {51140000, 74823.9142753156}, {51150000, 74826.6133380552}, + {51160000, 74829.2930551795}, {51170000, 74831.9524896569}, + {51180000, 74834.6190206562}, {51190000, 74837.3001575002}, + {51200000, 74839.9922286527}, {51210000, 74842.6907310696}, + {51220000, 74845.3991024923}, {51230000, 74848.1478398367}, + {51240000, 74850.9421125334}, {51250000, 74853.7466396308}, + {51260000, 74856.5400685823}, {51270000, 74859.3350604045}, + {51280000, 74862.1607050149}, {51290000, 74865.0181700271}, + {51300000, 74867.8731868852}, {51310000, 74870.7163177107}, + {51320000, 74873.5670849685}, {51330000, 74876.4495772784}, + {51340000, 74879.3565666803}, {51350000, 74882.2312318815}, + {51360000, 74885.0652849629}, {51370000, 74887.8920657308}, + {51380000, 74890.7317471914}, {51390000, 74893.5823390556}, + {51400000, 74896.4393460248}, {51410000, 74899.3020055063}, + {51420000, 74902.1628910845}, {51430000, 74905.0199636504}, + {51440000, 74907.8729644847}, {51450000, 74910.7215705722}, + {51460000, 74913.5658189735}, {51470000, 74916.4059210968}, + {51480000, 74919.2419260539}, {51490000, 74922.0737714449}, + {51500000, 74924.9014276788}, {51510000, 74927.7356201245}, + {51520000, 74930.6010253717}, {51530000, 74933.4977844294}, + {51540000, 74936.3770943358}, {51550000, 74939.2255646473}, + {51560000, 74942.0540623285}, {51570000, 74944.875941131}, + {51580000, 74947.692024672}, {51590000, 74950.512349093}, + {51600000, 74953.3397383656}, {51610000, 74956.1792086279}, + {51620000, 74959.033773147}, {51630000, 74961.8954747973}, + {51640000, 74964.7460842891}, {51650000, 74967.5844926838}, + {51660000, 74970.424007262}, {51670000, 74973.2682924119}, + {51680000, 74976.1132387236}, {51690000, 74978.9537924775}, + {51700000, 74981.7894933201}, {51710000, 74984.6134807377}, + {51720000, 74987.4239481694}, {51730000, 74990.2323511436}, + {51740000, 74993.045629072}, {51750000, 74995.8586702638}, + {51760000, 74998.6597326842}, {51770000, 75001.4486374905}, + {51780000, 75004.2462359633}, {51790000, 75007.0582447629}, + {51800000, 75009.8727456831}, {51810000, 75012.6750702006}, + {51820000, 75015.4620335698}, {51830000, 75018.2101856431}, + {51840000, 75020.9155729351}, {51850000, 75023.613200178}, + {51860000, 75026.3242750129}, {51870000, 75029.0441586898}, + {51880000, 75031.7622544456}, {51890000, 75034.478447676}, + {51900000, 75037.2135999626}, {51910000, 75039.9733937909}, + {51920000, 75042.7416673624}, {51930000, 75045.4985353182}, + {51940000, 75048.2457143715}, {51950000, 75051.0445660649}, + {51960000, 75053.9121791226}, {51970000, 75056.7874255422}, + {51980000, 75059.6332352384}, {51990000, 75062.445802524}, + {52000000, 75065.2161466214}, {52010000, 75067.9427002101}, + {52020000, 75070.6037045428}, {52030000, 75073.1933859433}, + {52040000, 75075.7096272035}, {52050000, 75078.1497325684}, + {52060000, 75080.5155728324}, {52070000, 75082.8451482742}, + {52080000, 75085.1490476654}, {52090000, 75087.4181458554}, + {52100000, 75089.6469790922}, {52110000, 75091.8488914237}, + {52120000, 75094.0543884185}, {52130000, 75096.2663972774}, + {52140000, 75098.4866193907}, {52150000, 75100.7154941604}, + {52160000, 75102.9597171411}, {52170000, 75105.2275488059}, + {52180000, 75107.5187252103}, {52190000, 75109.8004297021}, + {52200000, 75112.0623826991}, {52210000, 75114.2803444339}, + {52220000, 75116.4397067305}, {52230000, 75118.5642500771}, + {52240000, 75120.7084246005}, {52250000, 75122.8773971882}, + {52260000, 75125.0741953771}, {52270000, 75127.2995541559}, + {52280000, 75129.5633974269}, {52290000, 75131.8779976205}, + {52300000, 75134.2446367456}, {52310000, 75136.6969886725}, + {52320000, 75139.2444099272}, {52330000, 75141.8931430002}, + {52340000, 75144.6467815364}, {52350000, 75147.4703372272}, + {52360000, 75150.2838196012}, {52370000, 75153.0813454476}, + {52380000, 75155.9013117121}, {52390000, 75158.7542311106}, + {52400000, 75161.6315080753}, {52410000, 75164.52258141}, + {52420000, 75167.4267302348}, {52430000, 75170.3242177653}, + {52440000, 75173.2089525257}, {52450000, 75176.0682678116}, + {52460000, 75178.8945215353}, {52470000, 75181.6956078899}, + {52480000, 75184.4895389352}, {52490000, 75187.278384857}, + {52500000, 75190.0703431617}, {52510000, 75192.8676642982}, + {52520000, 75195.6698959105}, {52530000, 75198.476486509}, + {52540000, 75201.2888589029}, {52550000, 75204.1406960999}, + {52560000, 75207.041076128}, {52570000, 75209.9466938252}, + {52580000, 75212.8312431747}, {52590000, 75215.704627876}, + {52600000, 75218.5895462159}, {52610000, 75221.4869419476}, + {52620000, 75224.3694271629}, {52630000, 75227.2294993645}, + {52640000, 75230.0706344512}, {52650000, 75232.8970923905}, + {52660000, 75235.7093499502}, {52670000, 75238.5155821843}, + {52680000, 75241.318157719}, {52690000, 75244.1168333949}, + {52700000, 75246.9114691412}, {52710000, 75249.7260920627}, + {52720000, 75252.6162175123}, {52730000, 75255.5827192613}, + {52740000, 75258.528342446}, {52750000, 75261.426300111}, + {52760000, 75264.2982278937}, {52770000, 75267.1707806206}, + {52780000, 75270.0430963505}, {52790000, 75272.8647677948}, + {52800000, 75275.6215601008}, {52810000, 75278.3380383458}, + {52820000, 75281.0291973421}, {52830000, 75283.6983294258}, + {52840000, 75286.3528710964}, {52850000, 75288.994200125}, + {52860000, 75291.6371151321}, {52870000, 75294.2856978414}, + {52880000, 75296.9132530361}, {52890000, 75299.4868290425}, + {52900000, 75302.0057141442}, {52910000, 75304.4760833113}, + {52920000, 75306.9000216864}, {52930000, 75309.2921410581}, + {52940000, 75311.6613870639}, {52950000, 75314.0241606907}, + {52960000, 75316.418224822}, {52970000, 75318.8459009409}, + {52980000, 75321.2805658191}, {52990000, 75323.714840834}, + {53000000, 75326.1438105236}, {53010000, 75328.5614005779}, + {53020000, 75330.9679745941}, {53030000, 75333.3788795822}, + {53040000, 75335.7985102079}, {53050000, 75338.2321028193}, + {53060000, 75340.6828140105}, {53070000, 75343.1506972072}, + {53080000, 75345.6359883214}, {53090000, 75348.1377417426}, + {53100000, 75350.634444048}, {53110000, 75353.120171344}, + {53120000, 75355.5943650093}, {53130000, 75358.0563222438}, + {53140000, 75360.5113319381}, {53150000, 75363.0043550809}, + {53160000, 75365.543181287}, {53170000, 75368.1107722147}, + {53180000, 75370.6967128171}, {53190000, 75373.2978768327}, + {53200000, 75375.9071579843}, {53210000, 75378.5244242426}, + {53220000, 75381.1635431622}, {53230000, 75383.8282694987}, + {53240000, 75386.5213939015}, {53250000, 75389.2463954005}, + {53260000, 75392.002829829}, {53270000, 75394.7814653991}, + {53280000, 75397.5797072317}, {53290000, 75400.4186282867}, + {53300000, 75403.3109619273}, {53310000, 75406.2356295109}, + {53320000, 75409.1442556657}, {53330000, 75412.032530729}, + {53340000, 75414.904888474}, {53350000, 75417.7626118799}, + {53360000, 75420.59840373}, {53370000, 75423.4032295777}, + {53380000, 75426.1766042896}, {53390000, 75428.8911565723}, + {53400000, 75431.5384777188}, {53410000, 75434.1156056635}, + {53420000, 75436.6208730832}, {53430000, 75439.062487052}, + {53440000, 75441.4589474393}, {53450000, 75443.8104723343}, + {53460000, 75446.0754153123}, {53470000, 75448.242575735}, + {53480000, 75450.3444894029}, {53490000, 75452.4212421562}, + {53500000, 75454.4718703791}, {53510000, 75456.4763027528}, + {53520000, 75458.4312087453}, {53530000, 75460.3953331899}, + {53540000, 75462.4043748343}, {53550000, 75464.4940961389}, + {53560000, 75466.7474617937}, {53570000, 75469.1699829311}, + {53580000, 75471.7227608933}, {53590000, 75474.39457359}, + {53600000, 75477.1982860053}, {53610000, 75480.1499377618}, + {53620000, 75483.2186505724}, {53630000, 75486.1425219701}, + {53640000, 75488.8760371498}, {53650000, 75491.5824122441}, + {53660000, 75494.3610610867}, {53670000, 75497.1512838671}, + {53680000, 75499.8130883172}, {53690000, 75502.3402780413}, + {53700000, 75504.8898979002}, {53710000, 75507.5053158612}, + {53720000, 75510.1740135628}, {53730000, 75512.8805888361}, + {53740000, 75515.6221614044}, {53750000, 75518.3833451246}, + {53760000, 75521.1618744708}, {53770000, 75523.810692893}, + {53780000, 75526.2402984006}, {53790000, 75528.5681332178}, + {53800000, 75531.0654096322}, {53810000, 75533.7517730083}, + {53820000, 75536.4988063568}, {53830000, 75539.2707628041}, + {53840000, 75542.0589632078}, {53850000, 75544.8527040976}, + {53860000, 75547.65194255}, {53870000, 75550.4665752442}, + {53880000, 75553.2993868158}, {53890000, 75556.1077963221}, + {53900000, 75558.8659289525}, {53910000, 75561.578439457}, + {53920000, 75564.255768792}, {53930000, 75566.9026153394}, + {53940000, 75569.605517778}, {53950000, 75572.3882164426}, + {53960000, 75575.1734146961}, {53970000, 75577.8655356268}, + {53980000, 75580.4710495294}, {53990000, 75583.2683605546}, + {54000000, 75586.3368535645}, {54010000, 75589.3541341934}, + {54020000, 75592.1240371691}, {54030000, 75594.7474871346}, + {54040000, 75597.4564101542}, {54050000, 75600.2699122323}, + {54060000, 75603.1293044274}, {54070000, 75606.0181843569}, + {54080000, 75608.8956461602}, {54090000, 75611.7110945172}, + {54100000, 75614.464266801}, {54110000, 75617.2378205484}, + {54120000, 75620.0576015383}, {54130000, 75622.9112137534}, + {54140000, 75625.79103587}, {54150000, 75628.6860920246}, + {54160000, 75631.5711277861}, {54170000, 75634.4451968438}, + {54180000, 75637.3426585227}, {54190000, 75640.2729584148}, + {54200000, 75643.2237987048}, {54210000, 75646.1799975902}, + {54220000, 75649.1411026993}, {54230000, 75652.1087231116}, + {54240000, 75655.0832792823}, {54250000, 75658.0577308441}, + {54260000, 75661.0277865635}, {54270000, 75663.980006036}, + {54280000, 75666.8832236159}, {54290000, 75669.7375750175}, + {54300000, 75672.6130574518}, {54310000, 75675.5289767145}, + {54320000, 75678.4469558864}, {54330000, 75681.3195430869}, + {54340000, 75684.1464298023}, {54350000, 75686.9509685477}, + {54360000, 75689.7396114802}, {54370000, 75692.5252797216}, + {54380000, 75695.3158550523}, {54390000, 75698.1142648734}, + {54400000, 75700.9273232858}, {54410000, 75703.7556226965}, + {54420000, 75706.5994535082}, {54430000, 75709.4588402254}, + {54440000, 75712.3251014115}, {54450000, 75715.1875015141}, + {54460000, 75718.0457325268}, {54470000, 75720.9004196263}, + {54480000, 75723.7517491903}, {54490000, 75726.6342589518}, + {54500000, 75729.5689410419}, {54510000, 75732.5350277768}, + {54520000, 75735.4847516718}, {54530000, 75738.4141473763}, + {54540000, 75741.3348351895}, {54550000, 75744.2500640556}, + {54560000, 75747.159816159}, {54570000, 75750.0640628399}, + {54580000, 75752.9628532031}, {54590000, 75755.8577470368}, + {54600000, 75758.7492423751}, {54610000, 75761.6659049994}, + {54620000, 75764.6251207561}, {54630000, 75767.6033839554}, + {54640000, 75770.5464621908}, {54650000, 75773.4507208541}, + {54660000, 75776.3490152323}, {54670000, 75779.2504718092}, + {54680000, 75782.1718595003}, {54690000, 75785.1339377727}, + {54700000, 75788.1280183045}, {54710000, 75791.0755208287}, + {54720000, 75793.96274964}, {54730000, 75796.8461265865}, + {54740000, 75799.7600946901}, {54750000, 75802.6977597441}, + {54760000, 75805.6433350157}, {54770000, 75808.595258056}, + {54780000, 75811.5526481898}, {54790000, 75814.515241687}, + {54800000, 75817.4746864028}, {54810000, 75820.4206421207}, + {54820000, 75823.3531470196}, {54830000, 75826.2793888196}, + {54840000, 75829.2013545075}, {54850000, 75832.1071201259}, + {54860000, 75834.9894301059}, {54870000, 75837.8481407013}, + {54880000, 75840.6827636357}, {54890000, 75843.4945271863}, + {54900000, 75846.3121198562}, {54910000, 75849.1434709713}, + {54920000, 75851.9889451355}, {54930000, 75854.8490107442}, + {54940000, 75857.7229303302}, {54950000, 75860.6046131712}, + {54960000, 75863.492922417}, {54970000, 75866.3871467628}, + {54980000, 75869.2868406767}, {54990000, 75872.1839803646}, + {55000000, 75875.0599934929}, {55010000, 75877.9140508808}, + {55020000, 75880.7666284817}, {55030000, 75883.6234060193}, + {55040000, 75886.4766966337}, {55050000, 75889.3169830361}, + {55060000, 75892.146962045}, {55070000, 75894.9882734917}, + {55080000, 75897.8441366184}, {55090000, 75900.6917160346}, + {55100000, 75903.5170729478}, {55110000, 75906.3357642084}, + {55120000, 75909.1837607384}, {55130000, 75912.0620836363}, + {55140000, 75914.9154463387}, {55150000, 75917.7286173735}, + {55160000, 75920.5164272884}, {55170000, 75923.2971991317}, + {55180000, 75926.0733923025}, {55190000, 75928.9024390286}, + {55200000, 75931.8007486195}, {55210000, 75934.7128245952}, + {55220000, 75937.6047265014}, {55230000, 75940.472752249}, + {55240000, 75943.3081733002}, {55250000, 75946.1120326469}, + {55260000, 75948.9268676607}, {55270000, 75951.7644368252}, + {55280000, 75954.613021115}, {55290000, 75957.458118647}, + {55300000, 75960.2991608375}, {55310000, 75963.1289283283}, + {55320000, 75965.9452148415}, {55330000, 75968.7769245358}, + {55340000, 75971.6416910957}, {55350000, 75974.521402106}, + {55360000, 75977.3742251401}, {55370000, 75980.197387667}, + {55380000, 75983.0172113714}, {55390000, 75985.8410087233}, + {55400000, 75988.6461955888}, {55410000, 75991.4047762494}, + {55420000, 75994.1166775678}, {55430000, 75996.8137637459}, + {55440000, 75999.5058064823}, {55450000, 76002.1820195594}, + {55460000, 76004.8358419694}, {55470000, 76007.4777783591}, + {55480000, 76010.132068959}, {55490000, 76012.8001513031}, + {55500000, 76015.4619256237}, {55510000, 76018.111821286}, + {55520000, 76020.7613550894}, {55530000, 76023.4247914455}, + {55540000, 76026.1036648441}, {55550000, 76028.8077116643}, + {55560000, 76031.5385675006}, {55570000, 76034.2898862476}, + {55580000, 76037.0577455568}, {55590000, 76039.844601938}, + {55600000, 76042.6562744562}, {55610000, 76045.492634529}, + {55620000, 76048.339588736}, {55630000, 76051.1931900818}, + {55640000, 76054.0484388549}, {55650000, 76056.8991443604}, + {55660000, 76059.7450225275}, {55670000, 76062.5793819869}, + {55680000, 76065.4001830548}, {55690000, 76068.2188287398}, + {55700000, 76071.0423004462}, {55710000, 76073.873496617}, + {55720000, 76076.7191784303}, {55730000, 76079.57906814}, + {55740000, 76082.4320314425}, {55750000, 76085.2722266669}, + {55760000, 76088.1028561515}, {55770000, 76090.9278779563}, + {55780000, 76093.7473559741}, {55790000, 76096.5552184923}, + {55800000, 76099.3496187037}, {55810000, 76102.1478209829}, + {55820000, 76104.9603817414}, {55830000, 76107.7743424337}, + {55840000, 76110.5596800407}, {55850000, 76113.3156017049}, + {55860000, 76116.0905658187}, {55870000, 76118.8979999991}, + {55880000, 76121.7297928757}, {55890000, 76124.5759190298}, + {55900000, 76127.4348255994}, {55910000, 76130.2707732617}, + {55920000, 76133.0735404493}, {55930000, 76135.8662291927}, + {55940000, 76138.6629945008}, {55950000, 76141.4643143895}, + {55960000, 76144.2713268867}, {55970000, 76147.0835377248}, + {55980000, 76149.8866719759}, {55990000, 76152.6767997657}, + {56000000, 76155.468561911}, {56010000, 76158.2801099566}, + {56020000, 76161.111470429}, {56030000, 76163.9303887854}, + {56040000, 76166.7268627158}, {56050000, 76169.5176454367}, + {56060000, 76172.3129988242}, {56070000, 76175.1106122924}, + {56080000, 76177.9051401094}, {56090000, 76180.6969441869}, + {56100000, 76183.5071646097}, {56110000, 76186.3416033344}, + {56120000, 76189.1841946322}, {56130000, 76192.0150325632}, + {56140000, 76194.8334693287}, {56150000, 76197.6383087098}, + {56160000, 76200.4292653178}, {56170000, 76203.2238668576}, + {56180000, 76206.0328448355}, {56190000, 76208.8459034129}, + {56200000, 76211.6391825288}, {56210000, 76214.4104554377}, + {56220000, 76217.1584521699}, {56230000, 76219.8829032651}, + {56240000, 76222.5839472606}, {56250000, 76225.2617272136}, + {56260000, 76227.9183502664}, {56270000, 76230.5685458266}, + {56280000, 76233.2145713907}, {56290000, 76235.8686434519}, + {56300000, 76238.5382311233}, {56310000, 76241.2076052007}, + {56320000, 76243.8402712609}, {56330000, 76246.4354435127}, + {56340000, 76249.0555446159}, {56350000, 76251.7178269645}, + {56360000, 76254.4255633157}, {56370000, 76257.1828701414}, + {56380000, 76259.988437058}, {56390000, 76262.8048913116}, + {56400000, 76265.6214291798}, {56410000, 76268.4472206143}, + {56420000, 76271.2878659261}, {56430000, 76274.1408606531}, + {56440000, 76277.0004762678}, {56450000, 76279.8652630633}, + {56460000, 76282.7134163269}, {56470000, 76285.5389381582}, + {56480000, 76288.3454534766}, {56490000, 76291.1374362971}, + {56500000, 76293.9169953906}, {56510000, 76296.7312832865}, + {56520000, 76299.5932821302}, {56530000, 76302.4487617294}, + {56540000, 76305.2645100082}, {56550000, 76308.0608143725}, + {56560000, 76310.8846140728}, {56570000, 76313.7386275384}, + {56580000, 76316.5825040011}, {56590000, 76319.4050511997}, + {56600000, 76322.2207748768}, {56610000, 76325.047663839}, + {56620000, 76327.88489315}, {56630000, 76330.6984110587}, + {56640000, 76333.4788374384}, {56650000, 76336.2551028113}, + {56660000, 76339.0449396729}, {56670000, 76341.8409594022}, + {56680000, 76344.6260423617}, {56690000, 76347.3991483466}, + {56700000, 76350.1736500066}, {56710000, 76352.9532605421}, + {56720000, 76355.7178123637}, {56730000, 76358.4422439729}, + {56740000, 76361.1362164292}, {56750000, 76363.8716656306}, + {56760000, 76366.6586260811}, {56770000, 76369.4702045289}, + {56780000, 76372.2898565504}, {56790000, 76375.1143009461}, + {56800000, 76377.9359487063}, {56810000, 76380.7532136789}, + {56820000, 76383.5441920155}, {56830000, 76386.3028879003}, + {56840000, 76389.055871129}, {56850000, 76391.8361273784}, + {56860000, 76394.6440812395}, {56870000, 76397.4498034032}, + {56880000, 76400.2441086511}, {56890000, 76403.0196857806}, + {56900000, 76405.7720856438}, {56910000, 76408.5092141976}, + {56920000, 76411.2493518982}, {56930000, 76413.9934029621}, + {56940000, 76416.7209710639}, {56950000, 76419.4264443166}, + {56960000, 76422.0910223859}, {56970000, 76424.6913095942}, + {56980000, 76427.2273496551}, {56990000, 76429.7360752387}, + {57000000, 76432.2291247011}, {57010000, 76434.7026077156}, + {57020000, 76437.1541752327}, {57030000, 76439.5785410012}, + {57040000, 76441.9632461798}, {57050000, 76444.3092651648}, + {57060000, 76446.666092721}, {57070000, 76449.0474518428}, + {57080000, 76451.4418849222}, {57090000, 76453.8351807731}, + {57100000, 76456.2276532975}, {57110000, 76458.6432776344}, + {57120000, 76461.0888777282}, {57130000, 76463.5861742295}, + {57140000, 76466.1484096827}, {57150000, 76468.7678623026}, + {57160000, 76471.4269595145}, {57170000, 76474.1235286515}, + {57180000, 76476.8492133988}, {57190000, 76479.6015837862}, + {57200000, 76482.3838170369}, {57210000, 76485.199898838}, + {57220000, 76488.0439943018}, {57230000, 76490.8659585948}, + {57240000, 76493.6569651404}, {57250000, 76496.4329265545}, + {57260000, 76499.2036453728}, {57270000, 76501.9747965606}, + {57280000, 76504.759606649}, {57290000, 76507.5590161337}, + {57300000, 76510.3665614548}, {57310000, 76513.1804147246}, + {57320000, 76516.0043055622}, {57330000, 76518.8428815402}, + {57340000, 76521.6842717465}, {57350000, 76524.4404061629}, + {57360000, 76527.098270921}, {57370000, 76529.7547078594}, + {57380000, 76532.4692017251}, {57390000, 76535.217125646}, + {57400000, 76537.9414421532}, {57410000, 76540.6378566561}, + {57420000, 76543.331853134}, {57430000, 76546.0305318726}, + {57440000, 76548.7263520621}, {57450000, 76551.4099385638}, + {57460000, 76554.0819575446}, {57470000, 76556.7492106651}, + {57480000, 76559.4127464926}, {57490000, 76562.0961085138}, + {57500000, 76564.8137381928}, {57510000, 76567.5527593254}, + {57520000, 76570.2833436141}, {57530000, 76573.0029126836}, + {57540000, 76575.7169468457}, {57550000, 76578.4269910286}, + {57560000, 76581.1366572601}, {57570000, 76583.8504340369}, + {57580000, 76586.5683009863}, {57590000, 76589.2854132654}, + {57600000, 76592.0003686558}, {57610000, 76594.7356111916}, + {57620000, 76597.5049052968}, {57630000, 76600.2953743602}, + {57640000, 76603.0771553933}, {57650000, 76605.8479471407}, + {57660000, 76608.620393113}, {57670000, 76611.3980115919}, + {57680000, 76614.1842955871}, {57690000, 76616.9835969129}, + {57700000, 76619.7948314643}, {57710000, 76622.5908254353}, + {57720000, 76625.3641825736}, {57730000, 76628.1259761354}, + {57740000, 76630.883038193}, {57750000, 76633.6435784609}, + {57760000, 76636.426729446}, {57770000, 76639.2333937089}, + {57780000, 76642.0430993483}, {57790000, 76644.8501385842}, + {57800000, 76647.6658333038}, {57810000, 76650.5042767848}, + {57820000, 76653.3635274547}, {57830000, 76656.2237338823}, + {57840000, 76659.0813751883}, {57850000, 76661.9237348222}, + {57860000, 76664.7430212223}, {57870000, 76667.5523191458}, + {57880000, 76670.3820184968}, {57890000, 76673.2332773972}, + {57900000, 76676.0648231306}, {57910000, 76678.8652317512}, + {57920000, 76681.6569243469}, {57930000, 76684.4677780287}, + {57940000, 76687.2974012771}, {57950000, 76690.1136462497}, + {57960000, 76692.9075481891}, {57970000, 76695.7074330709}, + {57980000, 76698.5307321282}, {57990000, 76701.3620664594}, + {58000000, 76704.1656931669}, {58010000, 76706.9399512166}, + {58020000, 76709.7258204054}, {58030000, 76712.5346911105}, + {58040000, 76715.3358641553}, {58050000, 76718.0911454383}, + {58060000, 76720.8018307567}, {58070000, 76723.5229838622}, + {58080000, 76726.2696786208}, {58090000, 76729.0245565496}, + {58100000, 76731.7769130643}, {58110000, 76734.5290700256}, + {58120000, 76737.2864364301}, {58130000, 76740.0492299889}, + {58140000, 76742.8105567797}, {58150000, 76745.568502064}, + {58160000, 76748.3187545841}, {58170000, 76751.0559422815}, + {58180000, 76753.7802070754}, {58190000, 76756.5150544606}, + {58200000, 76759.267885768}, {58210000, 76762.0141323626}, + {58220000, 76764.7386778554}, {58230000, 76767.454340356}, + {58240000, 76770.1909287986}, {58250000, 76772.9509669544}, + {58260000, 76775.7289209358}, {58270000, 76778.5231851712}, + {58280000, 76781.3173499902}, {58290000, 76784.0910044586}, + {58300000, 76786.8439749414}, {58310000, 76789.5893483716}, + {58320000, 76792.3309394426}, {58330000, 76795.0745780739}, + {58340000, 76797.823850329}, {58350000, 76800.5762311525}, + {58360000, 76803.3258511821}, {58370000, 76806.0727147063}, + {58380000, 76808.8308005607}, {58390000, 76811.6039681141}, + {58400000, 76814.3764248666}, {58410000, 76817.1285102458}, + {58420000, 76819.8596678934}, {58430000, 76822.5750674632}, + {58440000, 76825.2764674503}, {58450000, 76827.9700463417}, + {58460000, 76830.6596236009}, {58470000, 76833.3453513147}, + {58480000, 76836.0275581075}, {58490000, 76838.7065744328}, + {58500000, 76841.3895760159}, {58510000, 76844.0785486927}, + {58520000, 76846.7692052905}, {58530000, 76849.456210926}, + {58540000, 76852.1391360644}, {58550000, 76854.8111646923}, + {58560000, 76857.4704334144}, {58570000, 76860.1399999889}, + {58580000, 76862.8340433768}, {58590000, 76865.5503100981}, + {58600000, 76868.2836924623}, {58610000, 76871.0327675011}, + {58620000, 76873.7757282239}, {58630000, 76876.5065181563}, + {58640000, 76879.2245724691}, {58650000, 76881.9291714122}, + {58660000, 76884.6200889772}, {58670000, 76887.2895305828}, + {58680000, 76889.9353417337}, {58690000, 76892.5869948473}, + {58700000, 76895.2626504726}, {58710000, 76897.9628577235}, + {58720000, 76900.6890621445}, {58730000, 76903.4401605475}, + {58740000, 76906.1875136069}, {58750000, 76908.9231453104}, + {58760000, 76911.6425130177}, {58770000, 76914.3399413415}, + {58780000, 76917.0162698775}, {58790000, 76919.7011872394}, + {58800000, 76922.4032651652}, {58810000, 76925.1218989582}, + {58820000, 76927.8566843779}, {58830000, 76930.5996290827}, + {58840000, 76933.3321440148}, {58850000, 76936.0535929812}, + {58860000, 76938.7915748266}, {58870000, 76941.5537294057}, + {58880000, 76944.3241943486}, {58890000, 76947.0832168275}, + {58900000, 76949.8305014933}, {58910000, 76952.5886116411}, + {58920000, 76955.3645633869}, {58930000, 76958.1687492799}, + {58940000, 76961.0075316849}, {58950000, 76963.8572331182}, + {58960000, 76966.6626942326}, {58970000, 76969.420431207}, + {58980000, 76972.1703797766}, {58990000, 76974.9237086871}, + {59000000, 76977.6695268069}, {59010000, 76980.394255187}, + {59020000, 76983.0989287941}, {59030000, 76985.8283907418}, + {59040000, 76988.5955568325}, {59050000, 76991.3700030039}, + {59060000, 76994.1329332582}, {59070000, 76996.8837913446}, + {59080000, 76999.6211971831}, {59090000, 77002.3456393593}, + {59100000, 77005.0713788629}, {59110000, 77007.8023893971}, + {59120000, 77010.5268243297}, {59130000, 77013.2299154081}, + {59140000, 77015.9119608243}, {59150000, 77018.5791033938}, + {59160000, 77021.2325091019}, {59170000, 77023.8725045535}, + {59180000, 77026.4993167633}, {59190000, 77029.1130160216}, + {59200000, 77031.7136783811}, {59210000, 77034.3010882906}, + {59220000, 77036.8681644673}, {59230000, 77039.4130044415}, + {59240000, 77041.935829472}, {59250000, 77044.4368875419}, + {59260000, 77046.9172470524}, {59270000, 77049.3991320611}, + {59280000, 77051.888625991}, {59290000, 77054.3681064111}, + {59300000, 77056.8267131151}, {59310000, 77059.2773738966}, + {59320000, 77061.7502248961}, {59330000, 77064.2461414399}, + {59340000, 77066.7167261157}, {59350000, 77069.1485573324}, + {59360000, 77071.5826142395}, {59370000, 77074.0699994563}, + {59380000, 77076.6114440189}, {59390000, 77079.1354471851}, + {59400000, 77081.6193779425}, {59410000, 77084.1145821017}, + {59420000, 77086.6527365252}, {59430000, 77089.2188941994}, + {59440000, 77091.7783383612}, {59450000, 77094.3294047747}, + {59460000, 77096.9130205481}, {59470000, 77099.5404862087}, + {59480000, 77102.1840683018}, {59490000, 77104.8092043696}, + {59500000, 77107.4136330599}, {59510000, 77109.9871792608}, + {59520000, 77112.5281501061}, {59530000, 77115.0890464447}, + {59540000, 77117.7022418204}, {59550000, 77120.342241608}, + {59560000, 77122.94968977}, {59570000, 77125.5197892931}, + {59580000, 77128.0707601702}, {59590000, 77130.6077580296}, + {59600000, 77133.1313694841}, {59610000, 77135.6423091168}, + {59620000, 77138.136321066}, {59630000, 77140.5760908758}, + {59640000, 77142.95520512}, {59650000, 77145.3082567821}, + {59660000, 77147.6566510889}, {59670000, 77149.9694680111}, + {59680000, 77152.1742628051}, {59690000, 77154.2692283519}, + {59700000, 77156.3722660479}, {59710000, 77158.5162648176}, + {59720000, 77160.6960186457}, {59730000, 77162.9050809391}, + {59740000, 77165.130590409}, {59750000, 77167.2838098428}, + {59760000, 77169.3521880937}, {59770000, 77171.4377427363}, + {59780000, 77173.6035817586}, {59790000, 77175.81728943}, + {59800000, 77178.0034069846}, {59810000, 77180.1569317804}, + {59820000, 77182.3308578836}, {59830000, 77184.5399201928}, + {59840000, 77186.7799584981}, {59850000, 77189.0458200555}, + {59860000, 77191.3381833436}, {59870000, 77193.6854309444}, + {59880000, 77196.095477669}, {59890000, 77198.5183485534}, + {59900000, 77200.9231282656}, {59910000, 77203.3299736544}, + {59920000, 77205.7860209681}, {59930000, 77208.2953677148}, + {59940000, 77210.8533443738}, {59950000, 77213.4584717165}, + {59960000, 77216.1082560152}, {59970000, 77218.7996416801}, + {59980000, 77221.5330586813}, {59990000, 77224.3320594446}, + {60000000, 77227.2032473492}, {60010000, 77230.0897206274}, + {60020000, 77232.9562776214}, {60030000, 77235.8097670583}, + {60040000, 77238.6661118252}, {60050000, 77241.5271303851}, + {60060000, 77244.4008441221}, {60070000, 77247.2894489069}, + {60080000, 77250.1881881553}, {60090000, 77253.0911384044}, + {60100000, 77255.9980029935}, {60110000, 77258.9036166439}, + {60120000, 77261.8063750337}, {60130000, 77264.7168761646}, + {60140000, 77267.6416898166}, {60150000, 77270.5625354533}, + {60160000, 77273.4366038414}, {60170000, 77276.26214232}, + {60180000, 77279.0941420787}, {60190000, 77281.9479714387}, + {60200000, 77284.8047886847}, {60210000, 77287.6410827548}, + {60220000, 77290.4569612703}, {60230000, 77293.273167782}, + {60240000, 77296.0955006497}, {60250000, 77298.9062579514}, + {60260000, 77301.6945054961}, {60270000, 77304.4837047269}, + {60280000, 77307.3287695645}, {60290000, 77310.2320295482}, + {60300000, 77313.1248914707}, {60310000, 77315.9882098788}, + {60320000, 77318.8397800703}, {60330000, 77321.701814687}, + {60340000, 77324.5752236497}, {60350000, 77327.4651935586}, + {60360000, 77330.373111464}, {60370000, 77333.2682162336}, + {60380000, 77336.1314934478}, {60390000, 77338.975636418}, + {60400000, 77341.8302226428}, {60410000, 77344.6967010908}, + {60420000, 77347.5409410296}, {60430000, 77350.3534772189}, + {60440000, 77353.1569113419}, {60450000, 77355.9794629299}, + {60460000, 77358.8213263683}, {60470000, 77361.6659171146}, + {60480000, 77364.5086268194}, {60490000, 77367.3713015197}, + {60500000, 77370.2674589567}, {60510000, 77373.1816076816}, + {60520000, 77376.0776139253}, {60530000, 77378.9523112263}, + {60540000, 77381.8108860481}, {60550000, 77384.6548466451}, + {60560000, 77387.4806964508}, {60570000, 77390.2840449392}, + {60580000, 77393.0650281713}, {60590000, 77395.8376986119}, + {60600000, 77398.6065003033}, {60610000, 77401.3539484775}, + {60620000, 77404.0692479544}, {60630000, 77406.754824275}, + {60640000, 77409.4161535673}, {60650000, 77412.0538793435}, + {60660000, 77414.6684269684}, {60670000, 77417.2599985098}, + {60680000, 77419.8248292135}, {60690000, 77422.3581825777}, + {60700000, 77424.8625053473}, {60710000, 77427.3592020576}, + {60720000, 77429.8521261031}, {60730000, 77432.3827188353}, + {60740000, 77434.9765906911}, {60750000, 77437.6185584837}, + {60760000, 77440.2733747808}, {60770000, 77442.937817378}, + {60780000, 77445.6169746009}, {60790000, 77448.3122166854}, + {60800000, 77451.0074559173}, {60810000, 77453.682580659}, + {60820000, 77456.3359138559}, {60830000, 77458.9416693216}, + {60840000, 77461.4929162011}, {60850000, 77464.020148998}, + {60860000, 77466.5423104033}, {60870000, 77469.0337109617}, + {60880000, 77471.4339555472}, {60890000, 77473.7358972276}, + {60900000, 77475.8936688276}, {60910000, 77477.8949493724}, + {60920000, 77479.7689861766}, {60930000, 77481.5521792906}, + {60940000, 77483.2643340471}, {60950000, 77485.0695115606}, + {60960000, 77486.9976629076}, {60970000, 77489.133552896}, + {60980000, 77491.5293871512}, {60990000, 77494.1384292332}, + {61000000, 77496.8526217692}, {61010000, 77499.660384875}, + {61020000, 77502.5407607123}, {61030000, 77505.4876231077}, + {61040000, 77508.4996316272}, {61050000, 77511.5751938688}, + {61060000, 77514.6870717515}, {61070000, 77517.6363760768}, + {61080000, 77520.3934593091}, {61090000, 77523.0865236164}, + {61100000, 77525.7951366147}, {61110000, 77528.4983531682}, + {61120000, 77531.1470648859}, {61130000, 77533.7378279764}, + {61140000, 77536.2967004827}, {61150000, 77538.8310901032}, + {61160000, 77541.3986899356}, {61170000, 77544.071726899}, + {61180000, 77546.8514599984}, {61190000, 77549.7141888752}, + {61200000, 77552.6527207519}, {61210000, 77555.6311546759}, + {61220000, 77558.6271395997}, {61230000, 77561.6267286966}, + {61240000, 77564.5972350009}, {61250000, 77567.5320163598}, + {61260000, 77570.3364740887}, {61270000, 77572.9845761598}, + {61280000, 77575.539901544}, {61290000, 77578.0818796592}, + {61300000, 77580.6130715681}, {61310000, 77583.1162293526}, + {61320000, 77585.5860234881}, {61330000, 77588.0058512286}, + {61340000, 77590.3655045581}, {61350000, 77592.6780373231}, + {61360000, 77594.9737475003}, {61370000, 77597.2567727851}, + {61380000, 77599.5574938752}, {61390000, 77601.8843576156}, + {61400000, 77604.2403840657}, {61410000, 77606.6293893003}, + {61420000, 77609.0509470058}, {61430000, 77611.4887708409}, + {61440000, 77613.9379442227}, {61450000, 77616.3729718359}, + {61460000, 77618.7780606784}, {61470000, 77621.1580764687}, + {61480000, 77623.5242617083}, {61490000, 77625.8786030689}, + {61500000, 77628.2432364565}, {61510000, 77630.6243257116}, + {61520000, 77633.0818387403}, {61530000, 77635.6909041372}, + {61540000, 77638.4480839282}, {61550000, 77641.3060395742}, + {61560000, 77644.2557598987}, {61570000, 77647.2230389707}, + {61580000, 77650.1617998771}, {61590000, 77653.0810875411}, + {61600000, 77656.0019844197}, {61610000, 77658.9246158893}, + {61620000, 77661.8001457337}, {61630000, 77664.615062712}, + {61640000, 77667.3404793237}, {61650000, 77669.9401372718}, + {61660000, 77672.4141057408}, {61670000, 77674.819436049}, + {61680000, 77677.1743071868}, {61690000, 77679.5015895434}, + {61700000, 77681.8155436283}, {61710000, 77684.1377365617}, + {61720000, 77686.5188636633}, {61730000, 77688.9619664165}, + {61740000, 77691.4267913756}, {61750000, 77693.9019848854}, + {61760000, 77696.4078492457}, {61770000, 77698.9698471766}, + {61780000, 77701.587645143}, {61790000, 77704.1881389735}, + {61800000, 77706.748433444}, {61810000, 77709.2673191129}, + {61820000, 77711.7441221566}, {61830000, 77714.1816199228}, + {61840000, 77716.5860604394}, {61850000, 77718.9611892354}, + {61860000, 77721.3860925159}, {61870000, 77723.8828004661}, + {61880000, 77726.4275152034}, {61890000, 77728.9904733055}, + {61900000, 77731.5695821257}, {61910000, 77734.1356560788}, + {61920000, 77736.6803818439}, {61930000, 77739.2437312636}, + {61940000, 77741.8505029986}, {61950000, 77744.5040068806}, + {61960000, 77747.2123313012}, {61970000, 77749.976294707}, + {61980000, 77752.8032447922}, {61990000, 77755.6950158566}, + {62000000, 77758.6445875381}, {62010000, 77761.6432432427}, + {62020000, 77764.6900920667}, {62030000, 77767.7558446376}, + {62040000, 77770.8312170044}, {62050000, 77773.9015155776}, + {62060000, 77776.9576210868}, {62070000, 77780.0019402083}, + {62080000, 77783.0400438681}, {62090000, 77786.071956359}, + {62100000, 77789.0837251}, {62110000, 77792.0715106302}, + {62120000, 77795.0467287236}, {62130000, 77798.0236583667}, + {62140000, 77801.0035590607}, {62150000, 77804.0053946116}, + {62160000, 77807.0343355767}, {62170000, 77810.0713588959}, + {62180000, 77813.1046158972}, {62190000, 77816.1258542527}, + {62200000, 77819.115594741}, {62210000, 77822.0736929803}, + {62220000, 77825.0420671112}, {62230000, 77828.0324643795}, + {62240000, 77831.0215023992}, {62250000, 77833.9798498615}, + {62260000, 77836.9112873976}, {62270000, 77839.8505382252}, + {62280000, 77842.8029110788}, {62290000, 77845.7578893313}, + {62300000, 77848.7089260961}, {62310000, 77851.6531869866}, + {62320000, 77854.5839635784}, {62330000, 77857.5014822371}, + {62340000, 77860.4268616678}, {62350000, 77863.3659943628}, + {62360000, 77866.3108342751}, {62370000, 77869.2513047886}, + {62380000, 77872.1868691436}, {62390000, 77875.1104591402}, + {62400000, 77878.0200559414}, {62410000, 77880.9560263204}, + {62420000, 77883.9434316949}, {62430000, 77886.9513807603}, + {62440000, 77889.9074013641}, {62450000, 77892.8070915245}, + {62460000, 77895.7109065804}, {62470000, 77898.6357944186}, + {62480000, 77901.5631394601}, {62490000, 77904.4696142263}, + {62500000, 77907.3556128979}, {62510000, 77910.2496687632}, + {62520000, 77913.1597457093}, {62530000, 77916.0794916469}, + {62540000, 77919.0049370942}, {62550000, 77921.9359495869}, + {62560000, 77924.8722555868}, {62570000, 77927.8138045934}, + {62580000, 77930.7605581787}, {62590000, 77933.7124869224}, + {62600000, 77936.6613333836}, {62610000, 77939.59674463}, + {62620000, 77942.5195885089}, {62630000, 77945.4604255294}, + {62640000, 77948.427773042}, {62650000, 77951.4031660381}, + {62660000, 77954.375039978}, {62670000, 77957.340419342}, + {62680000, 77960.2922581532}, {62690000, 77963.2307461073}, + {62700000, 77966.1769917115}, {62710000, 77969.1368898447}, + {62720000, 77972.0986725054}, {62730000, 77975.0475934523}, + {62740000, 77977.9830616644}, {62750000, 77980.9041061452}, + {62760000, 77983.8106474178}, {62770000, 77986.7027274658}, + {62780000, 77989.5803994158}, {62790000, 77992.4568701216}, + {62800000, 77995.3631748708}, {62810000, 77998.3011261463}, + {62820000, 78001.2437921688}, {62830000, 78004.1835994912}, + {62840000, 78007.1193803509}, {62850000, 78010.0496647384}, + {62860000, 78012.9741517923}, {62870000, 78015.8706153046}, + {62880000, 78018.7321598479}, {62890000, 78021.5709916368}, + {62900000, 78024.3947557173}, {62910000, 78027.1880124438}, + {62920000, 78029.914222744}, {62930000, 78032.5714676015}, + {62940000, 78035.1937003049}, {62950000, 78037.7905806949}, + {62960000, 78040.3598822033}, {62970000, 78042.8987760994}, + {62980000, 78045.4078364348}, {62990000, 78047.9313449816}, + {63000000, 78050.4832118876}, {63010000, 78053.0682590403}, + {63020000, 78055.6894278695}, {63030000, 78058.3335769521}, + {63040000, 78060.9699393367}, {63050000, 78063.5930930943}, + {63060000, 78066.1370172238}, {63070000, 78068.5834558574}, + {63080000, 78070.9755290972}, {63090000, 78073.3672536901}, + {63100000, 78075.7613713854}, {63110000, 78078.1874803974}, + {63120000, 78080.6541055343}, {63130000, 78083.1417599085}, + {63140000, 78085.6382464193}, {63150000, 78088.1326623418}, + {63160000, 78090.5993381237}, {63170000, 78093.0297322222}, + {63180000, 78095.2580877801}, {63190000, 78097.2384533137}, + {63200000, 78099.0738476935}, {63210000, 78100.8933035134}, + {63220000, 78102.6981018371}, {63230000, 78104.4600684326}, + {63240000, 78106.1743223433}, {63250000, 78107.9160958573}, + {63260000, 78109.7321962867}, {63270000, 78111.6108177057}, + {63280000, 78113.524565511}, {63290000, 78115.4714062295}, + {63300000, 78117.4710466066}, {63310000, 78119.5288376593}, + {63320000, 78121.6244833494}, {63330000, 78123.7325463207}, + {63340000, 78125.8409810709}, {63350000, 78127.8668687132}, + {63360000, 78129.7977647625}, {63370000, 78131.6953467006}, + {63380000, 78133.5981574377}, {63390000, 78135.549502968}, + {63400000, 78137.6517674116}, {63410000, 78139.909449734}, + {63420000, 78142.1990772863}, {63430000, 78144.4858251561}, + {63440000, 78146.7621540389}, {63450000, 78149.0185828057}, + {63460000, 78151.2607114251}, {63470000, 78153.5322138131}, + {63480000, 78155.8397136327}, {63490000, 78158.1321804314}, + {63500000, 78160.3778039766}, {63510000, 78162.6176491056}, + {63520000, 78164.9484478584}, {63530000, 78167.3781927111}, + {63540000, 78169.8833828229}, {63550000, 78172.4571416699}, + {63560000, 78175.0731098506}, {63570000, 78177.6982416082}, + {63580000, 78180.3318382643}, {63590000, 78182.9901747363}, + {63600000, 78185.6779056951}, {63610000, 78188.404647226}, + {63620000, 78191.1763340509}, {63630000, 78193.9930191726}, + {63640000, 78196.8551353151}, {63650000, 78199.7614410562}, + {63660000, 78202.6831674245}, {63670000, 78205.612171713}, + {63680000, 78208.5695814533}, {63690000, 78211.5819872831}, + {63700000, 78214.6504999448}, {63710000, 78217.7868429417}, + {63720000, 78220.9940711129}, {63730000, 78224.2210844382}, + {63740000, 78227.4359645137}, {63750000, 78230.6324789781}, + {63760000, 78233.7958156}, {63770000, 78236.9254816263}, + {63780000, 78240.0422291571}, {63790000, 78243.1519382449}, + {63800000, 78246.2431784635}, {63810000, 78249.3015596647}, + {63820000, 78252.3290894192}, {63830000, 78255.3465289714}, + {63840000, 78258.3576683013}, {63850000, 78261.3632279798}, + {63860000, 78264.3636685017}, {63870000, 78267.3564083974}, + {63880000, 78270.3353049884}, {63890000, 78273.3011670837}, + {63900000, 78276.2894251846}, {63910000, 78279.3099593627}, + {63920000, 78282.3355695113}, {63930000, 78285.3321056217}, + {63940000, 78288.3004705775}, {63950000, 78291.2984565741}, + {63960000, 78294.3425118043}, {63970000, 78297.4314134989}, + {63980000, 78300.5643145534}, {63990000, 78303.7253171654}, + {64000000, 78306.8771084891}, {64010000, 78310.0163382178}, + {64020000, 78313.1480745792}, {64030000, 78316.2737714871}, + {64040000, 78319.3857139208}, {64050000, 78322.4741874903}, + {64060000, 78325.539525112}, {64070000, 78328.5955433438}, + {64080000, 78331.6461067487}, {64090000, 78334.6970859083}, + {64100000, 78337.7521520295}, {64110000, 78340.8140573982}, + {64120000, 78343.8893489757}, {64130000, 78346.9769964011}, + {64140000, 78350.0344146345}, {64150000, 78353.049730495}, + {64160000, 78356.0379730961}, {64170000, 78359.0179956987}, + {64180000, 78361.9907034933}, {64190000, 78364.9746776382}, + {64200000, 78367.9757503285}, {64210000, 78370.9924592302}, + {64220000, 78374.0238618042}, {64230000, 78377.0646584646}, + {64240000, 78380.1023974679}, {64250000, 78383.1361398836}, + {64260000, 78386.1723600586}, {64270000, 78389.2128706893}, + {64280000, 78392.2345833594}, {64290000, 78395.2084555727}, + {64300000, 78398.1348924006}, {64310000, 78401.0538120046}, + {64320000, 78403.9768808583}, {64330000, 78406.9047037273}, + {64340000, 78409.8376500792}, {64350000, 78412.7783422099}, + {64360000, 78415.7330262913}, {64370000, 78418.7019882091}, + {64380000, 78421.6783938331}, {64390000, 78424.6602890465}, + {64400000, 78427.6355579038}, {64410000, 78430.5889642284}, + {64420000, 78433.5200840776}, {64430000, 78436.4343279428}, + {64440000, 78439.3335623436}, {64450000, 78442.2007580174}, + {64460000, 78445.0253227121}, {64470000, 78447.7992218708}, + {64480000, 78450.5031330893}, {64490000, 78453.1378816038}, + {64500000, 78455.7670125784}, {64510000, 78458.4084392168}, + {64520000, 78461.0591512686}, {64530000, 78463.7153744533}, + {64540000, 78466.3787397532}, {64550000, 78469.0983254634}, + {64560000, 78471.8878145911}, {64570000, 78474.761691302}, + {64580000, 78477.7288589582}, {64590000, 78480.7630877992}, + {64600000, 78483.8028900819}, {64610000, 78486.8430087695}, + {64620000, 78489.9013694426}, {64630000, 78492.9829543701}, + {64640000, 78496.0642483744}, {64650000, 78499.1156719493}, + {64660000, 78502.1373678036}, {64670000, 78505.1640045384}, + {64680000, 78508.2056739517}, {64690000, 78511.2735948911}, + {64700000, 78514.3747359843}, {64710000, 78517.4909184952}, + {64720000, 78520.5792657}, {64730000, 78523.635691799}, + {64740000, 78526.6578656204}, {64750000, 78529.6452515071}, + {64760000, 78532.6099079199}, {64770000, 78535.5669856106}, + {64780000, 78538.5173450593}, {64790000, 78541.4711920962}, + {64800000, 78544.4315022398}, {64810000, 78547.391632197}, + {64820000, 78550.3474217394}, {64830000, 78553.2856752703}, + {64840000, 78556.1750740983}, {64850000, 78559.0146335102}, + {64860000, 78561.8528173638}, {64870000, 78564.7032770831}, + {64880000, 78567.5401988194}, {64890000, 78570.3310941749}, + {64900000, 78573.0754019848}, {64910000, 78575.8045647326}, + {64920000, 78578.5285752593}, {64930000, 78581.2656628856}, + {64940000, 78584.0272200989}, {64950000, 78586.8030789151}, + {64960000, 78589.5692973428}, {64970000, 78592.3238338327}, + {64980000, 78595.0725255967}, {64990000, 78597.8170385243}, + {65000000, 78600.5421855125}, {65010000, 78603.2288213628}, + {65020000, 78605.8778232696}, {65030000, 78608.5310139706}, + {65040000, 78611.2004158961}, {65050000, 78613.8513675517}, + {65060000, 78616.4621400991}, {65070000, 78619.0557337224}, + {65080000, 78621.6864098178}, {65090000, 78624.356403374}, + {65100000, 78626.9900380238}, {65110000, 78629.5661172585}, + {65120000, 78632.0952757777}, {65130000, 78634.5908399071}, + {65140000, 78637.0568108363}, {65150000, 78639.5233296377}, + {65160000, 78641.9958968084}, {65170000, 78644.4927198828}, + {65180000, 78647.0251570426}, {65190000, 78649.5882239224}, + {65200000, 78652.1703337095}, {65210000, 78654.7705277273}, + {65220000, 78657.395192313}, {65230000, 78660.046039731}, + {65240000, 78662.755931448}, {65250000, 78665.5663160327}, + {65260000, 78668.4759402145}, {65270000, 78671.432933444}, + {65280000, 78674.4229130521}, {65290000, 78677.4467227362}, + {65300000, 78680.5048291631}, {65310000, 78683.581439186}, + {65320000, 78686.6393400896}, {65330000, 78689.6752268959}, + {65340000, 78692.6942011401}, {65350000, 78695.6977609563}, + {65360000, 78698.697234817}, {65370000, 78701.7068791303}, + {65380000, 78704.7269121862}, {65390000, 78707.7312818832}, + {65400000, 78710.7117250896}, {65410000, 78713.6736021754}, + {65420000, 78716.62031709}, {65430000, 78719.5572723794}, + {65440000, 78722.4971881583}, {65450000, 78725.4407719175}, + {65460000, 78728.3744565802}, {65470000, 78731.2944510319}, + {65480000, 78734.1964651996}, {65490000, 78737.0750697181}, + {65500000, 78739.9309430566}, {65510000, 78742.7708714141}, + {65520000, 78745.5961512034}, {65530000, 78748.418724998}, + {65540000, 78751.2460866523}, {65550000, 78754.0836966876}, + {65560000, 78756.9445500257}, {65570000, 78759.828231448}, + {65580000, 78762.6925423711}, {65590000, 78765.5256502288}, + {65600000, 78768.3426126054}, {65610000, 78771.1623805808}, + {65620000, 78773.9858533783}, {65630000, 78776.8151998783}, + {65640000, 78779.6507891938}, {65650000, 78782.5154193741}, + {65660000, 78785.4233328969}, {65670000, 78788.3696213786}, + {65680000, 78791.3429311069}, {65690000, 78794.3407006234}, + {65700000, 78797.3264402156}, {65710000, 78800.2899012276}, + {65720000, 78803.2463852331}, {65730000, 78806.2151629162}, + {65740000, 78809.1960534116}, {65750000, 78812.1833198761}, + {65760000, 78815.1760996314}, {65770000, 78818.1682606141}, + {65780000, 78821.1559538455}, {65790000, 78824.149510898}, + {65800000, 78827.1734526669}, {65810000, 78830.228730172}, + {65820000, 78833.2808803998}, {65830000, 78836.3201944934}, + {65840000, 78839.3532418679}, {65850000, 78842.3882916486}, + {65860000, 78845.4250497771}, {65870000, 78848.4432978793}, + {65880000, 78851.4371679902}, {65890000, 78854.4353932121}, + {65900000, 78857.4560060839}, {65910000, 78860.4916755718}, + {65920000, 78863.5251346415}, {65930000, 78866.5541701965}, + {65940000, 78869.5635840956}, {65950000, 78872.5491564121}, + {65960000, 78875.5146518112}, {65970000, 78878.4647909942}, + {65980000, 78881.4002721905}, {65990000, 78884.3370979449}, + {66000000, 78887.2799520386}, {66010000, 78890.2282519081}, + {66020000, 78893.1816217594}, {66030000, 78896.1348353041}, + {66040000, 78899.0755078579}, {66050000, 78902.0043238605}, + {66060000, 78904.970666518}, {66070000, 78907.9883413169}, + {66080000, 78911.0260896103}, {66090000, 78914.0445190832}, + {66100000, 78917.0428303732}, {66110000, 78920.0645101704}, + {66120000, 78923.1232181467}, {66130000, 78926.1825564174}, + {66140000, 78929.2195549805}, {66150000, 78932.2205305922}, + {66160000, 78935.1527768073}, {66170000, 78938.0178632237}, + {66180000, 78940.9356540857}, {66190000, 78943.9397955625}, + {66200000, 78946.9655873653}, {66210000, 78949.9314673066}, + {66220000, 78952.8371580323}, {66230000, 78955.7403167254}, + {66240000, 78958.6569794278}, {66250000, 78961.6054282307}, + {66260000, 78964.5970833506}, {66270000, 78967.6112712732}, + {66280000, 78970.5991616768}, {66290000, 78973.5573893475}, + {66300000, 78976.5190382897}, {66310000, 78979.493435008}, + {66320000, 78982.4804787423}, {66330000, 78985.4800592939}, + {66340000, 78988.4913340088}, {66350000, 78991.4946880039}, + {66360000, 78994.4846883511}, {66370000, 78997.4893679152}, + {66380000, 79000.5263229092}, {66390000, 79003.5855784038}, + {66400000, 79006.6436269681}, {66410000, 79009.6981605673}, + {66420000, 79012.7478447091}, {66430000, 79015.792319714}, + {66440000, 79018.8274897009}, {66450000, 79021.8481726905}, + {66460000, 79024.854241795}, {66470000, 79027.8454305612}, + {66480000, 79030.8217185633}, {66490000, 79033.765868663}, + {66500000, 79036.6670758743}, {66510000, 79039.5173373152}, + {66520000, 79042.2972316003}, {66530000, 79045.0062131915}, + {66540000, 79047.6721162325}, {66550000, 79050.302951459}, + {66560000, 79052.896792688}, {66570000, 79055.4511615491}, + {66580000, 79057.9666634936}, {66590000, 79060.5097619801}, + {66600000, 79063.1016938736}, {66610000, 79065.671529057}, + {66620000, 79068.174717108}, {66630000, 79070.6413708382}, + {66640000, 79073.1427460886}, {66650000, 79075.6857050374}, + {66660000, 79078.2741535664}, {66670000, 79080.9090326382}, + {66680000, 79083.593469446}, {66690000, 79086.3314772574}, + {66700000, 79089.1190950866}, {66710000, 79091.9219955649}, + {66720000, 79094.7338646727}, {66730000, 79097.5933260165}, + {66740000, 79100.5245733562}, {66750000, 79103.5072391223}, + {66760000, 79106.4933646648}, {66770000, 79109.4774293207}, + {66780000, 79112.4352986109}, {66790000, 79115.3602480062}, + {66800000, 79118.2599319853}, {66810000, 79121.1439776423}, + {66820000, 79124.0136775464}, {66830000, 79126.8930827605}, + {66840000, 79129.7889568499}, {66850000, 79132.6832079546}, + {66860000, 79135.5644366056}, {66870000, 79138.4427691126}, + {66880000, 79141.3422322618}, {66890000, 79144.264573963}, + {66900000, 79147.1967476948}, {66910000, 79150.1350296497}, + {66920000, 79153.0906343764}, {66930000, 79156.0777512992}, + {66940000, 79159.0913926319}, {66950000, 79162.0823220386}, + {66960000, 79165.0413979943}, {66970000, 79167.9959690257}, + {66980000, 79170.9632580886}, {66990000, 79173.9359945967}, + {67000000, 79176.8969508555}, {67010000, 79179.8426467249}, + {67020000, 79182.7221518779}, {67030000, 79185.5213146946}, + {67040000, 79188.2515604754}, {67050000, 79190.9272171235}, + {67060000, 79193.5490670886}, {67070000, 79196.1174866983}, + {67080000, 79198.6327593764}, {67090000, 79201.1301894639}, + {67100000, 79203.6320321936}, {67110000, 79206.1207994008}, + {67120000, 79208.554871744}, {67130000, 79210.9327461913}, + {67140000, 79213.3165988592}, {67150000, 79215.7239877493}, + {67160000, 79218.1551989793}, {67170000, 79220.6106259941}, + {67180000, 79223.0910786806}, {67190000, 79225.6252726058}, + {67200000, 79228.2213223047}, {67210000, 79230.8815999428}, + {67220000, 79233.6074810062}, {67230000, 79236.4013937584}, + {67240000, 79239.2695750485}, {67250000, 79242.2089124175}, + {67260000, 79245.1265823565}, {67270000, 79247.9964177982}, + {67280000, 79250.8360844052}, {67290000, 79253.6678567622}, + {67300000, 79256.4928077383}, {67310000, 79259.3296511805}, + {67320000, 79262.1842137681}, {67330000, 79265.0435566115}, + {67340000, 79267.8995162058}, {67350000, 79270.7544686466}, + {67360000, 79273.6140556358}, {67370000, 79276.4795948961}, + {67380000, 79279.3727966538}, {67390000, 79282.2997003795}, + {67400000, 79285.2365744265}, {67410000, 79288.1534292745}, + {67420000, 79291.0503096158}, {67430000, 79293.963185361}, + {67440000, 79296.9025639408}, {67450000, 79299.8385616252}, + {67460000, 79302.7523503065}, {67470000, 79305.6512380311}, + {67480000, 79308.5524949362}, {67490000, 79311.4580729093}, + {67500000, 79314.3760716774}, {67510000, 79317.3087369682}, + {67520000, 79320.2439922668}, {67530000, 79323.166573212}, + {67540000, 79326.0784026433}, {67550000, 79329.0009689616}, + {67560000, 79331.9381610636}, {67570000, 79334.855568054}, + {67580000, 79337.7315385617}, {67590000, 79340.5785472305}, + {67600000, 79343.4260492995}, {67610000, 79346.2761647914}, + {67620000, 79349.1091142287}, {67630000, 79351.9193619702}, + {67640000, 79354.7326997963}, {67650000, 79357.5817393985}, + {67660000, 79360.4670355708}, {67670000, 79363.3287596603}, + {67680000, 79366.1477624436}, {67690000, 79368.9639879465}, + {67700000, 79371.8026160604}, {67710000, 79374.6617907893}, + {67720000, 79377.5372422448}, {67730000, 79380.4271771989}, + {67740000, 79383.2955553333}, {67750000, 79386.1322554214}, + {67760000, 79388.9593619047}, {67770000, 79391.8047823164}, + {67780000, 79394.6693648307}, {67790000, 79397.5452809105}, + {67800000, 79400.4299743917}, {67810000, 79403.3329803209}, + {67820000, 79406.260282372}, {67830000, 79409.1963737831}, + {67840000, 79412.1044513068}, {67850000, 79414.9802357786}, + {67860000, 79417.8003647184}, {67870000, 79420.5584259937}, + {67880000, 79423.2632641723}, {67890000, 79425.9259984241}, + {67900000, 79428.5493541337}, {67910000, 79431.2083670889}, + {67920000, 79433.9249310585}, {67930000, 79436.6400883007}, + {67940000, 79439.3166361521}, {67950000, 79441.9509174297}, + {67960000, 79444.5339349704}, {67970000, 79447.0668518977}, + {67980000, 79449.5994336546}, {67990000, 79452.1457633404}, + {68000000, 79454.7096885137}, {68010000, 79457.296101442}, + {68020000, 79459.9047112231}, {68030000, 79462.5024650648}, + {68040000, 79465.0789339872}, {68050000, 79467.6852784517}, + {68060000, 79470.3537287169}, {68070000, 79473.0694863332}, + {68080000, 79475.7976607594}, {68090000, 79478.5344992994}, + {68100000, 79481.2708749871}, {68110000, 79484.0042047508}, + {68120000, 79486.7301417353}, {68130000, 79489.4431757231}, + {68140000, 79492.1442493967}, {68150000, 79494.8642189372}, + {68160000, 79497.6118053034}, {68170000, 79500.3686049203}, + {68180000, 79503.1229874203}, {68190000, 79505.8954225713}, + {68200000, 79508.7347518441}, {68210000, 79511.6436898518}, + {68220000, 79514.5747226786}, {68230000, 79517.5143047836}, + {68240000, 79520.4488736238}, {68250000, 79523.3612467985}, + {68260000, 79526.2595823742}, {68270000, 79529.2092455434}, + {68280000, 79532.220210071}, {68290000, 79535.2133579273}, + {68300000, 79538.1387310802}, {68310000, 79541.0105083105}, + {68320000, 79543.8620981513}, {68330000, 79546.6971464418}, + {68340000, 79549.5247828705}, {68350000, 79552.3476193768}, + {68360000, 79555.1618451747}, {68370000, 79557.9626267005}, + {68380000, 79560.7504987797}, {68390000, 79563.548699584}, + {68400000, 79566.3640335941}, {68410000, 79569.1898245193}, + {68420000, 79572.0218349322}, {68430000, 79574.8573136144}, + {68440000, 79577.6897369973}, {68450000, 79580.5192506168}, + {68460000, 79583.3669093273}, {68470000, 79586.2386110441}, + {68480000, 79589.1147469585}, {68490000, 79591.9704905415}, + {68500000, 79594.8060691082}, {68510000, 79597.649887124}, + {68520000, 79600.5099701737}, {68530000, 79603.3569297069}, + {68540000, 79606.172220555}, {68550000, 79608.9761895595}, + {68560000, 79611.8172348215}, {68570000, 79614.6989440372}, + {68580000, 79617.5952946503}, {68590000, 79620.4988469582}, + {68600000, 79623.3968981718}, {68610000, 79626.273354018}, + {68620000, 79629.1279436238}, {68630000, 79631.9662726619}, + {68640000, 79634.7899849558}, {68650000, 79637.6052043499}, + {68660000, 79640.4158156351}, {68670000, 79643.2193708599}, + {68680000, 79646.0099886455}, {68690000, 79648.7871466732}, + {68700000, 79651.550567833}, {68710000, 79654.3002225816}, + {68720000, 79657.0119409038}, {68730000, 79659.6550623285}, + {68740000, 79662.2386766093}, {68750000, 79664.8340770483}, + {68760000, 79667.4517532591}, {68770000, 79670.0826621503}, + {68780000, 79672.7210657861}, {68790000, 79675.3771178865}, + {68800000, 79678.0751595274}, {68810000, 79680.8171498295}, + {68820000, 79683.5971733175}, {68830000, 79686.4134177271}, + {68840000, 79689.2635404711}, {68850000, 79692.144620987}, + {68860000, 79695.0561681405}, {68870000, 79697.9741176077}, + {68880000, 79700.89079976}, {68890000, 79703.8157601123}, + {68900000, 79706.755014897}, {68910000, 79709.7009276859}, + {68920000, 79712.6353508094}, {68930000, 79715.55324946}, + {68940000, 79718.3607883281}, {68950000, 79721.0317002037}, + {68960000, 79723.6355969289}, {68970000, 79726.2606178339}, + {68980000, 79728.9099532232}, {68990000, 79731.5966741734}, + {69000000, 79734.324804806}, {69010000, 79737.073654082}, + {69020000, 79739.8300942852}, {69030000, 79742.5989134351}, + {69040000, 79745.3916179124}, {69050000, 79748.2079561884}, + {69060000, 79751.0127557474}, {69070000, 79753.7960807681}, + {69080000, 79756.591000939}, {69090000, 79759.4394114289}, + {69100000, 79762.3405440495}, {69110000, 79765.2217041576}, + {69120000, 79768.0615623547}, {69130000, 79770.8529588007}, + {69140000, 79773.5914518828}, {69150000, 79776.2849099247}, + {69160000, 79778.9517862166}, {69170000, 79781.5917504342}, + {69180000, 79784.1416779283}, {69190000, 79786.5839398947}, + {69200000, 79788.9659287972}, {69210000, 79791.3476308009}, + {69220000, 79793.7300697691}, {69230000, 79796.103192814}, + {69240000, 79798.4651980716}, {69250000, 79800.7926648378}, + {69260000, 79803.0708388549}, {69270000, 79805.3435030758}, + {69280000, 79807.7153930822}, {69290000, 79810.1941545555}, + {69300000, 79812.720994754}, {69310000, 79815.2790246586}, + {69320000, 79817.8742349078}, {69330000, 79820.514282477}, + {69340000, 79823.1965167826}, {69350000, 79825.9002466978}, + {69360000, 79828.6221472533}, {69370000, 79831.3840938744}, + {69380000, 79834.199853202}, {69390000, 79837.0566732644}, + {69400000, 79839.924424866}, {69410000, 79842.8008477082}, + {69420000, 79845.705577472}, {69430000, 79848.6440876076}, + {69440000, 79851.5723717305}, {69450000, 79854.43459192}, + {69460000, 79857.234239516}, {69470000, 79860.0109617258}, + {69480000, 79862.7710876911}, {69490000, 79865.5047723406}, + {69500000, 79868.2058272922}, {69510000, 79870.8611967052}, + {69520000, 79873.4393872754}, {69530000, 79875.9391642828}, + {69540000, 79878.401993515}, {69550000, 79880.8397783475}, + {69560000, 79883.2466790516}, {69570000, 79885.6152453485}, + {69580000, 79887.9461238834}, {69590000, 79890.2662407556}, + {69600000, 79892.583574685}, {69610000, 79894.9218454031}, + {69620000, 79897.2960400914}, {69630000, 79899.6935339729}, + {69640000, 79902.0843446242}, {69650000, 79904.4660482546}, + {69660000, 79906.8512894494}, {69670000, 79909.243648179}, + {69680000, 79911.6577892751}, {69690000, 79914.1123455425}, + {69700000, 79916.6100910069}, {69710000, 79919.2142188965}, + {69720000, 79921.9422408248}, {69730000, 79924.7252579603}, + {69740000, 79927.5195270651}, {69750000, 79930.3417901223}, + {69760000, 79933.2322185911}, {69770000, 79936.188871239}, + {69780000, 79939.0566195486}, {69790000, 79941.7917411674}, + {69800000, 79944.4196625526}, {69810000, 79946.9724912279}, + {69820000, 79949.4491773572}, {69830000, 79951.8271840274}, + {69840000, 79954.1027815699}, {69850000, 79956.3118184582}, + {69860000, 79958.4771233329}, {69870000, 79960.5866949753}, + {69880000, 79962.6114881323}, {69890000, 79964.5492677545}, + {69900000, 79966.4059228258}, {69910000, 79968.1834155991}, + {69920000, 79969.9295756654}, {69930000, 79971.7050338603}, + {69940000, 79973.5106991053}, {69950000, 79975.3100492889}, + {69960000, 79977.0925162111}, {69970000, 79978.9146427942}, + {69980000, 79980.8122193376}, {69990000, 79982.7601872222}, + {70000000, 79984.6989987435}, {70010000, 79986.6238222859}, + {70020000, 79988.5599000084}, {70030000, 79990.5143636034}, + {70040000, 79992.4567869349}, {70050000, 79994.3485566956}, + {70060000, 79996.1940633776}, {70070000, 79998.1325843017}, + {70080000, 80000.2025644013}, {70090000, 80002.3499388975}, + {70100000, 80004.5402775632}, {70110000, 80006.7800948474}, + {70120000, 80009.0853089734}, {70130000, 80011.4599887082}, + {70140000, 80013.9832909346}, {70150000, 80016.6771760881}, + {70160000, 80019.4654950717}, {70170000, 80022.2516979065}, + {70180000, 80025.0326248794}, {70190000, 80027.8419469978}, + {70200000, 80030.6903005061}, {70210000, 80033.5638562485}, + {70220000, 80036.4537975891}, {70230000, 80039.3390351073}, + {70240000, 80042.1691237188}, {70250000, 80044.9416074458}, + {70260000, 80047.718210885}, {70270000, 80050.5164565315}, + {70280000, 80053.3477999385}, {70290000, 80056.2268307941}, + {70300000, 80059.1527510717}, {70310000, 80062.088834096}, + {70320000, 80065.0243431809}, {70330000, 80067.951075085}, + {70340000, 80070.8638428228}, {70350000, 80073.7703139219}, + {70360000, 80076.688833269}, {70370000, 80079.6189161139}, + {70380000, 80082.497270943}, {70390000, 80085.306055688}, + {70400000, 80088.0830002181}, {70410000, 80090.8760034383}, + {70420000, 80093.6866957726}, {70430000, 80096.5085378418}, + {70440000, 80099.3393608834}, {70450000, 80102.1541555606}, + {70460000, 80104.9370687428}, {70470000, 80107.6540332662}, + {70480000, 80110.2230630309}, {70490000, 80112.6442784732}, + {70500000, 80115.1279390767}, {70510000, 80117.733609815}, + {70520000, 80120.3867362348}, {70530000, 80122.9927282767}, + {70540000, 80125.5530768171}, {70550000, 80128.203730204}, + {70560000, 80130.983181271}, {70570000, 80133.7907781962}, + {70580000, 80136.5625517695}, {70590000, 80139.3173417529}, + {70600000, 80142.1001133642}, {70610000, 80144.9144319924}, + {70620000, 80147.7412760751}, {70630000, 80150.5751922009}, + {70640000, 80153.426083015}, {70650000, 80156.3065551484}, + {70660000, 80159.216709707}, {70670000, 80162.1484600188}, + {70680000, 80165.0993398554}, {70690000, 80168.0265594129}, + {70700000, 80170.9029879364}, {70710000, 80173.7667553091}, + {70720000, 80176.7093209006}, {70730000, 80179.7351503869}, + {70740000, 80182.7276105608}, {70750000, 80185.6536016181}, + {70760000, 80188.5532666718}, {70770000, 80191.4775787271}, + {70780000, 80194.4240230606}, {70790000, 80197.2382279416}, + {70800000, 80199.875166578}, {70810000, 80202.4538541257}, + {70820000, 80205.0499756561}, {70830000, 80207.6477587627}, + {70840000, 80210.2094711486}, {70850000, 80212.7328030116}, + {70860000, 80215.2514834792}, {70870000, 80217.7751200189}, + {70880000, 80220.3001748447}, {70890000, 80222.8221544931}, + {70900000, 80225.3410662026}, {70910000, 80227.8740198666}, + {70920000, 80230.426425614}, {70930000, 80233.002522587}, + {70940000, 80235.6049635771}, {70950000, 80238.228576572}, + {70960000, 80240.8611197548}, {70970000, 80243.5031066083}, + {70980000, 80246.2037850065}, {70990000, 80248.9769495421}, + {71000000, 80251.8279427265}, {71010000, 80254.7636669373}, + {71020000, 80257.7810112447}, {71030000, 80260.7699769075}, + {71040000, 80263.6981719814}, {71050000, 80266.6041296147}, + {71060000, 80269.512391006}, {71070000, 80272.4340722978}, + {71080000, 80275.3959872244}, {71090000, 80278.3971367169}, + {71100000, 80281.3388930202}, {71110000, 80284.1933543014}, + {71120000, 80286.998580727}, {71130000, 80289.8029075354}, + {71140000, 80292.6018968228}, {71150000, 80295.3398000038}, + {71160000, 80298.0065842233}, {71170000, 80300.6359600424}, + {71180000, 80303.2494295479}, {71190000, 80305.8581493599}, + {71200000, 80308.4888432028}, {71210000, 80311.1392917417}, + {71220000, 80313.6752478682}, {71230000, 80316.0589150446}, + {71240000, 80318.3558551883}, {71250000, 80320.6493272561}, + {71260000, 80322.9411773328}, {71270000, 80325.2002286042}, + {71280000, 80327.4178508844}, {71290000, 80329.6348314557}, + {71300000, 80331.8771059202}, {71310000, 80334.1402511784}, + {71320000, 80336.4138174502}, {71330000, 80338.6974754817}, + {71340000, 80341.0119800247}, {71350000, 80343.3631276528}, + {71360000, 80345.7419934869}, {71370000, 80348.1372656409}, + {71380000, 80350.5490644059}, {71390000, 80353.0445421434}, + {71400000, 80355.6448355485}, {71410000, 80358.2983929982}, + {71420000, 80360.9722985398}, {71430000, 80363.6783806652}, + {71440000, 80366.4452977607}, {71450000, 80369.2753697054}, + {71460000, 80372.1628089407}, {71470000, 80375.1057641463}, + {71480000, 80378.0595610883}, {71490000, 80380.9673517004}, + {71500000, 80383.8350575408}, {71510000, 80386.7321515736}, + {71520000, 80389.6712284479}, {71530000, 80392.6135780351}, + {71540000, 80395.534580747}, {71550000, 80398.4438423019}, + {71560000, 80401.3643176881}, {71570000, 80404.2979808122}, + {71580000, 80407.2389412752}, {71590000, 80410.18549544}, + {71600000, 80413.1214401216}, {71610000, 80416.0261364785}, + {71620000, 80418.9037338507}, {71630000, 80421.7970010902}, + {71640000, 80424.7137428299}, {71650000, 80427.6433503265}, + {71660000, 80430.5790464265}, {71670000, 80433.51023181}, + {71680000, 80436.4114541976}, {71690000, 80439.2815811332}, + {71700000, 80442.1550035014}, {71710000, 80445.0414965783}, + {71720000, 80447.9298031088}, {71730000, 80450.8055969307}, + {71740000, 80453.6743900855}, {71750000, 80456.5795068972}, + {71760000, 80459.5272456915}, {71770000, 80462.484288612}, + {71780000, 80465.4294071752}, {71790000, 80468.3619281705}, + {71800000, 80471.2801425516}, {71810000, 80474.1849438868}, + {71820000, 80477.1048675595}, {71830000, 80480.0479869696}, + {71840000, 80482.9763602602}, {71850000, 80485.841632}, + {71860000, 80488.6428887395}, {71870000, 80491.4005126553}, + {71880000, 80494.1206679087}, {71890000, 80496.7713119013}, + {71900000, 80499.3321696179}, {71910000, 80501.8158782903}, + {71920000, 80504.2522033581}, {71930000, 80506.6455547214}, + {71940000, 80509.0335401724}, {71950000, 80511.4268899825}, + {71960000, 80513.8296655829}, {71970000, 80516.2470496539}, + {71980000, 80518.6803196412}, {71990000, 80521.1729649372}, + {72000000, 80523.7376435363}, {72010000, 80526.3708660973}, + {72020000, 80529.07028801}, {72030000, 80531.8226729193}, + {72040000, 80534.5966140219}, {72050000, 80537.3886540065}, + {72060000, 80540.1898063228}, {72070000, 80542.9974769847}, + {72080000, 80545.8216382322}, {72090000, 80548.6750169356}, + {72100000, 80551.5576404596}, {72110000, 80554.4384484848}, + {72120000, 80557.3075613465}, {72130000, 80560.1922346824}, + {72140000, 80563.1098367325}, {72150000, 80566.047880167}, + {72160000, 80568.9765273759}, {72170000, 80571.8926137751}, + {72180000, 80574.7873787352}, {72190000, 80577.6584030216}, + {72200000, 80580.4983793367}, {72210000, 80583.29796342}, + {72220000, 80586.0595946048}, {72230000, 80588.8569038875}, + {72240000, 80591.7107125583}, {72250000, 80594.5682682725}, + {72260000, 80597.395937237}, {72270000, 80600.2082813774}, + {72280000, 80603.0401553988}, {72290000, 80605.8941820522}, + {72300000, 80608.7508484882}, {72310000, 80611.6045833021}, + {72320000, 80614.4507645988}, {72330000, 80617.2834939025}, + {72340000, 80620.0999580095}, {72350000, 80622.8298453863}, + {72360000, 80625.4537053175}, {72370000, 80628.0430586782}, + {72380000, 80630.6435584247}, {72390000, 80633.2463027827}, + {72400000, 80635.8299347028}, {72410000, 80638.3936643906}, + {72420000, 80640.9720459959}, {72430000, 80643.5748768109}, + {72440000, 80646.2092985337}, {72450000, 80648.8844532667}, + {72460000, 80651.5998491502}, {72470000, 80654.3398706513}, + {72480000, 80657.1001028909}, {72490000, 80659.88948566}, + {72500000, 80662.7136727024}, {72510000, 80665.5727425597}, + {72520000, 80668.4671309849}, {72530000, 80671.3947442669}, + {72540000, 80674.2983008132}, {72550000, 80677.1615452325}, + {72560000, 80679.9915869629}, {72570000, 80682.7974439183}, + {72580000, 80685.579844916}, {72590000, 80688.3694844716}, + {72600000, 80691.1761218011}, {72610000, 80693.9874378568}, + {72620000, 80696.7955615697}, {72630000, 80699.6002779824}, + {72640000, 80702.4010463609}, {72650000, 80705.198326934}, + {72660000, 80708.0063652964}, {72670000, 80710.8291837777}, + {72680000, 80713.6588738581}, {72690000, 80716.4853703384}, + {72700000, 80719.3066361534}, {72710000, 80722.1075266894}, + {72720000, 80724.8853317905}, {72730000, 80727.6684382686}, + {72740000, 80730.4749775512}, {72750000, 80733.2951213944}, + {72760000, 80736.1053424935}, {72770000, 80738.9043409117}, + {72780000, 80741.7194011916}, {72790000, 80744.5582497749}, + {72800000, 80747.4164934522}, {72810000, 80750.2885581143}, + {72820000, 80753.1737556679}, {72830000, 80756.0599545986}, + {72840000, 80758.9436905327}, {72850000, 80761.82378008}, + {72860000, 80764.6994712287}, {72870000, 80767.565633308}, + {72880000, 80770.4097931955}, {72890000, 80773.2317967082}, + {72900000, 80776.059614178}, {72910000, 80778.9012041422}, + {72920000, 80781.7529635147}, {72930000, 80784.6103126436}, + {72940000, 80787.4707151469}, {72950000, 80790.3123318214}, + {72960000, 80793.1311024182}, {72970000, 80795.9436626518}, + {72980000, 80798.7606548284}, {72990000, 80801.5772592728}, + {73000000, 80804.3818757682}, {73010000, 80807.1736538136}, + {73020000, 80809.9591318627}, {73030000, 80812.7401975817}, + {73040000, 80815.5130033208}, {73050000, 80818.2726275447}, + {73060000, 80821.0150373964}, {73070000, 80823.7103235825}, + {73080000, 80826.3539355596}, {73090000, 80828.9855052306}, + {73100000, 80831.6303812597}, {73110000, 80834.2867876653}, + {73120000, 80836.9505325092}, {73130000, 80839.6204258395}, + {73140000, 80842.2747972352}, {73150000, 80844.907519899}, + {73160000, 80847.5148533378}, {73170000, 80850.0919928022}, + {73180000, 80852.6389074959}, {73190000, 80855.1835943914}, + {73200000, 80857.7357360781}, {73210000, 80860.283571494}, + {73220000, 80862.8195922939}, {73230000, 80865.3539457594}, + {73240000, 80867.9110372666}, {73250000, 80870.49318795}, + {73260000, 80873.1016980083}, {73270000, 80875.7368449105}, + {73280000, 80878.3932714598}, {73290000, 80881.0641714399}, + {73300000, 80883.7492638101}, {73310000, 80886.4527907668}, + {73320000, 80889.1760440313}, {73330000, 80891.8996124674}, + {73340000, 80894.611090625}, {73350000, 80897.3282060578}, + {73360000, 80900.0937033106}, {73370000, 80902.9103811442}, + {73380000, 80905.7447300298}, {73390000, 80908.5871199683}, + {73400000, 80911.4358669781}, {73410000, 80914.2888311251}, + {73420000, 80917.1449621}, {73430000, 80919.9677551618}, + {73440000, 80922.7465019164}, {73450000, 80925.510325574}, + {73460000, 80928.2778642501}, {73470000, 80931.0445506546}, + {73480000, 80933.7993764252}, {73490000, 80936.5417935286}, + {73500000, 80939.2855222848}, {73510000, 80942.0344752554}, + {73520000, 80944.7926147886}, {73530000, 80947.5650202093}, + {73540000, 80950.3482957593}, {73550000, 80953.1067862322}, + {73560000, 80955.8334342482}, {73570000, 80958.5503826336}, + {73580000, 80961.2717992975}, {73590000, 80964.0032962284}, + {73600000, 80966.7584638055}, {73610000, 80969.5380539674}, + {73620000, 80972.3284504612}, {73630000, 80975.1257273407}, + {73640000, 80977.9250162727}, {73650000, 80980.7201077237}, + {73660000, 80983.5108039404}, {73670000, 80986.2982859525}, + {73680000, 80989.0829420122}, {73690000, 80991.8755540771}, + {73700000, 80994.6830069904}, {73710000, 80997.5029143723}, + {73720000, 81000.3296158492}, {73730000, 81003.1625192032}, + {73740000, 81006.0012862097}, {73750000, 81008.8457993789}, + {73760000, 81011.6768815195}, {73770000, 81014.4700213269}, + {73780000, 81017.2248528106}, {73790000, 81020.0144085425}, + {73800000, 81022.8622724646}, {73810000, 81025.7146832319}, + {73820000, 81028.5372327023}, {73830000, 81031.3367053338}, + {73840000, 81034.1292809173}, {73850000, 81036.9165978126}, + {73860000, 81039.6996159203}, {73870000, 81042.4786248022}, + {73880000, 81045.2533225005}, {73890000, 81048.0233172705}, + {73900000, 81050.7888528831}, {73910000, 81053.5591103709}, + {73920000, 81056.3368000159}, {73930000, 81059.1267550412}, + {73940000, 81061.9320514892}, {73950000, 81064.7476035766}, + {73960000, 81067.561214745}, {73970000, 81070.3711913497}, + {73980000, 81073.1625620214}, {73990000, 81075.9311150427}, + {74000000, 81078.6769295097}, {74010000, 81081.4000742326}, + {74020000, 81084.1007812593}, {74030000, 81086.793400565}, + {74040000, 81089.4825480685}, {74050000, 81092.156707476}, + {74060000, 81094.8085365861}, {74070000, 81097.4456396037}, + {74080000, 81100.0862570019}, {74090000, 81102.7314509821}, + {74100000, 81105.3607766885}, {74110000, 81107.9684486955}, + {74120000, 81110.5543401144}, {74130000, 81113.1182580844}, + {74140000, 81115.6605126055}, {74150000, 81118.1876835807}, + {74160000, 81120.7017182843}, {74170000, 81123.2431659985}, + {74180000, 81125.8379677698}, {74190000, 81128.4790258571}, + {74200000, 81131.1495456558}, {74210000, 81133.8462919354}, + {74220000, 81136.5253885622}, {74230000, 81139.174317249}, + {74240000, 81141.7641558834}, {74250000, 81144.2577772208}, + {74260000, 81146.6517572234}, {74270000, 81148.9273742358}, + {74280000, 81151.0821481096}, {74290000, 81153.1283543616}, + {74300000, 81155.0740535589}, {74310000, 81156.9277138481}, + {74320000, 81158.7091106386}, {74330000, 81160.4232066613}, + {74340000, 81162.1499721045}, {74350000, 81163.9122369815}, + {74360000, 81165.7029533949}, {74370000, 81167.5131503338}, + {74380000, 81169.3427306234}, {74390000, 81171.2028594903}, + {74400000, 81173.0966954413}, {74410000, 81175.0565064943}, + {74420000, 81177.1028837715}, {74430000, 81179.2155695584}, + {74440000, 81181.3461101079}, {74450000, 81183.4905768579}, + {74460000, 81185.674697568}, {74470000, 81187.9056906046}, + {74480000, 81190.1746723427}, {74490000, 81192.4703381634}, + {74500000, 81194.7879726595}, {74510000, 81197.0151603754}, + {74520000, 81199.1205272966}, {74530000, 81201.1172731895}, + {74540000, 81203.0140511057}, {74550000, 81204.8785067347}, + {74560000, 81206.8736052975}, {74570000, 81209.0118149383}, + {74580000, 81211.208911311}, {74590000, 81213.4405738395}, + {74600000, 81215.6655907838}, {74610000, 81217.8312145786}, + {74620000, 81219.9391099395}, {74630000, 81222.0798204887}, + {74640000, 81224.2787800503}, {74650000, 81226.5416062097}, + {74660000, 81228.8717909518}, {74670000, 81231.2589121209}, + {74680000, 81233.6782037732}, {74690000, 81236.1260910192}, + {74700000, 81238.5724681949}, {74710000, 81241.0087221471}, + {74720000, 81243.4541213967}, {74730000, 81245.9333366476}, + {74740000, 81248.4504826216}, {74750000, 81251.0297983383}, + {74760000, 81253.6746408721}, {74770000, 81256.3164693672}, + {74780000, 81258.9113031793}, {74790000, 81261.4913096775}, + {74800000, 81264.1340728876}, {74810000, 81266.8465436518}, + {74820000, 81269.6184971138}, {74830000, 81272.4467948308}, + {74840000, 81275.3061298751}, {74850000, 81278.1641616168}, + {74860000, 81281.0198169664}, {74870000, 81283.8885125615}, + {74880000, 81286.7751483769}, {74890000, 81289.6723879425}, + {74900000, 81292.5755043144}, {74910000, 81295.4869181074}, + {74920000, 81298.4125345766}, {74930000, 81301.3519302402}, + {74940000, 81304.2768194211}, {74950000, 81307.1791299372}, + {74960000, 81310.0805469444}, {74970000, 81313.0088428832}, + {74980000, 81315.9647442464}, {74990000, 81318.9103199114}, + {75000000, 81321.8332862104}, {75010000, 81324.761289638}, + {75020000, 81327.712063367}, {75030000, 81330.6783755245}, + {75040000, 81333.6428705393}, {75050000, 81336.6038316542}, + {75060000, 81339.5603295445}, {75070000, 81342.5121140232}, + {75080000, 81345.4551106776}, {75090000, 81348.38408853}, + {75100000, 81351.2995272184}, {75110000, 81354.2246095052}, + {75120000, 81357.1661708534}, {75130000, 81360.1347674534}, + {75140000, 81363.1371344909}, {75150000, 81366.1553826483}, + {75160000, 81369.1463716082}, {75170000, 81372.1071320584}, + {75180000, 81375.0710439757}, {75190000, 81378.0476597556}, + {75200000, 81381.0335820238}, {75210000, 81384.0244728515}, + {75220000, 81387.0169108885}, {75230000, 81389.9815310506}, + {75240000, 81392.9129980965}, {75250000, 81395.8335578518}, + {75260000, 81398.7575237859}, {75270000, 81401.6750846437}, + {75280000, 81404.5624726595}, {75290000, 81407.4191403294}, + {75300000, 81410.2938380062}, {75310000, 81413.2004689618}, + {75320000, 81416.1280156134}, {75330000, 81419.0623969187}, + {75340000, 81422.0029815688}, {75350000, 81424.9491613068}, + {75360000, 81427.9008155652}, {75370000, 81430.8462737797}, + {75380000, 81433.7780479001}, {75390000, 81436.6959451317}, + {75400000, 81439.5994003572}, {75410000, 81442.489143338}, + {75420000, 81445.3866172973}, {75430000, 81448.2979384068}, + {75440000, 81451.2155132589}, {75450000, 81454.1296253941}, + {75460000, 81457.0398662563}, {75470000, 81459.9457655547}, + {75480000, 81462.8472668301}, {75490000, 81465.7442952625}, + {75500000, 81468.636810678}, {75510000, 81471.5299828295}, + {75520000, 81474.4363160579}, {75530000, 81477.3565141524}, + {75540000, 81480.2769214191}, {75550000, 81483.1936246673}, + {75560000, 81486.1170460591}, {75570000, 81489.0605436215}, + {75580000, 81492.0238887796}, {75590000, 81494.9820249011}, + {75600000, 81497.9275108327}, {75610000, 81500.8591911911}, + {75620000, 81503.7763469773}, {75630000, 81506.6815870874}, + {75640000, 81509.5811481272}, {75650000, 81512.4763952303}, + {75660000, 81515.3891318948}, {75670000, 81518.3255479161}, + {75680000, 81521.2624575238}, {75690000, 81524.1701657602}, + {75700000, 81527.0484051558}, {75710000, 81529.9162598262}, + {75720000, 81532.7791567338}, {75730000, 81535.6660732062}, + {75740000, 81538.5956099154}, {75750000, 81541.5528025529}, + {75760000, 81544.501627239}, {75770000, 81547.4390136112}, + {75780000, 81550.3772273377}, {75790000, 81553.3197796766}, + {75800000, 81556.2510598747}, {75810000, 81559.1510409637}, + {75820000, 81562.025499492}, {75830000, 81564.9322002464}, + {75840000, 81567.8817037508}, {75850000, 81570.8292162089}, + {75860000, 81573.7459223512}, {75870000, 81576.6464225777}, + {75880000, 81579.5659417336}, {75890000, 81582.5071855061}, + {75900000, 81585.4506490071}, {75910000, 81588.3907315666}, + {75920000, 81591.3228315206}, {75930000, 81594.241038714}, + {75940000, 81597.1451891096}, {75950000, 81600.0349955898}, + {75960000, 81602.9104245919}, {75970000, 81605.7944324377}, + {75980000, 81608.7017733089}, {75990000, 81611.627721774}, + {76000000, 81614.5609353717}, {76010000, 81617.4997763346}, + {76020000, 81620.429303481}, {76030000, 81623.3452587465}, + {76040000, 81626.2472845905}, {76050000, 81629.1349022041}, + {76060000, 81632.0079039822}, {76070000, 81634.8585695057}, + {76080000, 81637.6847613202}, {76090000, 81640.5440738104}, + {76100000, 81643.4735496008}, {76110000, 81646.4381778205}, + {76120000, 81649.353371367}, {76130000, 81652.2130628922}, + {76140000, 81655.0769347259}, {76150000, 81657.9620990082}, + {76160000, 81660.8575855166}, {76170000, 81663.7493468307}, + {76180000, 81666.6370232892}, {76190000, 81669.5370961792}, + {76200000, 81672.4547845627}, {76210000, 81675.3771405463}, + {76220000, 81678.2958152109}, {76230000, 81681.2028741145}, + {76240000, 81684.0790072677}, {76250000, 81686.9245703668}, + {76260000, 81689.8028523303}, {76270000, 81692.7318989918}, + {76280000, 81695.6811793283}, {76290000, 81698.6115529175}, + {76300000, 81701.521748024}, {76310000, 81704.4158865448}, + {76320000, 81707.2952516911}, {76330000, 81710.1830360798}, + {76340000, 81713.0941650117}, {76350000, 81716.0187619576}, + {76360000, 81718.9329904113}, {76370000, 81721.8349902573}, + {76380000, 81724.7377366463}, {76390000, 81727.6449593952}, + {76400000, 81730.5452564051}, {76410000, 81733.4239894134}, + {76420000, 81736.2807144727}, {76430000, 81739.1446192406}, + {76440000, 81742.0254478077}, {76450000, 81744.9050198499}, + {76460000, 81747.7716262646}, {76470000, 81750.6326748201}, + {76480000, 81753.5060763198}, {76490000, 81756.3928466255}, + {76500000, 81759.2725285849}, {76510000, 81762.1392767875}, + {76520000, 81764.9963083399}, {76530000, 81767.8477365895}, + {76540000, 81770.6935148276}, {76550000, 81773.5273971574}, + {76560000, 81776.347657694}, {76570000, 81779.1769653725}, + {76580000, 81782.0299254575}, {76590000, 81784.9017943604}, + {76600000, 81787.7812002187}, {76610000, 81790.6667376652}, + {76620000, 81793.5506110653}, {76630000, 81796.4305892195}, + {76640000, 81799.3098168821}, {76650000, 81802.1923275164}, + {76660000, 81805.077747848}, {76670000, 81807.9456019212}, + {76680000, 81810.7898458966}, {76690000, 81813.6159905908}, + {76700000, 81816.4276177638}, {76710000, 81819.2351470386}, + {76720000, 81822.0639102464}, {76730000, 81824.9151783873}, + {76740000, 81827.7545846102}, {76750000, 81830.5722769592}, + {76760000, 81833.3714458696}, {76770000, 81836.1561611328}, + {76780000, 81838.9266508209}, {76790000, 81841.6832312502}, + {76800000, 81844.4260453769}, {76810000, 81847.1494397645}, + {76820000, 81849.8498020997}, {76830000, 81852.5194249065}, + {76840000, 81855.1393901238}, {76850000, 81857.7089811281}, + {76860000, 81860.255925779}, {76870000, 81862.7882678683}, + {76880000, 81865.2995321884}, {76890000, 81867.7813738174}, + {76900000, 81870.2338328187}, {76910000, 81872.6849824271}, + {76920000, 81875.1438366065}, {76930000, 81877.5530229193}, + {76940000, 81879.87562411}, {76950000, 81882.1210730618}, + {76960000, 81884.3116996663}, {76970000, 81886.4521062401}, + {76980000, 81888.6080187598}, {76990000, 81890.7982587195}, + {77000000, 81892.9894713069}, {77010000, 81895.1387928742}, + {77020000, 81897.2453827123}, {77030000, 81899.3325856955}, + {77040000, 81901.4074355441}, {77050000, 81903.4997302535}, + {77060000, 81905.6286827423}, {77070000, 81907.8101386747}, + {77080000, 81910.083001574}, {77090000, 81912.4493341075}, + {77100000, 81914.8680842661}, {77110000, 81917.3272665046}, + {77120000, 81919.8406163735}, {77130000, 81922.4258492579}, + {77140000, 81925.0789801786}, {77150000, 81927.7600156318}, + {77160000, 81930.4613336872}, {77170000, 81933.1862900827}, + {77180000, 81935.9370105657}, {77190000, 81938.7057714087}, + {77200000, 81941.4739444191}, {77210000, 81944.2406152256}, + {77220000, 81947.0332915908}, {77230000, 81949.8597878708}, + {77240000, 81952.7153978712}, {77250000, 81955.5941158865}, + {77260000, 81958.4963502335}, {77270000, 81961.4421490745}, + {77280000, 81964.4370142702}, {77290000, 81967.4323686715}, + {77300000, 81970.3968404466}, {77310000, 81973.334694372}, + {77320000, 81976.2560966029}, {77330000, 81979.1621360047}, + {77340000, 81982.0534787508}, {77350000, 81984.9303684458}, + {77360000, 81987.7855814805}, {77370000, 81990.6098031009}, + {77380000, 81993.402914645}, {77390000, 81996.1771423715}, + {77400000, 81998.936485219}, {77410000, 82001.6759054771}, + {77420000, 82004.3921846811}, {77430000, 82007.0802110294}, + {77440000, 82009.7273243637}, {77450000, 82012.3331369045}, + {77460000, 82014.9185226223}, {77470000, 82017.4895682066}, + {77480000, 82020.035164682}, {77490000, 82022.5409986324}, + {77500000, 82025.0138382638}, {77510000, 82027.5188971798}, + {77520000, 82030.0682164844}, {77530000, 82032.6116946583}, + {77540000, 82035.1169458044}, {77550000, 82037.5907553123}, + {77560000, 82040.049376229}, {77570000, 82042.4947336443}, + {77580000, 82044.9349386433}, {77590000, 82047.37234088}, + {77600000, 82049.7913707271}, {77610000, 82052.1719925693}, + {77620000, 82054.5166388694}, {77630000, 82056.8527618496}, + {77640000, 82059.1854954112}, {77650000, 82061.4700461227}, + {77660000, 82063.6775708635}, {77670000, 82065.8356198571}, + {77680000, 82068.0108197075}, {77690000, 82070.2092781193}, + {77700000, 82072.4203905676}, {77710000, 82074.6410616622}, + {77720000, 82076.9108673389}, {77730000, 82079.2807824767}, + {77740000, 82081.7559462559}, {77750000, 82084.3630282812}, + {77760000, 82087.1055150289}, {77770000, 82089.9201061691}, + {77780000, 82092.7657452109}, {77790000, 82095.6460231713}, + {77800000, 82098.5699202621}, {77810000, 82101.5357942779}, + {77820000, 82104.4725330815}, {77830000, 82107.3597836812}, + {77840000, 82110.2526830297}, {77850000, 82113.2221573442}, + {77860000, 82116.268694758}, {77870000, 82119.3175987089}, + {77880000, 82122.346554415}, {77890000, 82125.3012044691}, + {77900000, 82128.1465306431}, {77910000, 82130.9202808474}, + {77920000, 82133.7137161915}, {77930000, 82136.5318798289}, + {77940000, 82139.2584749691}, {77950000, 82141.8603720545}, + {77960000, 82144.3316549508}, {77970000, 82146.6645235855}, + {77980000, 82148.85865913}, {77990000, 82150.8872269331}, + {78000000, 82152.7428106053}, {78010000, 82154.4632986283}, + {78020000, 82156.0734259673}, {78030000, 82157.6460859224}, + {78040000, 82159.358234077}, {78050000, 82161.2234012992}, + {78060000, 82163.1438229422}, {78070000, 82165.0911798743}, + {78080000, 82167.0870193536}, {78090000, 82169.1591265525}, + {78100000, 82171.3079934498}, {78110000, 82173.5032437855}, + {78120000, 82175.7349227789}, {78130000, 82177.9754489908}, + {78140000, 82180.2069277672}, {78150000, 82182.3751231147}, + {78160000, 82184.347568027}, {78170000, 82186.1226174909}, + {78180000, 82188.0219809603}, {78190000, 82190.1378359336}, + {78200000, 82192.3845483108}, {78210000, 82194.6520724163}, + {78220000, 82196.9339812291}, {78230000, 82199.1636559942}, + {78240000, 82201.3220924232}, {78250000, 82203.4672521162}, + {78260000, 82205.6366838219}, {78270000, 82207.8186993913}, + {78280000, 82209.9849406073}, {78290000, 82212.1352193871}, + {78300000, 82214.3464910524}, {78310000, 82216.6406765055}, + {78320000, 82218.9977566653}, {78330000, 82221.3920529727}, + {78340000, 82223.8248600935}, {78350000, 82226.3627808599}, + {78360000, 82229.0242657519}, {78370000, 82231.70138715}, + {78380000, 82234.3242430925}, {78390000, 82236.9394640973}, + {78400000, 82239.6604938918}, {78410000, 82242.4940012717}, + {78420000, 82245.3174356958}, {78430000, 82248.0955513388}, + {78440000, 82250.8524034667}, {78450000, 82253.6189274441}, + {78460000, 82256.3945025644}, {78470000, 82259.1147776725}, + {78480000, 82261.7609536197}, {78490000, 82264.3569433789}, + {78500000, 82266.9183547027}, {78510000, 82269.3946425456}, + {78520000, 82271.6621661459}, {78530000, 82273.7232478824}, + {78540000, 82275.9929061004}, {78550000, 82278.5898826763}, + {78560000, 82281.4147808798}, {78570000, 82284.3399805139}, + {78580000, 82287.3590724638}, {78590000, 82290.3074381082}, + {78600000, 82293.1322922565}, {78610000, 82295.857184187}, + {78620000, 82298.4975531409}, {78630000, 82301.0592960796}, + {78640000, 82303.556214004}, {78650000, 82305.9923064427}, + {78660000, 82308.4400049447}, {78670000, 82310.9201209592}, + {78680000, 82313.4339782854}, {78690000, 82315.9833321276}, + {78700000, 82318.5707856281}, {78710000, 82321.2208551466}, + {78720000, 82323.9378572432}, {78730000, 82326.6124372042}, + {78740000, 82329.1737811324}, {78750000, 82331.6814040895}, + {78760000, 82334.2799389133}, {78770000, 82336.9785743525}, + {78780000, 82339.6351652947}, {78790000, 82342.2089051653}, + {78800000, 82344.7690184546}, {78810000, 82347.4046740113}, + {78820000, 82350.1164722436}, {78830000, 82352.7684557792}, + {78840000, 82355.319039241}, {78850000, 82357.8368451516}, + {78860000, 82360.3664140591}, {78870000, 82362.9167674566}, + {78880000, 82365.5100383235}, {78890000, 82368.1496364207}, + {78900000, 82370.8794059373}, {78910000, 82373.7116599738}, + {78920000, 82376.614380352}, {78930000, 82379.5464184546}, + {78940000, 82382.5052028319}, {78950000, 82385.4822965025}, + {78960000, 82388.4759991294}, {78970000, 82391.496661104}, + {78980000, 82394.5509535997}, {78990000, 82397.6287297052}, + {79000000, 82400.7054340265}, {79010000, 82403.7793111275}, + {79020000, 82406.8703925641}, {79030000, 82409.9843889667}, + {79040000, 82413.0778248611}, {79050000, 82416.094656175}, + {79060000, 82419.0458441537}, {79070000, 82422.0300831538}, + {79080000, 82425.0630619708}, {79090000, 82428.1136367145}, + {79100000, 82431.1615629197}, {79110000, 82434.2087356964}, + {79120000, 82437.2597725702}, {79130000, 82440.3137274683}, + {79140000, 82443.327998013}, {79150000, 82446.2904500102}, + {79160000, 82449.2089423812}, {79170000, 82452.0935442807}, + {79180000, 82454.9450728551}, {79190000, 82457.7771269341}, + {79200000, 82460.5939118426}, {79210000, 82463.3904571888}, + {79220000, 82466.1635720365}, {79230000, 82468.9285994815}, + {79240000, 82471.7228677824}, {79250000, 82474.549977147}, + {79260000, 82477.411863724}, {79270000, 82480.3089621404}, + {79280000, 82483.2355675412}, {79290000, 82486.1843731804}, + {79300000, 82489.155031126}, {79310000, 82492.153239412}, + {79320000, 82495.1807445523}, {79330000, 82498.228954499}, + {79340000, 82501.2922566757}, {79350000, 82504.3653363902}, + {79360000, 82507.4352996358}, {79370000, 82510.5013308438}, + {79380000, 82513.5769824331}, {79390000, 82516.6661282508}, + {79400000, 82519.7496389455}, {79410000, 82522.8028389856}, + {79420000, 82525.8255011173}, {79430000, 82528.8683778424}, + {79440000, 82531.9474470168}, {79450000, 82535.0556794139}, + {79460000, 82538.1884621388}, {79470000, 82541.3277083875}, + {79480000, 82544.4293435404}, {79490000, 82547.4905086858}, + {79500000, 82550.5517068167}, {79510000, 82553.6246171047}, + {79520000, 82556.6826376437}, {79530000, 82559.6914141805}, + {79540000, 82562.6557295396}, {79550000, 82565.6315321406}, + {79560000, 82568.6295339248}, {79570000, 82571.6054615156}, + {79580000, 82574.5306175447}, {79590000, 82577.4272722752}, + {79600000, 82580.3495460087}, {79610000, 82583.3015862952}, + {79620000, 82586.2506281188}, {79630000, 82589.1872341056}, + {79640000, 82592.110541872}, {79650000, 82595.0194187305}, + {79660000, 82597.9140791991}, {79670000, 82600.8260778283}, + {79680000, 82603.7655495201}, {79690000, 82606.7252262852}, + {79700000, 82609.7003557941}, {79710000, 82612.6856391103}, + {79720000, 82615.6682233866}, {79730000, 82618.6479865628}, + {79740000, 82621.6598921671}, {79750000, 82624.7139082962}, + {79760000, 82627.7646681056}, {79770000, 82630.7536664456}, + {79780000, 82633.6794037898}, {79790000, 82636.6081962735}, + {79800000, 82639.5614095905}, {79810000, 82642.5449040424}, + {79820000, 82645.5624356501}, {79830000, 82648.5987096217}, + {79840000, 82651.6165098187}, {79850000, 82654.612651877}, + {79860000, 82657.5994129786}, {79870000, 82660.5803693818}, + {79880000, 82663.5592399622}, {79890000, 82666.5408211785}, + {79900000, 82669.5253549823}, {79910000, 82672.5158575638}, + {79920000, 82675.5132118733}, {79930000, 82678.5219436448}, + {79940000, 82681.5449743138}, {79950000, 82684.5721536138}, + {79960000, 82687.5787232206}, {79970000, 82690.5634417329}, + {79980000, 82693.5606660037}, {79990000, 82696.5802667072}, + {80000000, 82699.6105975493}, {80010000, 82702.63664382}, + {80020000, 82705.6577152139}, {80030000, 82708.6508060332}, + {80040000, 82711.6085788224}, {80050000, 82714.5658153566}, + {80060000, 82717.545120045}, {80070000, 82720.5420319059}, + {80080000, 82723.5457723885}, {80090000, 82726.5554602102}, + {80100000, 82729.5775966069}, {80110000, 82732.6140136736}, + {80120000, 82735.6452841098}, {80130000, 82738.6463275824}, + {80140000, 82741.6169329119}, {80150000, 82744.5764935777}, + {80160000, 82747.5306677708}, {80170000, 82750.4854776013}, + {80180000, 82753.4448404497}, {80190000, 82756.4190885335}, + {80200000, 82759.4335625953}, {80210000, 82762.4885572855}, + {80220000, 82765.5210968905}, {80230000, 82768.5130869224}, + {80240000, 82771.4631229073}, {80250000, 82774.3693300848}, + {80260000, 82777.2383903329}, {80270000, 82780.1215502832}, + {80280000, 82783.0270482611}, {80290000, 82785.9165723783}, + {80300000, 82788.765221356}, {80310000, 82791.5850902455}, + {80320000, 82794.4055406909}, {80330000, 82797.2290560645}, + {80340000, 82800.0430225762}, {80350000, 82802.8438309281}, + {80360000, 82805.6533263769}, {80370000, 82808.49973911}, + {80380000, 82811.3836554979}, {80390000, 82814.2914351946}, + {80400000, 82817.2189047618}, {80410000, 82820.1291156087}, + {80420000, 82822.9980557473}, {80430000, 82825.8379056069}, + {80440000, 82828.6782333161}, {80450000, 82831.5210866606}, + {80460000, 82834.3395618703}, {80470000, 82837.1259749259}, + {80480000, 82839.8989288697}, {80490000, 82842.6824330242}, + {80500000, 82845.4760253726}, {80510000, 82848.2382986172}, + {80520000, 82850.9574172357}, {80530000, 82853.6733665601}, + {80540000, 82856.4121697888}, {80550000, 82859.1669112885}, + {80560000, 82861.9207990794}, {80570000, 82864.6719290736}, + {80580000, 82867.4122492255}, {80590000, 82870.1394703431}, + {80600000, 82872.8794395685}, {80610000, 82875.6655907768}, + {80620000, 82878.4988204104}, {80630000, 82881.3741705625}, + {80640000, 82884.2900792146}, {80650000, 82887.2318017592}, + {80660000, 82890.1896995941}, {80670000, 82893.1634200369}, + {80680000, 82896.1522158144}, {80690000, 82899.1552611075}, + {80700000, 82902.1510455273}, {80710000, 82905.1333821723}, + {80720000, 82908.1017361952}, {80730000, 82911.0553959461}, + {80740000, 82913.9963872492}, {80750000, 82916.9394668066}, + {80760000, 82919.8868829439}, {80770000, 82922.833392267}, + {80780000, 82925.7755802724}, {80790000, 82928.7057130163}, + {80800000, 82931.6047731539}, {80810000, 82934.4723534731}, + {80820000, 82937.3503459547}, {80830000, 82940.2508226334}, + {80840000, 82943.1623419657}, {80850000, 82946.0701289559}, + {80860000, 82948.9737150506}, {80870000, 82951.8816731196}, + {80880000, 82954.7967189}, {80890000, 82957.7234686887}, + {80900000, 82960.6649098444}, {80910000, 82963.6134546883}, + {80920000, 82966.5505833709}, {80930000, 82969.4751633046}, + {80940000, 82972.4076133134}, {80950000, 82975.3538170758}, + {80960000, 82978.3130896322}, {80970000, 82981.284563619}, + {80980000, 82984.2681207456}, {80990000, 82987.2526109901}, + {81000000, 82990.2343761974}, {81010000, 82993.2007244299}, + {81020000, 82996.1434134519}, {81030000, 82999.0750252884}, + {81040000, 83002.0262749987}, {81050000, 83004.9996999304}, + {81060000, 83007.9826529766}, {81070000, 83010.9714447736}, + {81080000, 83013.9613208325}, {81090000, 83016.9461362309}, + {81100000, 83019.9251507818}, {81110000, 83022.875949848}, + {81120000, 83025.7919103363}, {81130000, 83028.7018954163}, + {81140000, 83031.6247432762}, {81150000, 83034.5508183034}, + {81160000, 83037.4565599096}, {81170000, 83040.3406044141}, + {81180000, 83043.2302788673}, {81190000, 83046.1334622323}, + {81200000, 83049.0348879117}, {81210000, 83051.9148000284}, + {81220000, 83054.7731607853}, {81230000, 83057.6157744674}, + {81240000, 83060.4437933077}, {81250000, 83063.2518151569}, + {81260000, 83066.0363504537}, {81270000, 83068.7999430252}, + {81280000, 83071.5486733113}, {81290000, 83074.2834444274}, + {81300000, 83077.0118402513}, {81310000, 83079.7360772102}, + {81320000, 83082.4602661062}, {81330000, 83085.1897257786}, + {81340000, 83087.9200217606}, {81350000, 83090.6149079871}, + {81360000, 83093.2686236645}, {81370000, 83095.8802068757}, + {81380000, 83098.4491025201}, {81390000, 83100.9831278078}, + {81400000, 83103.5011831005}, {81410000, 83106.0050102669}, + {81420000, 83108.4886026071}, {81430000, 83110.9502940749}, + {81440000, 83113.4019654364}, {81450000, 83115.8589740423}, + {81460000, 83118.3239671847}, {81470000, 83120.8131938967}, + {81480000, 83123.3291910365}, {81490000, 83125.8778111286}, + {81500000, 83128.4628158331}, {81510000, 83131.0943525077}, + {81520000, 83133.7976249556}, {81530000, 83136.5746139474}, + {81540000, 83139.4192547969}, {81550000, 83142.3295537855}, + {81560000, 83145.2875475956}, {81570000, 83148.2700651865}, + {81580000, 83151.2751639861}, {81590000, 83154.267650755}, + {81600000, 83157.2371579802}, {81610000, 83160.1827527872}, + {81620000, 83163.1038677223}, {81630000, 83165.9980460954}, + {81640000, 83168.8590646167}, {81650000, 83171.6875734932}, + {81660000, 83174.5190360831}, {81670000, 83177.3637008272}, + {81680000, 83180.2029906477}, {81690000, 83183.0128608627}, + {81700000, 83185.7921166909}, {81710000, 83188.5291119705}, + {81720000, 83191.2206774333}, {81730000, 83193.8739535013}, + {81740000, 83196.4936694507}, {81750000, 83199.0852007576}, + {81760000, 83201.6615278326}, {81770000, 83204.2235738897}, + {81780000, 83206.7578804275}, {81790000, 83209.2606491344}, + {81800000, 83211.7201568545}, {81810000, 83214.1211572025}, + {81820000, 83216.4702663422}, {81830000, 83218.8318637607}, + {81840000, 83221.2180343908}, {81850000, 83223.6533454983}, + {81860000, 83226.1537586183}, {81870000, 83228.7373173485}, + {81880000, 83231.4488915001}, {81890000, 83234.2903938214}, + {81900000, 83237.1995308753}, {81910000, 83240.1580287394}, + {81920000, 83243.1323328419}, {81930000, 83246.0790142082}, + {81940000, 83248.9991705464}, {81950000, 83251.9890413979}, + {81960000, 83255.076742369}, {81970000, 83258.1399222344}, + {81980000, 83261.098610771}, {81990000, 83263.9786998041}, + {82000000, 83266.8431991707}, {82010000, 83269.6971697628}, + {82020000, 83272.501397905}, {82030000, 83275.2446975135}, + {82040000, 83277.9501155044}, {82050000, 83280.6474403791}, + {82060000, 83283.339902824}, {82070000, 83286.09292563}, + {82080000, 83288.9252505745}, {82090000, 83291.7999885024}, + {82100000, 83294.6929731277}, {82110000, 83297.6008485051}, + {82120000, 83300.5154911084}, {82130000, 83303.4342636381}, + {82140000, 83306.2996375891}, {82150000, 83309.0951465613}, + {82160000, 83311.8836568359}, {82170000, 83314.7465689194}, + {82180000, 83317.6865635213}, {82190000, 83320.6467244416}, + {82200000, 83323.6082868086}, {82210000, 83326.5733236518}, + {82220000, 83329.5431846987}, {82230000, 83332.5229838188}, + {82240000, 83335.5253524659}, {82250000, 83338.5505675722}, + {82260000, 83341.5707203863}, {82270000, 83344.5777424077}, + {82280000, 83347.5782902309}, {82290000, 83350.5809743259}, + {82300000, 83353.5848840417}, {82310000, 83356.5385754016}, + {82320000, 83359.4268250546}, {82330000, 83362.3246860416}, + {82340000, 83365.2812232107}, {82350000, 83368.2572085283}, + {82360000, 83371.1561248237}, {82370000, 83373.9718907771}, + {82380000, 83376.8064565482}, {82390000, 83379.6893659783}, + {82400000, 83382.5913978049}, {82410000, 83385.4747075252}, + {82420000, 83388.3381318212}, {82430000, 83391.2252660976}, + {82440000, 83394.1501783177}, {82450000, 83397.0883077324}, + {82460000, 83400.0235701318}, {82470000, 83402.9656610384}, + {82480000, 83405.9384407985}, {82490000, 83408.9430549806}, + {82500000, 83411.9450553057}, {82510000, 83414.9344698281}, + {82520000, 83417.9066881769}, {82530000, 83420.8557089486}, + {82540000, 83423.782529883}, {82550000, 83426.7245547588}, + {82560000, 83429.6926280759}, {82570000, 83432.6688760038}, + {82580000, 83435.6415958945}, {82590000, 83438.6053613073}, + {82600000, 83441.546780376}, {82610000, 83444.4668370285}, + {82620000, 83447.4362427406}, {82630000, 83450.4753112891}, + {82640000, 83453.5383853726}, {82650000, 83456.5663252861}, + {82660000, 83459.5576290225}, {82670000, 83462.5360309657}, + {82680000, 83465.5086089887}, {82690000, 83468.4531230447}, + {82700000, 83471.3550587731}, {82710000, 83474.2115965186}, + {82720000, 83477.015470961}, {82730000, 83479.7661885925}, + {82740000, 83482.4636055201}, {82750000, 83485.1078683837}, + {82760000, 83487.7043083585}, {82770000, 83490.2597629507}, + {82780000, 83492.7742533525}, {82790000, 83495.2285830748}, + {82800000, 83497.6171827037}, {82810000, 83499.95981432}, + {82820000, 83502.2694800117}, {82830000, 83504.5644834544}, + {82840000, 83506.889717687}, {82850000, 83509.247343023}, + {82860000, 83511.5683880427}, {82870000, 83513.8329819988}, + {82880000, 83516.0158869937}, {82890000, 83518.0842408871}, + {82900000, 83520.0382748626}, {82910000, 83522.0077982962}, + {82920000, 83524.0344489646}, {82930000, 83526.0850735415}, + {82940000, 83528.1379231783}, {82950000, 83530.2278859929}, + {82960000, 83532.4410086229}, {82970000, 83534.7822855356}, + {82980000, 83537.1561191487}, {82990000, 83539.5346734488}, + {83000000, 83541.9516890075}, {83010000, 83544.4509920922}, + {83020000, 83547.0335749572}, {83030000, 83549.6855843436}, + {83040000, 83552.4026210689}, {83050000, 83555.2246337744}, + {83060000, 83558.1776007927}, {83070000, 83561.2111457966}, + {83080000, 83564.2018694}, {83090000, 83567.1397562539}, + {83100000, 83570.0894002688}, {83110000, 83573.0695055079}, + {83120000, 83576.0772527594}, {83130000, 83579.1090268323}, + {83140000, 83582.1671268635}, {83150000, 83585.2754163269}, + {83160000, 83588.4382389018}, {83170000, 83591.6322178728}, + {83180000, 83594.8419745553}, {83190000, 83598.0238134578}, + {83200000, 83601.0699813591}, {83210000, 83603.9742374975}, + {83220000, 83606.8595881197}, {83230000, 83609.761768837}, + {83240000, 83612.7125198188}, {83250000, 83615.7530877385}, + {83260000, 83618.8783574993}, {83270000, 83621.9035408487}, + {83280000, 83624.7761500631}, {83290000, 83627.6613208679}, + {83300000, 83630.6672941864}, {83310000, 83633.7538666419}, + {83320000, 83636.8226777619}, {83330000, 83639.8634742548}, + {83340000, 83642.8565335594}, {83350000, 83645.7963007002}, + {83360000, 83648.6877114393}, {83370000, 83651.5371003478}, + {83380000, 83654.3450790983}, {83390000, 83657.1864412165}, + {83400000, 83660.0856103488}, {83410000, 83663.0065414383}, + {83420000, 83665.9255664714}, {83430000, 83668.8521420862}, + {83440000, 83671.8096256429}, {83450000, 83674.7989143071}, + {83460000, 83677.7783579564}, {83470000, 83680.7358945676}, + {83480000, 83683.6705748631}, {83490000, 83686.5811316527}, + {83500000, 83689.4707859123}, {83510000, 83692.36903988}, + {83520000, 83695.2814462348}, {83530000, 83698.2029034817}, + {83540000, 83701.1300517031}, {83550000, 83704.0475451712}, + {83560000, 83706.9175423733}, {83570000, 83709.7395337349}, + {83580000, 83712.61145055}, {83590000, 83715.5615367783}, + {83600000, 83718.5442609955}, {83610000, 83721.5005595197}, + {83620000, 83724.432556182}, {83630000, 83727.3804032269}, + {83640000, 83730.3516410504}, {83650000, 83733.3470504486}, + {83660000, 83736.3671021845}, {83670000, 83739.3888784259}, + {83680000, 83742.355984021}, {83690000, 83745.2658565063}, + {83700000, 83748.2083221256}, {83710000, 83751.2093339297}, + {83720000, 83754.2350837235}, {83730000, 83757.2417160457}, + {83740000, 83760.2271935044}, {83750000, 83763.1884838133}, + {83760000, 83766.1252238671}, {83770000, 83769.0715624093}, + {83780000, 83772.0498989889}, {83790000, 83775.0456204167}, + {83800000, 83778.0228468777}, {83810000, 83780.9789272614}, + {83820000, 83783.9404820902}, {83830000, 83786.9152236505}, + {83840000, 83789.8880953627}, {83850000, 83792.839529819}, + {83860000, 83795.7693320876}, {83870000, 83798.6984842731}, + {83880000, 83801.6333145972}, {83890000, 83804.5734858562}, + {83900000, 83807.5187676386}, {83910000, 83810.4742241927}, + {83920000, 83813.4524090728}, {83930000, 83816.4536076323}, + {83940000, 83819.4498890365}, {83950000, 83822.4331584656}, + {83960000, 83825.4174022256}, {83970000, 83828.4207956414}, + {83980000, 83831.4430498623}, {83990000, 83834.4437835461}, + {84000000, 83837.4109062134}, {84010000, 83840.3723607534}, + {84020000, 83843.3464989935}, {84030000, 83846.3262533396}, + {84040000, 83849.2942501435}, {84050000, 83852.2490129044}, + {84060000, 83855.1967575126}, {84070000, 83858.1393140869}, + {84080000, 83861.0764921075}, {84090000, 83864.008035806}, + {84100000, 83866.9341171435}, {84110000, 83869.8878339236}, + {84120000, 83872.8798420098}, {84130000, 83875.8624127901}, + {84140000, 83878.8041930717}, {84150000, 83881.7170712555}, + {84160000, 83884.6301282955}, {84170000, 83887.5462894111}, + {84180000, 83890.4671718098}, {84190000, 83893.3932285167}, + {84200000, 83896.3201394955}, {84210000, 83899.2422925846}, + {84220000, 83902.1592826257}, {84230000, 83905.0642905224}, + {84240000, 83907.9553764727}, {84250000, 83910.8266053046}, + {84260000, 83913.6741147679}, {84270000, 83916.4978830724}, + {84280000, 83919.2976813151}, {84290000, 83922.0740324346}, + {84300000, 83924.8413173032}, {84310000, 83927.6037446971}, + {84320000, 83930.3503404224}, {84330000, 83933.0668081964}, + {84340000, 83935.7535768655}, {84350000, 83938.4384402138}, + {84360000, 83941.1294837821}, {84370000, 83943.8267993917}, + {84380000, 83946.5304367723}, {84390000, 83949.2429189664}, + {84400000, 83951.9705351311}, {84410000, 83954.7134125863}, + {84420000, 83957.4575631554}, {84430000, 83960.1989196394}, + {84440000, 83962.936789205}, {84450000, 83965.6702654763}, + {84460000, 83968.4009805826}, {84470000, 83971.1767549502}, + {84480000, 83974.0110813223}, {84490000, 83976.8791252544}, + {84500000, 83979.7645074601}, {84510000, 83982.6691939521}, + {84520000, 83985.5981769573}, {84530000, 83988.5505449162}, + {84540000, 83991.4837100128}, {84550000, 83994.3853610512}, + {84560000, 83997.2806387052}, {84570000, 84000.2022288905}, + {84580000, 84003.151190478}, {84590000, 84006.105651795}, + {84600000, 84009.058481166}, {84610000, 84012.0134984035}, + {84620000, 84014.9732145455}, {84630000, 84017.9351824385}, + {84640000, 84020.8933819954}, {84650000, 84023.84700615}, + {84660000, 84026.7886023364}, {84670000, 84029.7160467841}, + {84680000, 84032.6330877987}, {84690000, 84035.5445841554}, + {84700000, 84038.4508357082}, {84710000, 84041.3526459794}, + {84720000, 84044.2501854307}, {84730000, 84047.1376287814}, + {84740000, 84050.0111580628}, {84750000, 84052.8757835978}, + {84760000, 84055.7438176102}, {84770000, 84058.6162673229}, + {84780000, 84061.4866505496}, {84790000, 84064.3530904104}, + {84800000, 84067.2040570456}, {84810000, 84070.0245149219}, + {84820000, 84072.8147340792}, {84830000, 84075.6024481136}, + {84840000, 84078.3958963457}, {84850000, 84081.2064958857}, + {84860000, 84084.0417341135}, {84870000, 84086.9017623041}, + {84880000, 84089.7871375312}, {84890000, 84092.6973699267}, + {84900000, 84095.6181002521}, {84910000, 84098.5451132315}, + {84920000, 84101.4699641898}, {84930000, 84104.3816674393}, + {84940000, 84107.2813131464}, {84950000, 84110.1831976676}, + {84960000, 84113.0901131584}, {84970000, 84116.0249338258}, + {84980000, 84119.0026715496}, {84990000, 84122.013519316}, + {85000000, 84125.033493636}, {85010000, 84128.0592714263}, + {85020000, 84131.0609115099}, {85030000, 84134.0297868314}, + {85040000, 84136.9850690702}, {85050000, 84139.9516985833}, + {85060000, 84142.9290187878}, {85070000, 84145.9044860639}, + {85080000, 84148.8760523283}, {85090000, 84151.8488297591}, + {85100000, 84154.8261818567}, {85110000, 84157.8006168228}, + {85120000, 84160.7536044869}, {85130000, 84163.6846696094}, + {85140000, 84166.6356535796}, {85150000, 84169.6186610464}, + {85160000, 84172.6109668959}, {85170000, 84175.582997638}, + {85180000, 84178.5337936857}, {85190000, 84181.4680825172}, + {85200000, 84184.38734466}, {85210000, 84187.2975504365}, + {85220000, 84190.2026602951}, {85230000, 84193.1003029099}, + {85240000, 84195.9845579794}, {85250000, 84198.8546738996}, + {85260000, 84201.7032579233}, {85270000, 84204.5282331697}, + {85280000, 84207.3190139064}, {85290000, 84210.061765034}, + {85300000, 84212.7563558866}, {85310000, 84215.4511288184}, + {85320000, 84218.1618393609}, {85330000, 84220.8828757063}, + {85340000, 84223.6105213745}, {85350000, 84226.3547822694}, + {85360000, 84229.1405289809}, {85370000, 84231.9690014981}, + {85380000, 84234.8056736893}, {85390000, 84237.6404702579}, + {85400000, 84240.4794539054}, {85410000, 84243.3305313825}, + {85420000, 84246.1942310709}, {85430000, 84249.0829046529}, + {85440000, 84252.0001921604}, {85450000, 84254.9326123545}, + {85460000, 84257.8712534242}, {85470000, 84260.8183543194}, + {85480000, 84263.7795152925}, {85490000, 84266.7545941132}, + {85500000, 84269.7224598641}, {85510000, 84272.6769844586}, + {85520000, 84275.6254122974}, {85530000, 84278.5771741184}, + {85540000, 84281.5327869927}, {85550000, 84284.4937903177}, + {85560000, 84287.4604613228}, {85570000, 84290.4267489698}, + {85580000, 84293.3886652826}, {85590000, 84296.3461016428}, + {85600000, 84299.2987562094}, {85610000, 84302.2466212685}, + {85620000, 84305.1897452159}, {85630000, 84308.1281588708}, + {85640000, 84311.0542204166}, {85650000, 84313.9579527543}, + {85660000, 84316.8392415273}, {85670000, 84319.7434016266}, + {85680000, 84322.6851257522}, {85690000, 84325.6172931423}, + {85700000, 84328.5088596155}, {85710000, 84331.3716866551}, + {85720000, 84334.2348981595}, {85730000, 84337.1012156441}, + {85740000, 84339.9651730623}, {85750000, 84342.8251869729}, + {85760000, 84345.6879625473}, {85770000, 84348.5622489994}, + {85780000, 84351.44821294}, {85790000, 84354.311593508}, + {85800000, 84357.1412917968}, {85810000, 84359.9769980332}, + {85820000, 84362.8448644378}, {85830000, 84365.7354678482}, + {85840000, 84368.6256705568}, {85850000, 84371.5135721842}, + {85860000, 84374.412191305}, {85870000, 84377.3252812481}, + {85880000, 84380.237427393}, {85890000, 84383.1285244161}, + {85900000, 84385.9985880273}, {85910000, 84388.8841845164}, + {85920000, 84391.7964235686}, {85930000, 84394.7116242913}, + {85940000, 84397.6141525929}, {85950000, 84400.5086512212}, + {85960000, 84403.4065563094}, {85970000, 84406.3079384348}, + {85980000, 84409.1777527378}, {85990000, 84412.0058970226}, + {86000000, 84414.810887153}, {86010000, 84417.6168357687}, + {86020000, 84420.4248301332}, {86030000, 84423.2551680064}, + {86040000, 84426.1143071642}, {86050000, 84429.0058184228}, + {86060000, 84431.9320041168}, {86070000, 84434.8827326909}, + {86080000, 84437.8330999613}, {86090000, 84440.7803812425}, + {86100000, 84443.7160619325}, {86110000, 84446.6377014345}, + {86120000, 84449.5377581274}, {86130000, 84452.4063627236}, + {86140000, 84455.2422937569}, {86150000, 84458.0113602747}, + {86160000, 84460.7037721184}, {86170000, 84463.3219388117}, + {86180000, 84465.8675769769}, {86190000, 84468.3460610748}, + {86200000, 84470.7702140949}, {86210000, 84473.1422151188}, + {86220000, 84475.4844318122}, {86230000, 84477.8034880798}, + {86240000, 84480.0883925773}, {86250000, 84482.3247573832}, + {86260000, 84484.5056353154}, {86270000, 84486.5774094562}, + {86280000, 84488.5314638206}, {86290000, 84490.5488088506}, + {86300000, 84492.7489529031}, {86310000, 84495.056764817}, + {86320000, 84497.2868067585}, {86330000, 84499.4234775388}, + {86340000, 84501.5494684113}, {86350000, 84503.6889166995}, + {86360000, 84505.8870222942}, {86370000, 84508.2028261333}, + {86380000, 84510.6371009474}, {86390000, 84513.1432212706}, + {86400000, 84515.7068370714}, {86410000, 84518.3442251104}, + {86420000, 84521.0660177306}, {86430000, 84523.8646614437}, + {86440000, 84526.7220039076}, {86450000, 84529.6344639148}, + {86460000, 84532.5508597937}, {86470000, 84535.4562493569}, + {86480000, 84538.3603150511}, {86490000, 84541.2756935033}, + {86500000, 84544.2036606889}, {86510000, 84547.1721401549}, + {86520000, 84550.1891379616}, {86530000, 84553.2124282576}, + {86540000, 84556.2140970343}, {86550000, 84559.198441322}, + {86560000, 84562.1759839465}, {86570000, 84565.1469684683}, + {86580000, 84568.0834830126}, {86590000, 84570.977507963}, + {86600000, 84573.8183703207}, {86610000, 84576.5920557223}, + {86620000, 84579.3013586384}, {86630000, 84582.0469360511}, + {86640000, 84584.8579645223}, {86650000, 84587.6944217986}, + {86660000, 84590.5298179852}, {86670000, 84593.3810194446}, + {86680000, 84596.2899528623}, {86690000, 84599.258469687}, + {86700000, 84602.2173253874}, {86710000, 84605.1463572643}, + {86720000, 84608.0478153234}, {86730000, 84610.9245936523}, + {86740000, 84613.7769302129}, {86750000, 84616.6049858166}, + {86760000, 84619.4088876521}, {86770000, 84622.1774775335}, + {86780000, 84624.9034411197}, {86790000, 84627.586747905}, + {86800000, 84630.2270049992}, {86810000, 84632.8247900683}, + {86820000, 84635.3945388911}, {86830000, 84637.9405608363}, + {86840000, 84640.4564866743}, {86850000, 84642.933955714}, + {86860000, 84645.3731985799}, {86870000, 84647.8323006609}, + {86880000, 84650.329917935}, {86890000, 84652.8310782232}, + {86900000, 84655.3126365472}, {86910000, 84657.7891037614}, + {86920000, 84660.2964525573}, {86930000, 84662.8367010639}, + {86940000, 84665.3617752389}, {86950000, 84667.85769553}, + {86960000, 84670.3674878923}, {86970000, 84672.947384498}, + {86980000, 84675.5992439288}, {86990000, 84678.3102455419}, + {87000000, 84681.0760006252}, {87010000, 84683.874058885}, + {87020000, 84686.689512288}, {87030000, 84689.5218793946}, + {87040000, 84692.3700914851}, {87050000, 84695.2350250536}, + {87060000, 84698.1522102507}, {87070000, 84701.1318343365}, + {87080000, 84704.1352090891}, {87090000, 84707.1118280225}, + {87100000, 84710.0601876878}, {87110000, 84712.9980087938}, + {87120000, 84715.9306952909}, {87130000, 84718.8584856203}, + {87140000, 84721.7815459036}, {87150000, 84724.6948723731}, + {87160000, 84727.5859749757}, {87170000, 84730.4541136719}, + {87180000, 84733.3129637551}, {87190000, 84736.1665498421}, + {87200000, 84739.0112825325}, {87210000, 84741.8424586956}, + {87220000, 84744.6607149893}, {87230000, 84747.4732628035}, + {87240000, 84750.2815021551}, {87250000, 84753.096886453}, + {87260000, 84755.9269818129}, {87270000, 84758.7518208537}, + {87280000, 84761.5218126753}, {87290000, 84764.234919675}, + {87300000, 84766.9813049052}, {87310000, 84769.7871910062}, + {87320000, 84772.6268119399}, {87330000, 84775.4665587702}, + {87340000, 84778.3066987546}, {87350000, 84781.159899296}, + {87360000, 84784.0281848836}, {87370000, 84786.9174094195}, + {87380000, 84789.8314160344}, {87390000, 84792.7399930656}, + {87400000, 84795.5680413369}, {87410000, 84798.3114757581}, + {87420000, 84801.073430983}, {87430000, 84803.8839711186}, + {87440000, 84806.7178048952}, {87450000, 84809.5418992723}, + {87460000, 84812.3565650938}, {87470000, 84815.174392462}, + {87480000, 84817.9974436813}, {87490000, 84820.8373455483}, + {87500000, 84823.7017723758}, {87510000, 84826.5807906637}, + {87520000, 84829.4498303011}, {87530000, 84832.306663102}, + {87540000, 84835.1571043605}, {87550000, 84838.0028741133}, + {87560000, 84840.8584468923}, {87570000, 84843.7427641901}, + {87580000, 84846.6559533257}, {87590000, 84849.5746732658}, + {87600000, 84852.4918296837}, {87610000, 84855.4112960681}, + {87620000, 84858.3356378575}, {87630000, 84861.2649377028}, + {87640000, 84864.1994379591}, {87650000, 84867.1389317281}, + {87660000, 84870.0762922742}, {87670000, 84873.009443483}, + {87680000, 84875.9341974787}, {87690000, 84878.8450652604}, + {87700000, 84881.7423516353}, {87710000, 84884.6413527149}, + {87720000, 84887.5465191919}, {87730000, 84890.4573201816}, + {87740000, 84893.3733945969}, {87750000, 84896.28717999}, + {87760000, 84899.1798709302}, {87770000, 84902.0507095548}, + {87780000, 84904.9343947021}, {87790000, 84907.8410178958}, + {87800000, 84910.7554716141}, {87810000, 84913.657997511}, + {87820000, 84916.5493061776}, {87830000, 84919.4430650666}, + {87840000, 84922.3418771424}, {87850000, 84925.2402500886}, + {87860000, 84928.1345415906}, {87870000, 84931.024659499}, + {87880000, 84933.9103434009}, {87890000, 84936.792629945}, + {87900000, 84939.7071955525}, {87910000, 84942.6643571701}, + {87920000, 84945.6372084128}, {87930000, 84948.5905625533}, + {87940000, 84951.5234442535}, {87950000, 84954.4480774072}, + {87960000, 84957.3680894008}, {87970000, 84960.272127059}, + {87980000, 84963.1526863984}, {87990000, 84966.0197103915}, + {88000000, 84968.8978281864}, {88010000, 84971.7890720636}, + {88020000, 84974.6805290296}, {88030000, 84977.5684140183}, + {88040000, 84980.4520525372}, {88050000, 84983.3305552261}, + {88060000, 84986.2031817306}, {88070000, 84989.0478840662}, + {88080000, 84991.8584257026}, {88090000, 84994.6577254135}, + {88100000, 84997.461003879}, {88110000, 85000.2687347829}, + {88120000, 85003.0821295854}, {88130000, 85005.9012841374}, + {88140000, 85008.7261942148}, {88150000, 85011.5568383116}, + {88160000, 85014.3888154988}, {88170000, 85017.216368539}, + {88180000, 85020.0392887827}, {88190000, 85022.8667270607}, + {88200000, 85025.7017015379}, {88210000, 85028.5430858501}, + {88220000, 85031.390122224}, {88230000, 85034.2453066942}, + {88240000, 85037.1149084018}, {88250000, 85039.9990803486}, + {88260000, 85042.8838591758}, {88270000, 85045.7651603103}, + {88280000, 85048.6386014347}, {88290000, 85051.4984352146}, + {88300000, 85054.3448171222}, {88310000, 85057.1931057042}, + {88320000, 85060.0479534118}, {88330000, 85062.9087487256}, + {88340000, 85065.7750756537}, {88350000, 85068.6444196778}, + {88360000, 85071.510521112}, {88370000, 85074.3725530864}, + {88380000, 85077.2230371017}, {88390000, 85080.0598238669}, + {88400000, 85082.897141585}, {88410000, 85085.7536269118}, + {88420000, 85088.629934071}, {88430000, 85091.5101598253}, + {88440000, 85094.3887148628}, {88450000, 85097.2526724705}, + {88460000, 85100.0934826508}, {88470000, 85102.9084782548}, + {88480000, 85105.6908245666}, {88490000, 85108.4406010362}, + {88500000, 85111.1789545745}, {88510000, 85113.9121080878}, + {88520000, 85116.6403539377}, {88530000, 85119.3640673105}, + {88540000, 85122.0831061005}, {88550000, 85124.7910420033}, + {88560000, 85127.4860216747}, {88570000, 85130.1847607881}, + {88580000, 85132.8983544553}, {88590000, 85135.6195603972}, + {88600000, 85138.3304022046}, {88610000, 85141.0303504487}, + {88620000, 85143.7612403005}, {88630000, 85146.5352037628}, + {88640000, 85149.3328460465}, {88650000, 85152.128801601}, + {88660000, 85154.9223784037}, {88670000, 85157.7290537731}, + {88680000, 85160.5534882337}, {88690000, 85163.3887268625}, + {88700000, 85166.2301327805}, {88710000, 85169.0851014374}, + {88720000, 85171.9721702692}, {88730000, 85174.8924550323}, + {88740000, 85177.8254465472}, {88750000, 85180.7650943666}, + {88760000, 85183.6991408719}, {88770000, 85186.6115087012}, + {88780000, 85189.5019386975}, {88790000, 85192.3838182464}, + {88800000, 85195.2612318897}, {88810000, 85198.1115638823}, + {88820000, 85200.9198393906}, {88830000, 85203.7134046803}, + {88840000, 85206.5603189407}, {88850000, 85209.4657860687}, + {88860000, 85212.3834189245}, {88870000, 85215.2996018273}, + {88880000, 85218.2090672118}, {88890000, 85221.1049051265}, + {88900000, 85223.9869245776}, {88910000, 85226.8626540748}, + {88920000, 85229.7345790198}, {88930000, 85232.6080117244}, + {88940000, 85235.4864821608}, {88950000, 85238.360032699}, + {88960000, 85241.2038037084}, {88970000, 85244.016029352}, + {88980000, 85246.8168790909}, {88990000, 85249.612299208}, + {89000000, 85252.4025435311}, {89010000, 85255.1879366068}, + {89020000, 85257.9685430969}, {89030000, 85260.7457690939}, + {89040000, 85263.5200535065}, {89050000, 85266.2738383553}, + {89060000, 85268.9954822289}, {89070000, 85271.6948182728}, + {89080000, 85274.3962460918}, {89090000, 85277.1024347827}, + {89100000, 85279.8218273524}, {89110000, 85282.5568516726}, + {89120000, 85285.2918435609}, {89130000, 85288.0062688139}, + {89140000, 85290.699209991}, {89150000, 85293.3689500293}, + {89160000, 85296.0152521138}, {89170000, 85298.694889901}, + {89180000, 85301.4455603606}, {89190000, 85304.2154629378}, + {89200000, 85306.8754665972}, {89210000, 85309.4162707346}, + {89220000, 85311.9452776803}, {89230000, 85314.4939796878}, + {89240000, 85317.0419222516}, {89250000, 85319.5622903901}, + {89260000, 85322.0535089032}, {89270000, 85324.4959981282}, + {89280000, 85326.8842771122}, {89290000, 85329.2822171614}, + {89300000, 85331.7323271853}, {89310000, 85334.2131170854}, + {89320000, 85336.6711860174}, {89330000, 85339.1032835101}, + {89340000, 85341.5778597381}, {89350000, 85344.1148095214}, + {89360000, 85346.6837310754}, {89370000, 85349.2448213713}, + {89380000, 85351.7965204139}, {89390000, 85354.3917782172}, + {89400000, 85357.0480292679}, {89410000, 85359.733931826}, + {89420000, 85362.4285699542}, {89430000, 85365.1338434085}, + {89440000, 85367.8545678087}, {89450000, 85370.5913659085}, + {89460000, 85373.351546463}, {89470000, 85376.1371691232}, + {89480000, 85378.9362540657}, {89490000, 85381.7331049386}, + {89500000, 85384.5238668459}, {89510000, 85387.278049105}, + {89520000, 85389.9899701347}, {89530000, 85392.6648008482}, + {89540000, 85395.3060451939}, {89550000, 85397.9089507244}, + {89560000, 85400.4613686447}, {89570000, 85402.9616750302}, + {89580000, 85405.3880170798}, {89590000, 85407.7342559485}, + {89600000, 85410.0048498368}, {89610000, 85412.2055277845}, + {89620000, 85414.3397695836}, {89630000, 85416.4355464712}, + {89640000, 85418.4983793369}, {89650000, 85420.5695122035}, + {89660000, 85422.676391216}, {89670000, 85424.8071956557}, + {89680000, 85426.9326051928}, {89690000, 85429.0515152875}, + {89700000, 85431.2264954962}, {89710000, 85433.4756853339}, + {89720000, 85435.7922475539}, {89730000, 85438.1673186205}, + {89740000, 85440.6003014465}, {89750000, 85443.0912071726}, + {89760000, 85445.6397941697}, {89770000, 85448.2962728816}, + {89780000, 85451.0938948539}, {89790000, 85454.003037868}, + {89800000, 85456.950450431}, {89810000, 85459.9277122086}, + {89820000, 85462.902022553}, {89830000, 85465.8637716016}, + {89840000, 85468.8084418969}, {89850000, 85471.7300793157}, + {89860000, 85474.6279532174}, {89870000, 85477.4770926424}, + {89880000, 85480.2701931017}, {89890000, 85483.0710205604}, + {89900000, 85485.9220169844}, {89910000, 85488.8042264166}, + {89920000, 85491.6705233848}, {89930000, 85494.5176081257}, + {89940000, 85497.3928537097}, {89950000, 85500.3100773566}, + {89960000, 85503.2537389815}, {89970000, 85506.2034744557}, + {89980000, 85509.1582872383}, {89990000, 85512.1118196273}, + {90000000, 85515.0621651848}, {90010000, 85517.9970800748}, + {90020000, 85520.9084276908}, {90030000, 85523.8086148575}, + {90040000, 85526.7285554209}, {90050000, 85529.6702725703}, + {90060000, 85532.5997437547}, {90070000, 85535.5070413232}, + {90080000, 85538.3989268622}, {90090000, 85541.2842697045}, + {90100000, 85544.1635963824}, {90110000, 85547.0626054512}, + {90120000, 85549.989556389}, {90130000, 85552.931373507}, + {90140000, 85555.8793157972}, {90150000, 85558.8255953053}, + {90160000, 85561.7507416111}, {90170000, 85564.6538856963}, + {90180000, 85567.5696752825}, {90190000, 85570.5082359133}, + {90200000, 85573.4507812973}, {90210000, 85576.3726487822}, + {90220000, 85579.274107844}, {90230000, 85582.191304463}, + {90240000, 85585.1346030189}, {90250000, 85588.080648551}, + {90260000, 85591.013867615}, {90270000, 85593.9488947195}, + {90280000, 85596.9223072204}, {90290000, 85599.936015231}, + {90300000, 85602.9348533732}, {90310000, 85605.9026942572}, + {90320000, 85608.8388119595}, {90330000, 85611.7422026557}, + {90340000, 85614.6144442803}, {90350000, 85617.5074491239}, + {90360000, 85620.4363898223}, {90370000, 85623.3779658566}, + {90380000, 85626.3166237975}, {90390000, 85629.2519219307}, + {90400000, 85632.1827300366}, {90410000, 85635.1093599945}, + {90420000, 85638.046011716}, {90430000, 85640.9968147042}, + {90440000, 85643.950127668}, {90450000, 85646.8906549325}, + {90460000, 85649.8183134969}, {90470000, 85652.747764837}, + {90480000, 85655.6832258062}, {90490000, 85658.6298112205}, + {90500000, 85661.5909167215}, {90510000, 85664.56661591}, + {90520000, 85667.5572038969}, {90530000, 85670.5612288491}, + {90540000, 85673.528747167}, {90550000, 85676.4452274693}, + {90560000, 85679.3398920652}, {90570000, 85682.2511117768}, + {90580000, 85685.1803597141}, {90590000, 85688.1046297237}, + {90600000, 85691.0163248102}, {90610000, 85693.9313097613}, + {90620000, 85696.8601682002}, {90630000, 85699.7931573539}, + {90640000, 85702.705938995}, {90650000, 85705.5955272882}, + {90660000, 85708.4392801116}, {90670000, 85711.2307125805}, + {90680000, 85713.9969632131}, {90690000, 85716.7736588004}, + {90700000, 85719.5586556397}, {90710000, 85722.3182271236}, + {90720000, 85725.0459828116}, {90730000, 85727.7467156693}, + {90740000, 85730.4236691523}, {90750000, 85733.0895797302}, + {90760000, 85735.7762215195}, {90770000, 85738.486120336}, + {90780000, 85741.1995920767}, {90790000, 85743.910846382}, + {90800000, 85746.6190162248}, {90810000, 85749.3229571698}, + {90820000, 85752.0224574834}, {90830000, 85754.7109656039}, + {90840000, 85757.3865961076}, {90850000, 85760.0491147371}, + {90860000, 85762.6983864142}, {90870000, 85765.3344686169}, + {90880000, 85767.9574054809}, {90890000, 85770.5684659177}, + {90900000, 85773.210480148}, {90910000, 85775.8959210767}, + {90920000, 85778.6057431429}, {90930000, 85781.3149545303}, + {90940000, 85784.0186437559}, {90950000, 85786.6782321596}, + {90960000, 85789.2862739947}, {90970000, 85791.8760959053}, + {90980000, 85794.4699995353}, {90990000, 85797.0511697221}, + {91000000, 85799.5774031665}, {91010000, 85802.0450639874}, + {91020000, 85804.4663030004}, {91030000, 85806.8448500153}, + {91040000, 85809.17355932}, {91050000, 85811.4429515264}, + {91060000, 85813.6564106262}, {91070000, 85815.8421508765}, + {91080000, 85818.004982091}, {91090000, 85820.2195758749}, + {91100000, 85822.5357496122}, {91110000, 85824.8920775308}, + {91120000, 85827.1350466196}, {91130000, 85829.2539957422}, + {91140000, 85831.3976894993}, {91150000, 85833.6097416662}, + {91160000, 85835.8689619575}, {91170000, 85838.1475527581}, + {91180000, 85840.4440938177}, {91190000, 85842.7454391698}, + {91200000, 85845.0474875216}, {91210000, 85847.3376317639}, + {91220000, 85849.607455638}, {91230000, 85851.8793283392}, + {91240000, 85854.2092802408}, {91250000, 85856.6019375932}, + {91260000, 85859.0316546346}, {91270000, 85861.4907674569}, + {91280000, 85863.9696594054}, {91290000, 85866.4557126497}, + {91300000, 85868.9484876703}, {91310000, 85871.4897125403}, + {91320000, 85874.0928940513}, {91330000, 85876.7771593405}, + {91340000, 85879.5551743592}, {91350000, 85882.41200133}, + {91360000, 85885.3107894342}, {91370000, 85888.2478062178}, + {91380000, 85891.2279048761}, {91390000, 85894.2523596377}, + {91400000, 85897.2789693111}, {91410000, 85900.252179145}, + {91420000, 85903.1711726874}, {91430000, 85906.0962119713}, + {91440000, 85909.0456455348}, {91450000, 85911.9745509431}, + {91460000, 85914.8529031041}, {91470000, 85917.7025064446}, + {91480000, 85920.5778054624}, {91490000, 85923.4814050348}, + {91500000, 85926.3164403567}, {91510000, 85929.0546976482}, + {91520000, 85931.7606093777}, {91530000, 85934.5188770367}, + {91540000, 85937.327490388}, {91550000, 85940.1356864494}, + {91560000, 85942.9335547775}, {91570000, 85945.7416166978}, + {91580000, 85948.5736040319}, {91590000, 85951.4173470317}, + {91600000, 85954.2424259698}, {91610000, 85957.0466323147}, + {91620000, 85959.8568743221}, {91630000, 85962.6810415275}, + {91640000, 85965.5222477071}, {91650000, 85968.384619632}, + {91660000, 85971.268145789}, {91670000, 85974.1398182558}, + {91680000, 85976.9888565096}, {91690000, 85979.8708896303}, + {91700000, 85982.8230864054}, {91710000, 85985.8163123101}, + {91720000, 85988.7778398029}, {91730000, 85991.7018181088}, + {91740000, 85994.6342159311}, {91750000, 85997.5885179998}, + {91760000, 86000.5607451773}, {91770000, 86003.5456877819}, + {91780000, 86006.5430672986}, {91790000, 86009.5493237534}, + {91800000, 86012.5632571802}, {91810000, 86015.5775345208}, + {91820000, 86018.5872484972}, {91830000, 86021.5922850169}, + {91840000, 86024.5923222186}, {91850000, 86027.5879491803}, + {91860000, 86030.600568697}, {91870000, 86033.6364132552}, + {91880000, 86036.6727364306}, {91890000, 86039.6795931351}, + {91900000, 86042.6563543003}, {91910000, 86045.6298373069}, + {91920000, 86048.6083342335}, {91930000, 86051.5805003263}, + {91940000, 86054.5387358761}, {91950000, 86057.4803819866}, + {91960000, 86060.3986472422}, {91970000, 86063.2931461397}, + {91980000, 86066.1707444169}, {91990000, 86069.0335199155}, + {92000000, 86071.8853474641}, {92010000, 86074.7313106645}, + {92020000, 86077.5716087706}, {92030000, 86080.3923382139}, + {92040000, 86083.1890100647}, {92050000, 86085.9730891564}, + {92060000, 86088.752276966}, {92070000, 86091.5218340895}, + {92080000, 86094.269792562}, {92090000, 86096.9948336681}, + {92100000, 86099.6892577277}, {92110000, 86102.3509068807}, + {92120000, 86104.9987101144}, {92130000, 86107.6575865184}, + {92140000, 86110.32750459}, {92150000, 86112.9748618207}, + {92160000, 86115.5899315999}, {92170000, 86118.211941576}, + {92180000, 86120.8671613254}, {92190000, 86123.5312922513}, + {92200000, 86126.1434179857}, {92210000, 86128.6987674683}, + {92220000, 86131.2369264725}, {92230000, 86133.7696023591}, + {92240000, 86136.2978818171}, {92250000, 86138.823189595}, + {92260000, 86141.3465509596}, {92270000, 86143.8756459019}, + {92280000, 86146.4117336204}, {92290000, 86148.9267251937}, + {92300000, 86151.4018130145}, {92310000, 86153.8415825093}, + {92320000, 86156.2572739056}, {92330000, 86158.6507332935}, + {92340000, 86161.0440887443}, {92350000, 86163.4438511716}, + {92360000, 86165.8462713241}, {92370000, 86168.2464091476}, + {92380000, 86170.6439403449}, {92390000, 86173.0321463015}, + {92400000, 86175.4090112681}, {92410000, 86177.7629908103}, + {92420000, 86180.0863781781}, {92430000, 86182.3815708909}, + {92440000, 86184.6543721089}, {92450000, 86186.9078529298}, + {92460000, 86189.2279647437}, {92470000, 86191.6397622188}, + {92480000, 86194.1050457755}, {92490000, 86196.5735688376}, + {92500000, 86199.0425703284}, {92510000, 86201.4869114742}, + {92520000, 86203.8992786353}, {92530000, 86206.3136324179}, + {92540000, 86208.7527501786}, {92550000, 86211.2047597337}, + {92560000, 86213.6399288987}, {92570000, 86216.0553087331}, + {92580000, 86218.4493419768}, {92590000, 86220.8216450498}, + {92600000, 86223.179903622}, {92610000, 86225.5342304649}, + {92620000, 86227.8855419522}, {92630000, 86230.2513199196}, + {92640000, 86232.6366597899}, {92650000, 86235.0066972266}, + {92660000, 86237.338041048}, {92670000, 86239.6651003449}, + {92680000, 86242.0742993982}, {92690000, 86244.5713028331}, + {92700000, 86247.060756569}, {92710000, 86249.5146098198}, + {92720000, 86251.9541037743}, {92730000, 86254.4072271847}, + {92740000, 86256.8705110915}, {92750000, 86259.3093293394}, + {92760000, 86261.7183335089}, {92770000, 86264.1640543834}, + {92780000, 86266.6910607708}, {92790000, 86269.2529790246}, + {92800000, 86271.7335554984}, {92810000, 86274.1242845479}, + {92820000, 86276.5259888144}, {92830000, 86278.9683172897}, + {92840000, 86281.4155822399}, {92850000, 86283.8207280795}, + {92860000, 86286.1823055665}, {92870000, 86288.6648708666}, + {92880000, 86291.3221167734}, {92890000, 86293.973194191}, + {92900000, 86296.4968005807}, {92910000, 86298.9222884364}, + {92920000, 86301.3226629489}, {92930000, 86303.7056617597}, + {92940000, 86306.0826188499}, {92950000, 86308.4568927604}, + {92960000, 86310.8320097808}, {92970000, 86313.212625596}, + {92980000, 86315.5989081601}, {92990000, 86318.0099960312}, + {93000000, 86320.4521357527}, {93010000, 86322.8949863881}, + {93020000, 86325.3181688565}, {93030000, 86327.7286525293}, + {93040000, 86330.1438718254}, {93050000, 86332.5657759239}, + {93060000, 86335.0024269202}, {93070000, 86337.4561488238}, + {93080000, 86339.9224323276}, {93090000, 86342.3953461013}, + {93100000, 86344.873784559}, {93110000, 86347.3210802689}, + {93120000, 86349.7263036243}, {93130000, 86352.12921685}, + {93140000, 86354.5565292526}, {93150000, 86357.0089550443}, + {93160000, 86359.4884821966}, {93170000, 86361.9948107518}, + {93180000, 86364.5137023787}, {93190000, 86367.0409040095}, + {93200000, 86369.5834447216}, {93210000, 86372.1506270987}, + {93220000, 86374.749191486}, {93230000, 86377.4411332485}, + {93240000, 86380.2380718976}, {93250000, 86383.0891285154}, + {93260000, 86385.9600434963}, {93270000, 86388.842159698}, + {93280000, 86391.7137857609}, {93290000, 86394.5737339353}, + {93300000, 86397.4564831751}, {93310000, 86400.3721218833}, + {93320000, 86403.3485548389}, {93330000, 86406.4227122643}, + {93340000, 86409.5806761213}, {93350000, 86412.7012547494}, + {93360000, 86415.7643037954}, {93370000, 86418.8333636939}, + {93380000, 86421.951100458}, {93390000, 86425.0737685761}, + {93400000, 86428.0913653853}, {93410000, 86430.9941418727}, + {93420000, 86433.8120837214}, {93430000, 86436.554325061}, + {93440000, 86439.2106433771}, {93450000, 86441.7674061598}, + {93460000, 86444.2343204924}, {93470000, 86446.6904200537}, + {93480000, 86449.1489179398}, {93490000, 86451.6296311429}, + {93500000, 86454.1458500669}, {93510000, 86456.692869323}, + {93520000, 86459.2590744376}, {93530000, 86461.8431953183}, + {93540000, 86464.4444559177}, {93550000, 86467.0625672189}, + {93560000, 86469.6636793083}, {93570000, 86472.2030480324}, + {93580000, 86474.6811563332}, {93590000, 86477.2044750773}, + {93600000, 86479.8054023042}, {93610000, 86482.4096673021}, + {93620000, 86484.9673198947}, {93630000, 86487.4745735498}, + {93640000, 86489.9215077612}, {93650000, 86492.3087264787}, + {93660000, 86494.6858230235}, {93670000, 86497.0674817853}, + {93680000, 86499.4690452127}, {93690000, 86501.910813496}, + {93700000, 86504.3940896378}, {93710000, 86506.9431876938}, + {93720000, 86509.5650587259}, {93730000, 86512.2557005726}, + {93740000, 86515.0123076494}, {93750000, 86517.8395525685}, + {93760000, 86520.7497418012}, {93770000, 86523.7398646976}, + {93780000, 86526.6676759216}, {93790000, 86529.4914436229}, + {93800000, 86532.3167938659}, {93810000, 86535.2832632608}, + {93820000, 86538.3859762096}, {93830000, 86541.5292228744}, + {93840000, 86544.6943653731}, {93850000, 86547.8261967692}, + {93860000, 86550.8876459434}, {93870000, 86553.8903117133}, + {93880000, 86556.8629547118}, {93890000, 86559.8101961167}, + {93900000, 86562.7907898611}, {93910000, 86565.8219464164}, + {93920000, 86568.8444066586}, {93930000, 86571.7798739559}, + {93940000, 86574.6267560672}, {93950000, 86577.4388396193}, + {93960000, 86580.2324369679}, {93970000, 86583.0045588129}, + {93980000, 86585.7532270647}, {93990000, 86588.4784858721}, + {94000000, 86591.1802674611}, {94010000, 86593.8635038948}, + {94020000, 86596.7064435993}, {94030000, 86599.7611360749}, + {94040000, 86602.866572086}, {94050000, 86605.8099565418}, + {94060000, 86608.5906571351}, {94070000, 86611.4520043153}, + {94080000, 86614.4644985886}, {94090000, 86617.4375911526}, + {94100000, 86620.2430474845}, {94110000, 86622.9498879349}, + {94120000, 86625.7313702641}, {94130000, 86628.5985947122}, + {94140000, 86631.3328333362}, {94150000, 86633.8700463049}, + {94160000, 86636.3098078171}, {94170000, 86638.7836100625}, + {94180000, 86641.2963968987}, {94190000, 86643.6381991858}, + {94200000, 86645.7405123635}, {94210000, 86647.8299293856}, + {94220000, 86650.0590379285}, {94230000, 86652.3720835008}, + {94240000, 86654.6291415612}, {94250000, 86656.8218075555}, + {94260000, 86659.1491998895}, {94270000, 86661.6696154278}, + {94280000, 86664.2747569715}, {94290000, 86666.8215783531}, + {94300000, 86669.3070715275}, {94310000, 86671.8693940976}, + {94320000, 86674.5505555606}, {94330000, 86677.2300426832}, + {94340000, 86679.826715624}, {94350000, 86682.373210588}, + {94360000, 86684.9518279701}, {94370000, 86687.5712152052}, + {94380000, 86690.2500657283}, {94390000, 86692.9937029559}, + {94400000, 86695.8315565309}, {94410000, 86698.8027251883}, + {94420000, 86701.9079883761}, {94430000, 86704.8681785831}, + {94440000, 86707.5916551278}, {94450000, 86710.3015650044}, + {94460000, 86713.1483640742}, {94470000, 86716.1160911511}, + {94480000, 86719.1653864903}, {94490000, 86722.2899360542}, + {94500000, 86725.4158905933}, {94510000, 86728.5214486849}, + {94520000, 86731.6159356643}, {94530000, 86734.7116628657}, + {94540000, 86737.8094256411}, {94550000, 86740.9203390407}, + {94560000, 86744.0476478925}, {94570000, 86747.1843759913}, + {94580000, 86750.325805195}, {94590000, 86753.4792589812}, + {94600000, 86756.6632930827}, {94610000, 86759.879855267}, + {94620000, 86763.1369581785}, {94630000, 86766.4368245169}, + {94640000, 86769.7483575429}, {94650000, 86773.0304267099}, + {94660000, 86776.2826930673}, {94670000, 86779.5703836616}, + {94680000, 86782.9133501972}, {94690000, 86786.287403415}, + {94700000, 86789.6761861826}, {94710000, 86793.0692427689}, + {94720000, 86796.4401854024}, {94730000, 86799.7856688071}, + {94740000, 86803.0758217935}, {94750000, 86806.3019917337}, + {94760000, 86809.4871559053}, {94770000, 86812.661652244}, + {94780000, 86815.8269917032}, {94790000, 86818.9942530152}, + {94800000, 86822.1668221052}, {94810000, 86825.3495414677}, + {94820000, 86828.5456593343}, {94830000, 86831.7502633417}, + {94840000, 86834.9510195607}, {94850000, 86838.1463029528}, + {94860000, 86841.3211909325}, {94870000, 86844.4713471862}, + {94880000, 86847.5932764193}, {94890000, 86850.682306926}, + {94900000, 86853.7384213284}, {94910000, 86856.7741417479}, + {94920000, 86859.7936557825}, {94930000, 86862.7864097423}, + {94940000, 86865.7453229378}, {94950000, 86868.7001452223}, + {94960000, 86871.7260200915}, {94970000, 86874.8287631892}, + {94980000, 86877.9552465989}, {94990000, 86881.0896941231}, + {95000000, 86884.2408294212}, {95010000, 86887.4202238103}, + {95020000, 86890.6278757038}, {95030000, 86893.8477070929}, + {95040000, 86897.074813336}, {95050000, 86900.3127512091}, + {95060000, 86903.5639010835}, {95070000, 86906.8059566632}, + {95080000, 86909.9823967217}, {95090000, 86913.089445318}, + {95100000, 86916.1884348901}, {95110000, 86919.2975432612}, + {95120000, 86922.4142122873}, {95130000, 86925.5350664082}, + {95140000, 86928.6577155884}, {95150000, 86931.7603963637}, + {95160000, 86934.8389294255}, {95170000, 86937.9208416449}, + {95180000, 86941.0247079141}, {95190000, 86944.1510132387}, + {95200000, 86947.3011554801}, {95210000, 86950.4751709531}, + {95220000, 86953.6730386981}, {95230000, 86956.8946688988}, + {95240000, 86960.124072069}, {95250000, 86963.3400843292}, + {95260000, 86966.541070195}, {95270000, 86969.7025865899}, + {95280000, 86972.8177667837}, {95290000, 86975.8648622305}, + {95300000, 86978.8293021356}, {95310000, 86981.7134617509}, + {95320000, 86984.5227266585}, {95330000, 86987.2595091965}, + {95340000, 86989.9814907667}, {95350000, 86992.7057745854}, + {95360000, 86995.425998202}, {95370000, 86998.1337283883}, + {95380000, 87000.8286978888}, {95390000, 87003.5735639911}, + {95400000, 87006.3888666008}, {95410000, 87009.2376203486}, + {95420000, 87012.0947655815}, {95430000, 87014.9819222055}, + {95440000, 87017.9540353947}, {95450000, 87021.0150129301}, + {95460000, 87024.117634164}, {95470000, 87027.2477795669}, + {95480000, 87030.4035521703}, {95490000, 87033.5824819153}, + {95500000, 87036.784521435}, {95510000, 87040.0111551635}, + {95520000, 87043.2625729276}, {95530000, 87046.5098655261}, + {95540000, 87049.7335262071}, {95550000, 87052.9231071335}, + {95560000, 87056.0519459781}, {95570000, 87059.118917776}, + {95580000, 87062.1726898427}, {95590000, 87065.2277101342}, + {95600000, 87068.2966294723}, {95610000, 87071.3962449888}, + {95620000, 87074.5204597408}, {95630000, 87077.6052504915}, + {95640000, 87080.6383742828}, {95650000, 87083.6574869342}, + {95660000, 87086.6880703216}, {95670000, 87089.720955749}, + {95680000, 87092.7329574396}, {95690000, 87095.7218004793}, + {95700000, 87098.6862881478}, {95710000, 87101.6261516562}, + {95720000, 87104.5728641241}, {95730000, 87107.5681679987}, + {95740000, 87110.6054232302}, {95750000, 87113.6218036073}, + {95760000, 87116.6073814458}, {95770000, 87119.6105682302}, + {95780000, 87122.6640673052}, {95790000, 87125.7488382729}, + {95800000, 87128.8168813873}, {95810000, 87131.8643060641}, + {95820000, 87134.924179986}, {95830000, 87138.0062526478}, + {95840000, 87141.0845675939}, {95850000, 87144.1247022032}, + {95860000, 87147.1261479495}, {95870000, 87150.1297177998}, + {95880000, 87153.1479307976}, {95890000, 87156.1582626233}, + {95900000, 87159.1454779472}, {95910000, 87162.1142031822}, + {95920000, 87165.0760041986}, {95930000, 87168.0319039735}, + {95940000, 87170.9754450609}, {95950000, 87173.9047598715}, + {95960000, 87176.8161074404}, {95970000, 87179.7044977158}, + {95980000, 87182.5686199261}, {95990000, 87185.344450136}, + {96000000, 87188.0127025988}, {96010000, 87190.5991189033}, + {96020000, 87193.1212340128}, {96030000, 87195.6071047499}, + {96040000, 87198.1274563635}, {96050000, 87200.6861434905}, + {96060000, 87203.165837349}, {96070000, 87205.5320946472}, + {96080000, 87207.8366073487}, {96090000, 87210.1478712335}, + {96100000, 87212.4687094171}, {96110000, 87214.8078741745}, + {96120000, 87217.1681988671}, {96130000, 87219.5870360828}, + {96140000, 87222.089578464}, {96150000, 87224.6787749899}, + {96160000, 87227.3627948408}, {96170000, 87230.1386898629}, + {96180000, 87232.8781895574}, {96190000, 87235.5434038862}, + {96200000, 87238.1954425404}, {96210000, 87240.9153107087}, + {96220000, 87243.7038360714}, {96230000, 87246.4850891876}, + {96240000, 87249.2369022166}, {96250000, 87252.0468716413}, + {96260000, 87254.9742034024}, {96270000, 87257.9805411728}, + {96280000, 87260.969314333}, {96290000, 87263.9329859082}, + {96300000, 87266.9517542527}, {96310000, 87270.0491773719}, + {96320000, 87273.1874632393}, {96330000, 87276.3165274265}, + {96340000, 87279.4358726647}, {96350000, 87282.5967603671}, + {96360000, 87285.8139678403}, {96370000, 87289.0126145711}, + {96380000, 87292.1420395998}, {96390000, 87295.2406877455}, + {96400000, 87298.4057257863}, {96410000, 87301.6441574396}, + {96420000, 87304.8613436709}, {96430000, 87308.0293312366}, + {96440000, 87311.1542950559}, {96450000, 87314.2443580328}, + {96460000, 87317.3008855723}, {96470000, 87320.3530574157}, + {96480000, 87323.4094043626}, {96490000, 87326.4925702291}, + {96500000, 87329.6178410465}, {96510000, 87332.7706640647}, + {96520000, 87335.9143392279}, {96530000, 87339.0451549608}, + {96540000, 87342.1611163359}, {96550000, 87345.2616831443}, + {96560000, 87348.3433071478}, {96570000, 87351.4012480787}, + {96580000, 87354.4354216121}, {96590000, 87357.4440562894}, + {96600000, 87360.4266353482}, {96610000, 87363.3895620633}, + {96620000, 87366.3372077958}, {96630000, 87369.2747279437}, + {96640000, 87372.2151208992}, {96650000, 87375.1600797925}, + {96660000, 87378.1245904495}, {96670000, 87381.1130224819}, + {96680000, 87384.0945011828}, {96690000, 87387.0279366682}, + {96700000, 87389.912926985}, {96710000, 87392.7602592331}, + {96720000, 87395.5721788629}, {96730000, 87398.4113582907}, + {96740000, 87401.320233271}, {96750000, 87404.2849687719}, + {96760000, 87407.2709039541}, {96770000, 87410.2730923514}, + {96780000, 87413.2396223146}, {96790000, 87416.1552328657}, + {96800000, 87419.0600943796}, {96810000, 87422.0075432598}, + {96820000, 87424.9987075597}, {96830000, 87427.9989958637}, + {96840000, 87430.9981184912}, {96850000, 87434.0331308947}, + {96860000, 87437.1290920364}, {96870000, 87440.241969498}, + {96880000, 87443.2600791244}, {96890000, 87446.172041562}, + {96900000, 87448.9578439095}, {96910000, 87451.6119964352}, + {96920000, 87454.2011723286}, {96930000, 87456.8138185074}, + {96940000, 87459.452852417}, {96950000, 87462.1114085467}, + {96960000, 87464.7880312489}, {96970000, 87467.3975743438}, + {96980000, 87469.8824327711}, {96990000, 87472.2982969113}, + {97000000, 87474.7860517878}, {97010000, 87477.3592345588}, + {97020000, 87480.0039709444}, {97030000, 87482.7158982394}, + {97040000, 87485.4549392868}, {97050000, 87488.1679088262}, + {97060000, 87490.8522117682}, {97070000, 87493.5039492044}, + {97080000, 87496.1225995622}, {97090000, 87498.7812342869}, + {97100000, 87501.5293791682}, {97110000, 87504.3434504274}, + {97120000, 87507.1640702014}, {97130000, 87509.9851317506}, + {97140000, 87512.8032841975}, {97150000, 87515.6175445788}, + {97160000, 87518.3948481082}, {97170000, 87521.0912163616}, + {97180000, 87523.7069746489}, {97190000, 87526.3303994804}, + {97200000, 87528.9883253921}, {97210000, 87531.7152549835}, + {97220000, 87534.5345231132}, {97230000, 87537.4267246277}, + {97240000, 87540.3430367322}, {97250000, 87543.2776059153}, + {97260000, 87546.1990808848}, {97270000, 87549.0982081451}, + {97280000, 87551.9817931715}, {97290000, 87554.8588567105}, + {97300000, 87557.7298076758}, {97310000, 87560.588877716}, + {97320000, 87563.4341943335}, {97330000, 87566.34404572}, + {97340000, 87569.3714590247}, {97350000, 87572.4507915382}, + {97360000, 87575.4155640807}, {97370000, 87578.2529487904}, + {97380000, 87581.0967372401}, {97390000, 87583.986591903}, + {97400000, 87586.9163652776}, {97410000, 87589.877952139}, + {97420000, 87592.8706909553}, {97430000, 87595.8851718422}, + {97440000, 87598.9184338815}, {97450000, 87601.9007310124}, + {97460000, 87604.7848115969}, {97470000, 87607.5968599572}, + {97480000, 87610.4028851926}, {97490000, 87613.2100460305}, + {97500000, 87616.0363348937}, {97510000, 87618.8870216837}, + {97520000, 87621.7275037161}, {97530000, 87624.5117651448}, + {97540000, 87627.2421647321}, {97550000, 87629.9584821746}, + {97560000, 87632.6686035}, {97570000, 87635.4300672142}, + {97580000, 87638.2819375438}, {97590000, 87641.2052368324}, + {97600000, 87644.1522726309}, {97610000, 87647.1165714173}, + {97620000, 87650.0383683692}, {97630000, 87652.9000849954}, + {97640000, 87655.7630506495}, {97650000, 87658.7087950089}, + {97660000, 87661.7403367574}, {97670000, 87664.8105575813}, + {97680000, 87667.9032509391}, {97690000, 87671.0080589233}, + {97700000, 87674.117933033}, {97710000, 87677.2128940434}, + {97720000, 87680.2420336001}, {97730000, 87683.2026418392}, + {97740000, 87686.1776489277}, {97750000, 87689.1916222342}, + {97760000, 87692.2121964665}, {97770000, 87695.1963213378}, + {97780000, 87698.1423636122}, {97790000, 87701.0432197329}, + {97800000, 87703.8966254066}, {97810000, 87706.7047033534}, + {97820000, 87709.468967619}, {97830000, 87712.2292182681}, + {97840000, 87715.0866068995}, {97850000, 87718.0492153793}, + {97860000, 87721.0509730278}, {97870000, 87724.0721298082}, + {97880000, 87727.066318878}, {97890000, 87729.9718047159}, + {97900000, 87732.7873568056}, {97910000, 87735.5675450869}, + {97920000, 87738.3293035556}, {97930000, 87741.1089324108}, + {97940000, 87743.9310996041}, {97950000, 87746.766727858}, + {97960000, 87749.5419150203}, {97970000, 87752.2495430416}, + {97980000, 87754.8929210132}, {97990000, 87757.4732560832}, + {98000000, 87760.0035917728}, {98010000, 87762.501198155}, + {98020000, 87764.9669566208}, {98030000, 87767.391050163}, + {98040000, 87769.7703580323}, {98050000, 87772.1068473096}, + {98060000, 87774.4019238002}, {98070000, 87776.6879138169}, + {98080000, 87779.0470228656}, {98090000, 87781.4856905887}, + {98100000, 87783.9440346136}, {98110000, 87786.4042100445}, + {98120000, 87788.8751277242}, {98130000, 87791.3686614181}, + {98140000, 87793.8855466129}, {98150000, 87796.4393604305}, + {98160000, 87799.0340157042}, {98170000, 87801.706199802}, + {98180000, 87804.4807499764}, {98190000, 87807.3506021751}, + {98200000, 87810.2985176692}, {98210000, 87813.3205530192}, + {98220000, 87816.3441750561}, {98230000, 87819.3478299837}, + {98240000, 87822.3607721648}, {98250000, 87825.4219730132}, + {98260000, 87828.52703774}, {98270000, 87831.6281063074}, + {98280000, 87834.7170482671}, {98290000, 87837.7920377601}, + {98300000, 87840.8518530016}, {98310000, 87843.921239831}, + {98320000, 87847.0632551036}, {98330000, 87850.2816576938}, + {98340000, 87853.4870085897}, {98350000, 87856.6527827966}, + {98360000, 87859.7885734848}, {98370000, 87862.9071045374}, + {98380000, 87866.0096766533}, {98390000, 87869.1361867931}, + {98400000, 87872.2988535478}, {98410000, 87875.4513644264}, + {98420000, 87878.5621883842}, {98430000, 87881.6528234376}, + {98440000, 87884.7778289186}, {98450000, 87887.9411779168}, + {98460000, 87891.0887341}, {98470000, 87894.2044698278}, + {98480000, 87897.2658192925}, {98490000, 87900.2426416111}, + {98500000, 87903.1371328067}, {98510000, 87906.054177165}, + {98520000, 87909.0243519283}, {98530000, 87911.9642006351}, + {98540000, 87914.8169931282}, {98550000, 87917.5814156903}, + {98560000, 87920.2534380278}, {98570000, 87922.8347055418}, + {98580000, 87925.3895098214}, {98590000, 87927.9370432718}, + {98600000, 87930.4678860434}, {98610000, 87932.9694662987}, + {98620000, 87935.4411087825}, {98630000, 87937.8718489571}, + {98640000, 87940.2585734201}, {98650000, 87942.6587910752}, + {98660000, 87945.1116544599}, {98670000, 87947.6156518508}, + {98680000, 87950.1673293237}, {98690000, 87952.7657556238}, + {98700000, 87955.3962434836}, {98710000, 87958.0543140568}, + {98720000, 87960.7197784738}, {98730000, 87963.3657422491}, + {98740000, 87966.0032655992}, {98750000, 87968.7262185769}, + {98760000, 87971.5493387535}, {98770000, 87974.4359551175}, + {98780000, 87977.3609883195}, {98790000, 87980.3679161724}, + {98800000, 87983.5681611059}, {98810000, 87986.9673449579}, + {98820000, 87990.3783840759}, {98830000, 87993.7456579381}, + {98840000, 87997.0621610615}, {98850000, 88000.3184708344}, + {98860000, 88003.5144771595}, {98870000, 88006.697279248}, + {98880000, 88009.8825078792}, {98890000, 88013.0765868561}, + {98900000, 88016.2838780053}, {98910000, 88019.4970709153}, + {98920000, 88022.6975840251}, {98930000, 88025.884476897}, + {98940000, 88029.0923898449}, {98950000, 88032.3315483826}, + {98960000, 88035.5829687108}, {98970000, 88038.8213706597}, + {98980000, 88042.045749722}, {98990000, 88045.2240278032}, + {99000000, 88048.3440080781}, {99010000, 88051.4188530332}, + {99020000, 88054.4576106233}, {99030000, 88057.4582095811}, + {99040000, 88060.4150750984}, {99050000, 88063.3280129891}, + {99060000, 88066.2040465649}, {99070000, 88069.0453930128}, + {99080000, 88071.8784050276}, {99090000, 88074.738190429}, + {99100000, 88077.6251860243}, {99110000, 88080.4857945397}, + {99120000, 88083.3035817487}, {99130000, 88086.0893258385}, + {99140000, 88088.850428072}, {99150000, 88091.5822822506}, + {99160000, 88094.2729098992}, {99170000, 88096.9221680108}, + {99180000, 88099.5651892215}, {99190000, 88102.2124488878}, + {99200000, 88104.8570159596}, {99210000, 88107.4896404788}, + {99220000, 88110.1137598518}, {99230000, 88112.7661459825}, + {99240000, 88115.4538739798}, {99250000, 88118.1885228101}, + {99260000, 88120.9779160049}, {99270000, 88123.8047957931}, + {99280000, 88126.6254301723}, {99290000, 88129.4355415271}, + {99300000, 88132.2398397131}, {99310000, 88135.0397453632}, + {99320000, 88137.8547868667}, {99330000, 88140.7110390126}, + {99340000, 88143.6034688175}, {99350000, 88146.4831496038}, + {99360000, 88149.341805541}, {99370000, 88152.2112847289}, + {99380000, 88155.1132913845}, {99390000, 88158.0483680419}, + {99400000, 88161.0181566236}, {99410000, 88164.0228498754}, + {99420000, 88167.0694696161}, {99430000, 88170.1599585772}, + {99440000, 88173.2706795899}, {99450000, 88176.3701372113}, + {99460000, 88179.4649013072}, {99470000, 88182.6194114109}, + {99480000, 88185.8443897289}, {99490000, 88189.0908639685}, + {99500000, 88192.325400082}, {99510000, 88195.5494627403}, + {99520000, 88198.7667066157}, {99530000, 88201.9782591014}, + {99540000, 88205.2128717962}, {99550000, 88208.479018984}, + {99560000, 88211.7611893959}, {99570000, 88215.0387196433}, + {99580000, 88218.3102135596}, {99590000, 88221.5446003867}, + {99600000, 88224.7324427117}, {99610000, 88227.9191681274}, + {99620000, 88231.1357996718}, {99630000, 88234.3708212808}, + {99640000, 88237.5949657418}, {99650000, 88240.8054551749}, + {99660000, 88244.0078248919}, {99670000, 88247.2037528364}, + {99680000, 88250.3967372295}, {99690000, 88253.5914473589}, + {99700000, 88256.7881455254}, {99710000, 88259.9897009925}, + {99720000, 88263.1969516342}, {99730000, 88266.4032036022}, + {99740000, 88269.6038874091}, {99750000, 88272.7915103015}, + {99760000, 88275.9468344564}, {99770000, 88279.0683902287}, + {99780000, 88282.1695141497}, {99790000, 88285.2542458734}, + {99800000, 88288.3306987057}, {99810000, 88291.4096902316}, + {99820000, 88294.4903031236}, {99830000, 88297.5591586665}, + {99840000, 88300.6136766231}, {99850000, 88303.6477893585}, + {99860000, 88306.6573853729}, {99870000, 88309.6473796849}, + {99880000, 88312.6301716078}, {99890000, 88315.60688696}, + {99900000, 88318.5711202134}, {99910000, 88321.52100757}, + {99920000, 88324.449203281}, {99930000, 88327.3458634079}, + {99940000, 88330.2114801711}, {99950000, 88333.0819068061}, + {99960000, 88335.9679861393}, {99970000, 88338.8694484475}, + {99980000, 88341.7860854759}, {99990000, 88344.7104626564}, + {100000000, 88347.6236533046}, {100010000, 88350.5244670162}, + {100020000, 88353.4404200077}, {100030000, 88356.3796722891}, + {100040000, 88359.3488837314}, {100050000, 88362.3569966812}, + {100060000, 88365.4035522635}, {100070000, 88368.4654052871}, + {100080000, 88371.5357100285}, {100090000, 88374.6569274225}, + {100100000, 88377.8580095268}, {100110000, 88381.1099665282}, + {100120000, 88384.3390748852}, {100130000, 88387.538401789}, + {100140000, 88390.725368815}, {100150000, 88393.9052069111}, + {100160000, 88397.0851578756}, {100170000, 88400.27489839}, + {100180000, 88403.4747930896}, {100190000, 88406.6900600837}, + {100200000, 88409.9223975902}, {100210000, 88413.136191996}, + {100220000, 88416.307152728}, {100230000, 88419.4446082106}, + {100240000, 88422.5721205267}, {100250000, 88425.6917948994}, + {100260000, 88428.7907496372}, {100270000, 88431.8652212765}, + {100280000, 88434.9370246403}, {100290000, 88438.0352791306}, + {100300000, 88441.1603127165}, {100310000, 88444.2736951468}, + {100320000, 88447.3637820258}, {100330000, 88450.4686287538}, + {100340000, 88453.6142316358}, {100350000, 88456.7913776445}, + {100360000, 88459.9767046173}, {100370000, 88463.1679501487}, + {100380000, 88466.3709199697}, {100390000, 88469.5873046428}, + {100400000, 88472.8089321162}, {100410000, 88476.024891863}, + {100420000, 88479.2347092954}, {100430000, 88482.4156568824}, + {100440000, 88485.5603595005}, {100450000, 88488.697309388}, + {100460000, 88491.8459994277}, {100470000, 88494.9995894751}, + {100480000, 88498.1406089147}, {100490000, 88501.2676737921}, + {100500000, 88504.3941167912}, {100510000, 88507.523913351}, + {100520000, 88510.6422602631}, {100530000, 88513.7293579034}, + {100540000, 88516.7840576726}, {100550000, 88519.787158258}, + {100560000, 88522.7330816153}, {100570000, 88525.6627700329}, + {100580000, 88528.604242009}, {100590000, 88531.548429849}, + {100600000, 88534.4721438401}, {100610000, 88537.3723819914}, + {100620000, 88540.2195163168}, {100630000, 88543.0049029265}, + {100640000, 88545.7477413093}, {100650000, 88548.4736348402}, + {100660000, 88551.1837821331}, {100670000, 88553.8797951738}, + {100680000, 88556.5622192601}, {100690000, 88559.2312066489}, + {100700000, 88561.8868824075}, {100710000, 88564.5416078724}, + {100720000, 88567.227017498}, {100730000, 88569.9464027289}, + {100740000, 88572.7085298534}, {100750000, 88575.515864064}, + {100760000, 88578.3736026841}, {100770000, 88581.2887828327}, + {100780000, 88584.2611048763}, {100790000, 88587.2704953515}, + {100800000, 88590.3106191006}, {100810000, 88593.4169438868}, + {100820000, 88596.6136469573}, {100830000, 88599.8592859462}, + {100840000, 88603.0481626532}, {100850000, 88606.1696675859}, + {100860000, 88609.2182040244}, {100870000, 88612.1923576425}, + {100880000, 88615.091058786}, {100890000, 88617.9127474825}, + {100900000, 88620.6577248993}, {100910000, 88623.3232262887}, + {100920000, 88625.9085877907}, {100930000, 88628.3849630028}, + {100940000, 88630.7327740581}, {100950000, 88632.9912870762}, + {100960000, 88635.2603130448}, {100970000, 88637.5491812255}, + {100980000, 88639.8277985403}, {100990000, 88642.0872257836}, + {101000000, 88644.327054735}, {101010000, 88646.546705832}, + {101020000, 88648.7476837391}, {101030000, 88651.0145276624}, + {101040000, 88653.3730956962}, {101050000, 88655.8373098655}, + {101060000, 88658.4165364137}, {101070000, 88661.0517032716}, + {101080000, 88663.5916947037}, {101090000, 88666.0283962027}, + {101100000, 88668.6387526793}, {101110000, 88671.5048186101}, + {101120000, 88674.5074688776}, {101130000, 88677.4874901022}, + {101140000, 88680.4362455044}, {101150000, 88683.3345472515}, + {101160000, 88686.1787886745}, {101170000, 88689.0641734989}, + {101180000, 88692.0558927622}, {101190000, 88695.1407362114}, + {101200000, 88698.285619324}, {101210000, 88701.4854604222}, + {101220000, 88704.6811498159}, {101230000, 88707.8550730369}, + {101240000, 88711.0205452722}, {101250000, 88714.1953743013}, + {101260000, 88717.3801956673}, {101270000, 88720.5720698534}, + {101280000, 88723.7701074409}, {101290000, 88726.9338620273}, + {101300000, 88730.035663893}, {101310000, 88733.092162497}, + {101320000, 88736.1456690585}, {101330000, 88739.2005488767}, + {101340000, 88742.2591871816}, {101350000, 88745.3222827794}, + {101360000, 88748.3641462759}, {101370000, 88751.3503855933}, + {101380000, 88754.2798005651}, {101390000, 88757.1900025053}, + {101400000, 88760.0936219114}, {101410000, 88762.9694312831}, + {101420000, 88765.8029239459}, {101430000, 88768.60369732}, + {101440000, 88771.3960894004}, {101450000, 88774.182289497}, + {101460000, 88776.9494217802}, {101470000, 88779.693709727}, + {101480000, 88782.4188466048}, {101490000, 88785.129742866}, + {101500000, 88787.8244401827}, {101510000, 88790.4809524371}, + {101520000, 88793.0950950501}, {101530000, 88795.6834675063}, + {101540000, 88798.2575015054}, {101550000, 88800.8348358183}, + {101560000, 88803.4606988778}, {101570000, 88806.1393492254}, + {101580000, 88808.8659271773}, {101590000, 88811.6388149104}, + {101600000, 88814.4378929859}, {101610000, 88817.2362767}, + {101620000, 88820.0357098848}, {101630000, 88822.8646510329}, + {101640000, 88825.7285898535}, {101650000, 88828.6220482691}, + {101660000, 88831.5412256667}, {101670000, 88834.4834303748}, + {101680000, 88837.4419454522}, {101690000, 88840.4168832671}, + {101700000, 88843.4433887345}, {101710000, 88846.5317716441}, + {101720000, 88849.655190179}, {101730000, 88852.7777769861}, + {101740000, 88855.9024331708}, {101750000, 88859.0635803619}, + {101760000, 88862.2666164033}, {101770000, 88865.501254929}, + {101780000, 88868.7603877516}, {101790000, 88872.0338676613}, + {101800000, 88875.2957144694}, {101810000, 88878.5434752963}, + {101820000, 88881.7828590824}, {101830000, 88885.0156016754}, + {101840000, 88888.223550042}, {101850000, 88891.3823426997}, + {101860000, 88894.4914366375}, {101870000, 88897.5674799296}, + {101880000, 88900.6157397403}, {101890000, 88903.6322357193}, + {101900000, 88906.6142854056}, {101910000, 88909.5717623053}, + {101920000, 88912.5298045709}, {101930000, 88915.4911669229}, + {101940000, 88918.4644000183}, {101950000, 88921.452022554}, + {101960000, 88924.431558087}, {101970000, 88927.3728821546}, + {101980000, 88930.2757825097}, {101990000, 88933.1969511408}, + {102000000, 88936.1539014296}, {102010000, 88939.1515155005}, + {102020000, 88942.1930809063}, {102030000, 88945.2711812385}, + {102040000, 88948.3670764821}, {102050000, 88951.4777144024}, + {102060000, 88954.5592411723}, {102070000, 88957.5986590016}, + {102080000, 88960.6139266745}, {102090000, 88963.6290608976}, + {102100000, 88966.6450909174}, {102110000, 88969.6743860976}, + {102120000, 88972.7210420248}, {102130000, 88975.772202631}, + {102140000, 88978.819038141}, {102150000, 88981.8466061973}, + {102160000, 88984.8163745623}, {102170000, 88987.7260164373}, + {102180000, 88990.630642852}, {102190000, 88993.546746089}, + {102200000, 88996.4893203598}, {102210000, 88999.4784983384}, + {102220000, 89002.5140419203}, {102230000, 89005.559352905}, + {102240000, 89008.6034509614}, {102250000, 89011.6551984027}, + {102260000, 89014.7206729688}, {102270000, 89017.8049195347}, + {102280000, 89020.9210442024}, {102290000, 89024.0699089594}, + {102300000, 89027.2378719273}, {102310000, 89030.4207883944}, + {102320000, 89033.6027630446}, {102330000, 89036.7625001437}, + {102340000, 89039.899981792}, {102350000, 89043.0437504883}, + {102360000, 89046.2021863726}, {102370000, 89049.352511936}, + {102380000, 89052.4790886264}, {102390000, 89055.5864726428}, + {102400000, 89058.6862154527}, {102410000, 89061.7790222718}, + {102420000, 89064.8442029072}, {102430000, 89067.8756686633}, + {102440000, 89070.8917967531}, {102450000, 89073.9172007272}, + {102460000, 89076.9516185887}, {102470000, 89079.9537294622}, + {102480000, 89082.9116558797}, {102490000, 89085.8420916874}, + {102500000, 89088.7565642551}, {102510000, 89091.650580321}, + {102520000, 89094.5124373454}, {102530000, 89097.3405553879}, + {102540000, 89100.1130542128}, {102550000, 89102.8235870457}, + {102560000, 89105.4808859382}, {102570000, 89108.0965665418}, + {102580000, 89110.6713261833}, {102590000, 89113.256308349}, + {102600000, 89115.8687314547}, {102610000, 89118.4745073286}, + {102620000, 89121.0502232854}, {102630000, 89123.5928836019}, + {102640000, 89126.0945328745}, {102650000, 89128.5553993873}, + {102660000, 89131.0108488248}, {102670000, 89133.4714722361}, + {102680000, 89135.9074637469}, {102690000, 89138.2788169999}, + {102700000, 89140.5888558804}, {102710000, 89142.8848562303}, + {102720000, 89145.1762356032}, {102730000, 89147.4480171531}, + {102740000, 89149.6899272443}, {102750000, 89151.9385636346}, + {102760000, 89154.2880906551}, {102770000, 89156.7451683055}, + {102780000, 89159.207720311}, {102790000, 89161.6452130899}, + {102800000, 89164.1026707921}, {102810000, 89166.6404963233}, + {102820000, 89169.2588475459}, {102830000, 89171.8741429574}, + {102840000, 89174.4614528136}, {102850000, 89177.0851250926}, + {102860000, 89179.7893740677}, {102870000, 89182.5482244107}, + {102880000, 89185.2953120032}, {102890000, 89188.024023433}, + {102900000, 89190.7378574028}, {102910000, 89193.4379125118}, + {102920000, 89196.1661751543}, {102930000, 89198.9790380728}, + {102940000, 89201.8728925863}, {102950000, 89204.7890552667}, + {102960000, 89207.7154977082}, {102970000, 89210.6772515867}, + {102980000, 89213.6915054335}, {102990000, 89216.7364844046}, + {103000000, 89219.7564372577}, {103010000, 89222.7484763103}, + {103020000, 89225.8235789007}, {103030000, 89229.0146564249}, + {103040000, 89232.2576681832}, {103050000, 89235.4667650024}, + {103060000, 89238.6447702376}, {103070000, 89241.8445178941}, + {103080000, 89245.0749937361}, {103090000, 89248.3265336351}, + {103100000, 89251.5924564297}, {103110000, 89254.8651426272}, + {103120000, 89258.1250297506}, {103130000, 89261.3706726446}, + {103140000, 89264.6224125881}, {103150000, 89267.8863138201}, + {103160000, 89271.1474711259}, {103170000, 89274.3858776639}, + {103180000, 89277.6018921341}, {103190000, 89280.8632200145}, + {103200000, 89284.1906435331}, {103210000, 89287.5151170176}, + {103220000, 89290.7890247704}, {103230000, 89294.0307998415}, + {103240000, 89297.287642853}, {103250000, 89300.5634956191}, + {103260000, 89303.825305226}, {103270000, 89307.0632322078}, + {103280000, 89310.2875307922}, {103290000, 89313.5119379515}, + {103300000, 89316.7370444055}, {103310000, 89319.9354083064}, + {103320000, 89323.0978461544}, {103330000, 89326.2469508376}, + {103340000, 89329.3983056174}, {103350000, 89332.5523629183}, + {103360000, 89335.7103088813}, {103370000, 89338.8724190604}, + {103380000, 89342.0458786517}, {103390000, 89345.2327993477}, + {103400000, 89348.4215158876}, {103410000, 89351.5963637318}, + {103420000, 89354.7568393184}, {103430000, 89357.9098618891}, + {103440000, 89361.0576054017}, {103450000, 89364.1942013281}, + {103460000, 89367.3156243221}, {103470000, 89370.4218362243}, + {103480000, 89373.5126183697}, {103490000, 89376.5885276535}, + {103500000, 89379.6709741105}, {103510000, 89382.7663451636}, + {103520000, 89385.8672065275}, {103530000, 89388.9635827542}, + {103540000, 89392.0565397563}, {103550000, 89395.1608055142}, + {103560000, 89398.2792611714}, {103570000, 89401.3840380504}, + {103580000, 89404.4558884334}, {103590000, 89407.5164099114}, + {103600000, 89410.6211784617}, {103610000, 89413.7745374748}, + {103620000, 89416.929485955}, {103630000, 89420.0719461479}, + {103640000, 89423.1864978509}, {103650000, 89426.2523814133}, + {103660000, 89429.2689333621}, {103670000, 89432.3069138167}, + {103680000, 89435.3908605168}, {103690000, 89438.5139135931}, + {103700000, 89441.6712820027}, {103710000, 89444.8651841365}, + {103720000, 89448.1016274745}, {103730000, 89451.3796799403}, + {103740000, 89454.6425229065}, {103750000, 89457.8731977701}, + {103760000, 89461.0746112471}, {103770000, 89464.2506163075}, + {103780000, 89467.4015004188}, {103790000, 89470.5572574907}, + {103800000, 89473.7282696674}, {103810000, 89476.90812196}, + {103820000, 89480.0923764765}, {103830000, 89483.2760169586}, + {103840000, 89486.446109584}, {103850000, 89489.6015506214}, + {103860000, 89492.7488465966}, {103870000, 89495.8899754809}, + {103880000, 89499.0319771228}, {103890000, 89502.1843164428}, + {103900000, 89505.3471801265}, {103910000, 89508.5095786845}, + {103920000, 89511.668106664}, {103930000, 89514.8160834521}, + {103940000, 89517.9489118694}, {103950000, 89521.0665326433}, + {103960000, 89524.1686723791}, {103970000, 89527.2555409221}, + {103980000, 89530.3343098209}, {103990000, 89533.4071561523}, + {104000000, 89536.4810376332}, {104010000, 89539.5653090616}, + {104020000, 89542.6603254707}, {104030000, 89545.7477157423}, + {104040000, 89548.8212980728}, {104050000, 89551.8914003924}, + {104060000, 89554.9651511125}, {104070000, 89558.0427520973}, + {104080000, 89561.1247548287}, {104090000, 89564.2115345326}, + {104100000, 89567.3173417684}, {104110000, 89570.4463801751}, + {104120000, 89573.594040737}, {104130000, 89576.7541603352}, + {104140000, 89579.9264916672}, {104150000, 89583.1144993934}, + {104160000, 89586.3191735897}, {104170000, 89589.5220788171}, + {104180000, 89592.7104872256}, {104190000, 89595.8865554976}, + {104200000, 89599.0557444064}, {104210000, 89602.2184788509}, + {104220000, 89605.3679654317}, {104230000, 89608.5022147876}, + {104240000, 89611.644289936}, {104250000, 89614.825207286}, + {104260000, 89618.0386012901}, {104270000, 89621.2211540603}, + {104280000, 89624.3619853712}, {104290000, 89627.5092436361}, + {104300000, 89630.6961678209}, {104310000, 89633.901591008}, + {104320000, 89637.0710416895}, {104330000, 89640.199728974}, + {104340000, 89643.3132830037}, {104350000, 89646.4194421408}, + {104360000, 89649.5078340693}, {104370000, 89652.5644724866}, + {104380000, 89655.5896814611}, {104390000, 89658.6268240256}, + {104400000, 89661.6891781721}, {104410000, 89664.7594351498}, + {104420000, 89667.8256303803}, {104430000, 89670.8850156984}, + {104440000, 89673.9304457002}, {104450000, 89676.9620839509}, + {104460000, 89680.0152046815}, {104470000, 89683.1003106124}, + {104480000, 89686.2021760159}, {104490000, 89689.3003453678}, + {104500000, 89692.3943626792}, {104510000, 89695.4997820286}, + {104520000, 89698.6211650391}, {104530000, 89701.7518550469}, + {104540000, 89704.8872411048}, {104550000, 89708.0271946161}, + {104560000, 89711.1714200497}, {104570000, 89714.3202029783}, + {104580000, 89717.4877352927}, {104590000, 89720.6782073401}, + {104600000, 89723.8797915509}, {104610000, 89727.076594423}, + {104620000, 89730.2683699801}, {104630000, 89733.4709414841}, + {104640000, 89736.6889523186}, {104650000, 89739.9102106418}, + {104660000, 89743.1262820149}, {104670000, 89746.3394049923}, + {104680000, 89749.5553324471}, {104690000, 89752.7741424821}, + {104700000, 89755.9747806466}, {104710000, 89759.1509967262}, + {104720000, 89762.3178841637}, {104730000, 89765.4957335568}, + {104740000, 89768.6837309949}, {104750000, 89771.8688992645}, + {104760000, 89775.0491290189}, {104770000, 89778.2183114301}, + {104780000, 89781.3722396381}, {104790000, 89784.5181818299}, + {104800000, 89787.6748506159}, {104810000, 89790.8432984171}, + {104820000, 89793.9889120494}, {104830000, 89797.1013836625}, + {104840000, 89800.1913255174}, {104850000, 89803.2729881235}, + {104860000, 89806.3470303129}, {104870000, 89809.4550462411}, + {104880000, 89812.6110742408}, {104890000, 89815.7846619999}, + {104900000, 89818.9547279239}, {104910000, 89822.1084845636}, + {104920000, 89825.2127677557}, {104930000, 89828.2660508754}, + {104940000, 89831.3379557214}, {104950000, 89834.449294681}, + {104960000, 89837.5923405666}, {104970000, 89840.7567440103}, + {104980000, 89843.9419533487}, {104990000, 89847.1304130047}, + {105000000, 89850.3157827764}, {105010000, 89853.4797227074}, + {105020000, 89856.6095850785}, {105030000, 89859.714926215}, + {105040000, 89862.8202381197}, {105050000, 89865.9277174722}, + {105060000, 89869.0244752835}, {105070000, 89872.1066809247}, + {105080000, 89875.1740553258}, {105090000, 89878.226196562}, + {105100000, 89881.2639767094}, {105110000, 89884.3420472075}, + {105120000, 89887.4772771535}, {105130000, 89890.628564141}, + {105140000, 89893.7674301432}, {105150000, 89896.8955679803}, + {105160000, 89900.0172653683}, {105170000, 89903.1329943978}, + {105180000, 89906.2430420576}, {105190000, 89909.3475142626}, + {105200000, 89912.438712499}, {105210000, 89915.5062467441}, + {105220000, 89918.5519062746}, {105230000, 89921.5970608001}, + {105240000, 89924.6459630343}, {105250000, 89927.6768481724}, + {105260000, 89930.6746765952}, {105270000, 89933.6537799387}, + {105280000, 89936.6510749239}, {105290000, 89939.6701298779}, + {105300000, 89942.7058059746}, {105310000, 89945.7565031605}, + {105320000, 89948.8257125839}, {105330000, 89951.9181721172}, + {105340000, 89955.0341107212}, {105350000, 89958.17451865}, + {105360000, 89961.3394652765}, {105370000, 89964.5118523089}, + {105380000, 89967.6798319474}, {105390000, 89970.8406178536}, + {105400000, 89973.9869546969}, {105410000, 89977.1183242415}, + {105420000, 89980.2415151411}, {105430000, 89983.3585931535}, + {105440000, 89986.4774341435}, {105450000, 89989.6086558068}, + {105460000, 89992.7501628329}, {105470000, 89995.8810790466}, + {105480000, 89998.9978436464}, {105490000, 90002.1163997125}, + {105500000, 90005.2477813243}, {105510000, 90008.3873889031}, + {105520000, 90011.5233921167}, {105530000, 90014.6547501973}, + {105540000, 90017.7879678611}, {105550000, 90020.9249922036}, + {105560000, 90024.0581236406}, {105570000, 90027.1769782904}, + {105580000, 90030.2816186173}, {105590000, 90033.4026881591}, + {105600000, 90036.5496810209}, {105610000, 90039.6991113291}, + {105620000, 90042.8347169928}, {105630000, 90045.9658650894}, + {105640000, 90049.1167462474}, {105650000, 90052.2891113743}, + {105660000, 90055.4557253489}, {105670000, 90058.6084286338}, + {105680000, 90061.7501526791}, {105690000, 90064.8848366869}, + {105700000, 90068.0130854435}, {105710000, 90071.1519828787}, + {105720000, 90074.3066187736}, {105730000, 90077.4592623124}, + {105740000, 90080.5976269023}, {105750000, 90083.7165514654}, + {105760000, 90086.8025171223}, {105770000, 90089.8554209594}, + {105780000, 90092.9245104562}, {105790000, 90096.0245312796}, + {105800000, 90099.1447070522}, {105810000, 90102.2705373169}, + {105820000, 90105.3983729915}, {105830000, 90108.4982915669}, + {105840000, 90111.5644457677}, {105850000, 90114.612833307}, + {105860000, 90117.6545557651}, {105870000, 90120.7021839832}, + {105880000, 90123.7883147106}, {105890000, 90126.9151625238}, + {105900000, 90130.0416143844}, {105910000, 90133.1553145807}, + {105920000, 90136.2588015449}, {105930000, 90139.3554783532}, + {105940000, 90142.4456990513}, {105950000, 90145.5388340086}, + {105960000, 90148.6377447691}, {105970000, 90151.7360200865}, + {105980000, 90154.8292171501}, {105990000, 90157.9245639678}, + {106000000, 90161.0407931276}, {106010000, 90164.1792616383}, + {106020000, 90167.3195627479}, {106030000, 90170.4555502283}, + {106040000, 90173.5827676142}, {106050000, 90176.695181068}, + {106060000, 90179.7929892431}, {106070000, 90182.8914160562}, + {106080000, 90185.994977373}, {106090000, 90189.086507835}, + {106100000, 90192.1541279702}, {106110000, 90195.2097937403}, + {106120000, 90198.2843670667}, {106130000, 90201.3804633701}, + {106140000, 90204.4783593025}, {106150000, 90207.5721204757}, + {106160000, 90210.6537452769}, {106170000, 90213.7124188371}, + {106180000, 90216.7477783024}, {106190000, 90219.7655638744}, + {106200000, 90222.7677920669}, {106210000, 90225.7548292299}, + {106220000, 90228.7269522761}, {106230000, 90231.6818086498}, + {106240000, 90234.6131592122}, {106250000, 90237.5209546845}, + {106260000, 90240.4263019871}, {106270000, 90243.3355536176}, + {106280000, 90246.2163083992}, {106290000, 90249.0248099765}, + {106300000, 90251.7601110145}, {106310000, 90254.4649367314}, + {106320000, 90257.1527072772}, {106330000, 90259.8088436601}, + {106340000, 90262.4232718432}, {106350000, 90265.0104805217}, + {106360000, 90267.6078247211}, {106370000, 90270.2188052901}, + {106380000, 90272.8312210636}, {106390000, 90275.4413903732}, + {106400000, 90278.0521568281}, {106410000, 90280.6673616307}, + {106420000, 90283.2871519075}, {106430000, 90285.8756780477}, + {106440000, 90288.420866398}, {106450000, 90290.9733979128}, + {106460000, 90293.5684476777}, {106470000, 90296.1946937156}, + {106480000, 90298.8230250126}, {106490000, 90301.4509057597}, + {106500000, 90304.0980509291}, {106510000, 90306.7703252059}, + {106520000, 90309.4777253381}, {106530000, 90312.2338139669}, + {106540000, 90315.0395669937}, {106550000, 90317.9199802537}, + {106560000, 90320.8822634933}, {106570000, 90323.9052611627}, + {106580000, 90326.9741941184}, {106590000, 90330.0884854907}, + {106600000, 90333.2470026805}, {106610000, 90336.448781679}, + {106620000, 90339.6650727189}, {106630000, 90342.8871752628}, + {106640000, 90346.117187079}, {106650000, 90349.3579551802}, + {106660000, 90352.6093894023}, {106670000, 90355.8601032849}, + {106680000, 90359.106547928}, {106690000, 90362.3142647071}, + {106700000, 90365.4593884898}, {106710000, 90368.5633417147}, + {106720000, 90371.6815394087}, {106730000, 90374.8190294982}, + {106740000, 90377.95033418}, {106750000, 90381.0677915956}, + {106760000, 90384.1743522054}, {106770000, 90387.2739844009}, + {106780000, 90390.3670362184}, {106790000, 90393.4629432031}, + {106800000, 90396.5646318533}, {106810000, 90399.6712779185}, + {106820000, 90402.782301675}, {106830000, 90405.8928073}, + {106840000, 90408.9900944549}, {106850000, 90412.073718911}, + {106860000, 90415.178624699}, {106870000, 90418.3152515073}, + {106880000, 90421.4718912767}, {106890000, 90424.6327550613}, + {106900000, 90427.7971293318}, {106910000, 90430.9437130759}, + {106920000, 90434.0652953191}, {106930000, 90437.1894447899}, + {106940000, 90440.3353214419}, {106950000, 90443.4961050767}, + {106960000, 90446.6542083328}, {106970000, 90449.8079832078}, + {106980000, 90452.9636013408}, {106990000, 90456.1229146376}, + {107000000, 90459.2925638064}, {107010000, 90462.4815429632}, + {107020000, 90465.6892287307}, {107030000, 90468.8513692685}, + {107040000, 90471.9480807802}, {107050000, 90475.0353515804}, + {107060000, 90478.1521149412}, {107070000, 90481.299394711}, + {107080000, 90484.480104597}, {107090000, 90487.6932874317}, + {107100000, 90490.8890875035}, {107110000, 90494.0525302124}, + {107120000, 90497.1940336642}, {107130000, 90500.3276398494}, + {107140000, 90503.4556177571}, {107150000, 90506.5942933195}, + {107160000, 90509.7468932575}, {107170000, 90512.8801255417}, + {107180000, 90515.9708482705}, {107190000, 90519.0428615943}, + {107200000, 90522.1579489148}, {107210000, 90525.3211968425}, + {107220000, 90528.4859458618}, {107230000, 90531.638141296}, + {107240000, 90534.7837823013}, {107250000, 90537.9309656755}, + {107260000, 90541.0797156796}, {107270000, 90544.2175163557}, + {107280000, 90547.3406916407}, {107290000, 90550.4653819476}, + {107300000, 90553.6028185773}, {107310000, 90556.7411573139}, + {107320000, 90559.849619258}, {107330000, 90562.9254691558}, + {107340000, 90565.9813308083}, {107350000, 90569.0210748399}, + {107360000, 90572.038037333}, {107370000, 90575.0231626589}, + {107380000, 90577.9762039418}, {107390000, 90580.8858933236}, + {107400000, 90583.7485151724}, {107410000, 90586.5992458658}, + {107420000, 90589.4625856465}, {107430000, 90592.348893602}, + {107440000, 90595.2853748411}, {107450000, 90598.2735289027}, + {107460000, 90601.2647928281}, {107470000, 90604.2444993605}, + {107480000, 90607.2189791164}, {107490000, 90610.1967866163}, + {107500000, 90613.1791718134}, {107510000, 90616.1749962665}, + {107520000, 90619.1859690197}, {107530000, 90622.2118104883}, + {107540000, 90625.2523037978}, {107550000, 90628.3195491959}, + {107560000, 90631.4452134493}, {107570000, 90634.6307190266}, + {107580000, 90637.8063438445}, {107590000, 90640.9511123265}, + {107600000, 90644.0786703229}, {107610000, 90647.2074467223}, + {107620000, 90650.332527158}, {107630000, 90653.3962949791}, + {107640000, 90656.3874694175}, {107650000, 90659.2996403459}, + {107660000, 90662.1284647924}, {107670000, 90664.8790479398}, + {107680000, 90667.5640303049}, {107690000, 90670.1850150472}, + {107700000, 90672.7430194576}, {107710000, 90675.2385690711}, + {107720000, 90677.6914951713}, {107730000, 90680.128548568}, + {107740000, 90682.5521384999}, {107750000, 90684.97150059}, + {107760000, 90687.388172877}, {107770000, 90689.802497793}, + {107780000, 90692.214717186}, {107790000, 90694.6248283908}, + {107800000, 90697.0328075275}, {107810000, 90699.4397635458}, + {107820000, 90701.8955902566}, {107830000, 90704.4151759535}, + {107840000, 90706.9789853938}, {107850000, 90709.5606485868}, + {107860000, 90712.1597511978}, {107870000, 90714.8333029562}, + {107880000, 90717.598816531}, {107890000, 90720.4466708709}, + {107900000, 90723.3700384575}, {107910000, 90726.3441679474}, + {107920000, 90729.3050589164}, {107930000, 90732.2480369407}, + {107940000, 90735.2550577814}, {107950000, 90738.3506142863}, + {107960000, 90741.5042036483}, {107970000, 90744.6746312919}, + {107980000, 90747.8598023809}, {107990000, 90751.0456665463}, + {108000000, 90754.2278326373}, {108010000, 90757.4216640234}, + {108020000, 90760.6378492798}, {108030000, 90763.8644907596}, + {108040000, 90767.0707119556}, {108050000, 90770.2537188664}, + {108060000, 90773.4260978501}, {108070000, 90776.5916815245}, + {108080000, 90779.7469456211}, {108090000, 90782.8870999237}, + {108100000, 90786.0120050778}, {108110000, 90789.1527144521}, + {108120000, 90792.3198408124}, {108130000, 90795.4896235724}, + {108140000, 90798.6454806229}, {108150000, 90801.7870215957}, + {108160000, 90804.9131153168}, {108170000, 90808.0241812994}, + {108180000, 90811.1415760123}, {108190000, 90814.2717278846}, + {108200000, 90817.4034208407}, {108210000, 90820.521471755}, + {108220000, 90823.62472265}, {108230000, 90826.6890443583}, + {108240000, 90829.7073143855}, {108250000, 90832.6914698794}, + {108260000, 90835.6498802622}, {108270000, 90838.5877604104}, + {108280000, 90841.5185153793}, {108290000, 90844.4434084447}, + {108300000, 90847.3560986643}, {108310000, 90850.2547162119}, + {108320000, 90853.121130899}, {108330000, 90855.9307162347}, + {108340000, 90858.6842382118}, {108350000, 90861.4439914448}, + {108360000, 90864.2284703374}, {108370000, 90867.0381552403}, + {108380000, 90869.87334374}, {108390000, 90872.7436588774}, + {108400000, 90875.6744547462}, {108410000, 90878.667149024}, + {108420000, 90881.6801912911}, {108430000, 90884.7009707987}, + {108440000, 90887.7204812367}, {108450000, 90890.7265263146}, + {108460000, 90893.7186109345}, {108470000, 90896.6960620976}, + {108480000, 90899.6587337731}, {108490000, 90902.6122021325}, + {108500000, 90905.5603714767}, {108510000, 90908.5155149563}, + {108520000, 90911.5097007512}, {108530000, 90914.5449830319}, + {108540000, 90917.5731212962}, {108550000, 90920.5795812351}, + {108560000, 90923.5811985251}, {108570000, 90926.6007785877}, + {108580000, 90929.6392445157}, {108590000, 90932.6727818432}, + {108600000, 90935.6932668571}, {108610000, 90938.7328760167}, + {108620000, 90941.8140587614}, {108630000, 90944.9227467993}, + {108640000, 90948.0225105093}, {108650000, 90951.1099247676}, + {108660000, 90954.1972515203}, {108670000, 90957.2881917647}, + {108680000, 90960.3752575412}, {108690000, 90963.4482948618}, + {108700000, 90966.5068558252}, {108710000, 90969.5503466641}, + {108720000, 90972.5787080603}, {108730000, 90975.5975205014}, + {108740000, 90978.610691815}, {108750000, 90981.6232243205}, + {108760000, 90984.6481602894}, {108770000, 90987.686484238}, + {108780000, 90990.7246389724}, {108790000, 90993.7585334775}, + {108800000, 90996.7838990298}, {108810000, 90999.7949306125}, + {108820000, 91002.7924544405}, {108830000, 91005.8227524315}, + {108840000, 91008.899685927}, {108850000, 91011.9884571182}, + {108860000, 91015.0646490734}, {108870000, 91018.1324919403}, + {108880000, 91021.2029516031}, {108890000, 91024.2771539598}, + {108900000, 91027.3556580864}, {108910000, 91030.4386179013}, + {108920000, 91033.5257879561}, {108930000, 91036.6168432409}, + {108940000, 91039.7104150328}, {108950000, 91042.7924708647}, + {108960000, 91045.8601760863}, {108970000, 91048.9185728167}, + {108980000, 91051.9711972147}, {108990000, 91055.0181907444}, + {109000000, 91058.05987685}, {109010000, 91061.0963127183}, + {109020000, 91064.1275366077}, {109030000, 91067.1535781774}, + {109040000, 91070.1782452199}, {109050000, 91073.2066996675}, + {109060000, 91076.2339865695}, {109070000, 91079.2165533532}, + {109080000, 91082.1469838299}, {109090000, 91085.068528631}, + {109100000, 91088.0114150181}, {109110000, 91090.9594955229}, + {109120000, 91093.8706950685}, {109130000, 91096.7412788436}, + {109140000, 91099.5904598678}, {109150000, 91102.4241154994}, + {109160000, 91105.2464147682}, {109170000, 91108.0629914698}, + {109180000, 91110.8741460185}, {109190000, 91113.681585941}, + {109200000, 91116.4858577057}, {109210000, 91119.2975375339}, + {109220000, 91122.1240119458}, {109230000, 91124.9678718397}, + {109240000, 91127.8360236686}, {109250000, 91130.729543796}, + {109260000, 91133.6700314293}, {109270000, 91136.6638471516}, + {109280000, 91139.6980825824}, {109290000, 91142.7553035737}, + {109300000, 91145.8346276428}, {109310000, 91148.9489093522}, + {109320000, 91152.1024349908}, {109330000, 91155.2365874707}, + {109340000, 91158.3103960068}, {109350000, 91161.3374830484}, + {109360000, 91164.3530423158}, {109370000, 91167.3603140073}, + {109380000, 91170.3399733697}, {109390000, 91173.2862795543}, + {109400000, 91176.2030970484}, {109410000, 91179.0956137688}, + {109420000, 91181.9629940007}, {109430000, 91184.7342577781}, + {109440000, 91187.3878015191}, {109450000, 91189.9879782817}, + {109460000, 91192.5798786187}, {109470000, 91195.176931751}, + {109480000, 91197.81424709}, {109490000, 91200.4954466304}, + {109500000, 91203.2294122129}, {109510000, 91206.0186453088}, + {109520000, 91208.8698778361}, {109530000, 91211.7923606553}, + {109540000, 91214.7807947238}, {109550000, 91217.7797610812}, + {109560000, 91220.7780042358}, {109570000, 91223.8007969858}, + {109580000, 91226.865845972}, {109590000, 91229.9541117639}, + {109600000, 91233.0160648746}, {109610000, 91236.0471421877}, + {109620000, 91239.0660783736}, {109630000, 91242.0785784822}, + {109640000, 91245.0671574323}, {109650000, 91248.008036687}, + {109660000, 91250.9003868053}, {109670000, 91253.7368594882}, + {109680000, 91256.5151219102}, {109690000, 91259.2546368502}, + {109700000, 91261.9690748766}, {109710000, 91264.6758795906}, + {109720000, 91267.4205395487}, {109730000, 91270.2071458059}, + {109740000, 91273.0166510459}, {109750000, 91275.8432183608}, + {109760000, 91278.6956822886}, {109770000, 91281.5860822974}, + {109780000, 91284.5147726649}, {109790000, 91287.4761346671}, + {109800000, 91290.4680745962}, {109810000, 91293.4705622957}, + {109820000, 91296.4695548239}, {109830000, 91299.4719549886}, + {109840000, 91302.4958156691}, {109850000, 91305.5419882719}, + {109860000, 91308.5686803771}, {109870000, 91311.5633271184}, + {109880000, 91314.5613242552}, {109890000, 91317.6107257584}, + {109900000, 91320.7127736876}, {109910000, 91323.8187165347}, + {109920000, 91326.9132674375}, {109930000, 91329.9831342369}, + {109940000, 91333.0190331049}, {109950000, 91336.0377747054}, + {109960000, 91339.0831682166}, {109970000, 91342.1587276776}, + {109980000, 91345.2240684285}, {109990000, 91348.267009563}, + {110000000, 91351.2904597637}, {110010000, 91354.2983352988}, + {110020000, 91357.2908848182}, {110030000, 91360.3074441584}, + {110040000, 91363.361422357}, {110050000, 91366.4121595568}, + {110060000, 91369.4311859551}, {110070000, 91372.425097736}, + {110080000, 91375.4109355787}, {110090000, 91378.3906596829}, + {110100000, 91381.372347351}, {110110000, 91384.3584351546}, + {110120000, 91387.3592572412}, {110130000, 91390.3888806358}, + {110140000, 91393.4479445919}, {110150000, 91396.5436547635}, + {110160000, 91399.6780751125}, {110170000, 91402.8151709671}, + {110180000, 91405.9296716273}, {110190000, 91409.0354668634}, + {110200000, 91412.168840247}, {110210000, 91415.332828941}, + {110220000, 91418.5008570343}, {110230000, 91421.66487128}, + {110240000, 91424.7972494236}, {110250000, 91427.8604056815}, + {110260000, 91430.8612800968}, {110270000, 91433.8702377591}, + {110280000, 91436.8995556359}, {110290000, 91439.9681382754}, + {110300000, 91443.0892331053}, {110310000, 91446.2460538155}, + {110320000, 91449.3950056143}, {110330000, 91452.5303656197}, + {110340000, 91455.5928485588}, {110350000, 91458.5647735828}, + {110360000, 91461.5047488922}, {110370000, 91464.4923424786}, + {110380000, 91467.530657349}, {110390000, 91470.6040186431}, + {110400000, 91473.7074066159}, {110410000, 91476.8318751759}, + {110420000, 91479.9711204623}, {110430000, 91483.1176797267}, + {110440000, 91486.252079836}, {110450000, 91489.3729587659}, + {110460000, 91492.5077688549}, {110470000, 91495.6647724885}, + {110480000, 91498.8325894896}, {110490000, 91501.995764955}, + {110500000, 91505.1530688835}, {110510000, 91508.2815825618}, + {110520000, 91511.3745623056}, {110530000, 91514.4599532581}, + {110540000, 91517.5573611468}, {110550000, 91520.6624743611}, + {110560000, 91523.7640705747}, {110570000, 91526.8606912647}, + {110580000, 91529.9374919944}, {110590000, 91532.9900511146}, + {110600000, 91536.0363054076}, {110610000, 91539.1006336408}, + {110620000, 91542.1833254578}, {110630000, 91545.2443659756}, + {110640000, 91548.2715297618}, {110650000, 91551.2864644818}, + {110660000, 91554.3043857725}, {110670000, 91557.3184715063}, + {110680000, 91560.3108346096}, {110690000, 91563.2803201959}, + {110700000, 91566.2544887209}, {110710000, 91569.2416673925}, + {110720000, 91572.2463253267}, {110730000, 91575.2745715524}, + {110740000, 91578.324830996}, {110750000, 91581.3831741801}, + {110760000, 91584.4472650807}, {110770000, 91587.5385585272}, + {110780000, 91590.6720768716}, {110790000, 91593.8287397101}, + {110800000, 91596.958795195}, {110810000, 91600.0579491333}, + {110820000, 91603.159166204}, {110830000, 91606.2724187423}, + {110840000, 91609.3903692689}, {110850000, 91612.5030489272}, + {110860000, 91615.6100377257}, {110870000, 91618.6810948504}, + {110880000, 91621.7059687466}, {110890000, 91624.7408921358}, + {110900000, 91627.8253282733}, {110910000, 91630.9408899704}, + {110920000, 91634.0396493431}, {110930000, 91637.1174543958}, + {110940000, 91640.2073152306}, {110950000, 91643.3191832585}, + {110960000, 91646.4382421384}, {110970000, 91649.5443405175}, + {110980000, 91652.6366382852}, {110990000, 91655.7140385364}, + {111000000, 91658.7761989671}, {111010000, 91661.83972358}, + {111020000, 91664.916267162}, {111030000, 91668.0061273748}, + {111040000, 91671.1101926993}, {111050000, 91674.2280358331}, + {111060000, 91677.3382991779}, {111070000, 91680.4345433875}, + {111080000, 91683.5019887759}, {111090000, 91686.520467859}, + {111100000, 91689.489537093}, {111110000, 91692.4261039356}, + {111120000, 91695.3355725474}, {111130000, 91698.2139946949}, + {111140000, 91701.058640559}, {111150000, 91703.8816548385}, + {111160000, 91706.7146850545}, {111170000, 91709.5602244389}, + {111180000, 91712.3843604313}, {111190000, 91715.176892943}, + {111200000, 91717.956174652}, {111210000, 91720.7471586303}, + {111220000, 91723.5497292739}, {111230000, 91726.3518500556}, + {111240000, 91729.1510989328}, {111250000, 91731.941303678}, + {111260000, 91734.7181443791}, {111270000, 91737.503290186}, + {111280000, 91740.3535902265}, {111290000, 91743.2740658888}, + {111300000, 91746.2391022061}, {111310000, 91749.2407841516}, + {111320000, 91752.2549597792}, {111330000, 91755.2487820186}, + {111340000, 91758.2249514795}, {111350000, 91761.2181018043}, + {111360000, 91764.2342376465}, {111370000, 91767.2742312677}, + {111380000, 91770.3386608634}, {111390000, 91773.425021826}, + {111400000, 91776.5269225239}, {111410000, 91779.6427228802}, + {111420000, 91782.7293179455}, {111430000, 91785.7737497192}, + {111440000, 91788.7943521629}, {111450000, 91791.8160548859}, + {111460000, 91794.8367233821}, {111470000, 91797.8289401329}, + {111480000, 91800.7880315726}, {111490000, 91803.7021949373}, + {111500000, 91806.5631996588}, {111510000, 91809.3638002103}, + {111520000, 91812.0844954663}, {111530000, 91814.7245168959}, + {111540000, 91817.3258522343}, {111550000, 91819.9013565135}, + {111560000, 91822.4419579076}, {111570000, 91824.9352350709}, + {111580000, 91827.3802831305}, {111590000, 91829.732101099}, + {111600000, 91831.9768665578}, {111610000, 91834.251290405}, + {111620000, 91836.6515444856}, {111630000, 91839.1557309585}, + {111640000, 91841.7072508723}, {111650000, 91844.3002913365}, + {111660000, 91846.9457474434}, {111670000, 91849.6467511804}, + {111680000, 91852.3725052344}, {111690000, 91855.0810325902}, + {111700000, 91857.7704310555}, {111710000, 91860.4369658937}, + {111720000, 91863.0795998272}, {111730000, 91865.6933047751}, + {111740000, 91868.2745887764}, {111750000, 91870.7848872396}, + {111760000, 91873.1224495235}, {111770000, 91875.281642919}, + {111780000, 91877.4569090364}, {111790000, 91879.7071464474}, + {111800000, 91881.9832802542}, {111810000, 91884.2185111278}, + {111820000, 91886.4234000487}, {111830000, 91888.7336723698}, + {111840000, 91891.1761793089}, {111850000, 91893.6701590752}, + {111860000, 91896.1586975573}, {111870000, 91898.6497592334}, + {111880000, 91901.164283188}, {111890000, 91903.7059792234}, + {111900000, 91906.3541988627}, {111910000, 91909.1326505115}, + {111920000, 91912.0094107257}, {111930000, 91914.9411391566}, + {111940000, 91917.9252244227}, {111950000, 91920.9370172743}, + {111960000, 91923.968799664}, {111970000, 91927.0506215931}, + {111980000, 91930.2035587683}, {111990000, 91933.423144728}, + {112000000, 91936.6981934863}, {112010000, 91940.0264012109}, + {112020000, 91943.3641774644}, {112030000, 91946.6982624059}, + {112040000, 91950.02001357}, {112050000, 91953.3176257491}, + {112060000, 91956.5888553057}, {112070000, 91959.7464260267}, + {112080000, 91962.764256458}, {112090000, 91965.7565387439}, + {112100000, 91968.803676948}, {112110000, 91971.9198033117}, + {112120000, 91975.1425998853}, {112130000, 91978.4718060044}, + {112140000, 91981.7310915199}, {112150000, 91984.867194861}, + {112160000, 91987.8840525735}, {112170000, 91990.7868112811}, + {112180000, 91993.5762457434}, {112190000, 91996.468593083}, + {112200000, 91999.5404159559}, {112210000, 92002.6381267658}, + {112220000, 92005.6535950073}, {112230000, 92008.5841647094}, + {112240000, 92011.422165773}, {112250000, 92014.1695859408}, + {112260000, 92016.9402476353}, {112270000, 92019.7686074894}, + {112280000, 92022.5942785271}, {112290000, 92025.3349290676}, + {112300000, 92027.9882916681}, {112310000, 92030.6388161832}, + {112320000, 92033.3130947985}, {112330000, 92035.9958652068}, + {112340000, 92038.6763603725}, {112350000, 92041.3615326778}, + {112360000, 92044.0697018676}, {112370000, 92046.8038319523}, + {112380000, 92049.6217628747}, {112390000, 92052.5407951926}, + {112400000, 92055.4976914902}, {112410000, 92058.4061602275}, + {112420000, 92061.2625341274}, {112430000, 92064.0854334345}, + {112440000, 92066.8814520918}, {112450000, 92069.7297139325}, + {112460000, 92072.6858288949}, {112470000, 92075.7244619826}, + {112480000, 92078.779670398}, {112490000, 92081.8431707439}, + {112500000, 92084.8472616697}, {112510000, 92087.7716064636}, + {112520000, 92090.6993932394}, {112530000, 92093.7440402949}, + {112540000, 92096.9076413952}, {112550000, 92100.0848353084}, + {112560000, 92103.2439558685}, {112570000, 92106.4194725051}, + {112580000, 92109.6356504458}, {112590000, 92112.8761655457}, + {112600000, 92116.098292541}, {112610000, 92119.2978073363}, + {112620000, 92122.47958599}, {112630000, 92125.645170644}, + {112640000, 92128.8018927083}, {112650000, 92131.9597394589}, + {112660000, 92135.1192920178}, {112670000, 92138.2916720456}, + {112680000, 92141.4803365992}, {112690000, 92144.7003975852}, + {112700000, 92147.9624580042}, {112710000, 92151.2546517951}, + {112720000, 92154.5459521148}, {112730000, 92157.8326912121}, + {112740000, 92161.0918394898}, {112750000, 92164.3164885433}, + {112760000, 92167.5210516774}, {112770000, 92170.7252262609}, + {112780000, 92173.9301461271}, {112790000, 92177.1553569057}, + {112800000, 92180.4069464298}, {112810000, 92183.6500177037}, + {112820000, 92186.8599622991}, {112830000, 92190.0506920048}, + {112840000, 92193.2586307134}, {112850000, 92196.48764576}, + {112860000, 92199.7467791215}, {112870000, 92203.0386721405}, + {112880000, 92206.3298404842}, {112890000, 92209.5745935248}, + {112900000, 92212.7710931592}, {112910000, 92215.9810000322}, + {112920000, 92219.2253792984}, {112930000, 92222.492401742}, + {112940000, 92225.7736886702}, {112950000, 92229.0641728231}, + {112960000, 92232.3506050941}, {112970000, 92235.6310331244}, + {112980000, 92238.8762478956}, {112990000, 92242.077501734}, + {113000000, 92245.2708090469}, {113010000, 92248.5053391206}, + {113020000, 92251.7822324811}, {113030000, 92255.0280608945}, + {113040000, 92258.219799894}, {113050000, 92261.378888913}, + {113060000, 92264.5205014373}, {113070000, 92267.6523434702}, + {113080000, 92270.7946683945}, {113090000, 92273.9502618684}, + {113100000, 92277.1557907765}, {113110000, 92280.4222422162}, + {113120000, 92283.7230347932}, {113130000, 92287.0219307116}, + {113140000, 92290.3149546926}, {113150000, 92293.577802849}, + {113160000, 92296.8056444935}, {113170000, 92300.0256410223}, + {113180000, 92303.2569669298}, {113190000, 92306.4977392791}, + {113200000, 92309.743078635}, {113210000, 92312.9914350377}, + {113220000, 92316.1927372862}, {113230000, 92319.3319319632}, + {113240000, 92322.438158171}, {113250000, 92325.5511492594}, + {113260000, 92328.6726288139}, {113270000, 92331.8009511744}, + {113280000, 92334.9356006399}, {113290000, 92338.0918917055}, + {113300000, 92341.2806112189}, {113310000, 92344.4851202126}, + {113320000, 92347.6616942274}, {113330000, 92350.8069156788}, + {113340000, 92353.9683415749}, {113350000, 92357.1603681511}, + {113360000, 92360.3470740025}, {113370000, 92363.479392204}, + {113380000, 92366.5553653151}, {113390000, 92369.5880402266}, + {113400000, 92372.5821085106}, {113410000, 92375.5398586904}, + {113420000, 92378.4629599187}, {113430000, 92381.3491869635}, + {113440000, 92384.1923494525}, {113450000, 92386.9922819749}, + {113460000, 92389.7631045115}, {113470000, 92392.5092121587}, + {113480000, 92395.2500721779}, {113490000, 92398.0122608119}, + {113500000, 92400.795035522}, {113510000, 92403.5793717745}, + {113520000, 92406.3614096237}, {113530000, 92409.1071334822}, + {113540000, 92411.7925672802}, {113550000, 92414.4316953771}, + {113560000, 92417.0609946891}, {113570000, 92419.6850396211}, + {113580000, 92422.3414758613}, {113590000, 92425.041640357}, + {113600000, 92427.7743620305}, {113610000, 92430.5244452866}, + {113620000, 92433.3006409664}, {113630000, 92436.2000749535}, + {113640000, 92439.2418592829}, {113650000, 92442.382162827}, + {113660000, 92445.5898807607}, {113670000, 92448.8493752552}, + {113680000, 92452.1198564368}, {113690000, 92455.3954268734}, + {113700000, 92458.5955071388}, {113710000, 92461.6958521733}, + {113720000, 92464.7181174489}, {113730000, 92467.6917573911}, + {113740000, 92470.6194468656}, {113750000, 92473.5103722103}, + {113760000, 92476.3662246183}, {113770000, 92479.1765903443}, + {113780000, 92481.9341789252}, {113790000, 92484.6630280855}, + {113800000, 92487.4264029848}, {113810000, 92490.2298935544}, + {113820000, 92493.0341082028}, {113830000, 92495.8270643227}, + {113840000, 92498.5864227867}, {113850000, 92501.2815865561}, + {113860000, 92503.9123629504}, {113870000, 92506.5547387433}, + {113880000, 92509.2326462333}, {113890000, 92511.9352716928}, + {113900000, 92514.6549405478}, {113910000, 92517.3697491123}, + {113920000, 92520.0219272142}, {113930000, 92522.6070265185}, + {113940000, 92525.1861959214}, {113950000, 92527.7780530713}, + {113960000, 92530.3547503148}, {113970000, 92532.8781625902}, + {113980000, 92535.3466982233}, {113990000, 92537.7515330082}, + {114000000, 92540.0901115098}, {114010000, 92542.3378931505}, + {114020000, 92544.4776519979}, {114030000, 92546.5213325926}, + {114040000, 92548.4996614808}, {114050000, 92550.4177162493}, + {114060000, 92552.355760378}, {114070000, 92554.3381537375}, + {114080000, 92556.3786500524}, {114090000, 92558.4961736155}, + {114100000, 92560.6912165354}, {114110000, 92562.8321892856}, + {114120000, 92564.8733627522}, {114130000, 92567.0359220744}, + {114140000, 92569.4761304642}, {114150000, 92572.1084881191}, + {114160000, 92574.7087094305}, {114170000, 92577.2557751346}, + {114180000, 92579.8513560668}, {114190000, 92582.5262526186}, + {114200000, 92585.2296794497}, {114210000, 92587.8922135074}, + {114220000, 92590.5142776222}, {114230000, 92593.2652475312}, + {114240000, 92596.196267898}, {114250000, 92599.1818287467}, + {114260000, 92602.1330815907}, {114270000, 92605.0717108691}, + {114280000, 92608.0548314503}, {114290000, 92611.0873494486}, + {114300000, 92614.1295205377}, {114310000, 92617.1692146772}, + {114320000, 92620.2265583766}, {114330000, 92623.329118516}, + {114340000, 92626.4781805398}, {114350000, 92629.6838569185}, + {114360000, 92632.9489747308}, {114370000, 92636.2366825239}, + {114380000, 92639.5208836769}, {114390000, 92642.8032824056}, + {114400000, 92646.0883607852}, {114410000, 92649.3770049318}, + {114420000, 92652.6907899894}, {114430000, 92656.0361955545}, + {114440000, 92659.3906570036}, {114450000, 92662.7232952965}, + {114460000, 92666.0334514689}, {114470000, 92669.3491035621}, + {114480000, 92672.6786416309}, {114490000, 92676.0215712116}, + {114500000, 92679.3775225214}, {114510000, 92682.7440626808}, + {114520000, 92686.1148446341}, {114530000, 92689.4889012835}, + {114540000, 92692.8516207387}, {114550000, 92696.1985915457}, + {114560000, 92699.5294906862}, {114570000, 92702.8438462066}, + {114580000, 92706.1417154387}, {114590000, 92709.4464438359}, + {114600000, 92712.766178589}, {114610000, 92716.0722521939}, + {114620000, 92719.3443834822}, {114630000, 92722.5869628864}, + {114640000, 92725.81134503}, {114650000, 92729.0186556003}, + {114660000, 92732.202492584}, {114670000, 92735.3609872047}, + {114680000, 92738.5205144247}, {114690000, 92741.7172519746}, + {114700000, 92744.9487980719}, {114710000, 92748.1752032214}, + {114720000, 92751.388404345}, {114730000, 92754.6089086326}, + {114740000, 92757.8512276914}, {114750000, 92761.1061002191}, + {114760000, 92764.349163511}, {114770000, 92767.577924439}, + {114780000, 92770.7910953366}, {114790000, 92773.988337942}, + {114800000, 92777.1696917367}, {114810000, 92780.3351809767}, + {114820000, 92783.4854214867}, {114830000, 92786.6437293606}, + {114840000, 92789.8170790636}, {114850000, 92792.993750644}, + {114860000, 92796.1654398744}, {114870000, 92799.3271454766}, + {114880000, 92802.4655727627}, {114890000, 92805.5794367068}, + {114900000, 92808.6681234197}, {114910000, 92811.7315328743}, + {114920000, 92814.7661363162}, {114930000, 92817.767048057}, + {114940000, 92820.7340865421}, {114950000, 92823.6661267485}, + {114960000, 92826.5630715421}, {114970000, 92829.4419888911}, + {114980000, 92832.3150062074}, {114990000, 92835.1801103444}, + {115000000, 92838.0319113707}, {115010000, 92840.8697626876}, + {115020000, 92843.6863022698}, {115030000, 92846.4793614455}, + {115040000, 92849.2412693861}, {115050000, 92851.9614645758}, + {115060000, 92854.6429792332}, {115070000, 92857.3142307103}, + {115080000, 92859.9802641704}, {115090000, 92862.6806832061}, + {115100000, 92865.4435183516}, {115110000, 92868.2573292932}, + {115120000, 92871.0922795712}, {115130000, 92873.945577544}, + {115140000, 92876.8368176974}, {115150000, 92879.7718416829}, + {115160000, 92882.7809188572}, {115170000, 92885.9056699693}, + {115180000, 92889.1463920235}, {115190000, 92892.4086947792}, + {115200000, 92895.6626610299}, {115210000, 92898.8983925193}, + {115220000, 92902.1088973038}, {115230000, 92905.3036647169}, + {115240000, 92908.5077498194}, {115250000, 92911.7230323319}, + {115260000, 92914.915291977}, {115270000, 92918.0741771626}, + {115280000, 92921.2101816092}, {115290000, 92924.337642953}, + {115300000, 92927.4572554579}, {115310000, 92930.5170949424}, + {115320000, 92933.4991181187}, {115330000, 92936.4441079981}, + {115340000, 92939.3810337302}, {115350000, 92942.3059370367}, + {115360000, 92945.2082494031}, {115370000, 92948.0866851607}, + {115380000, 92950.9265499669}, {115390000, 92953.7234980384}, + {115400000, 92956.5173913504}, {115410000, 92959.3628513711}, + {115420000, 92962.2615500783}, {115430000, 92965.1650997917}, + {115440000, 92968.0582302576}, {115450000, 92970.9772627164}, + {115460000, 92973.9479445322}, {115470000, 92976.9732156523}, + {115480000, 92980.0613131861}, {115490000, 92983.212114272}, + {115500000, 92986.3901993029}, {115510000, 92989.5846770593}, + {115520000, 92992.782900042}, {115530000, 92995.9675430491}, + {115540000, 92999.1384844431}, {115550000, 93002.3021043255}, + {115560000, 93005.4597383862}, {115570000, 93008.6224986822}, + {115580000, 93011.7982663164}, {115590000, 93014.9872213151}, + {115600000, 93018.1899504013}, {115610000, 93021.4064530008}, + {115620000, 93024.6366698368}, {115630000, 93027.8805353967}, + {115640000, 93031.1263490622}, {115650000, 93034.3580659942}, + {115660000, 93037.575020172}, {115670000, 93040.7685765379}, + {115680000, 93043.9357731141}, {115690000, 93047.0990890262}, + {115700000, 93050.27448771}, {115710000, 93053.4575801493}, + {115720000, 93056.6368082184}, {115730000, 93059.8108407792}, + {115740000, 93062.9719669547}, {115750000, 93066.1178791075}, + {115760000, 93069.2589619996}, {115770000, 93072.409450208}, + {115780000, 93075.5699493655}, {115790000, 93078.7380968941}, + {115800000, 93081.9130438497}, {115810000, 93085.0656194491}, + {115820000, 93088.1751473793}, {115830000, 93091.2508337741}, + {115840000, 93094.3167755772}, {115850000, 93097.3758163649}, + {115860000, 93100.443550163}, {115870000, 93103.5247040058}, + {115880000, 93106.6220566599}, {115890000, 93109.7394500467}, + {115900000, 93112.8769643426}, {115910000, 93116.0407351422}, + {115920000, 93119.2327121846}, {115930000, 93122.4392672954}, + {115940000, 93125.650681241}, {115950000, 93128.866689312}, + {115960000, 93132.0866286357}, {115970000, 93135.3106917763}, + {115980000, 93138.5530676179}, {115990000, 93141.8180212747}, + {116000000, 93145.0832828956}, {116010000, 93148.3182813836}, + {116020000, 93151.5217607413}, {116030000, 93154.7356186427}, + {116040000, 93157.9745363877}, {116050000, 93161.1934616906}, + {116060000, 93164.3604405886}, {116070000, 93167.4939569096}, + {116080000, 93170.6427341634}, {116090000, 93173.8105599914}, + {116100000, 93176.936021709}, {116110000, 93180.0005169941}, + {116120000, 93183.0078221727}, {116130000, 93185.9630130276}, + {116140000, 93188.8663326791}, {116150000, 93191.7053750811}, + {116160000, 93194.4765631413}, {116170000, 93197.2321352058}, + {116180000, 93200.0092432337}, {116190000, 93202.8016757515}, + {116200000, 93205.5930931313}, {116210000, 93208.3819272459}, + {116220000, 93211.1743727475}, {116230000, 93213.9723083266}, + {116240000, 93216.7757568373}, {116250000, 93219.5847600924}, + {116260000, 93222.4052616761}, {116270000, 93225.2894027669}, + {116280000, 93228.2463152221}, {116290000, 93231.2548313882}, + {116300000, 93234.2997894522}, {116310000, 93237.3805823705}, + {116320000, 93240.4958912228}, {116330000, 93243.6450086784}, + {116340000, 93246.8063675281}, {116350000, 93249.97334116}, + {116360000, 93253.1623599591}, {116370000, 93256.3960210282}, + {116380000, 93259.6745721318}, {116390000, 93262.946440407}, + {116400000, 93266.1953425767}, {116410000, 93269.4415893429}, + {116420000, 93272.6996386439}, {116430000, 93275.9722645448}, + {116440000, 93279.2669421873}, {116450000, 93282.5833869551}, + {116460000, 93285.8720836174}, {116470000, 93289.1180115156}, + {116480000, 93292.335249675}, {116490000, 93295.5430712202}, + {116500000, 93298.7424516043}, {116510000, 93301.9358601715}, + {116520000, 93305.1240703027}, {116530000, 93308.3121357727}, + {116540000, 93311.5036533197}, {116550000, 93314.69394751}, + {116560000, 93317.8705989544}, {116570000, 93321.0330526299}, + {116580000, 93324.2162413985}, {116590000, 93327.4307664425}, + {116600000, 93330.6544955007}, {116610000, 93333.85703694}, + {116620000, 93337.0372625085}, {116630000, 93340.2076853822}, + {116640000, 93343.3722593603}, {116650000, 93346.536468506}, + {116660000, 93349.7042160858}, {116670000, 93352.8756168149}, + {116680000, 93356.051005543}, {116690000, 93359.2303993698}, + {116700000, 93362.4137886712}, {116710000, 93365.6011566961}, + {116720000, 93368.7885954023}, {116730000, 93371.9707400287}, + {116740000, 93375.1464338545}, {116750000, 93378.308101575}, + {116760000, 93381.454524069}, {116770000, 93384.5909810254}, + {116780000, 93387.7212439033}, {116790000, 93390.8478496581}, + {116800000, 93393.9775012883}, {116810000, 93397.1107504236}, + {116820000, 93400.2408465632}, {116830000, 93403.3657381609}, + {116840000, 93406.488406544}, {116850000, 93409.6129437506}, + {116860000, 93412.7395287075}, {116870000, 93415.8480366177}, + {116880000, 93418.931647958}, {116890000, 93422.0177243299}, + {116900000, 93425.1257341906}, {116910000, 93428.2561400666}, + {116920000, 93431.4103558178}, {116930000, 93434.5876017014}, + {116940000, 93437.7452013485}, {116950000, 93440.8701839826}, + {116960000, 93443.9762841726}, {116970000, 93447.0823369694}, + {116980000, 93450.1892070948}, {116990000, 93453.2934064289}, + {117000000, 93456.3936819006}, {117010000, 93459.4891172746}, + {117020000, 93462.5790662824}, {117030000, 93465.6659327243}, + {117040000, 93468.7560808475}, {117050000, 93471.8503006332}, + {117060000, 93474.9560572013}, {117070000, 93478.075591457}, + {117080000, 93481.204512249}, {117090000, 93484.3367971903}, + {117100000, 93487.4723476597}, {117110000, 93490.6291075967}, + {117120000, 93493.8126866822}, {117130000, 93496.9992787882}, + {117140000, 93500.1719100626}, {117150000, 93503.3230095944}, + {117160000, 93506.4323041243}, {117170000, 93509.4990751918}, + {117180000, 93512.5864161912}, {117190000, 93515.7135522207}, + {117200000, 93518.8550501346}, {117210000, 93521.9759927738}, + {117220000, 93525.0760531287}, {117230000, 93528.1675232467}, + {117240000, 93531.2529381855}, {117250000, 93534.3436341945}, + {117260000, 93537.4476845599}, {117270000, 93540.5652610434}, + {117280000, 93543.696933003}, {117290000, 93546.8424275189}, + {117300000, 93549.9875380799}, {117310000, 93553.1279211666}, + {117320000, 93556.2669491933}, {117330000, 93559.4092585336}, + {117340000, 93562.5542751114}, {117350000, 93565.6953255646}, + {117360000, 93568.831237934}, {117370000, 93571.9452248796}, + {117380000, 93575.0253509879}, {117390000, 93578.0857427355}, + {117400000, 93581.1637875659}, {117410000, 93584.2627846795}, + {117420000, 93587.3562639898}, {117430000, 93590.4361490841}, + {117440000, 93593.5132219955}, {117450000, 93596.6023086939}, + {117460000, 93599.7067875286}, {117470000, 93602.8503336226}, + {117480000, 93606.0370023803}, {117490000, 93609.2340302558}, + {117500000, 93612.4180191581}, {117510000, 93615.5883360283}, + {117520000, 93618.7431818591}, {117530000, 93621.8827072748}, + {117540000, 93625.0210894246}, {117550000, 93628.162668124}, + {117560000, 93631.3036305322}, {117570000, 93634.4387306823}, + {117580000, 93637.567659604}, {117590000, 93640.6836773072}, + {117600000, 93643.7847226653}, {117610000, 93646.9035151327}, + {117620000, 93650.0633817004}, {117630000, 93653.2505096235}, + {117640000, 93656.4283656663}, {117650000, 93659.5931590147}, + {117660000, 93662.742934855}, {117670000, 93665.8771472155}, + {117680000, 93669.0029521371}, {117690000, 93672.1301771462}, + {117700000, 93675.2595056105}, {117710000, 93678.401746827}, + {117720000, 93681.5601198914}, {117730000, 93684.7223870922}, + {117740000, 93687.8798088306}, {117750000, 93691.0393241625}, + {117760000, 93694.2194180278}, {117770000, 93697.4209989602}, + {117780000, 93700.595209024}, {117790000, 93703.727188909}, + {117800000, 93706.8424213896}, {117810000, 93709.9759578878}, + {117820000, 93713.123284013}, {117830000, 93716.2212287186}, + {117840000, 93719.2570639353}, {117850000, 93722.2844289811}, + {117860000, 93725.341618412}, {117870000, 93728.4105269895}, + {117880000, 93731.4430677095}, {117890000, 93734.4338230794}, + {117900000, 93737.3519005097}, {117910000, 93740.1880957618}, + {117920000, 93742.9796905983}, {117930000, 93745.777927429}, + {117940000, 93748.5847799926}, {117950000, 93751.3762187442}, + {117960000, 93754.1448186673}, {117970000, 93756.9175881484}, + {117980000, 93759.7138211163}, {117990000, 93762.5244490455}, + {118000000, 93765.325429368}, {118010000, 93768.1149461829}, + {118020000, 93770.9272941533}, {118030000, 93773.7728989313}, + {118040000, 93776.6296147311}, {118050000, 93779.4669735524}, + {118060000, 93782.2843360749}, {118070000, 93785.1174624168}, + {118080000, 93787.9772403727}, {118090000, 93790.8573485947}, + {118100000, 93793.7532413648}, {118110000, 93796.6838251757}, + {118120000, 93799.6997665646}, {118130000, 93802.8049306478}, + {118140000, 93805.9448365589}, {118150000, 93809.1026894939}, + {118160000, 93812.2862335595}, {118170000, 93815.5061796317}, + {118180000, 93818.7628487753}, {118190000, 93821.9966640792}, + {118200000, 93825.1860070875}, {118210000, 93828.3523395722}, + {118220000, 93831.5110301402}, {118230000, 93834.6577806508}, + {118240000, 93837.7810388169}, {118250000, 93840.8798297794}, + {118260000, 93843.9607376972}, {118270000, 93847.0258410364}, + {118280000, 93850.0789168507}, {118290000, 93853.1251466296}, + {118300000, 93856.1655076167}, {118310000, 93859.2640455459}, + {118320000, 93862.4408271126}, {118330000, 93865.6379236759}, + {118340000, 93868.8139117381}, {118350000, 93871.9558399006}, + {118360000, 93875.028914218}, {118370000, 93878.0318560626}, + {118380000, 93881.0768518826}, {118390000, 93884.1981977686}, + {118400000, 93887.3668313047}, {118410000, 93890.5427968203}, + {118420000, 93893.7242117478}, {118430000, 93896.9040414203}, + {118440000, 93900.0797971777}, {118450000, 93903.2449551491}, + {118460000, 93906.3948625721}, {118470000, 93909.538990795}, + {118480000, 93912.7025572759}, {118490000, 93915.8879911877}, + {118500000, 93919.0894885548}, {118510000, 93922.3052161633}, + {118520000, 93925.5162503797}, {118530000, 93928.6965064519}, + {118540000, 93931.8455237709}, {118550000, 93934.9980520548}, + {118560000, 93938.1647851134}, {118570000, 93941.323537222}, + {118580000, 93944.4584660112}, {118590000, 93947.5763977427}, + {118600000, 93950.6953787118}, {118610000, 93953.8174308282}, + {118620000, 93956.9506383945}, {118630000, 93960.0974391251}, + {118640000, 93963.2499398601}, {118650000, 93966.3972657949}, + {118660000, 93969.5392796021}, {118670000, 93972.6999976998}, + {118680000, 93975.8868522384}, {118690000, 93979.0764531043}, + {118700000, 93982.2520616009}, {118710000, 93985.4108998449}, + {118720000, 93988.5454169124}, {118730000, 93991.6548010417}, + {118740000, 93994.7316558791}, {118750000, 93997.7738211746}, + {118760000, 94000.7925446596}, {118770000, 94003.8032934047}, + {118780000, 94006.8069260464}, {118790000, 94009.813556469}, + {118800000, 94012.8263840596}, {118810000, 94015.8226231126}, + {118820000, 94018.785994458}, {118830000, 94021.7376346999}, + {118840000, 94024.7338298066}, {118850000, 94027.7793708325}, + {118860000, 94030.8273580264}, {118870000, 94033.863406614}, + {118880000, 94036.8933053715}, {118890000, 94039.925025996}, + {118900000, 94042.9589292901}, {118910000, 94045.9595979801}, + {118920000, 94048.9149198447}, {118930000, 94051.8694172766}, + {118940000, 94054.8549850128}, {118950000, 94057.8581050718}, + {118960000, 94060.8428638426}, {118970000, 94063.8059662072}, + {118980000, 94066.7668450965}, {118990000, 94069.7314650225}, + {119000000, 94072.7067369887}, {119010000, 94075.7022127525}, + {119020000, 94078.718642359}, {119030000, 94081.7931483093}, + {119040000, 94084.937287657}, {119050000, 94088.1090306134}, + {119060000, 94091.2782675836}, {119070000, 94094.4441991524}, + {119080000, 94097.6046650762}, {119090000, 94100.7592023266}, + {119100000, 94103.8934985888}, {119110000, 94107.0032331582}, + {119120000, 94110.1144466109}, {119130000, 94113.263086581}, + {119140000, 94116.4440743428}, {119150000, 94119.5876680962}, + {119160000, 94122.6796226101}, {119170000, 94125.7565370134}, + {119180000, 94128.8446500747}, {119190000, 94131.9399340072}, + {119200000, 94135.0316918649}, {119210000, 94138.1188145863}, + {119220000, 94141.2006886725}, {119230000, 94144.2771440296}, + {119240000, 94147.3407801586}, {119250000, 94150.3813571145}, + {119260000, 94153.3994721395}, {119270000, 94156.4397987359}, + {119280000, 94159.5157700864}, {119290000, 94162.5716239191}, + {119300000, 94165.5674430692}, {119310000, 94168.4975976266}, + {119320000, 94171.3464999966}, {119330000, 94174.1128748255}, + {119340000, 94176.796252577}, {119350000, 94179.3967755405}, + {119360000, 94181.9139561749}, {119370000, 94184.3469605374}, + {119380000, 94186.6961501226}, {119390000, 94189.06581562}, + {119400000, 94191.4927472023}, {119410000, 94193.9657436189}, + {119420000, 94196.4767068258}, {119430000, 94199.0490259037}, + {119440000, 94201.7459055337}, {119450000, 94204.5718812573}, + {119460000, 94207.4444921228}, {119470000, 94210.3382810229}, + {119480000, 94213.2095134885}, {119490000, 94215.997567201}, + {119500000, 94218.686497375}, {119510000, 94221.1351215267}, + {119520000, 94223.3154124946}, {119530000, 94225.2716434862}, + {119540000, 94227.0358425518}, {119550000, 94228.7359281683}, + {119560000, 94230.7129990368}, {119570000, 94233.0015307962}, + {119580000, 94235.6118285861}, {119590000, 94238.5459436293}, + {119600000, 94241.671570409}, {119610000, 94244.8064525817}, + {119620000, 94247.9302895719}, {119630000, 94250.9193904337}, + {119640000, 94253.7489003197}, {119650000, 94256.4392916822}, + {119660000, 94259.0054417411}, {119670000, 94261.4245774896}, + {119680000, 94263.6345695901}, {119690000, 94265.6345938245}, + {119700000, 94267.6853310543}, {119710000, 94269.8666351362}, + {119720000, 94272.1843865301}, {119730000, 94274.646965795}, + {119740000, 94277.2408495217}, {119750000, 94279.857586394}, + {119760000, 94282.4787405977}, {119770000, 94285.1549319879}, + {119780000, 94287.9223901527}, {119790000, 94290.7699055894}, + {119800000, 94293.6680772478}, {119810000, 94296.613583931}, + {119820000, 94299.6046395412}, {119830000, 94302.6405372131}, + {119840000, 94305.6942717257}, {119850000, 94308.7285689781}, + {119860000, 94311.7412283195}, {119870000, 94314.6742301238}, + {119880000, 94317.5093782175}, {119890000, 94320.282344033}, + {119900000, 94323.0187988726}, {119910000, 94325.7077256953}, + {119920000, 94328.3192663503}, {119930000, 94330.8497492667}, + {119940000, 94333.2480449233}, {119950000, 94335.4988762948}, + {119960000, 94337.6521479257}, {119970000, 94339.7766156753}, + {119980000, 94341.8749221724}, {119990000, 94343.8719753078}, + {120000000, 94345.7441830027}, {120010000, 94347.6161977205}, + {120020000, 94349.5774245657}, {120030000, 94351.6275986758}, + {120040000, 94353.7667603629}, {120050000, 94355.9932266171}, + {120060000, 94358.2354859573}, {120070000, 94360.4715299687}, + {120080000, 94362.713426382}, {120090000, 94364.9778585289}, + {120100000, 94367.2654959469}, {120110000, 94369.5755545032}, + {120120000, 94371.9076853467}, {120130000, 94374.2705371414}, + {120140000, 94376.6702780029}, {120150000, 94379.1117063023}, + {120160000, 94381.6080188121}, {120170000, 94384.1601039715}, + {120180000, 94386.7542351496}, {120190000, 94389.3860501339}, + {120200000, 94392.0427921738}, {120210000, 94394.7068705192}, + {120220000, 94397.3781554035}, {120230000, 94400.0968697037}, + {120240000, 94402.8752045134}, {120250000, 94405.6942250388}, + {120260000, 94408.5402774091}, {120270000, 94411.4081545133}, + {120280000, 94414.2841008523}, {120290000, 94417.1672717475}, + {120300000, 94420.0923967745}, {120310000, 94423.0700013267}, + {120320000, 94426.0453228127}, {120330000, 94428.94263469}, + {120340000, 94431.7604545324}, {120350000, 94434.5775340976}, + {120360000, 94437.4177106034}, {120370000, 94440.2767289672}, + {120380000, 94443.1515073897}, {120390000, 94446.0157801021}, + {120400000, 94448.799144723}, {120410000, 94451.4963451774}, + {120420000, 94454.203468244}, {120430000, 94456.9500006319}, + {120440000, 94459.7365245645}, {120450000, 94462.5639228247}, + {120460000, 94465.4318694058}, {120470000, 94468.3322285059}, + {120480000, 94471.2624290013}, {120490000, 94474.2032350143}, + {120500000, 94477.1408182101}, {120510000, 94480.0748356766}, + {120520000, 94483.0043382362}, {120530000, 94485.9293725177}, + {120540000, 94488.8570108694}, {120550000, 94491.7894188146}, + {120560000, 94494.7539097203}, {120570000, 94497.7883130637}, + {120580000, 94500.8940615283}, {120590000, 94504.0574760524}, + {120600000, 94507.2734781206}, {120610000, 94510.4874721327}, + {120620000, 94513.660206493}, {120630000, 94516.8097725805}, + {120640000, 94519.9844624413}, {120650000, 94523.1892479174}, + {120660000, 94526.426687898}, {120670000, 94529.6974566125}, + {120680000, 94533.0233558557}, {120690000, 94536.4346388577}, + {120700000, 94539.9244599425}, {120710000, 94543.4097305868}, + {120720000, 94546.8733771831}, {120730000, 94550.3397506504}, + {120740000, 94553.826355588}, {120750000, 94557.3193828448}, + {120760000, 94560.7818759699}, {120770000, 94564.210713487}, + {120780000, 94567.6395547573}, {120790000, 94571.0787488344}, + {120800000, 94574.5175865978}, {120810000, 94577.9412466304}, + {120820000, 94581.3497575979}, {120830000, 94584.7732456125}, + {120840000, 94588.2207695075}, {120850000, 94591.653011685}, + {120860000, 94595.0417238352}, {120870000, 94598.3981705494}, + {120880000, 94601.7523051421}, {120890000, 94605.1066604142}, + {120900000, 94608.4273384792}, {120910000, 94611.7040329959}, + {120920000, 94614.9401304514}, {120930000, 94618.1402383797}, + {120940000, 94621.3012926734}, {120950000, 94624.385486209}, + {120960000, 94627.3851374622}, {120970000, 94630.3169430814}, + {120980000, 94633.1930018638}, {120990000, 94636.0162992508}, + {121000000, 94638.7943910294}, {121010000, 94641.5309313881}, + {121020000, 94644.3758658106}, {121030000, 94647.3749236821}, + {121040000, 94650.4925303861}, {121050000, 94653.6796840868}, + {121060000, 94656.9301905032}, {121070000, 94660.2125805869}, + {121080000, 94663.5210697195}, {121090000, 94666.8704219218}, + {121100000, 94670.2712092933}, {121110000, 94673.7045431801}, + {121120000, 94677.1200149418}, {121130000, 94680.5118878523}, + {121140000, 94683.8490157609}, {121150000, 94687.122010995}, + {121160000, 94690.3355274401}, {121170000, 94693.495889817}, + {121180000, 94696.6041382219}, {121190000, 94699.7099463132}, + {121200000, 94702.8291091876}, {121210000, 94705.9291678576}, + {121220000, 94708.9867818092}, {121230000, 94712.0062382967}, + {121240000, 94714.9987184303}, {121250000, 94717.9663968887}, + {121260000, 94720.9597730151}, {121270000, 94723.9942968061}, + {121280000, 94727.0479826476}, {121290000, 94730.0904149342}, + {121300000, 94733.1202217595}, {121310000, 94736.1202200273}, + {121320000, 94739.0843568881}, {121330000, 94742.0134633385}, + {121340000, 94744.9081859127}, {121350000, 94747.7663013975}, + {121360000, 94750.5815344356}, {121370000, 94753.3532901401}, + {121380000, 94756.0743212816}, {121390000, 94758.7425726599}, + {121400000, 94761.3841044191}, {121410000, 94764.0349611663}, + {121420000, 94766.6969897315}, {121430000, 94769.3919881245}, + {121440000, 94772.1267926119}, {121450000, 94774.9100339652}, + {121460000, 94777.7478585817}, {121470000, 94780.663950193}, + {121480000, 94783.7225218803}, {121490000, 94786.9275722075}, + {121500000, 94790.1611006904}, {121510000, 94793.3867007434}, + {121520000, 94796.6124432455}, {121530000, 94799.8495077443}, + {121540000, 94803.1020686323}, {121550000, 94806.4093467297}, + {121560000, 94809.779228839}, {121570000, 94813.1623032877}, + {121580000, 94816.5229371991}, {121590000, 94819.8767599548}, + {121600000, 94823.2658002871}, {121610000, 94826.6928332002}, + {121620000, 94830.0746492084}, {121630000, 94833.3858007278}, + {121640000, 94836.6301157885}, {121650000, 94839.8127702386}, + {121660000, 94842.9343001889}, {121670000, 94846.0803384911}, + {121680000, 94849.2814460388}, {121690000, 94852.5090922676}, + {121700000, 94855.7427017469}, {121710000, 94858.9982962928}, + {121720000, 94862.3191043323}, {121730000, 94865.7081509646}, + {121740000, 94869.0964181346}, {121750000, 94872.4626557552}, + {121760000, 94875.7985187523}, {121770000, 94879.0923784373}, + {121780000, 94882.3438882505}, {121790000, 94885.5479828837}, + {121800000, 94888.7030043567}, {121810000, 94891.8548731872}, + {121820000, 94895.036692111}, {121830000, 94898.2374210094}, + {121840000, 94901.4275613304}, {121850000, 94904.6039274517}, + {121860000, 94907.7578396182}, {121870000, 94910.8867023993}, + {121880000, 94913.9907318077}, {121890000, 94917.0701785983}, + {121900000, 94920.1256069226}, {121910000, 94923.2025252023}, + {121920000, 94926.31534488}, {121930000, 94929.4245748002}, + {121940000, 94932.5017556247}, {121950000, 94935.558091043}, + {121960000, 94938.6235377185}, {121970000, 94941.7005937087}, + {121980000, 94944.7552820532}, {121990000, 94947.7772172402}, + {122000000, 94950.8708553269}, {122010000, 94954.1811485453}, + {122020000, 94957.7138752874}, {122030000, 94961.2335229163}, + {122040000, 94964.6557374598}, {122050000, 94968.0689685434}, + {122060000, 94971.5370593828}, {122070000, 94975.0283822892}, + {122080000, 94978.458167596}, {122090000, 94981.8183761324}, + {122100000, 94985.140200497}, {122110000, 94988.4333780414}, + {122120000, 94991.6921256324}, {122130000, 94994.9083583474}, + {122140000, 94998.0799619551}, {122150000, 95001.0863328189}, + {122160000, 95003.8906760661}, {122170000, 95006.6630654446}, + {122180000, 95009.5262808308}, {122190000, 95012.4691352335}, + {122200000, 95015.4622163111}, {122210000, 95018.5012165589}, + {122220000, 95021.5274115248}, {122230000, 95024.5227485581}, + {122240000, 95027.5426589723}, {122250000, 95030.664104525}, + {122260000, 95033.8726410319}, {122270000, 95037.0133548293}, + {122280000, 95040.0585160886}, {122290000, 95043.129171976}, + {122300000, 95046.3126429369}, {122310000, 95049.5920431599}, + {122320000, 95052.9227709845}, {122330000, 95056.2990251621}, + {122340000, 95059.6683157565}, {122350000, 95063.0145034923}, + {122360000, 95066.3436751686}, {122370000, 95069.6642430085}, + {122380000, 95072.9768079527}, {122390000, 95076.2988319814}, + {122400000, 95079.6358448708}, {122410000, 95082.9593833897}, + {122420000, 95086.248925112}, {122430000, 95089.4945896646}, + {122440000, 95092.6694298379}, {122450000, 95095.7716565054}, + {122460000, 95098.8427900642}, {122470000, 95101.8957326371}, + {122480000, 95104.9246117188}, {122490000, 95107.921231601}, + {122500000, 95110.8850441031}, {122510000, 95113.7976098085}, + {122520000, 95116.6534155354}, {122530000, 95119.4597015557}, + {122540000, 95122.2217607633}, {122550000, 95124.9422815018}, + {122560000, 95127.6281415703}, {122570000, 95130.2799754749}, + {122580000, 95132.8841149582}, {122590000, 95135.4365121656}, + {122600000, 95137.9489107803}, {122610000, 95140.4375269838}, + {122620000, 95142.9049322654}, {122630000, 95145.4361163557}, + {122640000, 95148.0567458644}, {122650000, 95150.7044565389}, + {122660000, 95153.33420524}, {122670000, 95155.9637684724}, + {122680000, 95158.6410131129}, {122690000, 95161.3696726475}, + {122700000, 95164.0881521319}, {122710000, 95166.777505296}, + {122720000, 95169.4628948556}, {122730000, 95172.1792577193}, + {122740000, 95174.9346843517}, {122750000, 95177.7834390933}, + {122760000, 95180.7344337811}, {122770000, 95183.7613173895}, + {122780000, 95186.8449462654}, {122790000, 95189.9844862289}, + {122800000, 95193.1781668181}, {122810000, 95196.4253139214}, + {122820000, 95199.7113347116}, {122830000, 95203.0315983747}, + {122840000, 95206.3663032478}, {122850000, 95209.6879782652}, + {122860000, 95212.9953894404}, {122870000, 95216.271488496}, + {122880000, 95219.5104202849}, {122890000, 95222.6583157478}, + {122900000, 95225.6763759663}, {122910000, 95228.5569572536}, + {122920000, 95231.2783067717}, {122930000, 95233.8401751668}, + {122940000, 95236.3202879339}, {122950000, 95238.742896725}, + {122960000, 95241.1119082355}, {122970000, 95243.4326421099}, + {122980000, 95245.7055786617}, {122990000, 95247.817393063}, + {123000000, 95249.7270809579}, {123010000, 95251.4923963074}, + {123020000, 95253.1554189895}, {123030000, 95254.7529709666}, + {123040000, 95256.3841135955}, {123050000, 95258.0606347796}, + {123060000, 95259.8730639342}, {123070000, 95261.8488522684}, + {123080000, 95263.9063358232}, {123090000, 95265.9321668715}, + {123100000, 95267.921368382}, {123110000, 95269.9008527722}, + {123120000, 95271.8792521533}, {123130000, 95273.8626327509}, + {123140000, 95275.8553763518}, {123150000, 95277.8977417192}, + {123160000, 95280.0986882356}, {123170000, 95282.4691338207}, + {123180000, 95285.0213616343}, {123190000, 95287.7585341252}, + {123200000, 95290.6443883985}, {123210000, 95293.6288149023}, + {123220000, 95296.7035088208}, {123230000, 95299.8099106836}, + {123240000, 95302.93578367}, {123250000, 95306.1054666058}, + {123260000, 95309.3365076042}, {123270000, 95312.6220583619}, + {123280000, 95315.9441208314}, {123290000, 95319.3001458896}, + {123300000, 95322.6605344151}, {123310000, 95326.0161431229}, + {123320000, 95329.3661499718}, {123330000, 95332.7094012697}, + {123340000, 95336.0392281226}, {123350000, 95339.2967851619}, + {123360000, 95342.4716498601}, {123370000, 95345.639040615}, + {123380000, 95348.8533838125}, {123390000, 95352.0995203321}, + {123400000, 95355.3368527547}, {123410000, 95358.5628179021}, + {123420000, 95361.8747808055}, {123430000, 95365.3024953165}, + {123440000, 95368.7981089631}, {123450000, 95372.2952432469}, + {123460000, 95375.7860747544}, {123470000, 95379.2295376784}, + {123480000, 95382.6184011124}, {123490000, 95386.0008534848}, + {123500000, 95389.4117650964}, {123510000, 95392.8473033895}, + {123520000, 95396.2973458826}, {123530000, 95399.7605183111}, + {123540000, 95403.2219522428}, {123550000, 95406.6770648215}, + {123560000, 95410.135718819}, {123570000, 95413.6116300834}, + {123580000, 95417.1050882329}, {123590000, 95420.5833337437}, + {123600000, 95424.0359429304}, {123610000, 95427.4840196899}, + {123620000, 95430.9428564349}, {123630000, 95434.4010370486}, + {123640000, 95437.8277421505}, {123650000, 95441.2198559853}, + {123660000, 95444.5758295495}, {123670000, 95447.8953091157}, + {123680000, 95451.2109237103}, {123690000, 95454.5680580697}, + {123700000, 95457.9685820287}, {123710000, 95461.4082312088}, + {123720000, 95464.8855744599}, {123730000, 95468.3483023432}, + {123740000, 95471.7585452004}, {123750000, 95475.10840268}, + {123760000, 95478.3760347606}, {123770000, 95481.5605725281}, + {123780000, 95484.7252365898}, {123790000, 95487.8896217789}, + {123800000, 95491.0477399727}, {123810000, 95494.1912482505}, + {123820000, 95497.32117202}, {123830000, 95500.4519751992}, + {123840000, 95503.5866501368}, {123850000, 95506.7198946226}, + {123860000, 95509.847870028}, {123870000, 95512.9657866626}, + {123880000, 95516.0606305271}, {123890000, 95519.1312483374}, + {123900000, 95522.1841221026}, {123910000, 95525.2213149006}, + {123920000, 95528.2289754197}, {123930000, 95531.1877755346}, + {123940000, 95534.0974289823}, {123950000, 95536.9906111607}, + {123960000, 95539.8776635555}, {123970000, 95542.7649472648}, + {123980000, 95545.6570695324}, {123990000, 95548.5541524385}, + {124000000, 95551.4565678691}, {124010000, 95554.3639747593}, + {124020000, 95557.2550621211}, {124030000, 95560.1233039159}, + {124040000, 95562.9720746307}, {124050000, 95565.806030075}, + {124060000, 95568.6255986928}, {124070000, 95571.4388704571}, + {124080000, 95574.2483613335}, {124090000, 95577.0538989549}, + {124100000, 95579.8553636623}, {124110000, 95582.6480613293}, + {124120000, 95585.4192318378}, {124130000, 95588.1678604407}, + {124140000, 95590.907578232}, {124150000, 95593.6426259942}, + {124160000, 95596.376477249}, {124170000, 95599.113961868}, + {124180000, 95601.8552914263}, {124190000, 95604.5807993036}, + {124200000, 95607.2832538105}, {124210000, 95609.9734590484}, + {124220000, 95612.6592574114}, {124230000, 95615.3408902238}, + {124240000, 95618.0189732727}, {124250000, 95620.6933494052}, + {124260000, 95623.3498462765}, {124270000, 95625.9841480723}, + {124280000, 95628.6033447492}, {124290000, 95631.2172696235}, + {124300000, 95633.8263661685}, {124310000, 95636.4248124728}, + {124320000, 95639.010780222}, {124330000, 95641.5949842655}, + {124340000, 95644.1851976695}, {124350000, 95646.7745471279}, + {124360000, 95649.3444512887}, {124370000, 95651.8931473194}, + {124380000, 95654.4268175323}, {124390000, 95656.947428785}, + {124400000, 95659.4552114522}, {124410000, 95661.9504607503}, + {124420000, 95664.4332502242}, {124430000, 95666.9036528328}, + {124440000, 95669.3617342569}, {124450000, 95671.8020998371}, + {124460000, 95674.2208611866}, {124470000, 95676.6250756543}, + {124480000, 95679.0336900515}, {124490000, 95681.4484522939}, + {124500000, 95683.856181349}, {124510000, 95686.2528271981}, + {124520000, 95688.6345606661}, {124530000, 95690.9960203959}, + {124540000, 95693.3371409577}, {124550000, 95695.664154798}, + {124560000, 95697.9790483327}, {124570000, 95700.287625532}, + {124580000, 95702.5941041248}, {124590000, 95704.8986126892}, + {124600000, 95707.2014822065}, {124610000, 95709.5025199276}, + {124620000, 95711.7875562094}, {124630000, 95714.0522662925}, + {124640000, 95716.3037212358}, {124650000, 95718.5517402155}, + {124660000, 95720.7967402787}, {124670000, 95723.0328833513}, + {124680000, 95725.2583537215}, {124690000, 95727.478411277}, + {124700000, 95729.6968779419}, {124710000, 95731.9067975226}, + {124720000, 95734.089298926}, {124730000, 95736.2429658454}, + {124740000, 95738.3953137888}, {124750000, 95740.5548714505}, + {124760000, 95742.7181735904}, {124770000, 95744.8803985715}, + {124780000, 95747.0411993224}, {124790000, 95749.1860955324}, + {124800000, 95751.310510814}, {124810000, 95753.425402931}, + {124820000, 95755.5387413498}, {124830000, 95757.6554624603}, + {124840000, 95759.7889507865}, {124850000, 95761.9399652672}, + {124860000, 95764.0736421737}, {124870000, 95766.1792567432}, + {124880000, 95768.2671614919}, {124890000, 95770.3517481839}, + {124900000, 95772.4337174006}, {124910000, 95774.5076965283}, + {124920000, 95776.5718185277}, {124930000, 95778.6258605762}, + {124940000, 95780.6696744645}, {124950000, 95782.708020911}, + {124960000, 95784.7537332758}, {124970000, 95786.8080191265}, + {124980000, 95788.864413853}, {124990000, 95790.9209105174}, + {125000000, 95792.9735040948}, {125010000, 95795.016605431}, + {125020000, 95797.0499910725}, {125030000, 95799.0733776967}, + {125040000, 95801.0867082403}, {125050000, 95803.0791071958}, + {125060000, 95805.0427058724}, {125070000, 95806.9844739909}, + {125080000, 95808.9231030585}, {125090000, 95810.8604717881}, + {125100000, 95812.7904974988}, {125110000, 95814.7113196013}, + {125120000, 95816.6191209525}, {125130000, 95818.5085560129}, + {125140000, 95820.3812479788}, {125150000, 95822.2588632383}, + {125160000, 95824.1461822011}, {125170000, 95826.0381423707}, + {125180000, 95827.931057018}, {125190000, 95829.8224593823}, + {125200000, 95831.7056547059}, {125210000, 95833.5798541222}, + {125220000, 95835.4375919462}, {125230000, 95837.2766154059}, + {125240000, 95839.1077489839}, {125250000, 95840.9460617899}, + {125260000, 95842.7921515674}, {125270000, 95844.6416356772}, + {125280000, 95846.4931654165}, {125290000, 95848.3405188126}, + {125300000, 95850.1791780285}, {125310000, 95852.0043595791}, + {125320000, 95853.8029905617}, {125330000, 95855.5743816454}, + {125340000, 95857.3534680794}, {125350000, 95859.1510380423}, + {125360000, 95860.9529591954}, {125370000, 95862.7395284535}, + {125380000, 95864.5098791312}, {125390000, 95866.2767593574}, + {125400000, 95868.0449212724}, {125410000, 95869.8033295511}, + {125420000, 95871.5439744857}, {125430000, 95873.2784794798}, + {125440000, 95875.0383134918}, {125450000, 95876.8261197925}, + {125460000, 95878.6079468761}, {125470000, 95880.3733051971}, + {125480000, 95882.1251941469}, {125490000, 95883.8677702887}, + {125500000, 95885.6013021485}, {125510000, 95887.3261132885}, + {125520000, 95889.04230523}, {125530000, 95890.7444707739}, + {125540000, 95892.4286976656}, {125550000, 95894.1043849059}, + {125560000, 95895.7969184148}, {125570000, 95897.5084480396}, + {125580000, 95899.2118101138}, {125590000, 95900.8986238661}, + {125600000, 95902.5795075926}, {125610000, 95904.2692598229}, + {125620000, 95905.965938526}, {125630000, 95907.6415471189}, + {125640000, 95909.2903448374}, {125650000, 95910.9226122872}, + {125660000, 95912.5458457951}, {125670000, 95914.1626577049}, + {125680000, 95915.780068967}, {125690000, 95917.3985892187}, + {125700000, 95919.0043666653}, {125710000, 95920.5931571025}, + {125720000, 95922.1760794094}, {125730000, 95923.768630454}, + {125740000, 95925.3698957}, {125750000, 95926.9664324365}, + {125760000, 95928.5559391511}, {125770000, 95930.1379403117}, + {125780000, 95931.7120998248}, {125790000, 95933.2807910997}, + {125800000, 95934.8504186584}, {125810000, 95936.4216575175}, + {125820000, 95937.99486649}, {125830000, 95939.5701500533}, + {125840000, 95941.1401564266}, {125850000, 95942.6946118008}, + {125860000, 95944.233209438}, {125870000, 95945.7696286789}, + {125880000, 95947.3082573959}, {125890000, 95948.8436455784}, + {125900000, 95950.3718304681}, {125910000, 95951.8927387804}, + {125920000, 95953.4061091503}, {125930000, 95954.9117195788}, + {125940000, 95956.3953717067}, {125950000, 95957.8527423738}, + {125960000, 95959.3052816516}, {125970000, 95960.7829244649}, + {125980000, 95962.2866898765}, {125990000, 95963.7769883289}, + {126000000, 95965.2411505694}, {126010000, 95966.7005160321}, + {126020000, 95968.1706242466}, {126030000, 95969.6447949614}, + {126040000, 95971.1049467978}, {126050000, 95972.5494564924}, + {126060000, 95973.9916728371}, {126070000, 95975.4357390964}, + {126080000, 95976.8712219716}, {126090000, 95978.2835391612}, + {126100000, 95979.6721037702}, {126110000, 95981.0639239845}, + {126120000, 95982.4687775395}, {126130000, 95983.8701147323}, + {126140000, 95985.2558936386}, {126150000, 95986.6305689862}, + {126160000, 95988.0061685413}, {126170000, 95989.3836221496}, + {126180000, 95990.7422369635}, {126190000, 95992.075667149}, + {126200000, 95993.3981877768}, {126210000, 95994.7297224295}, + {126220000, 95996.0711167625}, {126230000, 95997.4183228709}, + {126240000, 95998.7700689588}, {126250000, 96000.1201332808}, + {126260000, 96001.4639836622}, {126270000, 96002.7991815812}, + {126280000, 96004.11903152}, {126290000, 96005.4231177244}, + {126300000, 96006.7253525122}, {126310000, 96008.0300554487}, + {126320000, 96009.3337558186}, {126330000, 96010.6316064335}, + {126340000, 96011.9235199873}, {126350000, 96013.2169629526}, + {126360000, 96014.5142466366}, {126370000, 96015.809683114}, + {126380000, 96017.0991294802}, {126390000, 96018.3848587846}, + {126400000, 96019.6730106139}, {126410000, 96020.963998819}, + {126420000, 96022.2439029784}, {126430000, 96023.5084454282}, + {126440000, 96024.7682240878}, {126450000, 96026.0380370991}, + {126460000, 96027.318317114}, {126470000, 96028.5969334808}, + {126480000, 96029.870180087}, {126490000, 96031.1429736209}, + {126500000, 96032.418897978}, {126510000, 96033.6980474477}, + {126520000, 96034.9807065572}, {126530000, 96036.2668895865}, + {126540000, 96037.5565788035}, {126550000, 96038.849756672}, + {126560000, 96040.1356418761}, {126570000, 96041.3991557187}, + {126580000, 96042.6396822527}, {126590000, 96043.8842389683}, + {126600000, 96045.1425695017}, {126610000, 96046.4090449944}, + {126620000, 96047.6795472473}, {126630000, 96048.9516065173}, + {126640000, 96050.2185305452}, {126650000, 96051.4795208272}, + {126660000, 96052.7271461195}, {126670000, 96053.959148417}, + {126680000, 96055.1829357085}, {126690000, 96056.4088421066}, + {126700000, 96057.6367654092}, {126710000, 96058.8603607896}, + {126720000, 96060.0783211761}, {126730000, 96061.2958653876}, + {126740000, 96062.5168021397}, {126750000, 96063.7365271164}, + {126760000, 96064.9425137077}, {126770000, 96066.1338333912}, + {126780000, 96067.3312055688}, {126790000, 96068.5410330547}, + {126800000, 96069.756145089}, {126810000, 96070.9665331149}, + {126820000, 96072.1715824277}, {126830000, 96073.3629758623}, + {126840000, 96074.538215613}, {126850000, 96075.7084431128}, + {126860000, 96076.8817949099}, {126870000, 96078.0584856438}, + {126880000, 96079.2391283673}, {126890000, 96080.4235500926}, + {126900000, 96081.5975447591}, {126910000, 96082.7567372423}, + {126920000, 96083.9083479222}, {126930000, 96085.0624587971}, + {126940000, 96086.2189765766}, {126950000, 96087.3715403979}, + {126960000, 96088.5188077912}, {126970000, 96089.6714427384}, + {126980000, 96090.8372291815}, {126990000, 96092.0069427813}, + {127000000, 96093.1555424787}, {127010000, 96094.2810248248}, + {127020000, 96095.4176518802}, {127030000, 96096.5760155803}, + {127040000, 96097.737941656}, {127050000, 96098.87802153}, + {127060000, 96099.9957330996}, {127070000, 96101.0964579873}, + {127080000, 96102.1812466933}, {127090000, 96103.261346922}, + {127100000, 96104.3449723375}, {127110000, 96105.4300038316}, + {127120000, 96106.5106862682}, {127130000, 96107.5866511029}, + {127140000, 96108.6718029162}, {127150000, 96109.7704242271}, + {127160000, 96110.871661758}, {127170000, 96111.9603430487}, + {127180000, 96113.0358393544}, {127190000, 96114.1037277721}, + {127200000, 96115.1658264582}, {127210000, 96116.2333004157}, + {127220000, 96117.3142996206}, {127230000, 96118.4043069557}, + {127240000, 96119.4911067231}, {127250000, 96120.5734174346}, + {127260000, 96121.6505885558}, {127270000, 96122.7224358919}, + {127280000, 96123.7889663337}, {127290000, 96124.8501787657}, + {127300000, 96125.9060983785}, {127310000, 96126.9567515703}, + {127320000, 96128.0021646073}, {127330000, 96129.0478027576}, + {127340000, 96130.0976586223}, {127350000, 96131.1471403859}, + {127360000, 96132.1837478552}, {127370000, 96133.2064328861}, + {127380000, 96134.2287908482}, {127390000, 96135.255044149}, + {127400000, 96136.2817013888}, {127410000, 96137.3038765893}, + {127420000, 96138.3214639124}, {127430000, 96139.3497825703}, + {127440000, 96140.3937234932}, {127450000, 96141.4363566757}, + {127460000, 96142.4653148666}, {127470000, 96143.487354978}, + {127480000, 96144.5208065591}, {127490000, 96145.5672324127}, + {127500000, 96146.6062543561}, {127510000, 96147.6315704828}, + {127520000, 96148.6502334308}, {127530000, 96149.6721010516}, + {127540000, 96150.6956862918}, {127550000, 96151.6997089594}, + {127560000, 96152.6797715066}, {127570000, 96153.6626959786}, + {127580000, 96154.6680746462}, {127590000, 96155.6870009656}, + {127600000, 96156.6953523869}, {127610000, 96157.6907271535}, + {127620000, 96158.6789379516}, {127630000, 96159.6618141683}, + {127640000, 96160.6395404689}, {127650000, 96161.6123648775}, + {127660000, 96162.58032259}, {127670000, 96163.551128888}, + {127680000, 96164.5275751362}, {127690000, 96165.5038606085}, + {127700000, 96166.475747534}, {127710000, 96167.4431449184}, + {127720000, 96168.40576626}, {127730000, 96169.3638229475}, + {127740000, 96170.3315486939}, {127750000, 96171.3133298105}, + {127760000, 96172.2983465458}, {127770000, 96173.2714614106}, + {127780000, 96174.2320028234}, {127790000, 96175.185339166}, + {127800000, 96176.1334507139}, {127810000, 96177.087510873}, + {127820000, 96178.0556749989}, {127830000, 96179.0287394469}, + {127840000, 96179.9816587333}, {127850000, 96180.9121897857}, + {127860000, 96181.8404018672}, {127870000, 96182.7725405635}, + {127880000, 96183.7052879591}, {127890000, 96184.6339959178}, + {127900000, 96185.5585110323}, {127910000, 96186.4863616448}, + {127920000, 96187.4199596214}, {127930000, 96188.3426893217}, + {127940000, 96189.242405871}, {127950000, 96190.1259124751}, + {127960000, 96191.0116131963}, {127970000, 96191.9014514662}, + {127980000, 96192.7963971717}, {127990000, 96193.6967342424}, + {128000000, 96194.6020989614}, {128010000, 96195.5119918932}, + {128020000, 96196.4263674581}, {128030000, 96197.3312988561}, + {128040000, 96198.2217610442}, {128050000, 96199.1087457184}, + {128060000, 96200.0003011161}, {128070000, 96200.8895991486}, + {128080000, 96201.7580077036}, {128090000, 96202.6040760678}, + {128100000, 96203.4553206584}, {128110000, 96204.3202759708}, + {128120000, 96205.195474485}, {128130000, 96206.0760780456}, + {128140000, 96206.9616256796}, {128150000, 96207.8375691815}, + {128160000, 96208.6993937248}, {128170000, 96209.5470900165}, + {128180000, 96210.3806698249}, {128190000, 96211.2048776857}, + {128200000, 96212.0325653069}, {128210000, 96212.8649729509}, + {128220000, 96213.6956812524}, {128230000, 96214.5227008667}, + {128240000, 96215.3533852242}, {128250000, 96216.1980461073}, + {128260000, 96217.0555859699}, {128270000, 96217.9123101091}, + {128280000, 96218.7657155742}, {128290000, 96219.6207392169}, + {128300000, 96220.4809961058}, {128310000, 96221.3442260285}, + {128320000, 96222.2042864538}, {128330000, 96223.060538871}, + {128340000, 96223.9126479036}, {128350000, 96224.7605234418}, + {128360000, 96225.6076702031}, {128370000, 96226.4590021208}, + {128380000, 96227.3147493168}, {128390000, 96228.1765716897}, + {128400000, 96229.0449818194}, {128410000, 96229.9139671186}, + {128420000, 96230.7791214517}, {128430000, 96231.6380001855}, + {128440000, 96232.4838770922}, {128450000, 96233.3163129818}, + {128460000, 96234.1492424149}, {128470000, 96234.9869946339}, + {128480000, 96235.8225727208}, {128490000, 96236.6461589449}, + {128500000, 96237.4574236496}, {128510000, 96238.2623073721}, + {128520000, 96239.0626806436}, {128530000, 96239.8642841878}, + {128540000, 96240.6713225742}, {128550000, 96241.4792039162}, + {128560000, 96242.2754037669}, {128570000, 96243.0588585916}, + {128580000, 96243.8431687276}, {128590000, 96244.6325614708}, + {128600000, 96245.4235509026}, {128610000, 96246.2112512273}, + {128620000, 96246.9955401219}, {128630000, 96247.783877491}, + {128640000, 96248.5785883898}, {128650000, 96249.3794182341}, + {128660000, 96250.1861724464}, {128670000, 96250.994148499}, + {128680000, 96251.7905080617}, {128690000, 96252.574045595}, + {128700000, 96253.3512211249}, {128710000, 96254.1240657801}, + {128720000, 96254.8927781594}, {128730000, 96255.6576283606}, + {128740000, 96256.4195298371}, {128750000, 96257.1858689432}, + {128760000, 96257.9579059869}, {128770000, 96258.7304008407}, + {128780000, 96259.4995134988}, {128790000, 96260.2674888376}, + {128800000, 96261.0404507499}, {128810000, 96261.8189219672}, + {128820000, 96262.5961130236}, {128830000, 96263.3699149379}, + {128840000, 96264.1332230807}, {128850000, 96264.8760429051}, + {128860000, 96265.5979875016}, {128870000, 96266.3264926692}, + {128880000, 96267.0713084842}, {128890000, 96267.8322374306}, + {128900000, 96268.609113498}, {128910000, 96269.3948754282}, + {128920000, 96270.1703067457}, {128930000, 96270.9335182471}, + {128940000, 96271.6906125784}, {128950000, 96272.4435088699}, + {128960000, 96273.1923922544}, {128970000, 96273.9375143891}, + {128980000, 96274.67890531}, {128990000, 96275.4242739509}, + {129000000, 96276.1764230125}, {129010000, 96276.9295530305}, + {129020000, 96277.6793978196}, {129030000, 96278.4258611061}, + {129040000, 96279.1686503875}, {129050000, 96279.9078571113}, + {129060000, 96280.6506034354}, {129070000, 96281.399094155}, + {129080000, 96282.1426704726}, {129090000, 96282.8663601468}, + {129100000, 96283.5696715442}, {129110000, 96284.27244752}, + {129120000, 96284.9810719831}, {129130000, 96285.684949918}, + {129140000, 96286.3763055407}, {129150000, 96287.0619980403}, + {129160000, 96287.7607198328}, {129170000, 96288.4742933642}, + {129180000, 96289.1965673333}, {129190000, 96289.9255971956}, + {129200000, 96290.6499660573}, {129210000, 96291.3536380266}, + {129220000, 96292.0371290303}, {129230000, 96292.713524179}, + {129240000, 96293.3855939465}, {129250000, 96294.0538798155}, + {129260000, 96294.7187839727}, {129270000, 96295.3873432164}, + {129280000, 96296.0788393175}, {129290000, 96296.7946907815}, + {129300000, 96297.5003046731}, {129310000, 96298.1849482764}, + {129320000, 96298.8591714917}, {129330000, 96299.5377751367}, + {129340000, 96300.2215882657}, {129350000, 96300.9117588887}, + {129360000, 96301.6084715769}, {129370000, 96302.3062298542}, + {129380000, 96303.000995223}, {129390000, 96303.6926699655}, + {129400000, 96304.3809601673}, {129410000, 96305.0659554614}, + {129420000, 96305.7547514229}, {129430000, 96306.4495436778}, + {129440000, 96307.1429329379}, {129450000, 96307.8245205861}, + {129460000, 96308.4954152198}, {129470000, 96309.1695155771}, + {129480000, 96309.849346037}, {129490000, 96310.5244818641}, + {129500000, 96311.1872722762}, {129510000, 96311.844560874}, + {129520000, 96312.5150210232}, {129530000, 96313.2002654625}, + {129540000, 96313.8799230069}, {129550000, 96314.5476670721}, + {129560000, 96315.2103336678}, {129570000, 96315.877516708}, + {129580000, 96316.5495714489}, {129590000, 96317.212823088}, + {129600000, 96317.8628934437}, {129610000, 96318.5161135068}, + {129620000, 96319.1844889406}, {129630000, 96319.8612861179}, + {129640000, 96320.5281579924}, {129650000, 96321.1833023015}, + {129660000, 96321.8328543841}, {129670000, 96322.4787445881}, + {129680000, 96323.1246555874}, {129690000, 96323.7757659646}, + {129700000, 96324.4323294074}, {129710000, 96325.0959105671}, + {129720000, 96325.7669688182}, {129730000, 96326.4449777973}, + {129740000, 96327.129541373}, {129750000, 96327.8182906575}, + {129760000, 96328.5047741949}, {129770000, 96329.18821117}, + {129780000, 96329.8611713478}, {129790000, 96330.5213760677}, + {129800000, 96331.1761901526}, {129810000, 96331.8359588336}, + {129820000, 96332.4998854515}, {129830000, 96333.1541511324}, + {129840000, 96333.7959069205}, {129850000, 96334.4411350238}, + {129860000, 96335.1015697546}, {129870000, 96335.770476422}, + {129880000, 96336.4294837296}, {129890000, 96337.0769947377}, + {129900000, 96337.7333526691}, {129910000, 96338.4048642287}, + {129920000, 96339.0808702224}, {129930000, 96339.746404102}, + {129940000, 96340.4008451962}, {129950000, 96341.0497912663}, + {129960000, 96341.6950386905}, {129970000, 96342.3477102206}, + {129980000, 96343.0159758338}, {129990000, 96343.6906660525}, + {130000000, 96344.3467231542}, {130010000, 96344.9818741381}, + {130020000, 96345.6161407912}, {130030000, 96346.2557676992}, + {130040000, 96346.8939686741}, {130050000, 96347.5211981061}, + {130060000, 96348.1370775821}, {130070000, 96348.747492294}, + {130080000, 96349.3543631587}, {130090000, 96349.9634097281}, + {130100000, 96350.5788353122}, {130110000, 96351.2007284769}, + {130120000, 96351.8293883252}, {130130000, 96352.4647130627}, + {130140000, 96353.0995779817}, {130150000, 96353.7317636133}, + {130160000, 96354.3610989183}, {130170000, 96354.9873375087}, + {130180000, 96355.6104820893}, {130190000, 96356.2228876977}, + {130200000, 96356.8217126472}, {130210000, 96357.4182307051}, + {130220000, 96358.0207355683}, {130230000, 96358.62709006}, + {130240000, 96359.2314744102}, {130250000, 96359.8334853728}, + {130260000, 96360.447048689}, {130270000, 96361.0764659791}, + {130280000, 96361.714386933}, {130290000, 96362.3504931437}, + {130300000, 96362.984287653}, {130310000, 96363.6151724002}, + {130320000, 96364.2429639902}, {130330000, 96364.8622259542}, + {130340000, 96365.4689664796}, {130350000, 96366.0701255589}, + {130360000, 96366.6846845805}, {130370000, 96367.3145021308}, + {130380000, 96367.9534256705}, {130390000, 96368.5995046059}, + {130400000, 96369.241829704}, {130410000, 96369.8650393576}, + {130420000, 96370.4684754345}, {130430000, 96371.0636682152}, + {130440000, 96371.6548801936}, {130450000, 96372.2535273422}, + {130460000, 96372.8680056028}, {130470000, 96373.4938207572}, + {130480000, 96374.1187484182}, {130490000, 96374.7415934811}, + {130500000, 96375.3688097535}, {130510000, 96376.0023956738}, + {130520000, 96376.6386703192}, {130530000, 96377.2724586519}, + {130540000, 96377.9037258992}, {130550000, 96378.547662832}, + {130560000, 96379.2089817722}, {130570000, 96379.8654781349}, + {130580000, 96380.5008089319}, {130590000, 96381.1216082714}, + {130600000, 96381.7459403916}, {130610000, 96382.3755083002}, + {130620000, 96382.9970694611}, {130630000, 96383.6065199929}, + {130640000, 96384.2073797808}, {130650000, 96384.8045850148}, + {130660000, 96385.3984653832}, {130670000, 96385.9971100522}, + {130680000, 96386.6030850567}, {130690000, 96387.2052744459}, + {130700000, 96387.7954984515}, {130710000, 96388.378247749}, + {130720000, 96388.9657708349}, {130730000, 96389.5593500636}, + {130740000, 96390.1596163039}, {130750000, 96390.7667436294}, + {130760000, 96391.3769126625}, {130770000, 96391.9847495562}, + {130780000, 96392.5900001919}, {130790000, 96393.1923672648}, + {130800000, 96393.7917655422}, {130810000, 96394.3881894153}, + {130820000, 96394.981638612}, {130830000, 96395.5744659271}, + {130840000, 96396.1731175519}, {130850000, 96396.7781512802}, + {130860000, 96397.38276181}, {130870000, 96397.9848275294}, + {130880000, 96398.5876319379}, {130890000, 96399.1957978174}, + {130900000, 96399.8095250747}, {130910000, 96400.4151350683}, + {130920000, 96401.0077746765}, {130930000, 96401.5983905895}, + {130940000, 96402.1950553715}, {130950000, 96402.7909679655}, + {130960000, 96403.3674502664}, {130970000, 96403.9229024535}, + {130980000, 96404.4777484775}, {130990000, 96405.0383668702}, + {131000000, 96405.6049331573}, {131010000, 96406.1777069248}, + {131020000, 96406.7565890183}, {131030000, 96407.3273686201}, + {131040000, 96407.8854790564}, {131050000, 96408.4417922755}, + {131060000, 96409.004325449}, {131070000, 96409.5686126415}, + {131080000, 96410.1224085396}, {131090000, 96410.6645551196}, + {131100000, 96411.2015280453}, {131110000, 96411.7353682627}, + {131120000, 96412.2699512115}, {131130000, 96412.8107375572}, + {131140000, 96413.3566955881}, {131150000, 96413.8937090867}, + {131160000, 96414.418818568}, {131170000, 96414.9533842092}, + {131180000, 96415.5131599861}, {131190000, 96416.0914919092}, + {131200000, 96416.6702535655}, {131210000, 96417.2474098268}, + {131220000, 96417.8148505204}, {131230000, 96418.3700768635}, + {131240000, 96418.923780048}, {131250000, 96419.4910170276}, + {131260000, 96420.0720811484}, {131270000, 96420.6471034068}, + {131280000, 96421.2100295851}, {131290000, 96421.7768150013}, + {131300000, 96422.3592169998}, {131310000, 96422.9504990098}, + {131320000, 96423.5322444765}, {131330000, 96424.1027364396}, + {131340000, 96424.675259238}, {131350000, 96425.2539533563}, + {131360000, 96425.8318783215}, {131370000, 96426.3992558648}, + {131380000, 96426.9556583707}, {131390000, 96427.5219227469}, + {131400000, 96428.1059137453}, {131410000, 96428.6962755905}, + {131420000, 96429.2846182708}, {131430000, 96429.8707359354}, + {131440000, 96430.4540425006}, {131450000, 96431.0344879336}, + {131460000, 96431.6120498888}, {131470000, 96432.1867312417}, + {131480000, 96432.7622439772}, {131490000, 96433.3438232664}, + {131500000, 96433.9317660287}, {131510000, 96434.5268009075}, + {131520000, 96435.1290533859}, {131530000, 96435.7275041275}, + {131540000, 96436.3140245492}, {131550000, 96436.8954190703}, + {131560000, 96437.4903456366}, {131570000, 96438.1004304212}, + {131580000, 96438.7053390129}, {131590000, 96439.2987406251}, + {131600000, 96439.8876215011}, {131610000, 96440.4818219837}, + {131620000, 96441.0805330639}, {131630000, 96441.6699507438}, + {131640000, 96442.2472152903}, {131650000, 96442.8174252519}, + {131660000, 96443.3843530011}, {131670000, 96443.9527700072}, + {131680000, 96444.5358044863}, {131690000, 96445.1343918799}, + {131700000, 96445.7207523315}, {131710000, 96446.2862481856}, + {131720000, 96446.8453756807}, {131730000, 96447.4185594879}, + {131740000, 96448.0060522886}, {131750000, 96448.6020207823}, + {131760000, 96449.2054083247}, {131770000, 96449.7942657509}, + {131780000, 96450.3524108818}, {131790000, 96450.8934681287}, + {131800000, 96451.4547804888}, {131810000, 96452.0398466184}, + {131820000, 96452.6221917144}, {131830000, 96453.1935471652}, + {131840000, 96453.7640234175}, {131850000, 96454.3478855792}, + {131860000, 96454.9456149238}, {131870000, 96455.5296303093}, + {131880000, 96456.09105523}, {131890000, 96456.6515880309}, + {131900000, 96457.2272652753}, {131910000, 96457.8114933066}, + {131920000, 96458.3862021192}, {131930000, 96458.9497035301}, + {131940000, 96459.515243885}, {131950000, 96460.086957966}, + {131960000, 96460.6613678497}, {131970000, 96461.2335714298}, + {131980000, 96461.8033835861}, {131990000, 96462.3783095876}, + {132000000, 96462.9607566923}, {132010000, 96463.5449963648}, + {132020000, 96464.1267928271}, {132030000, 96464.7060503673}, + {132040000, 96465.2824832337}, {132050000, 96465.8558742243}, + {132060000, 96466.4120099039}, {132070000, 96466.94650849}, + {132080000, 96467.4701511269}, {132090000, 96467.9981285411}, + {132100000, 96468.5311652963}, {132110000, 96469.0716414086}, + {132120000, 96469.6204106712}, {132130000, 96470.1605842109}, + {132140000, 96470.6796919145}, {132150000, 96471.1890738906}, + {132160000, 96471.7199632098}, {132170000, 96472.2752225024}, + {132180000, 96472.8280571303}, {132190000, 96473.370078695}, + {132200000, 96473.907921509}, {132210000, 96474.4509385937}, + {132220000, 96474.9995899089}, {132230000, 96475.5557208744}, + {132240000, 96476.119883211}, {132250000, 96476.6861254309}, + {132260000, 96477.2500466221}, {132270000, 96477.8115384852}, + {132280000, 96478.3702815929}, {132290000, 96478.9263527178}, + {132300000, 96479.486867471}, {132310000, 96480.0540355034}, + {132320000, 96480.624200754}, {132330000, 96481.1922103736}, + {132340000, 96481.7577069059}, {132350000, 96482.3126432226}, + {132360000, 96482.8545437442}, {132370000, 96483.394511483}, + {132380000, 96483.9407642825}, {132390000, 96484.4934908335}, + {132400000, 96485.0532681396}, {132410000, 96485.6201265661}, + {132420000, 96486.1940779085}, {132430000, 96486.7751015952}, + {132440000, 96487.3523425912}, {132450000, 96487.9104619599}, + {132460000, 96488.4493949187}, {132470000, 96489.0045061052}, + {132480000, 96489.586651678}, {132490000, 96490.1685693606}, + {132500000, 96490.7300874647}, {132510000, 96491.2800237616}, + {132520000, 96491.8426286727}, {132530000, 96492.4202450423}, + {132540000, 96492.9999372239}, {132550000, 96493.5776474758}, + {132560000, 96494.1495942967}, {132570000, 96494.7104248564}, + {132580000, 96495.2599287528}, {132590000, 96495.8116475475}, + {132600000, 96496.3705954608}, {132610000, 96496.9420925947}, + {132620000, 96497.530059368}, {132630000, 96498.1298992941}, + {132640000, 96498.7290528023}, {132650000, 96499.3261827224}, + {132660000, 96499.9206022336}, {132670000, 96500.5121056935}, + {132680000, 96501.0970003072}, {132690000, 96501.6700567602}, + {132700000, 96502.2316836655}, {132710000, 96502.7886131689}, + {132720000, 96503.3422807952}, {132730000, 96503.8929619048}, + {132740000, 96504.440864062}, {132750000, 96504.988330197}, + {132760000, 96505.5418117491}, {132770000, 96506.1019704648}, + {132780000, 96506.6691399618}, {132790000, 96507.2434006602}, + {132800000, 96507.8174096031}, {132810000, 96508.3807954962}, + {132820000, 96508.933322657}, {132830000, 96509.4886541913}, + {132840000, 96510.0510057888}, {132850000, 96510.609576351}, + {132860000, 96511.1563689084}, {132870000, 96511.7004845734}, + {132880000, 96512.2670651872}, {132890000, 96512.8584180888}, + {132900000, 96513.4544974678}, {132910000, 96514.0490007104}, + {132920000, 96514.6340489163}, {132930000, 96515.1984946044}, + {132940000, 96515.7436798816}, {132950000, 96516.290398724}, + {132960000, 96516.8431514389}, {132970000, 96517.4025351913}, + {132980000, 96517.9689839312}, {132990000, 96518.5401634551}, + {133000000, 96519.1096766563}, {133010000, 96519.6768477742}, + {133020000, 96520.2413217421}, {133030000, 96520.8029965938}, + {133040000, 96521.3618797827}, {133050000, 96521.9179759876}, + {133060000, 96522.4721184216}, {133070000, 96523.0316857802}, + {133080000, 96523.5980151405}, {133090000, 96524.165866861}, + {133100000, 96524.7313573143}, {133110000, 96525.2897526481}, + {133120000, 96525.8279317633}, {133130000, 96526.3449670153}, + {133140000, 96526.8686381324}, {133150000, 96527.4076213318}, + {133160000, 96527.9514978172}, {133170000, 96528.4855500855}, + {133180000, 96529.0091267539}, {133190000, 96529.5278212964}, + {133200000, 96530.0434653242}, {133210000, 96530.5617373959}, + {133220000, 96531.0868410141}, {133230000, 96531.6142240749}, + {133240000, 96532.1313497012}, {133250000, 96532.6373083036}, + {133260000, 96533.1598663065}, {133270000, 96533.7076617068}, + {133280000, 96534.2664611279}, {133290000, 96534.8161676856}, + {133300000, 96535.3558346247}, {133310000, 96535.8905120854}, + {133320000, 96536.4220713326}, {133330000, 96536.9561814143}, + {133340000, 96537.4970440501}, {133350000, 96538.0424285237}, + {133360000, 96538.5862140703}, {133370000, 96539.1277538194}, + {133380000, 96539.6667165881}, {133390000, 96540.2030074782}, + {133400000, 96540.7366333086}, {133410000, 96541.2675981266}, + {133420000, 96541.7959147465}, {133430000, 96542.3215963763}, + {133440000, 96542.844656158}, {133450000, 96543.3705042627}, + {133460000, 96543.9031451593}, {133470000, 96544.4449855649}, + {133480000, 96545.0027538421}, {133490000, 96545.5767193229}, + {133500000, 96546.1387492159}, {133510000, 96546.6800682796}, + {133520000, 96547.2113083751}, {133530000, 96547.7474903889}, + {133540000, 96548.2887905848}, {133550000, 96548.8291230752}, + {133560000, 96549.3671951341}, {133570000, 96549.9081733414}, + {133580000, 96550.4558862652}, {133590000, 96551.0080991805}, + {133600000, 96551.5586800578}, {133610000, 96552.106981205}, + {133620000, 96552.6526840276}, {133630000, 96553.195697565}, + {133640000, 96553.7394566476}, {133650000, 96554.2888224871}, + {133660000, 96554.8440084377}, {133670000, 96555.3991337377}, + {133680000, 96555.9520147075}, {133690000, 96556.4969671775}, + {133700000, 96557.0297850386}, {133710000, 96557.5573633776}, + {133720000, 96558.0986986988}, {133730000, 96558.6555698226}, + {133740000, 96559.2147349389}, {133750000, 96559.7720366006}, + {133760000, 96560.3236891104}, {133770000, 96560.8643245278}, + {133780000, 96561.3937301342}, {133790000, 96561.9254690282}, + {133800000, 96562.4645477884}, {133810000, 96563.0108613474}, + {133820000, 96563.5643225252}, {133830000, 96564.1249112941}, + {133840000, 96564.6926354645}, {133850000, 96565.2672747839}, + {133860000, 96565.8345795263}, {133870000, 96566.3901092903}, + {133880000, 96566.9373444193}, {133890000, 96567.4811914945}, + {133900000, 96568.0219101522}, {133910000, 96568.5598161877}, + {133920000, 96569.095021607}, {133930000, 96569.6329607539}, + {133940000, 96570.1776659842}, {133950000, 96570.724582066}, + {133960000, 96571.2611328901}, {133970000, 96571.7862072676}, + {133980000, 96572.3133927505}, {133990000, 96572.8469432552}, + {134000000, 96573.3833861678}, {134010000, 96573.9178101961}, + {134020000, 96574.4499820068}, {134030000, 96574.9796231259}, + {134040000, 96575.506640656}, {134050000, 96576.0310373712}, + {134060000, 96576.5528186468}, {134070000, 96577.0743123554}, + {134080000, 96577.6019527731}, {134090000, 96578.136400316}, + {134100000, 96578.6779745174}, {134110000, 96579.2267511601}, + {134120000, 96579.7649377988}, {134130000, 96580.2673391677}, + {134140000, 96580.7334923469}, {134150000, 96581.2111492034}, + {134160000, 96581.7152642826}, {134170000, 96582.2245520901}, + {134180000, 96582.7231984177}, {134190000, 96583.2200841292}, + {134200000, 96583.7397501842}, {134210000, 96584.2841586491}, + {134220000, 96584.8119473269}, {134230000, 96585.3102015838}, + {134240000, 96585.796796018}, {134250000, 96586.2970173559}, + {134260000, 96586.8114668177}, {134270000, 96587.3347682144}, + {134280000, 96587.8658881829}, {134290000, 96588.3991072479}, + {134300000, 96588.9301699879}, {134310000, 96589.4566631727}, + {134320000, 96589.9718653428}, {134330000, 96590.4752940555}, + {134340000, 96590.9808081629}, {134350000, 96591.4927467503}, + {134360000, 96592.0076580862}, {134370000, 96592.5206606186}, + {134380000, 96593.0315935974}, {134390000, 96593.555756689}, + {134400000, 96594.0980741025}, {134410000, 96594.6416920916}, + {134420000, 96595.1740925819}, {134430000, 96595.6949966216}, + {134440000, 96596.2035297586}, {134450000, 96596.7000270748}, + {134460000, 96597.2129276506}, {134470000, 96597.751094103}, + {134480000, 96598.2967800108}, {134490000, 96598.8248494734}, + {134500000, 96599.3343969646}, {134510000, 96599.8447083572}, + {134520000, 96600.361823188}, {134530000, 96600.8859972874}, + {134540000, 96601.4174119831}, {134550000, 96601.9491095848}, + {134560000, 96602.4618307855}, {134570000, 96602.953880369}, + {134580000, 96603.4456279708}, {134590000, 96603.9434626459}, + {134600000, 96604.444084822}, {134610000, 96604.942828021}, + {134620000, 96605.4394785389}, {134630000, 96605.9493648877}, + {134640000, 96606.4775049164}, {134650000, 96607.0070363261}, + {134660000, 96607.5254192231}, {134670000, 96608.0370075461}, + {134680000, 96608.5537944351}, {134690000, 96609.07694719}, + {134700000, 96609.5999808302}, {134710000, 96610.1208605249}, + {134720000, 96610.6431713485}, {134730000, 96611.1719974186}, + {134740000, 96611.7067561032}, {134750000, 96612.240543324}, + {134760000, 96612.7721429726}, {134770000, 96613.2959143814}, + {134780000, 96613.8076732396}, {134790000, 96614.3142890118}, + {134800000, 96614.8347335564}, {134810000, 96615.3706985803}, + {134820000, 96615.9018793558}, {134830000, 96616.4219198097}, + {134840000, 96616.9306805599}, {134850000, 96617.4279401861}, + {134860000, 96617.9137422199}, {134870000, 96618.4096838846}, + {134880000, 96618.9235440688}, {134890000, 96619.43870377}, + {134900000, 96619.9428041164}, {134910000, 96620.4401779934}, + {134920000, 96620.9427751208}, {134930000, 96621.4516723154}, + {134940000, 96621.9533340078}, {134950000, 96622.4435305802}, + {134960000, 96622.929165955}, {134970000, 96623.4200238703}, + {134980000, 96623.916565449}, {134990000, 96624.4132183118}, + {135000000, 96624.9079001957}, {135010000, 96625.4057529836}, + {135020000, 96625.9106053906}, {135030000, 96626.4202194822}, + {135040000, 96626.9284346965}, {135050000, 96627.4345053975}, + {135060000, 96627.930962276}, {135070000, 96628.4154939994}, + {135080000, 96628.8883096239}, {135090000, 96629.3496806433}, + {135100000, 96629.7998035964}, {135110000, 96630.2684929269}, + {135120000, 96630.7653826996}, {135130000, 96631.2682669911}, + {135140000, 96631.7606065782}, {135150000, 96632.244322834}, + {135160000, 96632.7246645036}, {135170000, 96633.2022989756}, + {135180000, 96633.6846216148}, {135190000, 96634.1739390976}, + {135200000, 96634.6666350459}, {135210000, 96635.1575866914}, + {135220000, 96635.6478696173}, {135230000, 96636.1520706899}, + {135240000, 96636.6732187422}, {135250000, 96637.195230575}, + {135260000, 96637.7061316071}, {135270000, 96638.2079572896}, + {135280000, 96638.7062685362}, {135290000, 96639.2016759204}, + {135300000, 96639.6944873975}, {135310000, 96640.1848085481}, + {135320000, 96640.6726647772}, {135330000, 96641.1580868893}, + {135340000, 96641.6418991181}, {135350000, 96642.1314906375}, + {135360000, 96642.6282122145}, {135370000, 96643.1268277825}, + {135380000, 96643.62342731}, {135390000, 96644.1225297877}, + {135400000, 96644.6366829664}, {135410000, 96645.1667996755}, + {135420000, 96645.6851079512}, {135430000, 96646.1829256981}, + {135440000, 96646.6746170498}, {135450000, 96647.1805627554}, + {135460000, 96647.7002863461}, {135470000, 96648.2207496123}, + {135480000, 96648.7395218691}, {135490000, 96649.2668984938}, + {135500000, 96649.8105427408}, {135510000, 96650.3659801887}, + {135520000, 96650.92089927}, {135530000, 96651.4737118236}, + {135540000, 96652.0024660214}, {135550000, 96652.5003495224}, + {135560000, 96652.9817738257}, {135570000, 96653.4671471337}, + {135580000, 96653.9574398711}, {135590000, 96654.4474293313}, + {135600000, 96654.935420428}, {135610000, 96655.4319541505}, + {135620000, 96655.944876906}, {135630000, 96656.4697215707}, + {135640000, 96656.9941979768}, {135650000, 96657.5168130152}, + {135660000, 96658.0227168861}, {135670000, 96658.5072992331}, + {135680000, 96658.984808108}, {135690000, 96659.4754751052}, + {135700000, 96659.9801890413}, {135710000, 96660.494884891}, + {135720000, 96661.0182606186}, {135730000, 96661.5441431659}, + {135740000, 96662.0679224613}, {135750000, 96662.5894898477}, + {135760000, 96663.1085240592}, {135770000, 96663.6250915668}, + {135780000, 96664.1462925995}, {135790000, 96664.6743429894}, + {135800000, 96665.2019299225}, {135810000, 96665.7186698843}, + {135820000, 96666.2253356837}, {135830000, 96666.7357770755}, + {135840000, 96667.2529235355}, {135850000, 96667.7717152118}, + {135860000, 96668.2883738916}, {135870000, 96668.8051088137}, + {135880000, 96669.3280587864}, {135890000, 96669.8577655941}, + {135900000, 96670.3874375428}, {135910000, 96670.9149384977}, + {135920000, 96671.4366199699}, {135930000, 96671.9472895469}, + {135940000, 96672.4469013555}, {135950000, 96672.9493982587}, + {135960000, 96673.459172293}, {135970000, 96673.9708566602}, + {135980000, 96674.4804437434}, {135990000, 96674.9901445871}, + {136000000, 96675.5060959897}, {136010000, 96676.0288377276}, + {136020000, 96676.5515778708}, {136030000, 96677.072181683}, + {136040000, 96677.5904774414}, {136050000, 96678.1062161973}, + {136060000, 96678.6193976752}, {136070000, 96679.1300366894}, + {136080000, 96679.6381465736}, {136090000, 96680.1491199135}, + {136100000, 96680.6669776198}, {136110000, 96681.187189}, + {136120000, 96681.6971870628}, {136130000, 96682.1958474081}, + {136140000, 96682.6967301461}, {136150000, 96683.2040928819}, + {136160000, 96683.7076409286}, {136170000, 96684.1927372335}, + {136180000, 96684.6587393521}, {136190000, 96685.1474291743}, + {136200000, 96685.6747834011}, {136210000, 96686.2127812321}, + {136220000, 96686.7404975075}, {136230000, 96687.259749519}, + {136240000, 96687.7755107478}, {136250000, 96688.2884177689}, + {136260000, 96688.8058538387}, {136270000, 96689.3301258326}, + {136280000, 96689.8610649745}, {136290000, 96690.3984456681}, + {136300000, 96690.9421972103}, {136310000, 96691.4858681516}, + {136320000, 96692.0273621037}, {136330000, 96692.5610251374}, + {136340000, 96693.0826422874}, {136350000, 96693.5990579118}, + {136360000, 96694.1292645516}, {136370000, 96694.6748839076}, + {136380000, 96695.2084896888}, {136390000, 96695.7214962298}, + {136400000, 96696.224234287}, {136410000, 96696.731374891}, + {136420000, 96697.2436302293}, {136430000, 96697.7634147576}, + {136440000, 96698.2917360478}, {136450000, 96698.8278698138}, + {136460000, 96699.3712657821}, {136470000, 96699.9172723071}, + {136480000, 96700.4529886397}, {136490000, 96700.9773434542}, + {136500000, 96701.5109971117}, {136510000, 96702.0604163874}, + {136520000, 96702.6150122097}, {136530000, 96703.1597484}, + {136540000, 96703.6940683223}, {136550000, 96704.2313176355}, + {136560000, 96704.7757090489}, {136570000, 96705.3218572129}, + {136580000, 96705.8657359393}, {136590000, 96706.4095609648}, + {136600000, 96706.9594953791}, {136610000, 96707.5159982152}, + {136620000, 96708.0651426992}, {136630000, 96708.6025701527}, + {136640000, 96709.1282914856}, {136650000, 96709.6422971447}, + {136660000, 96710.1448011025}, {136670000, 96710.6578430034}, + {136680000, 96711.1884707654}, {136690000, 96711.7148273506}, + {136700000, 96712.22058619}, {136710000, 96712.7146302615}, + {136720000, 96713.2215646541}, {136730000, 96713.743885228}, + {136740000, 96714.275741889}, {136750000, 96714.8152566061}, + {136760000, 96715.3480681408}, {136770000, 96715.8537008224}, + {136780000, 96716.3314813449}, {136790000, 96716.8151680303}, + {136800000, 96717.3156145314}, {136810000, 96717.8276604619}, + {136820000, 96718.3474308319}, {136830000, 96718.874811491}, + {136840000, 96719.4095530611}, {136850000, 96719.9515088976}, + {136860000, 96720.4935187941}, {136870000, 96721.0333287289}, + {136880000, 96721.5639097814}, {136890000, 96722.0752452339}, + {136900000, 96722.566925766}, {136910000, 96723.0507111189}, + {136920000, 96723.5310349417}, {136930000, 96724.0084853181}, + {136940000, 96724.4835057665}, {136950000, 96724.9630308209}, + {136960000, 96725.4663907951}, {136970000, 96725.9953774921}, + {136980000, 96726.5367144007}, {136990000, 96727.086180327}, + {137000000, 96727.6396078046}, {137010000, 96728.1910780967}, + {137020000, 96728.7403032185}, {137030000, 96729.286927189}, + {137040000, 96729.8308428804}, {137050000, 96730.3720627674}, + {137060000, 96730.9105995183}, {137070000, 96731.4464625608}, + {137080000, 96731.9796541609}, {137090000, 96732.5102698253}, + {137100000, 96733.0454342326}, {137110000, 96733.5873795357}, + {137120000, 96734.132480925}, {137130000, 96734.6755807368}, + {137140000, 96735.2163998618}, {137150000, 96735.7546113078}, + {137160000, 96736.2901550994}, {137170000, 96736.8230350167}, + {137180000, 96737.3532571844}, {137190000, 96737.8831401404}, + {137200000, 96738.4191381258}, {137210000, 96738.9618302685}, + {137220000, 96739.5044257296}, {137230000, 96740.0447856817}, + {137240000, 96740.5792522402}, {137250000, 96741.102605725}, + {137260000, 96741.6147331566}, {137270000, 96742.1218667518}, + {137280000, 96742.6259587134}, {137290000, 96743.1380810132}, + {137300000, 96743.666517164}, {137310000, 96744.2068122911}, + {137320000, 96744.7466656755}, {137330000, 96745.2847600157}, + {137340000, 96745.8204319997}, {137350000, 96746.3534809369}, + {137360000, 96746.8839004788}, {137370000, 96747.411675941}, + {137380000, 96747.9368191121}, {137390000, 96748.4517320574}, + {137400000, 96748.9535369127}, {137410000, 96749.45879885}, + {137420000, 96749.9799216792}, {137430000, 96750.5148690137}, + {137440000, 96751.0580934232}, {137450000, 96751.6088773111}, + {137460000, 96752.1597779444}, {137470000, 96752.7084504179}, + {137480000, 96753.2583700304}, {137490000, 96753.8144909146}, + {137500000, 96754.3764373047}, {137510000, 96754.9375113089}, + {137520000, 96755.4962879412}, {137530000, 96756.0471206076}, + {137540000, 96756.5857895454}, {137550000, 96757.1168348955}, + {137560000, 96757.6528479259}, {137570000, 96758.1950733414}, + {137580000, 96758.7370774044}, {137590000, 96759.2768326986}, + {137600000, 96759.8215060725}, {137610000, 96760.3813191159}, + {137620000, 96760.9548567092}, {137630000, 96761.5212434358}, + {137640000, 96762.0760553877}, {137650000, 96762.6241014573}, + {137660000, 96763.1689920667}, {137670000, 96763.7154479797}, + {137680000, 96764.2766467181}, {137690000, 96764.8535139405}, + {137700000, 96765.4111601845}, {137710000, 96765.9386523951}, + {137720000, 96766.4540093684}, {137730000, 96766.9828773158}, + {137740000, 96767.5249927038}, {137750000, 96768.0675411944}, + {137760000, 96768.6082507712}, {137770000, 96769.1520538414}, + {137780000, 96769.7026411897}, {137790000, 96770.2554803512}, + {137800000, 96770.797938006}, {137810000, 96771.3289538949}, + {137820000, 96771.8692217989}, {137830000, 96772.4252385418}, + {137840000, 96772.9829778905}, {137850000, 96773.5224421135}, + {137860000, 96774.0428110187}, {137870000, 96774.5714089298}, + {137880000, 96775.117120437}, {137890000, 96775.6744928041}, + {137900000, 96776.2394273049}, {137910000, 96776.807189683}, + {137920000, 96777.3646042855}, {137930000, 96777.9104667728}, + {137940000, 96778.4583230162}, {137950000, 96779.0124438097}, + {137960000, 96779.5659138733}, {137970000, 96780.1088792326}, + {137980000, 96780.6409142577}, {137990000, 96781.1678878019}, + {138000000, 96781.6917337777}, {138010000, 96782.2127432364}, + {138020000, 96782.7311379402}, {138030000, 96783.2538216526}, + {138040000, 96783.8001067224}, {138050000, 96784.3714627567}, + {138060000, 96784.92625651}, {138070000, 96785.4514102137}, + {138080000, 96785.9573148014}, {138090000, 96786.4587333326}, + {138100000, 96786.9564276851}, {138110000, 96787.4741463964}, + {138120000, 96788.0206998699}, {138130000, 96788.5788351869}, + {138140000, 96789.1355990645}, {138150000, 96789.6906707116}, + {138160000, 96790.2431378366}, {138170000, 96790.7928307859}, + {138180000, 96791.3326155365}, {138190000, 96791.8602752427}, + {138200000, 96792.3794616883}, {138210000, 96792.895364023}, + {138220000, 96793.4084411106}, {138230000, 96793.9345105883}, + {138240000, 96794.4785219562}, {138250000, 96795.0345837823}, + {138260000, 96795.5982629069}, {138270000, 96796.1625199472}, + {138280000, 96796.7077077695}, {138290000, 96797.2320513194}, + {138300000, 96797.7558758893}, {138310000, 96798.2855953369}, + {138320000, 96798.8179402983}, {138330000, 96799.3482543226}, + {138340000, 96799.8764888656}, {138350000, 96800.4178910174}, + {138360000, 96800.9772295559}, {138370000, 96801.5431846041}, + {138380000, 96802.1072585422}, {138390000, 96802.6715362879}, + {138400000, 96803.2418402886}, {138410000, 96803.8186858114}, + {138420000, 96804.3952711662}, {138430000, 96804.9694514869}, + {138440000, 96805.5410568935}, {138450000, 96806.1098395743}, + {138460000, 96806.675800264}, {138470000, 96807.2389417388}, + {138480000, 96807.7992745337}, {138490000, 96808.3514490342}, + {138500000, 96808.8914566434}, {138510000, 96809.4261027895}, + {138520000, 96809.9744374205}, {138530000, 96810.5382876651}, + {138540000, 96811.1044251504}, {138550000, 96811.6686647682}, + {138560000, 96812.2272419315}, {138570000, 96812.7747760944}, + {138580000, 96813.3110490766}, {138590000, 96813.8419249226}, + {138600000, 96814.3696289497}, {138610000, 96814.8998504683}, + {138620000, 96815.4368601447}, {138630000, 96815.9761464104}, + {138640000, 96816.5051143324}, {138650000, 96817.0227061153}, + {138660000, 96817.5496018294}, {138670000, 96818.0922937964}, + {138680000, 96818.6473748333}, {138690000, 96819.2100074719}, + {138700000, 96819.779922914}, {138710000, 96820.3572064249}, + {138720000, 96820.9418473988}, {138730000, 96821.5228786984}, + {138740000, 96822.0920663503}, {138750000, 96822.6515383659}, + {138760000, 96823.2071574839}, {138770000, 96823.7595706698}, + {138780000, 96824.3090993338}, {138790000, 96824.8558547932}, + {138800000, 96825.3963826366}, {138810000, 96825.9257375949}, + {138820000, 96826.443818134}, {138830000, 96826.9568698988}, + {138840000, 96827.4668508321}, {138850000, 96827.9848059198}, + {138860000, 96828.5190222804}, {138870000, 96829.0696530396}, + {138880000, 96829.6372761643}, {138890000, 96830.2216375415}, + {138900000, 96830.8014055934}, {138910000, 96831.3698547779}, + {138920000, 96831.9265839407}, {138930000, 96832.4709949481}, + {138940000, 96833.0049598851}, {138950000, 96833.5503842979}, + {138960000, 96834.1120349704}, {138970000, 96834.6742047013}, + {138980000, 96835.2250793447}, {138990000, 96835.7643799822}, + {139000000, 96836.2912210531}, {139010000, 96836.8058840715}, + {139020000, 96837.3367883664}, {139030000, 96837.8928596972}, + {139040000, 96838.4597097794}, {139050000, 96839.0168202527}, + {139060000, 96839.5638347572}, {139070000, 96840.1066144527}, + {139080000, 96840.6462756422}, {139090000, 96841.1884403263}, + {139100000, 96841.7373338094}, {139110000, 96842.2861615809}, + {139120000, 96842.815900981}, {139130000, 96843.3247521537}, + {139140000, 96843.8259649333}, {139150000, 96844.3237525109}, + {139160000, 96844.8219357003}, {139170000, 96845.3259750131}, + {139180000, 96845.8360708638}, {139190000, 96846.338346584}, + {139200000, 96846.828299074}, {139210000, 96847.31668534}, + {139220000, 96847.8115977207}, {139230000, 96848.3109367118}, + {139240000, 96848.8088645345}, {139250000, 96849.3046795548}, + {139260000, 96849.7909766808}, {139270000, 96850.2654481598}, + {139280000, 96850.735135203}, {139290000, 96851.2100887565}, + {139300000, 96851.6907915095}, {139310000, 96852.1869372555}, + {139320000, 96852.7021402164}, {139330000, 96853.2192160042}, + {139340000, 96853.725237821}, {139350000, 96854.2267969176}, + {139360000, 96854.7423059411}, {139370000, 96855.2736026873}, + {139380000, 96855.8145609418}, {139390000, 96856.3632118241}, + {139400000, 96856.9121022294}, {139410000, 96857.4505827612}, + {139420000, 96857.9781816972}, {139430000, 96858.500745927}, + {139440000, 96859.020204831}, {139450000, 96859.5422386998}, + {139460000, 96860.071116591}, {139470000, 96860.6091973244}, + {139480000, 96861.1631760702}, {139490000, 96861.7335420913}, + {139500000, 96862.3064064249}, {139510000, 96862.8773713975}, + {139520000, 96863.4497465873}, {139530000, 96864.0282641961}, + {139540000, 96864.61188818}, {139550000, 96865.186437243}, + {139560000, 96865.7489002205}, {139570000, 96866.3043270307}, + {139580000, 96866.8565289424}, {139590000, 96867.4079219908}, + {139600000, 96867.9652709889}, {139610000, 96868.5292769967}, + {139620000, 96869.1002609942}, {139630000, 96869.6783007511}, + {139640000, 96870.2527660479}, {139650000, 96870.8084459862}, + {139660000, 96871.3446597309}, {139670000, 96871.8880957918}, + {139680000, 96872.4488138791}, {139690000, 96873.015865319}, + {139700000, 96873.5809977616}, {139710000, 96874.1485910197}, + {139720000, 96874.7309440052}, {139730000, 96875.3292352303}, + {139740000, 96875.936971613}, {139750000, 96876.5520675662}, + {139760000, 96877.1671195756}, {139770000, 96877.7715392048}, + {139780000, 96878.3648409479}, {139790000, 96878.9602078266}, + {139800000, 96879.56262107}, {139810000, 96880.1666031033}, + {139820000, 96880.7680272514}, {139830000, 96881.364506422}, + {139840000, 96881.9493047835}, {139850000, 96882.5219080197}, + {139860000, 96883.0962304014}, {139870000, 96883.6766664993}, + {139880000, 96884.2563190848}, {139890000, 96884.825322187}, + {139900000, 96885.3832713633}, {139910000, 96885.9438353592}, + {139920000, 96886.5114700636}, {139930000, 96887.0807940224}, + {139940000, 96887.6477329539}, {139950000, 96888.2144747027}, + {139960000, 96888.7871796828}, {139970000, 96889.3664858452}, + {139980000, 96889.9526986948}, {139990000, 96890.5458913493}, + {140000000, 96891.142260493}, {140010000, 96891.7363736369}, + {140020000, 96892.3279665445}, {140030000, 96892.9320606901}, + {140040000, 96893.5541529749}, {140050000, 96894.1719832869}, + {140060000, 96894.7687942872}, {140070000, 96895.3488240176}, + {140080000, 96895.9238136747}, {140090000, 96896.4951288207}, + {140100000, 96897.0705444296}, {140110000, 96897.6525054037}, + {140120000, 96898.2339285503}, {140130000, 96898.8046735759}, + {140140000, 96899.3644819671}, {140150000, 96899.9347841807}, + {140160000, 96900.5223654677}, {140170000, 96901.1162175638}, + {140180000, 96901.7080332031}, {140190000, 96902.2976099364}, + {140200000, 96902.8843592858}, {140210000, 96903.4683095874}, + {140220000, 96904.0565482755}, {140230000, 96904.651302177}, + {140240000, 96905.2452433197}, {140250000, 96905.827889629}, + {140260000, 96906.4002729456}, {140270000, 96906.9763015114}, + {140280000, 96907.5585657303}, {140290000, 96908.1421110592}, + {140300000, 96908.7232004687}, {140310000, 96909.3017402287}, + {140320000, 96909.8774430615}, {140330000, 96910.4503685313}, + {140340000, 96911.0276278938}, {140350000, 96911.6114570215}, + {140360000, 96912.194786558}, {140370000, 96912.7674960997}, + {140380000, 96913.3291734296}, {140390000, 96913.9012289034}, + {140400000, 96914.490646237}, {140410000, 96915.0863705325}, + {140420000, 96915.6800491493}, {140430000, 96916.2760504905}, + {140440000, 96916.8866550513}, {140450000, 96917.5128089582}, + {140460000, 96918.1267408502}, {140470000, 96918.7197030505}, + {140480000, 96919.2986011427}, {140490000, 96919.8732892418}, + {140500000, 96920.4442931308}, {140510000, 96921.0122113145}, + {140520000, 96921.5772439332}, {140530000, 96922.1501671054}, + {140540000, 96922.7390959588}, {140550000, 96923.3396090622}, + {140560000, 96923.939388584}, {140570000, 96924.5371110532}, + {140580000, 96925.1321148967}, {140590000, 96925.7241999823}, + {140600000, 96926.3098941205}, {140610000, 96926.8842131238}, + {140620000, 96927.4471161854}, {140630000, 96928.0125659308}, + {140640000, 96928.584965053}, {140650000, 96929.1643358821}, + {140660000, 96929.7506869883}, {140670000, 96930.3417210523}, + {140680000, 96930.9310025233}, {140690000, 96931.5178444993}, + {140700000, 96932.1018924381}, {140710000, 96932.6830436351}, + {140720000, 96933.2650315172}, {140730000, 96933.8532020656}, + {140740000, 96934.4461639769}, {140750000, 96935.0296932922}, + {140760000, 96935.6012791559}, {140770000, 96936.17123183}, + {140780000, 96936.7473362236}, {140790000, 96937.3274888764}, + {140800000, 96937.9058163719}, {140810000, 96938.4817709265}, + {140820000, 96939.062156264}, {140830000, 96939.649112193}, + {140840000, 96940.2355978727}, {140850000, 96940.8115249277}, + {140860000, 96941.3764307626}, {140870000, 96941.9435835233}, + {140880000, 96942.5178810236}, {140890000, 96943.0992386816}, + {140900000, 96943.6875841506}, {140910000, 96944.2851795409}, + {140920000, 96944.8984650054}, {140930000, 96945.5277582469}, + {140940000, 96946.1449328248}, {140950000, 96946.741121746}, + {140960000, 96947.3266395437}, {140970000, 96947.9162403373}, + {140980000, 96948.5106544266}, {140990000, 96949.1122010853}, + {141000000, 96949.7217317182}, {141010000, 96950.3278747821}, + {141020000, 96950.9220502787}, {141030000, 96951.5063726007}, + {141040000, 96952.0867000892}, {141050000, 96952.6637586001}, + {141060000, 96953.2450029615}, {141070000, 96953.8327800321}, + {141080000, 96954.4200293551}, {141090000, 96954.9966254366}, + {141100000, 96955.5621159821}, {141110000, 96956.1223701651}, + {141120000, 96956.6793308147}, {141130000, 96957.2386596012}, + {141140000, 96957.8046327595}, {141150000, 96958.3773308951}, + {141160000, 96958.9570416644}, {141170000, 96959.5437647995}, + {141180000, 96960.137477522}, {141190000, 96960.7381488532}, + {141200000, 96961.3419921699}, {141210000, 96961.9435893731}, + {141220000, 96962.5426438804}, {141230000, 96963.138805591}, + {141240000, 96963.7320106033}, {141250000, 96964.3169034681}, + {141260000, 96964.8894465187}, {141270000, 96965.4587191981}, + {141280000, 96966.0502336849}, {141290000, 96966.6663394057}, + {141300000, 96967.279930892}, {141310000, 96967.8824255194}, + {141320000, 96968.4806163865}, {141330000, 96969.0842349785}, + {141340000, 96969.6922595789}, {141350000, 96970.2907914795}, + {141360000, 96970.877239855}, {141370000, 96971.4619301555}, + {141380000, 96972.0526779751}, {141390000, 96972.6496747052}, + {141400000, 96973.2535195147}, {141410000, 96973.8641714769}, + {141420000, 96974.4745314704}, {141430000, 96975.0823503968}, + {141440000, 96975.6874473171}, {141450000, 96976.2895567849}, + {141460000, 96976.8894708217}, {141470000, 96977.4945406335}, + {141480000, 96978.1061327097}, {141490000, 96978.7190630971}, + {141500000, 96979.3294073866}, {141510000, 96979.9416384511}, + {141520000, 96980.5683716717}, {141530000, 96981.2106016149}, + {141540000, 96981.8405230648}, {141550000, 96982.4493648981}, + {141560000, 96983.0474886576}, {141570000, 96983.649741669}, + {141580000, 96984.256832404}, {141590000, 96984.8553731932}, + {141600000, 96985.4410009326}, {141610000, 96986.0298873236}, + {141620000, 96986.6342659542}, {141630000, 96987.249823232}, + {141640000, 96987.8645261806}, {141650000, 96988.4771571138}, + {141660000, 96989.0941626195}, {141670000, 96989.7175710973}, + {141680000, 96990.3437558611}, {141690000, 96990.9675179855}, + {141700000, 96991.5886856608}, {141710000, 96992.2147097054}, + {141720000, 96992.8479310991}, {141730000, 96993.4827318915}, + {141740000, 96994.1148537773}, {141750000, 96994.7464731008}, + {141760000, 96995.3837150971}, {141770000, 96996.027067571}, + {141780000, 96996.6626732381}, {141790000, 96997.2861630665}, + {141800000, 96997.9009829917}, {141810000, 96998.5120595195}, + {141820000, 96999.120339325}, {141830000, 96999.7335654938}, + {141840000, 97000.3533856713}, {141850000, 97000.9745515697}, + {141860000, 97001.5930900875}, {141870000, 97002.2111930545}, + {141880000, 97002.8350299324}, {141890000, 97003.4650921391}, + {141900000, 97004.0874608427}, {141910000, 97004.6977473085}, + {141920000, 97005.2994131765}, {141930000, 97005.8974076008}, + {141940000, 97006.4920720532}, {141950000, 97007.091485136}, + {141960000, 97007.6982095651}, {141970000, 97008.3066282488}, + {141980000, 97008.9124833956}, {141990000, 97009.5156778357}, + {142000000, 97010.11591359}, {142010000, 97010.7133198049}, + {142020000, 97011.3221037167}, {142030000, 97011.9467330208}, + {142040000, 97012.5730290918}, {142050000, 97013.1806463226}, + {142060000, 97013.7689065268}, {142070000, 97014.3574123949}, + {142080000, 97014.9522907654}, {142090000, 97015.5538304339}, + {142100000, 97016.1622422797}, {142110000, 97016.7775034873}, + {142120000, 97017.3996123337}, {142130000, 97018.0283162542}, + {142140000, 97018.6422927479}, {142150000, 97019.2348286303}, + {142160000, 97019.813007272}, {142170000, 97020.3869631082}, + {142180000, 97020.9572330715}, {142190000, 97021.5243871257}, + {142200000, 97022.0886579674}, {142210000, 97022.6608012885}, + {142220000, 97023.2489567461}, {142230000, 97023.8487147779}, + {142240000, 97024.4477466543}, {142250000, 97025.044652858}, + {142260000, 97025.6316760312}, {142270000, 97026.2063873936}, + {142280000, 97026.7792825178}, {142290000, 97027.36543396}, + {142300000, 97027.9655131322}, {142310000, 97028.5597595647}, + {142320000, 97029.1417012466}, {142330000, 97029.7325006241}, + {142340000, 97030.3481808343}, {142350000, 97030.9754052945}, + {142360000, 97031.5766707452}, {142370000, 97032.1484098729}, + {142380000, 97032.7241627706}, {142390000, 97033.3145621321}, + {142400000, 97033.912893485}, {142410000, 97034.5095292425}, + {142420000, 97035.1039853605}, {142430000, 97035.695735127}, + {142440000, 97036.2845876332}, {142450000, 97036.8812326685}, + {142460000, 97037.493769996}, {142470000, 97038.1132329792}, + {142480000, 97038.7143992592}, {142490000, 97039.2949200012}, + {142500000, 97039.88190304}, {142510000, 97040.48393102}, + {142520000, 97041.0941178798}, {142530000, 97041.7025900532}, + {142540000, 97042.3088458649}, {142550000, 97042.9123169525}, + {142560000, 97043.5128313202}, {142570000, 97044.1103735662}, + {142580000, 97044.7049355578}, {142590000, 97045.2965321592}, + {142600000, 97045.8851781601}, {142610000, 97046.4710335696}, + {142620000, 97047.0682926192}, {142630000, 97047.6814221228}, + {142640000, 97048.303200589}, {142650000, 97048.9232737009}, + {142660000, 97049.54115268}, {142670000, 97050.164028257}, + {142680000, 97050.7942205694}, {142690000, 97051.4153412572}, + {142700000, 97052.0149692845}, {142710000, 97052.6042567082}, + {142720000, 97053.2145953967}, {142730000, 97053.8489229521}, + {142740000, 97054.4733497156}, {142750000, 97055.0771440941}, + {142760000, 97055.6704995763}, {142770000, 97056.2680485107}, + {142780000, 97056.8705318414}, {142790000, 97057.4800944479}, + {142800000, 97058.0974074048}, {142810000, 97058.7219379555}, + {142820000, 97059.3532734104}, {142830000, 97059.9913880037}, + {142840000, 97060.636271118}, {142850000, 97061.287818529}, + {142860000, 97061.9388752958}, {142870000, 97062.587171957}, + {142880000, 97063.2291366107}, {142890000, 97063.8596197645}, + {142900000, 97064.4784120259}, {142910000, 97065.0837796869}, + {142920000, 97065.6751031884}, {142930000, 97066.2637690327}, + {142940000, 97066.8584284265}, {142950000, 97067.4592866025}, + {142960000, 97068.0669806331}, {142970000, 97068.6814772347}, + {142980000, 97069.2956578285}, {142990000, 97069.9072622375}, + {143000000, 97070.5195577125}, {143010000, 97071.1372473568}, + {143020000, 97071.7605367791}, {143030000, 97072.3832617425}, + {143040000, 97073.003397676}, {143050000, 97073.6260257861}, + {143060000, 97074.2549975916}, {143070000, 97074.885842345}, + {143080000, 97075.505954535}, {143090000, 97076.1141639242}, + {143100000, 97076.7240134337}, {143110000, 97077.339799467}, + {143120000, 97077.9581038441}, {143130000, 97078.5740177233}, + {143140000, 97079.1878986806}, {143150000, 97079.8068833448}, + {143160000, 97080.4325242078}, {143170000, 97081.0648788989}, + {143180000, 97081.7039832616}, {143190000, 97082.3475373252}, + {143200000, 97082.9890803549}, {143210000, 97083.6279233749}, + {143220000, 97084.2637134273}, {143230000, 97084.8963486729}, + {143240000, 97085.51891435}, {143250000, 97086.1214377246}, + {143260000, 97086.7038740123}, {143270000, 97087.29414607}, + {143280000, 97087.9009751838}, {143290000, 97088.5137258445}, + {143300000, 97089.1243133726}, {143310000, 97089.7325450445}, + {143320000, 97090.3378544351}, {143330000, 97090.9403361829}, + {143340000, 97091.5541577663}, {143350000, 97092.1837810491}, + {143360000, 97092.8118151756}, {143370000, 97093.4132312138}, + {143380000, 97093.9868708088}, {143390000, 97094.5722061078}, + {143400000, 97095.1846872679}, {143410000, 97095.8132421221}, + {143420000, 97096.4494423644}, {143430000, 97097.0885063563}, + {143440000, 97097.7169435854}, {143450000, 97098.3334799182}, + {143460000, 97098.9516314545}, {143470000, 97099.5756956497}, + {143480000, 97100.2058923802}, {143490000, 97100.8425520122}, + {143500000, 97101.483743344}, {143510000, 97102.1075722682}, + {143520000, 97102.70939315}, {143530000, 97103.3048570743}, + {143540000, 97103.9058585736}, {143550000, 97104.5149729199}, + {143560000, 97105.1395544223}, {143570000, 97105.7801179082}, + {143580000, 97106.4156884398}, {143590000, 97107.0396152725}, + {143600000, 97107.6587922874}, {143610000, 97108.2831378873}, + {143620000, 97108.9119344382}, {143630000, 97109.53135702}, + {143640000, 97110.1384565942}, {143650000, 97110.7489732249}, + {143660000, 97111.374872118}, {143670000, 97112.0118611128}, + {143680000, 97112.6478943669}, {143690000, 97113.2816743797}, + {143700000, 97113.9125530422}, {143710000, 97114.5403340203}, + {143720000, 97115.1650134018}, {143730000, 97115.7865786301}, + {143740000, 97116.4067170815}, {143750000, 97117.0401141397}, + {143760000, 97117.6893673674}, {143770000, 97118.3388158705}, + {143780000, 97118.9765503988}, {143790000, 97119.6068366884}, + {143800000, 97120.2416792948}, {143810000, 97120.882287488}, + {143820000, 97121.5221977329}, {143830000, 97122.1593546906}, + {143840000, 97122.7901760542}, {143850000, 97123.4094836387}, + {143860000, 97124.0171754186}, {143870000, 97124.6349300248}, + {143880000, 97125.2697420304}, {143890000, 97125.9159734777}, + {143900000, 97126.5693236645}, {143910000, 97127.2251193943}, + {143920000, 97127.8701568794}, {143930000, 97128.5031948451}, + {143940000, 97129.1377509817}, {143950000, 97129.7781204173}, + {143960000, 97130.4243069757}, {143970000, 97131.0763291469}, + {143980000, 97131.7341368551}, {143990000, 97132.3757770578}, + {144000000, 97132.994069573}, {144010000, 97133.61071031}, + {144020000, 97134.2421994415}, {144030000, 97134.8820928233}, + {144040000, 97135.5122292691}, {144050000, 97136.1307583026}, + {144060000, 97136.7438195047}, {144070000, 97137.3533845651}, + {144080000, 97137.9630265165}, {144090000, 97138.577891638}, + {144100000, 97139.1982198046}, {144110000, 97139.8182052308}, + {144120000, 97140.4356226043}, {144130000, 97141.060903071}, + {144140000, 97141.70197928}, {144150000, 97142.3476393976}, + {144160000, 97142.966154934}, {144170000, 97143.5545482314}, + {144180000, 97144.1467047604}, {144190000, 97144.7534073353}, + {144200000, 97145.3714204424}, {144210000, 97145.9960972333}, + {144220000, 97146.6271762873}, {144230000, 97147.2656515452}, + {144240000, 97147.9118135444}, {144250000, 97148.5543920571}, + {144260000, 97149.184821072}, {144270000, 97149.8097480562}, + {144280000, 97150.4479590879}, {144290000, 97151.1012886538}, + {144300000, 97151.7564946263}, {144310000, 97152.4093580227}, + {144320000, 97153.052635344}, {144330000, 97153.6758634094}, + {144340000, 97154.2787905276}, {144350000, 97154.8815751979}, + {144360000, 97155.4906339147}, {144370000, 97156.1062608368}, + {144380000, 97156.7286722323}, {144390000, 97157.3555800959}, + {144400000, 97157.9805423964}, {144410000, 97158.6030066633}, + {144420000, 97159.236833703}, {144430000, 97159.8863976493}, + {144440000, 97160.5410135635}, {144450000, 97161.185290087}, + {144460000, 97161.8187535771}, {144470000, 97162.4625033059}, + {144480000, 97163.1231292114}, {144490000, 97163.7789962021}, + {144500000, 97164.4136377572}, {144510000, 97165.0357962474}, + {144520000, 97165.6701595725}, {144530000, 97166.3192116125}, + {144540000, 97166.9700449921}, {144550000, 97167.6185415102}, + {144560000, 97168.2643702694}, {144570000, 97168.9070478634}, + {144580000, 97169.5465642435}, {144590000, 97170.1905054286}, + {144600000, 97170.841749483}, {144610000, 97171.4838818812}, + {144620000, 97172.1044006133}, {144630000, 97172.7144203269}, + {144640000, 97173.3453776789}, {144650000, 97174.0002425769}, + {144660000, 97174.6451397852}, {144670000, 97175.2693187212}, + {144680000, 97175.886758895}, {144690000, 97176.5175971156}, + {144700000, 97177.1623491916}, {144710000, 97177.8156692608}, + {144720000, 97178.4763669801}, {144730000, 97179.1333273057}, + {144740000, 97179.7780817031}, {144750000, 97180.4149997324}, + {144760000, 97181.0564060056}, {144770000, 97181.7035475031}, + {144780000, 97182.3499724668}, {144790000, 97182.9936278604}, + {144800000, 97183.6343535336}, {144810000, 97184.2719118461}, + {144820000, 97184.9063055336}, {144830000, 97185.5375522248}, + {144840000, 97186.1656681982}, {144850000, 97186.7960085036}, + {144860000, 97187.4326526509}, {144870000, 97188.0756747886}, + {144880000, 97188.725344543}, {144890000, 97189.3815964816}, + {144900000, 97190.037327877}, {144910000, 97190.6902759737}, + {144920000, 97191.3438934096}, {144930000, 97192.0031631507}, + {144940000, 97192.6677622761}, {144950000, 97193.331011424}, + {144960000, 97193.991438239}, {144970000, 97194.6487910008}, + {144980000, 97195.3028814115}, {144990000, 97195.9537218455}, + {145000000, 97196.6013174017}, {145010000, 97197.2456830614}, + {145020000, 97197.8868349341}, {145030000, 97198.5247890484}, + {145040000, 97199.1669419664}, {145050000, 97199.8239748685}, + {145060000, 97200.4933440542}, {145070000, 97201.1466233948}, + {145080000, 97201.7784688527}, {145090000, 97202.4094533168}, + {145100000, 97203.0552794736}, {145110000, 97203.7117716035}, + {145120000, 97204.3671669544}, {145130000, 97205.0202632417}, + {145140000, 97205.6775068791}, {145150000, 97206.3409375678}, + {145160000, 97207.0035186218}, {145170000, 97207.6550956075}, + {145180000, 97208.295206142}, {145190000, 97208.9374944342}, + {145200000, 97209.5864557644}, {145210000, 97210.2367247748}, + {145220000, 97210.884204986}, {145230000, 97211.5310683313}, + {145240000, 97212.1834861261}, {145250000, 97212.8419104526}, + {145260000, 97213.4853690616}, {145270000, 97214.1072212996}, + {145280000, 97214.7179127421}, {145290000, 97215.3325024078}, + {145300000, 97215.9517506127}, {145310000, 97216.5779905775}, + {145320000, 97217.2120928861}, {145330000, 97217.8534242517}, + {145340000, 97218.5014929365}, {145350000, 97219.156261495}, + {145360000, 97219.8176855409}, {145370000, 97220.4857308022}, + {145380000, 97221.1603762903}, {145390000, 97221.8415929428}, + {145400000, 97222.5187449666}, {145410000, 97223.1764643847}, + {145420000, 97223.8140588534}, {145430000, 97224.4512771186}, + {145440000, 97225.0946420872}, {145450000, 97225.7390848836}, + {145460000, 97226.3807355771}, {145470000, 97227.02404914}, + {145480000, 97227.6816956148}, {145490000, 97228.3547871406}, + {145500000, 97229.0226350002}, {145510000, 97229.6786609084}, + {145520000, 97230.3297513036}, {145530000, 97230.9858395749}, + {145540000, 97231.6462374714}, {145550000, 97232.2971261652}, + {145560000, 97232.9355262003}, {145570000, 97233.5771349543}, + {145580000, 97234.2339292866}, {145590000, 97234.8994028712}, + {145600000, 97235.5550647381}, {145610000, 97236.1990816434}, + {145620000, 97236.8446528233}, {145630000, 97237.4959812424}, + {145640000, 97238.1496507613}, {145650000, 97238.8007291762}, + {145660000, 97239.4489731832}, {145670000, 97240.1017086192}, + {145680000, 97240.7617225656}, {145690000, 97241.4339692915}, + {145700000, 97242.1222157927}, {145710000, 97242.8219646301}, + {145720000, 97243.5205469214}, {145730000, 97244.2165965518}, + {145740000, 97244.9094423485}, {145750000, 97245.5988811845}, + {145760000, 97246.2849108206}, {145770000, 97246.9675203242}, + {145780000, 97247.6467252986}, {145790000, 97248.3225427242}, + {145800000, 97248.9949894962}, {145810000, 97249.6587471725}, + {145820000, 97250.3097616947}, {145830000, 97250.9547735817}, + {145840000, 97251.6128974043}, {145850000, 97252.2860150593}, + {145860000, 97252.9609112984}, {145870000, 97253.6333667557}, + {145880000, 97254.3064768171}, {145890000, 97254.9847168505}, + {145900000, 97255.6682845534}, {145910000, 97256.3432099668}, + {145920000, 97257.0049118632}, {145930000, 97257.6747877741}, + {145940000, 97258.3691792663}, {145950000, 97259.0770998724}, + {145960000, 97259.7673913916}, {145970000, 97260.437006068}, + {145980000, 97261.1127147572}, {145990000, 97261.8030445327}, + {146000000, 97262.49773397}, {146010000, 97263.1819616455}, + {146020000, 97263.8550090723}, {146030000, 97264.52985337}, + {146040000, 97265.2113373689}, {146050000, 97265.894025751}, + {146060000, 97266.5737636985}, {146070000, 97267.2527278261}, + {146080000, 97267.9371013091}, {146090000, 97268.6273379495}, + {146100000, 97269.3024435615}, {146110000, 97269.9557710526}, + {146120000, 97270.597821138}, {146130000, 97271.2437454829}, + {146140000, 97271.8942666371}, {146150000, 97272.5437964406}, + {146160000, 97273.1905474535}, {146170000, 97273.8449473103}, + {146180000, 97274.5149652568}, {146190000, 97275.1939659503}, + {146200000, 97275.8631387474}, {146210000, 97276.5206162387}, + {146220000, 97277.179595098}, {146230000, 97277.8442807404}, + {146240000, 97278.5112605994}, {146250000, 97279.1756031978}, + {146260000, 97279.8378163436}, {146270000, 97280.5049904203}, + {146280000, 97281.1784593367}, {146290000, 97281.8636789084}, + {146300000, 97282.5648149268}, {146310000, 97283.2751347296}, + {146320000, 97283.9755059877}, {146330000, 97284.6638967967}, + {146340000, 97285.3393323024}, {146350000, 97286.0015453656}, + {146360000, 97286.6508841691}, {146370000, 97287.2878232563}, + {146380000, 97287.9124724011}, {146390000, 97288.5546781086}, + {146400000, 97289.2242240637}, {146410000, 97289.9098292134}, + {146420000, 97290.6028440478}, {146430000, 97291.3007643824}, + {146440000, 97291.9965051344}, {146450000, 97292.6893082663}, + {146460000, 97293.3788099108}, {146470000, 97294.0649050703}, + {146480000, 97294.7475979196}, {146490000, 97295.4268867962}, + {146500000, 97296.1027877053}, {146510000, 97296.7753175446}, + {146520000, 97297.4444931273}, {146530000, 97298.1209961478}, + {146540000, 97298.8129906006}, {146550000, 97299.5138421286}, + {146560000, 97300.2047417267}, {146570000, 97300.8838831072}, + {146580000, 97301.5715684797}, {146590000, 97302.274251234}, + {146600000, 97302.9849099059}, {146610000, 97303.6934051937}, + {146620000, 97304.3992157458}, {146630000, 97305.1017525501}, + {146640000, 97305.8008384864}, {146650000, 97306.4911403573}, + {146660000, 97307.168582894}, {146670000, 97307.8398903711}, + {146680000, 97308.5241763271}, {146690000, 97309.2233305084}, + {146700000, 97309.9241392786}, {146710000, 97310.6223780276}, + {146720000, 97311.3177067408}, {146730000, 97312.009626508}, + {146740000, 97312.6997906055}, {146750000, 97313.4028399783}, + {146760000, 97314.12137222}, {146770000, 97314.8398009803}, + {146780000, 97315.5461868772}, {146790000, 97316.2447696531}, + {146800000, 97316.9475494638}, {146810000, 97317.6556832132}, + {146820000, 97318.355653394}, {146830000, 97319.0431716274}, + {146840000, 97319.7250651624}, {146850000, 97320.4112063355}, + {146860000, 97321.1020885666}, {146870000, 97321.7997474541}, + {146880000, 97322.5049286647}, {146890000, 97323.2169833675}, + {146900000, 97323.9354066538}, {146910000, 97324.6579079501}, + {146920000, 97325.3779948699}, {146930000, 97326.0949130363}, + {146940000, 97326.8012552632}, {146950000, 97327.4946905732}, + {146960000, 97328.185580387}, {146970000, 97328.8889211238}, + {146980000, 97329.6054339509}, {146990000, 97330.3161974461}, + {147000000, 97331.0139298746}, {147010000, 97331.7091312586}, + {147020000, 97332.4098772253}, {147030000, 97333.1163538057}, + {147040000, 97333.8291461718}, {147050000, 97334.5482282303}, + {147060000, 97335.2664855359}, {147070000, 97335.9816476328}, + {147080000, 97336.6866987721}, {147090000, 97337.371457969}, + {147100000, 97338.0355058257}, {147110000, 97338.6989319389}, + {147120000, 97339.3683678755}, {147130000, 97340.0387596387}, + {147140000, 97340.7062299308}, {147150000, 97341.3752135948}, + {147160000, 97342.0583682527}, {147170000, 97342.7568194264}, + {147180000, 97343.4499193469}, {147190000, 97344.1310886393}, + {147200000, 97344.8071880767}, {147210000, 97345.4881485191}, + {147220000, 97346.1745589696}, {147230000, 97346.8674915187}, + {147240000, 97347.5671540509}, {147250000, 97348.2733809606}, + {147260000, 97348.986037731}, {147270000, 97349.698306656}, + {147280000, 97350.3907234438}, {147290000, 97351.0614490083}, + {147300000, 97351.7308601748}, {147310000, 97352.405472314}, + {147320000, 97353.0820503322}, {147330000, 97353.7559146326}, + {147340000, 97354.4268019899}, {147350000, 97355.0944191172}, + {147360000, 97355.758723123}, {147370000, 97356.4250570566}, + {147380000, 97357.097516494}, {147390000, 97357.7716627131}, + {147400000, 97358.4348414061}, {147410000, 97359.0858489365}, + {147420000, 97359.7382732064}, {147430000, 97360.3964542844}, + {147440000, 97361.064326445}, {147450000, 97361.7476131683}, + {147460000, 97362.4442761021}, {147470000, 97363.1329854114}, + {147480000, 97363.809709763}, {147490000, 97364.4844165154}, + {147500000, 97365.1647525241}, {147510000, 97365.8531560141}, + {147520000, 97366.5566619237}, {147530000, 97367.2758462859}, + {147540000, 97367.9968472666}, {147550000, 97368.7152262612}, + {147560000, 97369.4237897562}, {147570000, 97370.1120908096}, + {147580000, 97370.7796906352}, {147590000, 97371.4544237775}, + {147600000, 97372.1454648505}, {147610000, 97372.8421325612}, + {147620000, 97373.5362183934}, {147630000, 97374.2320466367}, + {147640000, 97374.94199201}, {147650000, 97375.6670344206}, + {147660000, 97376.3722805379}, {147670000, 97377.0466398854}, + {147680000, 97377.7040031896}, {147690000, 97378.364479375}, + {147700000, 97379.0291211992}, {147710000, 97379.7003892081}, + {147720000, 97380.3790524267}, {147730000, 97381.0699437932}, + {147740000, 97381.7767605754}, {147750000, 97382.4972827861}, + {147760000, 97383.2253013632}, {147770000, 97383.9599889289}, + {147780000, 97384.6867602625}, {147790000, 97385.4009783925}, + {147800000, 97386.1024308776}, {147810000, 97386.7907804418}, + {147820000, 97387.4679619447}, {147830000, 97388.1559060304}, + {147840000, 97388.8593282791}, {147850000, 97389.568001096}, + {147860000, 97390.2740647855}, {147870000, 97390.9818276124}, + {147880000, 97391.7036180946}, {147890000, 97392.4405358106}, + {147900000, 97393.1719226376}, {147910000, 97393.8911868206}, + {147920000, 97394.6015735199}, {147930000, 97395.3077693937}, + {147940000, 97396.0100409003}, {147950000, 97396.7086979084}, + {147960000, 97397.4038524183}, {147970000, 97398.1008560714}, + {147980000, 97398.8038162609}, {147990000, 97399.5150662529}, + {148000000, 97400.2413517312}, {148010000, 97400.983161869}, + {148020000, 97401.7195434121}, {148030000, 97402.4438098188}, + {148040000, 97403.1557560791}, {148050000, 97403.8550567125}, + {148060000, 97404.5420032462}, {148070000, 97405.2385393976}, + {148080000, 97405.9515654383}, {148090000, 97406.6702592179}, + {148100000, 97407.3862938902}, {148110000, 97408.0994734356}, + {148120000, 97408.8092102517}, {148130000, 97409.5154557783}, + {148140000, 97410.2181907018}, {148150000, 97410.9174207201}, + {148160000, 97411.6199094277}, {148170000, 97412.3354744799}, + {148180000, 97413.0645666994}, {148190000, 97413.7881088977}, + {148200000, 97414.4985891661}, {148210000, 97415.2118087096}, + {148220000, 97415.9398980749}, {148230000, 97416.6786004378}, + {148240000, 97417.4158492621}, {148250000, 97418.1504000131}, + {148260000, 97418.8886996594}, {148270000, 97419.6327985058}, + {148280000, 97420.3722633999}, {148290000, 97421.0919510575}, + {148300000, 97421.7911642509}, {148310000, 97422.4974497594}, + {148320000, 97423.2199295287}, {148330000, 97423.9479039332}, + {148340000, 97424.6731405243}, {148350000, 97425.3976996486}, + {148360000, 97426.1274704514}, {148370000, 97426.8630695569}, + {148380000, 97427.604809629}, {148390000, 97428.3527700203}, + {148400000, 97429.0998059504}, {148410000, 97429.835543056}, + {148420000, 97430.5594920033}, {148430000, 97431.2771897416}, + {148440000, 97431.9908019066}, {148450000, 97432.7112766672}, + {148460000, 97433.4470235502}, {148470000, 97434.189178809}, + {148480000, 97434.9124396405}, {148490000, 97435.6143723964}, + {148500000, 97436.322098777}, {148510000, 97437.0442843061}, + {148520000, 97437.7706552724}, {148530000, 97438.4863066675}, + {148540000, 97439.1906080641}, {148550000, 97439.896933359}, + {148560000, 97440.6095709298}, {148570000, 97441.3285187725}, + {148580000, 97442.0537681924}, {148590000, 97442.7807912898}, + {148600000, 97443.4966485108}, {148610000, 97444.2001568172}, + {148620000, 97444.911945506}, {148630000, 97445.6385926426}, + {148640000, 97446.3696899538}, {148650000, 97447.0901243874}, + {148660000, 97447.7991903929}, {148670000, 97448.510209044}, + {148680000, 97449.2275342699}, {148690000, 97449.940520924}, + {148700000, 97450.6409895908}, {148710000, 97451.3377942004}, + {148720000, 97452.0562351408}, {148730000, 97452.7986760754}, + {148740000, 97453.5308948242}, {148750000, 97454.2419670722}, + {148760000, 97454.9453972722}, {148770000, 97455.6608302402}, + {148780000, 97456.3892435181}, {148790000, 97457.1189038923}, + {148800000, 97457.8459055972}, {148810000, 97458.5644089428}, + {148820000, 97459.2699283003}, {148830000, 97459.9691582325}, + {148840000, 97460.6812190394}, {148850000, 97461.4079063003}, + {148860000, 97462.1218277576}, {148870000, 97462.8142484044}, + {148880000, 97463.5021581448}, {148890000, 97464.210233032}, + {148900000, 97464.9396711584}, {148910000, 97465.6735294524}, + {148920000, 97466.4052453328}, {148930000, 97467.13931958}, + {148940000, 97467.8792141015}, {148950000, 97468.6205042847}, + {148960000, 97469.3505271403}, {148970000, 97470.0680715422}, + {148980000, 97470.7866769953}, {148990000, 97471.5106756353}, + {149000000, 97472.2332592186}, {149010000, 97472.9445320877}, + {149020000, 97473.6440290132}, {149030000, 97474.3453563751}, + {149040000, 97475.0530253684}, {149050000, 97475.7617128957}, + {149060000, 97476.4673202413}, {149070000, 97477.1697583832}, + {149080000, 97477.8687420882}, {149090000, 97478.5643119343}, + {149100000, 97479.2635528977}, {149110000, 97479.9687230294}, + {149120000, 97480.6726539189}, {149130000, 97481.3649269879}, + {149140000, 97482.0474564435}, {149150000, 97482.7489125617}, + {149160000, 97483.4755318724}, {149170000, 97484.20652087}, + {149180000, 97484.9258423587}, {149190000, 97485.6376171667}, + {149200000, 97486.3535803196}, {149210000, 97487.0748195615}, + {149220000, 97487.7806786286}, {149230000, 97488.464589982}, + {149240000, 97489.1439209865}, {149250000, 97489.8438959881}, + {149260000, 97490.5654384143}, {149270000, 97491.2827515894}, + {149280000, 97491.9877117533}, {149290000, 97492.6957434306}, + {149300000, 97493.4187358498}, {149310000, 97494.1546729624}, + {149320000, 97494.8978912037}, {149330000, 97495.6475784997}, + {149340000, 97496.3821338885}, {149350000, 97497.0946794873}, + {149360000, 97497.7955907976}, {149370000, 97498.4999344072}, + {149380000, 97499.2084858068}, {149390000, 97499.9085343889}, + {149400000, 97500.5950350134}, {149410000, 97501.2840941502}, + {149420000, 97501.9881274}, {149430000, 97502.705145108}, + {149440000, 97503.4295598232}, {149450000, 97504.1606266319}, + {149460000, 97504.8837885137}, {149470000, 97505.5943958393}, + {149480000, 97506.2958670819}, {149490000, 97506.9931540931}, + {149500000, 97507.6884532701}, {149510000, 97508.4043958134}, + {149520000, 97509.1458619486}, {149530000, 97509.8971363864}, + {149540000, 97510.6460765113}, {149550000, 97511.3946199104}, + {149560000, 97512.1483229004}, {149570000, 97512.9076029156}, + {149580000, 97513.651461688}, {149590000, 97514.3732156413}, + {149600000, 97515.0871030428}, {149610000, 97515.813818385}, + {149620000, 97516.5526628009}, {149630000, 97517.2834492293}, + {149640000, 97518.0018115694}, {149650000, 97518.717834869}, + {149660000, 97519.4392975674}, {149670000, 97520.166381391}, + {149680000, 97520.8996606347}, {149690000, 97521.6391701591}, + {149700000, 97522.3849024882}, {149710000, 97523.136834193}, + {149720000, 97523.8875433468}, {149730000, 97524.6262208041}, + {149740000, 97525.3522587145}, {149750000, 97526.0648658015}, + {149760000, 97526.7639516646}, {149770000, 97527.4602388915}, + {149780000, 97528.1619979953}, {149790000, 97528.8671812028}, + {149800000, 97529.5699373244}, {149810000, 97530.2696924712}, + {149820000, 97530.9732112839}, {149830000, 97531.6826541386}, + {149840000, 97532.4012802178}, {149850000, 97533.1338603599}, + {149860000, 97533.8805284635}, {149870000, 97534.6208968366}, + {149880000, 97535.34830815}, {149890000, 97536.0731235855}, + {149900000, 97536.8033347766}, {149910000, 97537.5346296327}, + {149920000, 97538.2546444834}, {149930000, 97538.9621940849}, + {149940000, 97539.6708398862}, {149950000, 97540.3849283407}, + {149960000, 97541.0942441225}, {149970000, 97541.7839026962}, + {149980000, 97542.4532132904}, {149990000, 97543.1297194132}, + {150000000, 97543.8225415148}, {150010000, 97544.5316458707}, + {150020000, 97545.2569882426}, {150030000, 97545.9917726323}, + {150040000, 97546.7165624532}, {150050000, 97547.4293939173}, + {150060000, 97548.1434476483}, {150070000, 97548.8629506013}, + {150080000, 97549.5811220197}, {150090000, 97550.28808605}, + {150100000, 97550.9833756987}, {150110000, 97551.6800899135}, + {150120000, 97552.3833253485}, {150130000, 97553.0876764498}, + {150140000, 97553.7889690732}, {150150000, 97554.4893551302}, + {150160000, 97555.1950087086}, {150170000, 97555.9065249695}, + {150180000, 97556.6171370469}, {150190000, 97557.324675778}, + {150200000, 97558.0289830514}, {150210000, 97558.7298209663}, + {150220000, 97559.4271931976}, {150230000, 97560.1210945363}, + {150240000, 97560.8115350276}, {150250000, 97561.5144678156}, + {150260000, 97562.2422092831}, {150270000, 97562.9837541207}, + {150280000, 97563.7075746116}, {150290000, 97564.4105301965}, + {150300000, 97565.1193702476}, {150310000, 97565.8426616445}, + {150320000, 97566.5667347401}, {150330000, 97567.2716707701}, + {150340000, 97567.9567253884}, {150350000, 97568.6491884964}, + {150360000, 97569.3577804143}, {150370000, 97570.0772355164}, + {150380000, 97570.8034767802}, {150390000, 97571.5341251007}, + {150400000, 97572.2623865975}, {150410000, 97572.9875858382}, + {150420000, 97573.7164382325}, {150430000, 97574.451087138}, + {150440000, 97575.1845384549}, {150450000, 97575.9065970095}, + {150460000, 97576.6169235705}, {150470000, 97577.32915321}, + {150480000, 97578.047600079}, {150490000, 97578.766981325}, + {150500000, 97579.4832127561}, {150510000, 97580.198454046}, + {150520000, 97580.9189312164}, {150530000, 97581.6452502828}, + {150540000, 97582.3706080488}, {150550000, 97583.0928191008}, + {150560000, 97583.8150813179}, {150570000, 97584.5420550412}, + {150580000, 97585.273963835}, {150590000, 97586.0050094873}, + {150600000, 97586.7329333301}, {150610000, 97587.4627739335}, + {150620000, 97588.1984235077}, {150630000, 97588.935479808}, + {150640000, 97589.6612925928}, {150650000, 97590.3746385675}, + {150660000, 97591.0890423023}, {150670000, 97591.8088448851}, + {150680000, 97592.5379043785}, {150690000, 97593.2818645303}, + {150700000, 97594.0391494431}, {150710000, 97594.7885780439}, + {150720000, 97595.5255573546}, {150730000, 97596.2601275306}, + {150740000, 97597.0000608119}, {150750000, 97597.7410460995}, + {150760000, 97598.4706768142}, {150770000, 97599.1877041405}, + {150780000, 97599.8986359917}, {150790000, 97600.6055835693}, + {150800000, 97601.3156041034}, {150810000, 97602.0389891123}, + {150820000, 97602.7760865681}, {150830000, 97603.5144684306}, + {150840000, 97604.2501921926}, {150850000, 97604.9774051799}, + {150860000, 97605.6915932968}, {150870000, 97606.3994122059}, + {150880000, 97607.1199942887}, {150890000, 97607.8552690844}, + {150900000, 97608.5920439728}, {150910000, 97609.3260696898}, + {150920000, 97610.0606120003}, {150930000, 97610.8004354609}, + {150940000, 97611.5452308591}, {150950000, 97612.2883047738}, + {150960000, 97613.0281584786}, {150970000, 97613.7592377042}, + {150980000, 97614.4772540098}, {150990000, 97615.1888819377}, + {151000000, 97615.9132846635}, {151010000, 97616.6523911641}, + {151020000, 97617.3929835803}, {151030000, 97618.1308076693}, + {151040000, 97618.8728569914}, {151050000, 97619.6293419813}, + {151060000, 97620.3977473261}, {151070000, 97621.1496446442}, + {151080000, 97621.8796403051}, {151090000, 97622.6028486586}, + {151100000, 97623.3309734606}, {151110000, 97624.0620660648}, + {151120000, 97624.790542162}, {151130000, 97625.5159070276}, + {151140000, 97626.2520893059}, {151150000, 97627.003530203}, + {151160000, 97627.7596413189}, {151170000, 97628.504989553}, + {151180000, 97629.2388101514}, {151190000, 97629.9744209226}, + {151200000, 97630.7162728396}, {151210000, 97631.4536973178}, + {151220000, 97632.1784332962}, {151230000, 97632.8948200854}, + {151240000, 97633.6152917476}, {151250000, 97634.3411851531}, + {151260000, 97635.0731210682}, {151270000, 97635.8112788067}, + {151280000, 97636.5552860296}, {151290000, 97637.3046132453}, + {151300000, 97638.0592073477}, {151310000, 97638.8205056331}, + {151320000, 97639.5890483113}, {151330000, 97640.353570662}, + {151340000, 97641.1053492926}, {151350000, 97641.8487010446}, + {151360000, 97642.5959793501}, {151370000, 97643.3485124154}, + {151380000, 97644.1069584656}, {151390000, 97644.8715093026}, + {151400000, 97645.6384313475}, {151410000, 97646.402279616}, + {151420000, 97647.1627803329}, {151430000, 97647.9196173013}, + {151440000, 97648.6726975434}, {151450000, 97649.4273328507}, + {151460000, 97650.1876370474}, {151470000, 97650.9492172242}, + {151480000, 97651.6994177966}, {151490000, 97652.4370588623}, + {151500000, 97653.1828037054}, {151510000, 97653.9432725669}, + {151520000, 97654.7114931307}, {151530000, 97655.4773048398}, + {151540000, 97656.2395055089}, {151550000, 97656.9900242331}, + {151560000, 97657.7271245637}, {151570000, 97658.4613606169}, + {151580000, 97659.2009128135}, {151590000, 97659.9459700751}, + {151600000, 97660.6971293039}, {151610000, 97661.4544283979}, + {151620000, 97662.2178629636}, {151630000, 97662.987410887}, + {151640000, 97663.7559583878}, {151650000, 97664.5131179985}, + {151660000, 97665.2583935195}, {151670000, 97666.0048571657}, + {151680000, 97666.7575883441}, {151690000, 97667.5111944804}, + {151700000, 97668.2614964783}, {151710000, 97669.0084068233}, + {151720000, 97669.7516410451}, {151730000, 97670.4912838532}, + {151740000, 97671.2415467102}, {151750000, 97672.0069657476}, + {151760000, 97672.7803763796}, {151770000, 97673.551337921}, + {151780000, 97674.3193091445}, {151790000, 97675.0761845698}, + {151800000, 97675.8188414512}, {151810000, 97676.5582608149}, + {151820000, 97677.3029542607}, {151830000, 97678.0508730029}, + {151840000, 97678.7961395712}, {151850000, 97679.5381748392}, + {151860000, 97680.2837796319}, {151870000, 97681.0351297976}, + {151880000, 97681.7886503277}, {151890000, 97682.5391226606}, + {151900000, 97683.2862843672}, {151910000, 97684.0220955367}, + {151920000, 97684.7438988092}, {151930000, 97685.4626090068}, + {151940000, 97686.1866965738}, {151950000, 97686.9185900583}, + {151960000, 97687.6653752044}, {151970000, 97688.4277101079}, + {151980000, 97689.1987929877}, {151990000, 97689.9764045345}, + {152000000, 97690.7532617298}, {152010000, 97691.5187212106}, + {152020000, 97692.2722722093}, {152030000, 97693.0270285384}, + {152040000, 97693.7879927764}, {152050000, 97694.5444945254}, + {152060000, 97695.2882612547}, {152070000, 97696.0236052462}, + {152080000, 97696.7628970399}, {152090000, 97697.5074683764}, + {152100000, 97698.2580006963}, {152110000, 97699.0146932745}, + {152120000, 97699.7669674108}, {152130000, 97700.4993556878}, + {152140000, 97701.2112075615}, {152150000, 97701.9146130894}, + {152160000, 97702.6135006186}, {152170000, 97703.3243363531}, + {152180000, 97704.0598962564}, {152190000, 97704.8114547059}, + {152200000, 97705.5539708134}, {152210000, 97706.2849473541}, + {152220000, 97707.0314486008}, {152230000, 97707.8021353689}, + {152240000, 97708.5791513745}, {152250000, 97709.3364206527}, + {152260000, 97710.0755022069}, {152270000, 97710.8238254942}, + {152280000, 97711.5866603519}, {152290000, 97712.3541937204}, + {152300000, 97713.11880807}, {152310000, 97713.8825403268}, + {152320000, 97714.6512703486}, {152330000, 97715.4255705753}, + {152340000, 97716.1986647677}, {152350000, 97716.968373834}, + {152360000, 97717.7311491839}, {152370000, 97718.4817849549}, + {152380000, 97719.2200617934}, {152390000, 97719.9675495141}, + {152400000, 97720.7314707287}, {152410000, 97721.4903632792}, + {152420000, 97722.2275633516}, {152430000, 97722.9516649446}, + {152440000, 97723.6873866767}, {152450000, 97724.4372779314}, + {152460000, 97725.1884768509}, {152470000, 97725.93683822}, + {152480000, 97726.6854611786}, {152490000, 97727.43887866}, + {152500000, 97728.1973200542}, {152510000, 97728.9622984988}, + {152520000, 97729.7342782408}, {152530000, 97730.5074231363}, + {152540000, 97731.27719907}, {152550000, 97732.0390399265}, + {152560000, 97732.7796708131}, {152570000, 97733.4978789597}, + {152580000, 97734.2143627134}, {152590000, 97734.9357964547}, + {152600000, 97735.6623802314}, {152610000, 97736.3944186685}, + {152620000, 97737.1319610895}, {152630000, 97737.8840105537}, + {152640000, 97738.6534201448}, {152650000, 97739.4182093259}, + {152660000, 97740.1612903842}, {152670000, 97740.8912651711}, + {152680000, 97741.6328749311}, {152690000, 97742.3886734042}, + {152700000, 97743.1457520718}, {152710000, 97743.8999477679}, + {152720000, 97744.6472770383}, {152730000, 97745.3818982138}, + {152740000, 97746.1051297441}, {152750000, 97746.8311528293}, + {152760000, 97747.5625713987}, {152770000, 97748.2945409735}, + {152780000, 97749.0232983211}, {152790000, 97749.7509971077}, + {152800000, 97750.4838529818}, {152810000, 97751.222474112}, + {152820000, 97751.9600710588}, {152830000, 97752.6944598638}, + {152840000, 97753.4288488249}, {152850000, 97754.1679340506}, + {152860000, 97754.9119434137}, {152870000, 97755.6625637029}, + {152880000, 97756.4204175564}, {152890000, 97757.1848942979}, + {152900000, 97757.95551183}, {152910000, 97758.725533972}, + {152920000, 97759.4754824648}, {152930000, 97760.2035093326}, + {152940000, 97760.937008617}, {152950000, 97761.6847876365}, + {152960000, 97762.4400579102}, {152970000, 97763.1929004801}, + {152980000, 97763.9427986758}, {152990000, 97764.6967401177}, + {153000000, 97765.457458003}, {153010000, 97766.2245732118}, + {153020000, 97766.9977836288}, {153030000, 97767.7748307905}, + {153040000, 97768.5492145484}, {153050000, 97769.3202370094}, + {153060000, 97770.0875488217}, {153070000, 97770.8510498597}, + {153080000, 97771.6039601785}, {153090000, 97772.3363308302}, + {153100000, 97773.0477290477}, {153110000, 97773.7659027818}, + {153120000, 97774.5001749861}, {153130000, 97775.2399286884}, + {153140000, 97775.9769018295}, {153150000, 97776.7153641132}, + {153160000, 97777.467687529}, {153170000, 97778.2350697199}, + {153180000, 97779.0039515904}, {153190000, 97779.7699564583}, + {153200000, 97780.536336582}, {153210000, 97781.3078532978}, + {153220000, 97782.0835431654}, {153230000, 97782.8492783268}, + {153240000, 97783.6019976318}, {153250000, 97784.3572704666}, + {153260000, 97785.1272012862}, {153270000, 97785.9053476301}, + {153280000, 97786.6731184925}, {153290000, 97787.4286207845}, + {153300000, 97788.1851064638}, {153310000, 97788.946844816}, + {153320000, 97789.710441578}, {153330000, 97790.470928419}, + {153340000, 97791.2287873301}, {153350000, 97791.9910818482}, + {153360000, 97792.7591639465}, {153370000, 97793.5278890626}, + {153380000, 97794.2932510512}, {153390000, 97795.0551592213}, + {153400000, 97795.8133178197}, {153410000, 97796.5677112192}, + {153420000, 97797.3183460162}, {153430000, 97798.0652370065}, + {153440000, 97798.8120528207}, {153450000, 97799.5641679481}, + {153460000, 97800.3219017663}, {153470000, 97801.0857816911}, + {153480000, 97801.8558853212}, {153490000, 97802.6321268607}, + {153500000, 97803.4144328521}, {153510000, 97804.2005436949}, + {153520000, 97804.9839476676}, {153530000, 97805.7639008706}, + {153540000, 97806.53296512}, {153550000, 97807.2887772061}, + {153560000, 97808.0349245171}, {153570000, 97808.7766399265}, + {153580000, 97809.5142234959}, {153590000, 97810.2557491847}, + {153600000, 97811.0039102677}, {153610000, 97811.7584231997}, + {153620000, 97812.5190603271}, {153630000, 97813.2858025984}, + {153640000, 97814.0586530364}, {153650000, 97814.8374511901}, + {153660000, 97815.6008993565}, {153670000, 97816.342177628}, + {153680000, 97817.0750840433}, {153690000, 97817.8198134672}, + {153700000, 97818.5773151518}, {153710000, 97819.3358128288}, + {153720000, 97820.0915017249}, {153730000, 97820.8491658868}, + {153740000, 97821.6125279294}, {153750000, 97822.3816610758}, + {153760000, 97823.1568340236}, {153770000, 97823.9379157796}, + {153780000, 97824.7036312011}, {153790000, 97825.4471677147}, + {153800000, 97826.1862618144}, {153810000, 97826.9469105621}, + {153820000, 97827.7275408113}, {153830000, 97828.49387083}, + {153840000, 97829.2383956032}, {153850000, 97829.9866830408}, + {153860000, 97830.7586599765}, {153870000, 97831.5458283048}, + {153880000, 97832.3236765303}, {153890000, 97833.0895668819}, + {153900000, 97833.8422296757}, {153910000, 97834.581299832}, + {153920000, 97835.3105253332}, {153930000, 97836.035373905}, + {153940000, 97836.7562018495}, {153950000, 97837.4810898596}, + {153960000, 97838.2126403206}, {153970000, 97838.9506101325}, + {153980000, 97839.6948028584}, {153990000, 97840.445195165}, + {154000000, 97841.201778595}, {154010000, 97841.9644814404}, + {154020000, 97842.7261840382}, {154030000, 97843.4845909525}, + {154040000, 97844.2361036716}, {154050000, 97844.975429302}, + {154060000, 97845.7023995754}, {154070000, 97846.4232528962}, + {154080000, 97847.1399984661}, {154090000, 97847.8529350403}, + {154100000, 97848.5622996211}, {154110000, 97849.2747981144}, + {154120000, 97850.0099412175}, {154130000, 97850.7696729461}, + {154140000, 97851.5407106281}, {154150000, 97852.3187305448}, + {154160000, 97853.0963049062}, {154170000, 97853.8625410676}, + {154180000, 97854.6169104018}, {154190000, 97855.3648476414}, + {154200000, 97856.1085654467}, {154210000, 97856.8483500091}, + {154220000, 97857.5844286711}, {154230000, 97858.3212704425}, + {154240000, 97859.0718491365}, {154250000, 97859.8374352819}, + {154260000, 97860.6045079137}, {154270000, 97861.3686963571}, + {154280000, 97862.1296637199}, {154290000, 97862.8869083969}, + {154300000, 97863.6404211504}, {154310000, 97864.3979514723}, + {154320000, 97865.1620919264}, {154330000, 97865.9219504504}, + {154340000, 97866.6690410032}, {154350000, 97867.4098903249}, + {154360000, 97868.1633756574}, {154370000, 97868.931460967}, + {154380000, 97869.7080458455}, {154390000, 97870.4911319498}, + {154400000, 97871.2768076375}, {154410000, 97872.0593432673}, + {154420000, 97872.8384474481}, {154430000, 97873.6062798755}, + {154440000, 97874.3597803773}, {154450000, 97875.1152330185}, + {154460000, 97875.8853450508}, {154470000, 97876.6636862467}, + {154480000, 97877.4316555448}, {154490000, 97878.1873491051}, + {154500000, 97878.9440175606}, {154510000, 97879.7059391134}, + {154520000, 97880.4697118371}, {154530000, 97881.2303473528}, + {154540000, 97881.9876270094}, {154550000, 97882.7490295228}, + {154560000, 97883.516971557}, {154570000, 97884.2806050445}, + {154580000, 97885.0314679426}, {154590000, 97885.7738558803}, + {154600000, 97886.5201665448}, {154610000, 97887.2717816986}, + {154620000, 97888.0364446543}, {154630000, 97888.816611624}, + {154640000, 97889.5948016795}, {154650000, 97890.3453546302}, + {154660000, 97891.0670451416}, {154670000, 97891.7855037023}, + {154680000, 97892.5091990542}, {154690000, 97893.2386758005}, + {154700000, 97893.9743527745}, {154710000, 97894.7162182679}, + {154720000, 97895.4642975155}, {154730000, 97896.2184816931}, + {154740000, 97896.9645757043}, {154750000, 97897.6980201396}, + {154760000, 97898.4256012561}, {154770000, 97899.1572736507}, + {154780000, 97899.8935520012}, {154790000, 97900.6363421335}, + {154800000, 97901.3862710137}, {154810000, 97902.1427855169}, + {154820000, 97902.9054468593}, {154830000, 97903.6742319814}, + {154840000, 97904.4491325232}, {154850000, 97905.2299941859}, + {154860000, 97905.9954966853}, {154870000, 97906.7388028343}, + {154880000, 97907.4735968057}, {154890000, 97908.219941716}, + {154900000, 97908.9788572864}, {154910000, 97909.7243068716}, + {154920000, 97910.4460254853}, {154930000, 97911.1706912807}, + {154940000, 97911.9191481782}, {154950000, 97912.687363738}, + {154960000, 97913.463798778}, {154970000, 97914.2470728161}, + {154980000, 97915.0223647067}, {154990000, 97915.7849089087}, + {155000000, 97916.5414650171}, {155010000, 97917.3019481682}, + {155020000, 97918.0668716978}, {155030000, 97918.8227056808}, + {155040000, 97919.5649378346}, {155050000, 97920.3147298161}, + {155060000, 97921.0886098592}, {155070000, 97921.8757833161}, + {155080000, 97922.6449805182}, {155090000, 97923.392943674}, + {155100000, 97924.1322498637}, {155110000, 97924.8669920933}, + {155120000, 97925.5975238394}, {155130000, 97926.3243543316}, + {155140000, 97927.0481017206}, {155150000, 97927.7762875001}, + {155160000, 97928.5106259324}, {155170000, 97929.2511355245}, + {155180000, 97929.9978241787}, {155190000, 97930.7506722448}, + {155200000, 97931.5096816492}, {155210000, 97932.2747437779}, + {155220000, 97933.0316638842}, {155230000, 97933.7758795108}, + {155240000, 97934.5176171731}, {155250000, 97935.2718930025}, + {155260000, 97936.0392738955}, {155270000, 97936.7998986446}, + {155280000, 97937.5474548185}, {155290000, 97938.2869662302}, + {155300000, 97939.0223672443}, {155310000, 97939.7604422955}, + {155320000, 97940.5209501538}, {155330000, 97941.3057900141}, + {155340000, 97942.0875605252}, {155350000, 97942.8574117983}, + {155360000, 97943.6150593397}, {155370000, 97944.3600562585}, + {155380000, 97945.0924382763}, {155390000, 97945.8331766947}, + {155400000, 97946.5907236807}, {155410000, 97947.3487459236}, + {155420000, 97948.0944640495}, {155430000, 97948.8342882672}, + {155440000, 97949.5868295971}, {155450000, 97950.3539468693}, + {155460000, 97951.11531361}, {155470000, 97951.8643766179}, + {155480000, 97952.6043568893}, {155490000, 97953.3399683932}, + {155500000, 97954.0721160886}, {155510000, 97954.808568068}, + {155520000, 97955.5510442335}, {155530000, 97956.2996392189}, + {155540000, 97957.0544205424}, {155550000, 97957.8109158941}, + {155560000, 97958.55611759}, {155570000, 97959.2887740145}, + {155580000, 97960.0295168622}, {155590000, 97960.7849901634}, + {155600000, 97961.5518571661}, {155610000, 97962.325239219}, + {155620000, 97963.1036171275}, {155630000, 97963.8722235477}, + {155640000, 97964.6278295856}, {155650000, 97965.3753774485}, + {155660000, 97966.1187424131}, {155670000, 97966.8580484681}, + {155680000, 97967.5936176855}, {155690000, 97968.3255413946}, + {155700000, 97969.0609383318}, {155710000, 97969.802100318}, + {155720000, 97970.5491538252}, {155730000, 97971.3022988296}, + {155740000, 97972.0607209096}, {155750000, 97972.8171909533}, + {155760000, 97973.5703788825}, {155770000, 97974.3253251207}, + {155780000, 97975.0859713243}, {155790000, 97975.8501716025}, + {155800000, 97976.6117108966}, {155810000, 97977.36992086}, + {155820000, 97978.1244890961}, {155830000, 97978.8753265423}, + {155840000, 97979.6190478412}, {155850000, 97980.350654332}, + {155860000, 97981.0699392737}, {155870000, 97981.8063525733}, + {155880000, 97982.569576312}, {155890000, 97983.337904234}, + {155900000, 97984.0943483429}, {155910000, 97984.8429841814}, + {155920000, 97985.5956199288}, {155930000, 97986.3533831833}, + {155940000, 97987.0885429522}, {155950000, 97987.7921889492}, + {155960000, 97988.485017723}, {155970000, 97989.197459083}, + {155980000, 97989.9310588493}, {155990000, 97990.6606656309}, + {156000000, 97991.3777363252}, {156010000, 97992.0923676782}, + {156020000, 97992.8124617895}, {156030000, 97993.5381977645}, + {156040000, 97994.2701514066}, {156050000, 97995.0083185979}, + {156060000, 97995.7456046001}, {156070000, 97996.4797166341}, + {156080000, 97997.2071271653}, {156090000, 97997.9226293043}, + {156100000, 97998.6259988911}, {156110000, 97999.3380865363}, + {156120000, 98000.0670944772}, {156130000, 98000.8072796073}, + {156140000, 98001.5541312981}, {156150000, 98002.3053024416}, + {156160000, 98003.0539909911}, {156170000, 98003.7994629361}, + {156180000, 98004.5413561853}, {156190000, 98005.279565438}, + {156200000, 98006.0107003054}, {156210000, 98006.7297548219}, + {156220000, 98007.4366305644}, {156230000, 98008.1530097232}, + {156240000, 98008.8858848138}, {156250000, 98009.6191846474}, + {156260000, 98010.3403196692}, {156270000, 98011.0534704473}, + {156280000, 98011.7707496975}, {156290000, 98012.4933893527}, + {156300000, 98013.2078456652}, {156310000, 98013.909760451}, + {156320000, 98014.6093389778}, {156330000, 98015.3215930498}, + {156340000, 98016.0472099255}, {156350000, 98016.774126407}, + {156360000, 98017.4984271265}, {156370000, 98018.2195784126}, + {156380000, 98018.9371655642}, {156390000, 98019.6534265889}, + {156400000, 98020.374882281}, {156410000, 98021.1021858283}, + {156420000, 98021.8285364098}, {156430000, 98022.5517349998}, + {156440000, 98023.2750308507}, {156450000, 98024.0032055756}, + {156460000, 98024.7364352749}, {156470000, 98025.4685022926}, + {156480000, 98026.197430173}, {156490000, 98026.9282504138}, + {156500000, 98027.6649071583}, {156510000, 98028.4008175818}, + {156520000, 98029.1167567441}, {156530000, 98029.8108592796}, + {156540000, 98030.5105607971}, {156550000, 98031.2247266163}, + {156560000, 98031.9465947813}, {156570000, 98032.6662244802}, + {156580000, 98033.3830900726}, {156590000, 98034.1116388253}, + {156600000, 98034.8575793589}, {156610000, 98035.6096029204}, + {156620000, 98036.3588337683}, {156630000, 98037.1028560319}, + {156640000, 98037.8345666337}, {156650000, 98038.5533896955}, + {156660000, 98039.2873492244}, {156670000, 98040.0454755718}, + {156680000, 98040.8137263462}, {156690000, 98041.5714436415}, + {156700000, 98042.3180322119}, {156710000, 98043.0592289384}, + {156720000, 98043.796328125}, {156730000, 98044.5401061012}, + {156740000, 98045.2990075557}, {156750000, 98046.0643212281}, + {156760000, 98046.8106775245}, {156770000, 98047.5354542269}, + {156780000, 98048.2515555582}, {156790000, 98048.9631923451}, + {156800000, 98049.674121281}, {156810000, 98050.3898736683}, + {156820000, 98051.1106695037}, {156830000, 98051.8303491434}, + {156840000, 98052.5469515672}, {156850000, 98053.2655072236}, + {156860000, 98053.9899593686}, {156870000, 98054.7203738409}, + {156880000, 98055.4570007062}, {156890000, 98056.199805399}, + {156900000, 98056.9416956546}, {156910000, 98057.6803729534}, + {156920000, 98058.4192551577}, {156930000, 98059.1633767128}, + {156940000, 98059.9124616016}, {156950000, 98060.6598197597}, + {156960000, 98061.4039360838}, {156970000, 98062.1498462679}, + {156980000, 98062.9015026682}, {156990000, 98063.6567669828}, + {157000000, 98064.4094315061}, {157010000, 98065.1588273676}, + {157020000, 98065.9046170424}, {157030000, 98066.6467032832}, + {157040000, 98067.3887262839}, {157050000, 98068.1360520603}, + {157060000, 98068.8874968687}, {157070000, 98069.6289089664}, + {157080000, 98070.3575589222}, {157090000, 98071.0783315083}, + {157100000, 98071.7950707399}, {157110000, 98072.5101022279}, + {157120000, 98073.230207198}, {157130000, 98073.9561068246}, + {157140000, 98074.6881623975}, {157150000, 98075.4264703819}, + {157160000, 98076.1673144641}, {157170000, 98076.9052223566}, + {157180000, 98077.6399121958}, {157190000, 98078.3633478188}, + {157200000, 98079.07284105}, {157210000, 98079.7739743163}, + {157220000, 98080.4711399684}, {157230000, 98081.1688962053}, + {157240000, 98081.8805722883}, {157250000, 98082.6074607136}, + {157260000, 98083.32891997}, {157270000, 98084.038274533}, + {157280000, 98084.7454391953}, {157290000, 98085.4650374724}, + {157300000, 98086.1978024012}, {157310000, 98086.9324322022}, + {157320000, 98087.6644281915}, {157330000, 98088.3985161482}, + {157340000, 98089.1384092846}, {157350000, 98089.8797571102}, + {157360000, 98090.6098572569}, {157370000, 98091.3275096632}, + {157380000, 98092.0604299881}, {157390000, 98092.8175547333}, + {157400000, 98093.5782444804}, {157410000, 98094.3120823327}, + {157420000, 98095.0175512665}, {157430000, 98095.7275033239}, + {157440000, 98096.4531527457}, {157450000, 98097.189439826}, + {157460000, 98097.9323802819}, {157470000, 98098.6796393373}, + {157480000, 98099.4244342075}, {157490000, 98100.1659962445}, + {157500000, 98100.8968649738}, {157510000, 98101.6146570102}, + {157520000, 98102.3265232759}, {157530000, 98103.0430003345}, + {157540000, 98103.7647251133}, {157550000, 98104.492748669}, + {157560000, 98105.2272808736}, {157570000, 98105.9576478255}, + {157580000, 98106.6754620751}, {157590000, 98107.3849645356}, + {157600000, 98108.0985319631}, {157610000, 98108.8175066598}, + {157620000, 98109.5425560104}, {157630000, 98110.2738765067}, + {157640000, 98111.0044205208}, {157650000, 98111.7237692797}, + {157660000, 98112.431409468}, {157670000, 98113.1478377576}, + {157680000, 98113.881188436}, {157690000, 98114.6204508204}, + {157700000, 98115.3569516269}, {157710000, 98116.0927108094}, + {157720000, 98116.8336327935}, {157730000, 98117.5802735145}, + {157740000, 98118.3187477395}, {157750000, 98119.0445768575}, + {157760000, 98119.7678467306}, {157770000, 98120.5034323897}, + {157780000, 98121.2520810436}, {157790000, 98122.0024940816}, + {157800000, 98122.7501941589}, {157810000, 98123.4946467421}, + {157820000, 98124.2354349808}, {157830000, 98124.9725657489}, + {157840000, 98125.706023751}, {157850000, 98126.435823616}, + {157860000, 98127.1619835889}, {157870000, 98127.8845218239}, + {157880000, 98128.6068359486}, {157890000, 98129.333938456}, + {157900000, 98130.0660781255}, {157910000, 98130.80488601}, + {157920000, 98131.550894193}, {157930000, 98132.2982702588}, + {157940000, 98133.0424217613}, {157950000, 98133.7832510336}, + {157960000, 98134.520438831}, {157970000, 98135.2539355115}, + {157980000, 98135.9766471391}, {157990000, 98136.6863027985}, + {158000000, 98137.3965208175}, {158010000, 98138.1274135563}, + {158020000, 98138.879974335}, {158030000, 98139.6294947522}, + {158040000, 98140.3663478246}, {158050000, 98141.1006218981}, + {158060000, 98141.8402607615}, {158070000, 98142.5810198002}, + {158080000, 98143.3104721865}, {158090000, 98144.027372735}, + {158100000, 98144.7452747856}, {158110000, 98145.4685733236}, + {158120000, 98146.1939051382}, {158130000, 98146.9163084839}, + {158140000, 98147.6355549646}, {158150000, 98148.3590939695}, + {158160000, 98149.0893408213}, {158170000, 98149.8155076469}, + {158180000, 98150.5291069581}, {158190000, 98151.2366133812}, + {158200000, 98151.9569399515}, {158210000, 98152.6920395004}, + {158220000, 98153.4286896424}, {158230000, 98154.1625911194}, + {158240000, 98154.8897781402}, {158250000, 98155.6043779688}, + {158260000, 98156.3068274343}, {158270000, 98157.0039648606}, + {158280000, 98157.6971483329}, {158290000, 98158.3971877258}, + {158300000, 98159.1125849537}, {158310000, 98159.8412703451}, + {158320000, 98160.577308188}, {158330000, 98161.3199825177}, + {158340000, 98162.0618821634}, {158350000, 98162.8006011676}, + {158360000, 98163.5292248943}, {158370000, 98164.2375177082}, + {158380000, 98164.9250203423}, {158390000, 98165.6192819999}, + {158400000, 98166.3297266925}, {158410000, 98167.0510904536}, + {158420000, 98167.7792133527}, {158430000, 98168.5117619476}, + {158440000, 98169.2419248409}, {158450000, 98169.9689971206}, + {158460000, 98170.6997016023}, {158470000, 98171.4362093574}, + {158480000, 98172.1749856002}, {158490000, 98172.9108111602}, + {158500000, 98173.6434819111}, {158510000, 98174.3881515692}, + {158520000, 98175.1497082154}, {158530000, 98175.9223617553}, + {158540000, 98176.7015374255}, {158550000, 98177.4804710164}, + {158560000, 98178.2393394943}, {158570000, 98178.9761888051}, + {158580000, 98179.7184244735}, {158590000, 98180.4749285111}, + {158600000, 98181.2423491021}, {158610000, 98182.0157584585}, + {158620000, 98182.7947866873}, {158630000, 98183.5649143969}, + {158640000, 98184.321464196}, {158650000, 98185.0696835259}, + {158660000, 98185.8137166085}, {158670000, 98186.5536868849}, + {158680000, 98187.2899170298}, {158690000, 98188.0225204257}, + {158700000, 98188.7657010736}, {158710000, 98189.5240429564}, + {158720000, 98190.2904831449}, {158730000, 98191.0546017388}, + {158740000, 98191.8149711078}, {158750000, 98192.5636101248}, + {158760000, 98193.2990731211}, {158770000, 98194.0369501186}, + {158780000, 98194.7895253301}, {158790000, 98195.5548524456}, + {158800000, 98196.3273451912}, {158810000, 98197.106326201}, + {158820000, 98197.8843596693}, {158830000, 98198.6590322129}, + {158840000, 98199.4268143351}, {158850000, 98200.1824725063}, + {158860000, 98200.9257795294}, {158870000, 98201.6626016498}, + {158880000, 98202.3952261591}, {158890000, 98203.1239566201}, + {158900000, 98203.8490363132}, {158910000, 98204.57048724}, + {158920000, 98205.2883386834}, {158930000, 98206.0027057503}, + {158940000, 98206.7348864644}, {158950000, 98207.4917426519}, + {158960000, 98208.2592741575}, {158970000, 98209.0167953069}, + {158980000, 98209.7632272982}, {158990000, 98210.5035245162}, + {159000000, 98211.2396778623}, {159010000, 98211.977227462}, + {159020000, 98212.720548765}, {159030000, 98213.469715457}, + {159040000, 98214.2250009049}, {159050000, 98214.9863442127}, + {159060000, 98215.7395790263}, {159070000, 98216.480128649}, + {159080000, 98217.2113762912}, {159090000, 98217.9383044327}, + {159100000, 98218.6612046532}, {159110000, 98219.3880563779}, + {159120000, 98220.1215870043}, {159130000, 98220.8615307959}, + {159140000, 98221.6076714467}, {159150000, 98222.3577842832}, + {159160000, 98223.1053730004}, {159170000, 98223.849734843}, + {159180000, 98224.5905199794}, {159190000, 98225.3276266439}, + {159200000, 98226.0646470192}, {159210000, 98226.8068951098}, + {159220000, 98227.5546977295}, {159230000, 98228.308786396}, + {159240000, 98229.0692998146}, {159250000, 98229.8307968416}, + {159260000, 98230.5889830008}, {159270000, 98231.3415671625}, + {159280000, 98232.0817645852}, {159290000, 98232.8089458561}, + {159300000, 98233.5369454035}, {159310000, 98234.27025978}, + {159320000, 98235.0055476575}, {159330000, 98235.7378707227}, + {159340000, 98236.4669425798}, {159350000, 98237.1924715613}, + {159360000, 98237.9144147797}, {159370000, 98238.643304179}, + {159380000, 98239.3874532101}, {159390000, 98240.1425984586}, + {159400000, 98240.8962873523}, {159410000, 98241.6471561835}, + {159420000, 98242.3945482798}, {159430000, 98243.138261379}, + {159440000, 98243.8819187778}, {159450000, 98244.6308853456}, + {159460000, 98245.383987186}, {159470000, 98246.1270499223}, + {159480000, 98246.8573270097}, {159490000, 98247.5902059209}, + {159500000, 98248.3378406008}, {159510000, 98249.0960738288}, + {159520000, 98249.8527819951}, {159530000, 98250.6066387202}, + {159540000, 98251.3569995039}, {159550000, 98252.1036664759}, + {159560000, 98252.8466391239}, {159570000, 98253.5859077206}, + {159580000, 98254.3214891996}, {159590000, 98255.0611009805}, + {159600000, 98255.807380225}, {159610000, 98256.5547832935}, + {159620000, 98257.2989293709}, {159630000, 98258.0419353263}, + {159640000, 98258.7900160618}, {159650000, 98259.5438029521}, + {159660000, 98260.2965111659}, {159670000, 98261.0459361369}, + {159680000, 98261.7919168098}, {159690000, 98262.5342063253}, + {159700000, 98263.2728085718}, {159710000, 98264.0077306964}, + {159720000, 98264.7389873815}, {159730000, 98265.4718549304}, + {159740000, 98266.2105001436}, {159750000, 98266.955007919}, + {159760000, 98267.7056851424}, {159770000, 98268.4624792713}, + {159780000, 98269.2111884482}, {159790000, 98269.9472176804}, + {159800000, 98270.6739394047}, {159810000, 98271.3963245192}, + {159820000, 98272.1146911092}, {159830000, 98272.8293848564}, + {159840000, 98273.5404971663}, {159850000, 98274.2585803934}, + {159860000, 98274.991964088}, {159870000, 98275.7363820946}, + {159880000, 98276.4793946608}, {159890000, 98277.2196402542}, + {159900000, 98277.9564620491}, {159910000, 98278.689657766}, + {159920000, 98279.4158415382}, {159930000, 98280.1299828519}, + {159940000, 98280.8319390383}, {159950000, 98281.5511208294}, + {159960000, 98282.2971046822}, {159970000, 98283.0536076651}, + {159980000, 98283.8077341043}, {159990000, 98284.556978126}, + {160000000, 98285.2939219569}, {160010000, 98286.0178929338}, + {160020000, 98286.7498346193}, {160030000, 98287.4965365401}, + {160040000, 98288.2375065317}, {160050000, 98288.9423879532}, + {160060000, 98289.6100705833}, {160070000, 98290.2879736603}, + {160080000, 98290.9912586791}, {160090000, 98291.7045189507}, + {160100000, 98292.4155527416}, {160110000, 98293.1284688432}, + {160120000, 98293.8554204566}, {160130000, 98294.5976010158}, + {160140000, 98295.3343335529}, {160150000, 98296.058900367}, + {160160000, 98296.7711923439}, {160170000, 98297.4710177365}, + {160180000, 98298.1584248246}, {160190000, 98298.8543107522}, + {160200000, 98299.5672339483}, {160210000, 98300.2861925844}, + {160220000, 98301.0024745828}, {160230000, 98301.7180888497}, + {160240000, 98302.4389471347}, {160250000, 98303.1656489494}, + {160260000, 98303.891409013}, {160270000, 98304.6140200305}, + {160280000, 98305.340066763}, {160290000, 98306.0793191932}, + {160300000, 98306.8322491414}, {160310000, 98307.5866576017}, + {160320000, 98308.3383371681}, {160330000, 98309.0815010712}, + {160340000, 98309.8115732352}, {160350000, 98310.5328981009}, + {160360000, 98311.2581889383}, {160370000, 98311.9888548248}, + {160380000, 98312.7326597487}, {160390000, 98313.4920889237}, + {160400000, 98314.2532286913}, {160410000, 98314.995438588}, + {160420000, 98315.7176775066}, {160430000, 98316.4459112033}, + {160440000, 98317.1905411074}, {160450000, 98317.9408267735}, + {160460000, 98318.6882633483}, {160470000, 98319.4326681615}, + {160480000, 98320.1734734137}, {160490000, 98320.9106325767}, + {160500000, 98321.6441271531}, {160510000, 98322.37396341}, + {160520000, 98323.1001595934}, {160530000, 98323.8227338582}, + {160540000, 98324.541763468}, {160550000, 98325.2804676843}, + {160560000, 98326.0463866283}, {160570000, 98326.8229688423}, + {160580000, 98327.597090136}, {160590000, 98328.3684526515}, + {160600000, 98329.1361507717}, {160610000, 98329.9001010085}, + {160620000, 98330.6602610237}, {160630000, 98331.416629725}, + {160640000, 98332.1624777581}, {160650000, 98332.8877945414}, + {160660000, 98333.5921286345}, {160670000, 98334.303244377}, + {160680000, 98335.0304702218}, {160690000, 98335.7685219795}, + {160700000, 98336.513202102}, {160710000, 98337.2621965151}, + {160720000, 98338.0087216996}, {160730000, 98338.7520972108}, + {160740000, 98339.5061417303}, {160750000, 98340.2753212072}, + {160760000, 98341.0458351034}, {160770000, 98341.7972098787}, + {160780000, 98342.5284145533}, {160790000, 98343.2662350604}, + {160800000, 98344.0201456216}, {160810000, 98344.7795886005}, + {160820000, 98345.5361531388}, {160830000, 98346.2852658245}, + {160840000, 98347.0133126393}, {160850000, 98347.71901792}, + {160860000, 98348.4372160194}, {160870000, 98349.1792212694}, + {160880000, 98349.9314196464}, {160890000, 98350.6736360574}, + {160900000, 98351.4048127087}, {160910000, 98352.1374033877}, + {160920000, 98352.8764085413}, {160930000, 98353.6164441412}, + {160940000, 98354.3532434939}, {160950000, 98355.0845189522}, + {160960000, 98355.8034685563}, {160970000, 98356.5094512075}, + {160980000, 98357.2163601237}, {160990000, 98357.9287214779}, + {161000000, 98358.6431812989}, {161010000, 98359.3547682097}, + {161020000, 98360.0632235052}, {161030000, 98360.7759420371}, + {161040000, 98361.4954614613}, {161050000, 98362.2110082951}, + {161060000, 98362.9140405821}, {161070000, 98363.6109922186}, + {161080000, 98364.3208051015}, {161090000, 98365.0454077826}, + {161100000, 98365.7574121183}, {161110000, 98366.4479252051}, + {161120000, 98367.1307926976}, {161130000, 98367.8265578312}, + {161140000, 98368.5358821929}, {161150000, 98369.2535170081}, + {161160000, 98369.9782340437}, {161170000, 98370.709585297}, + {161180000, 98371.447208684}, {161190000, 98372.1888811158}, + {161200000, 98372.928076766}, {161210000, 98373.6640877279}, + {161220000, 98374.3965762935}, {161230000, 98375.1254441797}, + {161240000, 98375.8540974093}, {161250000, 98376.5875936987}, + {161260000, 98377.3260918559}, {161270000, 98378.0556282622}, + {161280000, 98378.7717387367}, {161290000, 98379.4954468828}, + {161300000, 98380.2434218125}, {161310000, 98381.0093788683}, + {161320000, 98381.7749337368}, {161330000, 98382.5380883403}, + {161340000, 98383.3049393573}, {161350000, 98384.0774633832}, + {161360000, 98384.8487907238}, {161370000, 98385.6087163384}, + {161380000, 98386.3567340984}, {161390000, 98387.1057363882}, + {161400000, 98387.8610413732}, {161410000, 98388.6172849077}, + {161420000, 98389.3702109794}, {161430000, 98390.1241104196}, + {161440000, 98390.8917126358}, {161450000, 98391.6742860571}, + {161460000, 98392.4512037302}, {161470000, 98393.2157552559}, + {161480000, 98393.9711417573}, {161490000, 98394.72209467}, + {161500000, 98395.4694452676}, {161510000, 98396.2209751027}, + {161520000, 98396.978515272}, {161530000, 98397.7473633948}, + {161540000, 98398.5317154916}, {161550000, 98399.3272158684}, + {161560000, 98400.1211100447}, {161570000, 98400.9120002457}, + {161580000, 98401.6992184337}, {161590000, 98402.4825589769}, + {161600000, 98403.2584596966}, {161610000, 98404.0216074139}, + {161620000, 98404.7723098344}, {161630000, 98405.5172852718}, + {161640000, 98406.2580607623}, {161650000, 98407.0001662162}, + {161660000, 98407.7479868429}, {161670000, 98408.5016075699}, + {161680000, 98409.2613361524}, {161690000, 98410.0271541599}, + {161700000, 98410.7919584683}, {161710000, 98411.553435145}, + {161720000, 98412.3114243861}, {161730000, 98413.0656800673}, + {161740000, 98413.8169962477}, {161750000, 98414.5727033674}, + {161760000, 98415.3341654501}, {161770000, 98416.0910642988}, + {161780000, 98416.83520973}, {161790000, 98417.5752314696}, + {161800000, 98418.3366073587}, {161810000, 98419.1219068342}, + {161820000, 98419.8898700435}, {161830000, 98420.627084747}, + {161840000, 98421.3504195133}, {161850000, 98422.0849137445}, + {161860000, 98422.8318910109}, {161870000, 98423.5799013404}, + {161880000, 98424.3251399427}, {161890000, 98425.0723601346}, + {161900000, 98425.825335035}, {161910000, 98426.5797472538}, + {161920000, 98427.3228442545}, {161930000, 98428.0533666401}, + {161940000, 98428.7990413682}, {161950000, 98429.5688698369}, + {161960000, 98430.3456866206}, {161970000, 98431.103971439}, + {161980000, 98431.8424065119}, {161990000, 98432.5799741095}, + {162000000, 98433.3232576295}, {162010000, 98434.07250315}, + {162020000, 98434.8279003734}, {162030000, 98435.5850352665}, + {162040000, 98436.330872471}, {162050000, 98437.0640494928}, + {162060000, 98437.7910311038}, {162070000, 98438.5139486552}, + {162080000, 98439.2329809943}, {162090000, 98439.9483846021}, + {162100000, 98440.6601906968}, {162110000, 98441.3833938926}, + {162120000, 98442.1240126041}, {162130000, 98442.8707987562}, + {162140000, 98443.6148020168}, {162150000, 98444.353636019}, + {162160000, 98445.080193355}, {162170000, 98445.7937857017}, + {162180000, 98446.5082534561}, {162190000, 98447.2281219803}, + {162200000, 98447.9534225544}, {162210000, 98448.6842151311}, + {162220000, 98449.4204258962}, {162230000, 98450.1478681086}, + {162240000, 98450.861943978}, {162250000, 98451.5626462875}, + {162260000, 98452.2499826946}, {162270000, 98452.9305746553}, + {162280000, 98453.6239599941}, {162290000, 98454.3322138126}, + {162300000, 98455.0492631455}, {162310000, 98455.7730944294}, + {162320000, 98456.4930929463}, {162330000, 98457.193457383}, + {162340000, 98457.8734947635}, {162350000, 98458.560697485}, + {162360000, 98459.2640278949}, {162370000, 98459.9782937885}, + {162380000, 98460.6993555155}, {162390000, 98461.4248936621}, + {162400000, 98462.1480851993}, {162410000, 98462.8681881262}, + {162420000, 98463.584839849}, {162430000, 98464.2979334658}, + {162440000, 98465.007480435}, {162450000, 98465.7134890442}, + {162460000, 98466.4160266338}, {162470000, 98467.1228109677}, + {162480000, 98467.8363154301}, {162490000, 98468.5510765986}, + {162500000, 98469.2627435782}, {162510000, 98469.973426377}, + {162520000, 98470.6893702165}, {162530000, 98471.4112002301}, + {162540000, 98472.1250007082}, {162550000, 98472.8262455968}, + {162560000, 98473.528289538}, {162570000, 98474.2510203095}, + {162580000, 98474.9954373913}, {162590000, 98475.7445386287}, + {162600000, 98476.4914576533}, {162610000, 98477.2406273457}, + {162620000, 98477.9955746502}, {162630000, 98478.7541758655}, + {162640000, 98479.5101715325}, {162650000, 98480.2628597592}, + {162660000, 98481.0048082591}, {162670000, 98481.7336248056}, + {162680000, 98482.4599695596}, {162690000, 98483.1997099676}, + {162700000, 98483.9526131759}, {162710000, 98484.7056421055}, + {162720000, 98485.455867134}, {162730000, 98486.1975695149}, + {162740000, 98486.9262048288}, {162750000, 98487.648280984}, + {162760000, 98488.3830253622}, {162770000, 98489.1324602624}, + {162780000, 98489.8833812192}, {162790000, 98490.6314661256}, + {162800000, 98491.3763940975}, {162810000, 98492.1176795029}, + {162820000, 98492.8553615205}, {162830000, 98493.5971519904}, + {162840000, 98494.3455246647}, {162850000, 98495.0897474501}, + {162860000, 98495.8212802479}, {162870000, 98496.5465483421}, + {162880000, 98497.2845370883}, {162890000, 98498.0372664756}, + {162900000, 98498.7985850565}, {162910000, 98499.5664485853}, + {162920000, 98500.3370113103}, {162930000, 98501.1045381223}, + {162940000, 98501.8681274037}, {162950000, 98502.6200239539}, + {162960000, 98503.3584928309}, {162970000, 98504.0939409612}, + {162980000, 98504.8346667707}, {162990000, 98505.5808587583}, + {163000000, 98506.3331304723}, {163010000, 98507.0914798602}, + {163020000, 98507.8417569277}, {163030000, 98508.5793624401}, + {163040000, 98509.3112508225}, {163050000, 98510.0477634398}, + {163060000, 98510.7880614736}, {163070000, 98511.5183342996}, + {163080000, 98512.2358841166}, {163090000, 98512.9403353141}, + {163100000, 98513.6314019116}, {163110000, 98514.3178916708}, + {163120000, 98515.0258692585}, {163130000, 98515.7580079805}, + {163140000, 98516.4801968393}, {163150000, 98517.1813167421}, + {163160000, 98517.8746387659}, {163170000, 98518.5799225049}, + {163180000, 98519.2982034219}, {163190000, 98520.0102174589}, + {163200000, 98520.709285755}, {163210000, 98521.405700185}, + {163220000, 98522.1076671023}, {163230000, 98522.8109850966}, + {163240000, 98523.5031817094}, {163250000, 98524.1829689569}, + {163260000, 98524.8639180092}, {163270000, 98525.5504651844}, + {163280000, 98526.2492196895}, {163290000, 98526.9700620709}, + {163300000, 98527.7134342281}, {163310000, 98528.4467697552}, + {163320000, 98529.1570114307}, {163330000, 98529.8598342624}, + {163340000, 98530.5677402615}, {163350000, 98531.2810014285}, + {163360000, 98532.0004780559}, {163370000, 98532.7262374802}, + {163380000, 98533.4582717811}, {163390000, 98534.1965573618}, + {163400000, 98534.9307013514}, {163410000, 98535.6451903123}, + {163420000, 98536.3392581073}, {163430000, 98537.0324264133}, + {163440000, 98537.7314975448}, {163450000, 98538.4367161585}, + {163460000, 98539.1482711734}, {163470000, 98539.8705201435}, + {163480000, 98540.6165189094}, {163490000, 98541.3875235893}, + {163500000, 98542.155780187}, {163510000, 98542.9122173664}, + {163520000, 98543.6633890309}, {163530000, 98544.4190499169}, + {163540000, 98545.1786244364}, {163550000, 98545.9283046517}, + {163560000, 98546.6650034836}, {163570000, 98547.3989001138}, + {163580000, 98548.1381112146}, {163590000, 98548.8806410432}, + {163600000, 98549.6205767681}, {163610000, 98550.3572759782}, + {163620000, 98551.0904254684}, {163630000, 98551.8199345696}, + {163640000, 98552.5458151621}, {163650000, 98553.2680759334}, + {163660000, 98553.9867344141}, {163670000, 98554.7092789306}, + {163680000, 98555.4387160122}, {163690000, 98556.1746914842}, + {163700000, 98556.9169162344}, {163710000, 98557.6609898271}, + {163720000, 98558.3938532687}, {163730000, 98559.1141517666}, + {163740000, 98559.8354193198}, {163750000, 98560.5620839065}, + {163760000, 98561.2941101485}, {163770000, 98562.0314586211}, + {163780000, 98562.774102074}, {163790000, 98563.5085669398}, + {163800000, 98564.2294072582}, {163810000, 98564.9576787075}, + {163820000, 98565.7101779714}, {163830000, 98566.4741013923}, + {163840000, 98567.211511974}, {163850000, 98567.9184506162}, + {163860000, 98568.635507635}, {163870000, 98569.3759390093}, + {163880000, 98570.1296717383}, {163890000, 98570.8817129643}, + {163900000, 98571.6312407565}, {163910000, 98572.3697175114}, + {163920000, 98573.0942100791}, {163930000, 98573.8154813629}, + {163940000, 98574.5421345745}, {163950000, 98575.2721685782}, + {163960000, 98575.9996698535}, {163970000, 98576.7239965194}, + {163980000, 98577.4448352062}, {163990000, 98578.1620949064}, + {164000000, 98578.8791097747}, {164010000, 98579.6008527857}, + {164020000, 98580.3275769382}, {164030000, 98581.0684925249}, + {164040000, 98581.827180784}, {164050000, 98582.5869462032}, + {164060000, 98583.3344634412}, {164070000, 98584.0694703021}, + {164080000, 98584.7910636232}, {164090000, 98585.4992409225}, + {164100000, 98586.2081724797}, {164110000, 98586.9224953191}, + {164120000, 98587.6422575464}, {164130000, 98588.3675446641}, + {164140000, 98589.0983168895}, {164150000, 98589.8203678308}, + {164160000, 98590.5290496568}, {164170000, 98591.2348348785}, + {164180000, 98591.9460943521}, {164190000, 98592.6651903681}, + {164200000, 98593.3992298088}, {164210000, 98594.1488561819}, + {164220000, 98594.8860352985}, {164230000, 98595.6016300255}, + {164240000, 98596.3095512853}, {164250000, 98597.0305310054}, + {164260000, 98597.7643567819}, {164270000, 98598.4980134245}, + {164280000, 98599.2289156366}, {164290000, 98599.9513715231}, + {164300000, 98600.6608412981}, {164310000, 98601.3638137674}, + {164320000, 98602.0795561548}, {164330000, 98602.8101093956}, + {164340000, 98603.542270796}, {164350000, 98604.2717060347}, + {164360000, 98604.9980878416}, {164370000, 98605.7209199674}, + {164380000, 98606.4401916122}, {164390000, 98607.1635622512}, + {164400000, 98607.8936780415}, {164410000, 98608.6302443538}, + {164420000, 98609.3730194295}, {164430000, 98610.1219857917}, + {164440000, 98610.8771531032}, {164450000, 98611.638459602}, + {164460000, 98612.3916931675}, {164470000, 98613.132224223}, + {164480000, 98613.8634155709}, {164490000, 98614.5902646836}, + {164500000, 98615.3130882149}, {164510000, 98616.0399483036}, + {164520000, 98616.7734742604}, {164530000, 98617.5134180163}, + {164540000, 98618.259575049}, {164550000, 98619.0119143216}, + {164560000, 98619.7704048562}, {164570000, 98620.5349630972}, + {164580000, 98621.2843486989}, {164590000, 98622.0116530453}, + {164600000, 98622.7304787497}, {164610000, 98623.4611318851}, + {164620000, 98624.204676098}, {164630000, 98624.9571106032}, + {164640000, 98625.7170932615}, {164650000, 98626.468152567}, + {164660000, 98627.1971197689}, {164670000, 98627.9103080277}, + {164680000, 98628.6263689589}, {164690000, 98629.3473849897}, + {164700000, 98630.0885473275}, {164710000, 98630.8547695471}, + {164720000, 98631.6317242742}, {164730000, 98632.3980470076}, + {164740000, 98633.1524399432}, {164750000, 98633.8934465939}, + {164760000, 98634.6208458521}, {164770000, 98635.3451583926}, + {164780000, 98636.0748039434}, {164790000, 98636.8077896595}, + {164800000, 98637.5382115565}, {164810000, 98638.2654610217}, + {164820000, 98639.0034139673}, {164830000, 98639.7565842814}, + {164840000, 98640.5146072656}, {164850000, 98641.2620064041}, + {164860000, 98641.9979720172}, {164870000, 98642.7352114281}, + {164880000, 98643.4787652742}, {164890000, 98644.2233157}, + {164900000, 98644.9646073608}, {164910000, 98645.7025551616}, + {164920000, 98646.4368723245}, {164930000, 98647.1675596378}, + {164940000, 98647.9017056033}, {164950000, 98648.6416228571}, + {164960000, 98649.3837997463}, {164970000, 98650.1229942292}, + {164980000, 98650.8589291588}, {164990000, 98651.5987989233}, + {165000000, 98652.3455170118}, {165010000, 98653.0934776278}, + {165020000, 98653.8381948283}, {165030000, 98654.5817503105}, + {165040000, 98655.3303421839}, {165050000, 98656.0846187138}, + {165060000, 98656.8378230469}, {165070000, 98657.5877417216}, + {165080000, 98658.3308760065}, {165090000, 98659.0619805315}, + {165100000, 98659.7808205696}, {165110000, 98660.5011179789}, + {165120000, 98661.2276398907}, {165130000, 98661.960403212}, + {165140000, 98662.6994154147}, {165150000, 98663.4424748523}, + {165160000, 98664.1830543601}, {165170000, 98664.9204755064}, + {165180000, 98665.6685410618}, {165190000, 98666.4317411299}, + {165200000, 98667.2066200894}, {165210000, 98667.9880432061}, + {165220000, 98668.7739198658}, {165230000, 98669.5420101908}, + {165240000, 98670.2873658914}, {165250000, 98671.0200750939}, + {165260000, 98671.7482208241}, {165270000, 98672.4763880108}, + {165280000, 98673.218253673}, {165290000, 98673.9752398367}, + {165300000, 98674.7338258553}, {165310000, 98675.4895700128}, + {165320000, 98676.2457337103}, {165330000, 98677.0071960749}, + {165340000, 98677.7720555162}, {165350000, 98678.5187598856}, + {165360000, 98679.2430849632}, {165370000, 98679.9706407335}, + {165380000, 98680.721937352}, {165390000, 98681.4908616012}, + {165400000, 98682.2593309361}, {165410000, 98683.0253456654}, + {165420000, 98683.7879304015}, {165430000, 98684.5467765681}, + {165440000, 98685.3054845119}, {165450000, 98686.0694389202}, + {165460000, 98686.8389686691}, {165470000, 98687.614583012}, + {165480000, 98688.3963587239}, {165490000, 98689.1789872795}, + {165500000, 98689.9582157829}, {165510000, 98690.7317707378}, + {165520000, 98691.4928137875}, {165530000, 98692.2406741585}, + {165540000, 98692.9892160794}, {165550000, 98693.7429863755}, + {165560000, 98694.4986564979}, {165570000, 98695.2512527076}, + {165580000, 98696.0005127034}, {165590000, 98696.7461576715}, + {165600000, 98697.4881015186}, {165610000, 98698.2367989735}, + {165620000, 98699.0006277896}, {165630000, 98699.7775579534}, + {165640000, 98700.5616571596}, {165650000, 98701.3522066568}, + {165660000, 98702.1346798706}, {165670000, 98702.9043373677}, + {165680000, 98703.6678978092}, {165690000, 98704.4353949871}, + {165700000, 98705.207297047}, {165710000, 98705.9700015288}, + {165720000, 98706.7191325165}, {165730000, 98707.4703564855}, + {165740000, 98708.2362353183}, {165750000, 98709.0126812491}, + {165760000, 98709.787530084}, {165770000, 98710.5594391178}, + {165780000, 98711.3277642564}, {165790000, 98712.0923059856}, + {165800000, 98712.8530643915}, {165810000, 98713.6100300822}, + {165820000, 98714.3626249857}, {165830000, 98715.1034482246}, + {165840000, 98715.8308790741}, {165850000, 98716.5605484642}, + {165860000, 98717.3049896307}, {165870000, 98718.062267671}, + {165880000, 98718.8267317113}, {165890000, 98719.597710569}, + {165900000, 98720.3677972593}, {165910000, 98721.1345626596}, + {165920000, 98721.8978342079}, {165930000, 98722.657344781}, + {165940000, 98723.4131086088}, {165950000, 98724.1728363214}, + {165960000, 98724.939051319}, {165970000, 98725.7062916191}, + {165980000, 98726.4701759308}, {165990000, 98727.2306162778}, + {166000000, 98727.9873151221}, {166010000, 98728.7402838656}, + {166020000, 98729.5037050155}, {166030000, 98730.2822005092}, + {166040000, 98731.0653734942}, {166050000, 98731.8376713161}, + {166060000, 98732.5983064665}, {166070000, 98733.3528819621}, + {166080000, 98734.103234727}, {166090000, 98734.8443989019}, + {166100000, 98735.5723960689}, {166110000, 98736.2936613504}, + {166120000, 98737.0275976527}, {166130000, 98737.7762963863}, + {166140000, 98738.5336202295}, {166150000, 98739.2975251539}, + {166160000, 98740.0575559298}, {166170000, 98740.798050991}, + {166180000, 98741.5182292546}, {166190000, 98742.2366022683}, + {166200000, 98742.9608820231}, {166210000, 98743.6860209228}, + {166220000, 98744.4079652461}, {166230000, 98745.1309846528}, + {166240000, 98745.8678582108}, {166250000, 98746.619914539}, + {166260000, 98747.373609356}, {166270000, 98748.1244867067}, + {166280000, 98748.8722143792}, {166290000, 98749.6162866509}, + {166300000, 98750.3566924889}, {166310000, 98751.1010990426}, + {166320000, 98751.8521861648}, {166330000, 98752.5991910899}, + {166340000, 98753.3334759419}, {166350000, 98754.0614234857}, + {166360000, 98754.8020578383}, {166370000, 98755.5574020551}, + {166380000, 98756.3142410155}, {166390000, 98757.0682305031}, + {166400000, 98757.8223471121}, {166410000, 98758.5810511952}, + {166420000, 98759.3445702373}, {166430000, 98760.1146130613}, + {166440000, 98760.8918648639}, {166450000, 98761.6652431958}, + {166460000, 98762.4258207811}, {166470000, 98763.1777753129}, + {166480000, 98763.9335917397}, {166490000, 98764.6946272968}, + {166500000, 98765.4544403237}, {166510000, 98766.2109182552}, + {166520000, 98766.9639080467}, {166530000, 98767.7131715801}, + {166540000, 98768.4587130899}, {166550000, 98769.2005399158}, + {166560000, 98769.938666865}, {166570000, 98770.6835528559}, + {166580000, 98771.4435892179}, {166590000, 98772.2145702089}, + {166600000, 98772.9840281306}, {166610000, 98773.7506016115}, + {166620000, 98774.5207283018}, {166630000, 98775.2965116635}, + {166640000, 98776.0777676029}, {166650000, 98776.8642340878}, + {166660000, 98777.6558719563}, {166670000, 98778.4386248331}, + {166680000, 98779.2077097009}, {166690000, 98779.9839962387}, + {166700000, 98780.7842549055}, {166710000, 98781.5957637443}, + {166720000, 98782.3805430389}, {166730000, 98783.1345596037}, + {166740000, 98783.8913133143}, {166750000, 98784.6618105357}, + {166760000, 98785.4395351327}, {166770000, 98786.214733113}, + {166780000, 98786.9868707197}, {166790000, 98787.7554047723}, + {166800000, 98788.5201592864}, {166810000, 98789.2863408434}, + {166820000, 98790.0581337028}, {166830000, 98790.837782795}, + {166840000, 98791.6320886853}, {166850000, 98792.4417022722}, + {166860000, 98793.2457149938}, {166870000, 98794.037275267}, + {166880000, 98794.8228563367}, {166890000, 98795.6121424168}, + {166900000, 98796.405656864}, {166910000, 98797.1904941885}, + {166920000, 98797.9614251955}, {166930000, 98798.729011894}, + {166940000, 98799.5017483987}, {166950000, 98800.2798220484}, + {166960000, 98801.0638472621}, {166970000, 98801.8538543791}, + {166980000, 98802.6427567215}, {166990000, 98803.428227721}, + {167000000, 98804.2134377702}, {167010000, 98805.0031408604}, + {167020000, 98805.7975817864}, {167030000, 98806.5830602131}, + {167040000, 98807.3548009059}, {167050000, 98808.1180526725}, + {167060000, 98808.8770432172}, {167070000, 98809.6362337025}, + {167080000, 98810.4089838756}, {167090000, 98811.1966799686}, + {167100000, 98811.9787472736}, {167110000, 98812.7484391646}, + {167120000, 98813.5089229409}, {167130000, 98814.2649253204}, + {167140000, 98815.0178788423}, {167150000, 98815.7829967619}, + {167160000, 98816.5637526285}, {167170000, 98817.3550436251}, + {167180000, 98818.1527475857}, {167190000, 98818.9567391808}, + {167200000, 98819.7667058008}, {167210000, 98820.5825522876}, + {167220000, 98821.3830060942}, {167230000, 98822.1611237339}, + {167240000, 98822.9304849343}, {167250000, 98823.7114512362}, + {167260000, 98824.5049658374}, {167270000, 98825.2838279275}, + {167280000, 98826.0392744172}, {167290000, 98826.7921456746}, + {167300000, 98827.5592182928}, {167310000, 98828.3364975054}, + {167320000, 98829.1121095153}, {167330000, 98829.8847679093}, + {167340000, 98830.6680161489}, {167350000, 98831.466272263}, + {167360000, 98832.2692031064}, {167370000, 98833.0613238422}, + {167380000, 98833.8418191145}, {167390000, 98834.6083965779}, + {167400000, 98835.3601322912}, {167410000, 98836.1133462219}, + {167420000, 98836.8811726886}, {167430000, 98837.6617089568}, + {167440000, 98838.4493504455}, {167450000, 98839.2434326608}, + {167460000, 98840.0365217182}, {167470000, 98840.8261747608}, + {167480000, 98841.6157532705}, {167490000, 98842.4103027864}, + {167500000, 98843.2089702695}, {167510000, 98843.9976468861}, + {167520000, 98844.7731714276}, {167530000, 98845.550892384}, + {167540000, 98846.34316146}, {167550000, 98847.1458776659}, + {167560000, 98847.9468511629}, {167570000, 98848.7447483454}, + {167580000, 98849.5460192738}, {167590000, 98850.3527751237}, + {167600000, 98851.1579691704}, {167610000, 98851.951020017}, + {167620000, 98852.7318964632}, {167630000, 98853.5069906418}, + {167640000, 98854.277768233}, {167650000, 98855.0549098924}, + {167660000, 98855.8470062741}, {167670000, 98856.6520404211}, + {167680000, 98857.4640880536}, {167690000, 98858.2824306244}, + {167700000, 98859.0854759982}, {167710000, 98859.8661701946}, + {167720000, 98860.6349587908}, {167730000, 98861.4074908467}, + {167740000, 98862.18474629}, {167750000, 98862.9678396446}, + {167760000, 98863.7569604539}, {167770000, 98864.5520713747}, + {167780000, 98865.3531366344}, {167790000, 98866.1579632544}, + {167800000, 98866.9600062768}, {167810000, 98867.7585620615}, + {167820000, 98868.5603744404}, {167830000, 98869.367651648}, + {167840000, 98870.1735503626}, {167850000, 98870.9677857894}, + {167860000, 98871.7498354615}, {167870000, 98872.5407491528}, + {167880000, 98873.3479604309}, {167890000, 98874.1607151263}, + {167900000, 98874.9703415838}, {167910000, 98875.7788247762}, + {167920000, 98876.5921116147}, {167930000, 98877.4108227827}, + {167940000, 98878.221062119}, {167950000, 98879.018282001}, + {167960000, 98879.8125223213}, {167970000, 98880.6188592642}, + {167980000, 98881.4380822308}, {167990000, 98882.2507418919}, + {168000000, 98883.0500286707}, {168010000, 98883.8461280888}, + {168020000, 98884.6472513147}, {168030000, 98885.4535784361}, + {168040000, 98886.2657023772}, {168050000, 98887.0836455562}, + {168060000, 98887.8932420008}, {168070000, 98888.6898548241}, + {168080000, 98889.4768370018}, {168090000, 98890.2592014937}, + {168100000, 98891.0372514432}, {168110000, 98891.8261591933}, + {168120000, 98892.6321157415}, {168130000, 98893.438759756}, + {168140000, 98894.2328895703}, {168150000, 98895.0164193501}, + {168160000, 98895.7949953631}, {168170000, 98896.5692838969}, + {168180000, 98897.3537585366}, {168190000, 98898.1531513253}, + {168200000, 98898.9638297107}, {168210000, 98899.7803601125}, + {168220000, 98900.6023939323}, {168230000, 98901.4153913793}, + {168240000, 98902.2145913477}, {168250000, 98903.0051945316}, + {168260000, 98903.7914001346}, {168270000, 98904.5754994688}, + {168280000, 98905.3643579271}, {168290000, 98906.1587075866}, + {168300000, 98906.9517927809}, {168310000, 98907.7413931435}, + {168320000, 98908.5307066131}, {168330000, 98909.3245369879}, + {168340000, 98910.1231096051}, {168350000, 98910.9125148885}, + {168360000, 98911.6882107642}, {168370000, 98912.46583779}, + {168380000, 98913.2580136119}, {168390000, 98914.060649039}, + {168400000, 98914.8615592738}, {168410000, 98915.6594072072}, + {168420000, 98916.4606304143}, {168430000, 98917.2673389889}, + {168440000, 98918.0760277241}, {168450000, 98918.881430804}, + {168460000, 98919.6832661025}, {168470000, 98920.4812261159}, + {168480000, 98921.2752239237}, {168490000, 98922.0704694531}, + {168500000, 98922.8711651182}, {168510000, 98923.675230731}, + {168520000, 98924.4764481746}, {168530000, 98925.2741400824}, + {168540000, 98926.0679950194}, {168550000, 98926.8579230032}, + {168560000, 98927.6406457006}, {168570000, 98928.411201656}, + {168580000, 98929.1693676453}, {168590000, 98929.9357335725}, + {168600000, 98930.7187611984}, {168610000, 98931.5127699357}, + {168620000, 98932.3131605779}, {168630000, 98933.1198159644}, + {168640000, 98933.9324467747}, {168650000, 98934.7509792473}, + {168660000, 98935.5611856876}, {168670000, 98936.3584054643}, + {168680000, 98937.1459779996}, {168690000, 98937.9289002646}, + {168700000, 98938.7075009318}, {168710000, 98939.4821274438}, + {168720000, 98940.2528738249}, {168730000, 98941.0301809069}, + {168740000, 98941.8224768668}, {168750000, 98942.6255776182}, + {168760000, 98943.4270010025}, {168770000, 98944.2253682748}, + {168780000, 98945.0200243079}, {168790000, 98945.8107655997}, + {168800000, 98946.6043211148}, {168810000, 98947.4108255952}, + {168820000, 98948.230673561}, {168830000, 98949.0359887307}, + {168840000, 98949.817747283}, {168850000, 98950.5967885165}, + {168860000, 98951.3899494236}, {168870000, 98952.1932363464}, + {168880000, 98952.9947333321}, {168890000, 98953.7931201847}, + {168900000, 98954.5806737681}, {168910000, 98955.3548815872}, + {168920000, 98956.1263085971}, {168930000, 98956.9108486608}, + {168940000, 98957.7083758387}, {168950000, 98958.5059052798}, + {168960000, 98959.3004119008}, {168970000, 98960.0914107213}, + {168980000, 98960.8785132549}, {168990000, 98961.6638865899}, + {169000000, 98962.4540347281}, {169010000, 98963.2496461532}, + {169020000, 98964.0369113501}, {169030000, 98964.8113043034}, + {169040000, 98965.5833292193}, {169050000, 98966.3687895849}, + {169060000, 98967.166469516}, {169070000, 98967.9556876396}, + {169080000, 98968.7323361323}, {169090000, 98969.5062241056}, + {169100000, 98970.2852781654}, {169110000, 98971.067509449}, + {169120000, 98971.8469574325}, {169130000, 98972.6229658396}, + {169140000, 98973.3881307061}, {169150000, 98974.1400466481}, + {169160000, 98974.8855819843}, {169170000, 98975.6350576863}, + {169180000, 98976.389036618}, {169190000, 98977.1417879201}, + {169200000, 98977.8912839766}, {169210000, 98978.6476867806}, + {169220000, 98979.4191989325}, {169230000, 98980.2016319478}, + {169240000, 98980.9824916048}, {169250000, 98981.760397717}, + {169260000, 98982.5346949922}, {169270000, 98983.3051790576}, + {169280000, 98984.0718502707}, {169290000, 98984.8346993115}, + {169300000, 98985.5937436268}, {169310000, 98986.3638683889}, + {169320000, 98987.1511758511}, {169330000, 98987.9392904559}, + {169340000, 98988.7149668589}, {169350000, 98989.4822830265}, + {169360000, 98990.2534417535}, {169370000, 98991.0297817588}, + {169380000, 98991.811910765}, {169390000, 98992.6000100215}, + {169400000, 98993.383760977}, {169410000, 98994.147608489}, + {169420000, 98994.8907684213}, {169430000, 98995.6327230009}, + {169440000, 98996.3803503943}, {169450000, 98997.1390911613}, + {169460000, 98997.9133352674}, {169470000, 98998.7009640117}, + {169480000, 98999.4957289101}, {169490000, 99000.2968940572}, + {169500000, 99001.0899634803}, {169510000, 99001.8701805472}, + {169520000, 99002.6514497479}, {169530000, 99003.4547196786}, + {169540000, 99004.2784052683}, {169550000, 99005.0879207968}, + {169560000, 99005.8753989354}, {169570000, 99006.6503951138}, + {169580000, 99007.4206494371}, {169590000, 99008.1885310186}, + {169600000, 99008.9611721881}, {169610000, 99009.7393452022}, + {169620000, 99010.5234247593}, {169630000, 99011.3135149146}, + {169640000, 99012.1059452619}, {169650000, 99012.8951926542}, + {169660000, 99013.6809603955}, {169670000, 99014.4703802064}, + {169680000, 99015.2663848833}, {169690000, 99016.052981617}, + {169700000, 99016.8172441655}, {169710000, 99017.5676169196}, + {169720000, 99018.3294032604}, {169730000, 99019.1053537831}, + {169740000, 99019.8825786054}, {169750000, 99020.6568198652}, + {169760000, 99021.4277661909}, {169770000, 99022.1949396406}, + {169780000, 99022.9583309458}, {169790000, 99023.7253583423}, + {169800000, 99024.4990581361}, {169810000, 99025.2790693417}, + {169820000, 99026.0650937791}, {169830000, 99026.854947001}, + {169840000, 99027.6420775297}, {169850000, 99028.4257691607}, + {169860000, 99029.2056977934}, {169870000, 99029.9817689387}, + {169880000, 99030.7473277392}, {169890000, 99031.4923222864}, + {169900000, 99032.2162821}, {169910000, 99032.9465910245}, + {169920000, 99033.692936094}, {169930000, 99034.45528138}, + {169940000, 99035.2335829323}, {169950000, 99036.0213091206}, + {169960000, 99036.7988501169}, {169970000, 99037.5640764131}, + {169980000, 99038.3301448079}, {169990000, 99039.1014003732}, + {170000000, 99039.8712269016}, {170010000, 99040.6296152657}, + {170020000, 99041.376050212}, {170030000, 99042.13100904}, + {170040000, 99042.9026591975}, {170050000, 99043.6697409731}, + {170060000, 99044.4150428347}, {170070000, 99045.1447254642}, + {170080000, 99045.8772399467}, {170090000, 99046.6146260752}, + {170100000, 99047.3578823626}, {170110000, 99048.1073189882}, + {170120000, 99048.859277121}, {170130000, 99049.6082466057}, + {170140000, 99050.3539300263}, {170150000, 99051.1037563798}, + {170160000, 99051.8601743491}, {170170000, 99052.6177148189}, + {170180000, 99053.3719479448}, {170190000, 99054.1227861893}, + {170200000, 99054.8699310525}, {170210000, 99055.613365718}, + {170220000, 99056.3530965251}, {170230000, 99057.0891379095}, + {170240000, 99057.8215082721}, {170250000, 99058.5502259222}, + {170260000, 99059.2760283768}, {170270000, 99060.0062658794}, + {170280000, 99060.7424025783}, {170290000, 99061.4846154441}, + {170300000, 99062.2330423473}, {170310000, 99062.9855082861}, + {170320000, 99063.7354567389}, {170330000, 99064.4821698962}, + {170340000, 99065.2394597655}, {170350000, 99066.0118598593}, + {170360000, 99066.7823814023}, {170370000, 99067.5254045846}, + {170380000, 99068.2396105399}, {170390000, 99068.9654317053}, + {170400000, 99069.7172083625}, {170410000, 99070.4740696371}, + {170420000, 99071.2190894257}, {170430000, 99071.9562213189}, + {170440000, 99072.6973627948}, {170450000, 99073.4438212588}, + {170460000, 99074.1962383795}, {170470000, 99074.9548063581}, + {170480000, 99075.7192146385}, {170490000, 99076.4890096085}, + {170500000, 99077.264120707}, {170510000, 99078.0225790754}, + {170520000, 99078.7571957593}, {170530000, 99079.4786414393}, + {170540000, 99080.1955797105}, {170550000, 99080.9147051392}, + {170560000, 99081.6562623295}, {170570000, 99082.4223934311}, + {170580000, 99083.1857193803}, {170590000, 99083.9372016668}, + {170600000, 99084.679842925}, {170610000, 99085.4181516695}, + {170620000, 99086.1524035739}, {170630000, 99086.8828865276}, + {170640000, 99087.6097084922}, {170650000, 99088.3381030753}, + {170660000, 99089.0723120589}, {170670000, 99089.810257579}, + {170680000, 99090.5456904576}, {170690000, 99091.2779262115}, + {170700000, 99092.0066394849}, {170710000, 99092.7317344924}, + {170720000, 99093.4568020154}, {170730000, 99094.1872673215}, + {170740000, 99094.9242319981}, {170750000, 99095.6755105974}, + {170760000, 99096.4425557862}, {170770000, 99097.2046841756}, + {170780000, 99097.9451037402}, {170790000, 99098.6721168951}, + {170800000, 99099.4107086696}, {170810000, 99100.1636013446}, + {170820000, 99100.9107999521}, {170830000, 99101.645715799}, + {170840000, 99102.3781402484}, {170850000, 99103.122843098}, + {170860000, 99103.8806029339}, {170870000, 99104.6327070435}, + {170880000, 99105.3716303243}, {170890000, 99106.102398255}, + {170900000, 99106.8290993965}, {170910000, 99107.5539922981}, + {170920000, 99108.2838924858}, {170930000, 99109.0195338262}, + {170940000, 99109.7400414132}, {170950000, 99110.4385606456}, + {170960000, 99111.1285173755}, {170970000, 99111.830174681}, + {170980000, 99112.5446275638}, {170990000, 99113.2610111667}, + {171000000, 99113.9748161485}, {171010000, 99114.6907444019}, + {171020000, 99115.4126122857}, {171030000, 99116.1383331971}, + {171040000, 99116.8616089286}, {171050000, 99117.5817480634}, + {171060000, 99118.3125662889}, {171070000, 99119.058609974}, + {171080000, 99119.8062479301}, {171090000, 99120.5348888155}, + {171100000, 99121.2434533136}, {171110000, 99121.951048615}, + {171120000, 99122.664472218}, {171130000, 99123.3839778979}, + {171140000, 99124.1097661633}, {171150000, 99124.8396637517}, + {171160000, 99125.5671366229}, {171170000, 99126.2914674402}, + {171180000, 99127.0052407606}, {171190000, 99127.7060388592}, + {171200000, 99128.4008851604}, {171210000, 99129.1003854727}, + {171220000, 99129.8057878619}, {171230000, 99130.5255841709}, + {171240000, 99131.2616525427}, {171250000, 99131.9983354227}, + {171260000, 99132.7229016634}, {171270000, 99133.4393879243}, + {171280000, 99134.1599413922}, {171290000, 99134.8858960247}, + {171300000, 99135.6108030723}, {171310000, 99136.3325329092}, + {171320000, 99137.0509454272}, {171330000, 99137.7658203571}, + {171340000, 99138.4778795427}, {171350000, 99139.1944691956}, + {171360000, 99139.9170539209}, {171370000, 99140.6354118246}, + {171380000, 99141.3412053743}, {171390000, 99142.0407496043}, + {171400000, 99142.7531130081}, {171410000, 99143.4803623112}, + {171420000, 99144.2022074647}, {171430000, 99144.911926596}, + {171440000, 99145.6198414406}, {171450000, 99146.3415564628}, + {171460000, 99147.0751583474}, {171470000, 99147.7925924447}, + {171480000, 99148.4882547278}, {171490000, 99149.1821565692}, + {171500000, 99149.8905700921}, {171510000, 99150.6095322204}, + {171520000, 99151.3271438744}, {171530000, 99152.0420875316}, + {171540000, 99152.7678617462}, {171550000, 99153.5088955016}, + {171560000, 99154.2548848571}, {171570000, 99154.9902604294}, + {171580000, 99155.7141869744}, {171590000, 99156.4320973814}, + {171600000, 99157.1459458052}, {171610000, 99157.8560085012}, + {171620000, 99158.5625135353}, {171630000, 99159.2654823475}, + {171640000, 99159.9649438285}, {171650000, 99160.6609167308}, + {171660000, 99161.3463531522}, {171670000, 99162.0189545059}, + {171680000, 99162.678883358}, {171690000, 99163.3263526947}, + {171700000, 99163.9614520567}, {171710000, 99164.590723571}, + {171720000, 99165.2163266861}, {171730000, 99165.8541049454}, + {171740000, 99166.5169447376}, {171750000, 99167.1986222286}, + {171760000, 99167.8804029797}, {171770000, 99168.5601963725}, + {171780000, 99169.2370007438}, {171790000, 99169.9104943769}, + {171800000, 99170.5841958354}, {171810000, 99171.2634266389}, + {171820000, 99171.9473706967}, {171830000, 99172.6219219414}, + {171840000, 99173.2838918937}, {171850000, 99173.9433509007}, + {171860000, 99174.608499003}, {171870000, 99175.2773663015}, + {171880000, 99175.9440151779}, {171890000, 99176.6077938248}, + {171900000, 99177.2754624758}, {171910000, 99177.9492501815}, + {171920000, 99178.6190101644}, {171930000, 99179.2693736591}, + {171940000, 99179.899556623}, {171950000, 99180.5368571861}, + {171960000, 99181.1906268571}, {171970000, 99181.8556652609}, + {171980000, 99182.5277288119}, {171990000, 99183.2023924262}, + {172000000, 99183.8662593341}, {172010000, 99184.517884543}, + {172020000, 99185.1778544223}, {172030000, 99185.8529576119}, + {172040000, 99186.5330437126}, {172050000, 99187.2027619001}, + {172060000, 99187.8612867005}, {172070000, 99188.5142191777}, + {172080000, 99189.1634344959}, {172090000, 99189.8091867254}, + {172100000, 99190.4516858333}, {172110000, 99191.0931041004}, + {172120000, 99191.7400200206}, {172130000, 99192.3931422907}, + {172140000, 99193.038643563}, {172150000, 99193.6719634328}, + {172160000, 99194.2997225487}, {172170000, 99194.9319275558}, + {172180000, 99195.5691274244}, {172190000, 99196.2206929369}, + {172200000, 99196.8905654624}, {172210000, 99197.5517722279}, + {172220000, 99198.1823372428}, {172230000, 99198.79692956}, + {172240000, 99199.4398840305}, {172250000, 99200.116015301}, + {172260000, 99200.7921465281}, {172270000, 99201.4572748376}, + {172280000, 99202.11424355}, {172290000, 99202.7673351417}, + {172300000, 99203.4168117289}, {172310000, 99204.055313648}, + {172320000, 99204.6802631023}, {172330000, 99205.302353619}, + {172340000, 99205.9303033978}, {172350000, 99206.5642974794}, + {172360000, 99207.2049597648}, {172370000, 99207.8523302876}, + {172380000, 99208.4993159387}, {172390000, 99209.1435618499}, + {172400000, 99209.7849062095}, {172410000, 99210.4230963157}, + {172420000, 99211.0581325826}, {172430000, 99211.6900109108}, + {172440000, 99212.3187377326}, {172450000, 99212.9443287663}, + {172460000, 99213.5667996517}, {172470000, 99214.1883104863}, + {172480000, 99214.8154206151}, {172490000, 99215.448837055}, + {172500000, 99216.0818084421}, {172510000, 99216.7120936274}, + {172520000, 99217.3361967156}, {172530000, 99217.9488102034}, + {172540000, 99218.549685855}, {172550000, 99219.1526819288}, + {172560000, 99219.7624587893}, {172570000, 99220.3790192741}, + {172580000, 99221.0023595763}, {172590000, 99221.6324680122}, + {172600000, 99222.2693783812}, {172610000, 99222.9130643287}, + {172620000, 99223.5493118398}, {172630000, 99224.1734241017}, + {172640000, 99224.788735298}, {172650000, 99225.4002736736}, + {172660000, 99226.0083438125}, {172670000, 99226.6132598544}, + {172680000, 99227.2151411141}, {172690000, 99227.8295774478}, + {172700000, 99228.4692638389}, {172710000, 99229.127952722}, + {172720000, 99229.786862859}, {172730000, 99230.4438991754}, + {172740000, 99231.098060648}, {172750000, 99231.7490243143}, + {172760000, 99232.3901432035}, {172770000, 99233.011321706}, + {172780000, 99233.6120776495}, {172790000, 99234.2198731828}, + {172800000, 99234.8442505503}, {172810000, 99235.4800332006}, + {172820000, 99236.1229867039}, {172830000, 99236.7686943413}, + {172840000, 99237.4037524329}, {172850000, 99238.0267127178}, + {172860000, 99238.6439899757}, {172870000, 99239.2577339115}, + {172880000, 99239.8714206102}, {172890000, 99240.4903207977}, + {172900000, 99241.1147111561}, {172910000, 99241.7239562334}, + {172920000, 99242.3097107362}, {172930000, 99242.898367583}, + {172940000, 99243.5114614605}, {172950000, 99244.140817316}, + {172960000, 99244.761740335}, {172970000, 99245.3715127127}, + {172980000, 99245.9829947831}, {172990000, 99246.600452735}, + {173000000, 99247.223877771}, {173010000, 99247.853272144}, + {173020000, 99248.4886079204}, {173030000, 99249.1235776314}, + {173040000, 99249.75593261}, {173050000, 99250.385391534}, + {173060000, 99251.0117274358}, {173070000, 99251.6349521595}, + {173080000, 99252.2550698159}, {173090000, 99252.8720946226}, + {173100000, 99253.4931109795}, {173110000, 99254.1204626532}, + {173120000, 99254.7506813251}, {173130000, 99255.3785153877}, + {173140000, 99256.0036512711}, {173150000, 99256.6257778649}, + {173160000, 99257.2448349479}, {173170000, 99257.8608195316}, + {173180000, 99258.4737318794}, {173190000, 99259.0878758022}, + {173200000, 99259.7163524879}, {173210000, 99260.3605601383}, + {173220000, 99260.9999067202}, {173230000, 99261.6275572918}, + {173240000, 99262.2400019631}, {173250000, 99262.8318788641}, + {173260000, 99263.4030497374}, {173270000, 99263.9816212467}, + {173280000, 99264.5767755452}, {173290000, 99265.1886071142}, + {173300000, 99265.8171782666}, {173310000, 99266.4538441504}, + {173320000, 99267.0723642668}, {173330000, 99267.669889569}, + {173340000, 99268.2663465176}, {173350000, 99268.8683682996}, + {173360000, 99269.4695309792}, {173370000, 99270.0600915355}, + {173380000, 99270.6395430529}, {173390000, 99271.2280703134}, + {173400000, 99271.8342378629}, {173410000, 99272.44197828}, + {173420000, 99273.0381628405}, {173430000, 99273.628986975}, + {173440000, 99274.2332369708}, {173450000, 99274.8529493203}, + {173460000, 99275.4748819255}, {173470000, 99276.0946216987}, + {173480000, 99276.711849777}, {173490000, 99277.3260756469}, + {173500000, 99277.9372825868}, {173510000, 99278.5454494928}, + {173520000, 99279.1505831536}, {173530000, 99279.7526986977}, + {173540000, 99280.351811178}, {173550000, 99280.9500739101}, + {173560000, 99281.5540350341}, {173570000, 99282.1644003288}, + {173580000, 99282.7744366137}, {173590000, 99283.381901235}, + {173600000, 99283.9901511821}, {173610000, 99284.6042833612}, + {173620000, 99285.2234780927}, {173630000, 99285.8336170047}, + {173640000, 99286.4314946973}, {173650000, 99287.0323439249}, + {173660000, 99287.648607422}, {173670000, 99288.27409551}, + {173680000, 99288.8900553331}, {173690000, 99289.49443558}, + {173700000, 99290.1004171998}, {173710000, 99290.7123872614}, + {173720000, 99291.3270401389}, {173730000, 99291.9393659661}, + {173740000, 99292.5490539055}, {173750000, 99293.1557822972}, + {173760000, 99293.7595009482}, {173770000, 99294.3705786018}, + {173780000, 99294.9974904155}, {173790000, 99295.6318042098}, + {173800000, 99296.247887512}, {173810000, 99296.8429577656}, + {173820000, 99297.4369364252}, {173830000, 99298.036476277}, + {173840000, 99298.641758768}, {173850000, 99299.2530746085}, + {173860000, 99299.8704121099}, {173870000, 99300.479878728}, + {173880000, 99301.0764568694}, {173890000, 99301.6757303772}, + {173900000, 99302.2904445267}, {173910000, 99302.9165473696}, + {173920000, 99303.5418177016}, {173930000, 99304.1648948778}, + {173940000, 99304.7851331942}, {173950000, 99305.4023268952}, + {173960000, 99306.0164724764}, {173970000, 99306.6275566337}, + {173980000, 99307.2355929961}, {173990000, 99307.8405967645}, + {174000000, 99308.4425830639}, {174010000, 99309.0467526251}, + {174020000, 99309.6573577363}, {174030000, 99310.2723296317}, + {174040000, 99310.8854058556}, {174050000, 99311.4958952542}, + {174060000, 99312.1034702461}, {174070000, 99312.7080311545}, + {174080000, 99313.3095868127}, {174090000, 99313.908142745}, + {174100000, 99314.503713367}, {174110000, 99315.0888964677}, + {174120000, 99315.6606449533}, {174130000, 99316.2349014297}, + {174140000, 99316.8247048074}, {174150000, 99317.4238710769}, + {174160000, 99318.0136423458}, {174170000, 99318.5919648624}, + {174180000, 99319.1720133566}, {174190000, 99319.7581794266}, + {174200000, 99320.3471465622}, {174210000, 99320.933884195}, + {174220000, 99321.5181143591}, {174230000, 99322.1072208881}, + {174240000, 99322.7037196203}, {174250000, 99323.2969915395}, + {174260000, 99323.8783425512}, {174270000, 99324.4497600491}, + {174280000, 99325.0172085904}, {174290000, 99325.5813724257}, + {174300000, 99326.1567108169}, {174310000, 99326.7480127824}, + {174320000, 99327.3450043458}, {174330000, 99327.9320938276}, + {174340000, 99328.5084337662}, {174350000, 99329.0795858659}, + {174360000, 99329.6474285623}, {174370000, 99330.2225671311}, + {174380000, 99330.8136702708}, {174390000, 99331.4187431768}, + {174400000, 99332.0318477548}, {174410000, 99332.6522851293}, + {174420000, 99333.2584898633}, {174430000, 99333.8433112522}, + {174440000, 99334.4168834432}, {174450000, 99334.994584831}, + {174460000, 99335.5772620955}, {174470000, 99336.1593217607}, + {174480000, 99336.7389375749}, {174490000, 99337.3262445552}, + {174500000, 99337.9295364634}, {174510000, 99338.5446606285}, + {174520000, 99339.1590620287}, {174530000, 99339.7713405463}, + {174540000, 99340.3667175741}, {174550000, 99340.9402847871}, + {174560000, 99341.4957538497}, {174570000, 99342.0387203365}, + {174580000, 99342.5695643897}, {174590000, 99343.1167560574}, + {174600000, 99343.6921693172}, {174610000, 99344.2794433451}, + {174620000, 99344.8651682122}, {174630000, 99345.4511949675}, + {174640000, 99346.0431775131}, {174650000, 99346.6417214372}, + {174660000, 99347.2329647041}, {174670000, 99347.8122973892}, + {174680000, 99348.386543261}, {174690000, 99348.9660638228}, + {174700000, 99349.5509453459}, {174710000, 99350.1348383826}, + {174720000, 99350.7162866603}, {174730000, 99351.2950550119}, + {174740000, 99351.8709529537}, {174750000, 99352.4482625875}, + {174760000, 99353.0400873041}, {174770000, 99353.6478283543}, + {174780000, 99354.2580001561}, {174790000, 99354.8660864055}, + {174800000, 99355.4684148453}, {174810000, 99356.0593819431}, + {174820000, 99356.6387332639}, {174830000, 99357.2126615992}, + {174840000, 99357.7832151143}, {174850000, 99358.3506738858}, + {174860000, 99358.915270026}, {174870000, 99359.4812999022}, + {174880000, 99360.061894037}, {174890000, 99360.6584555938}, + {174900000, 99361.257495843}, {174910000, 99361.8544900866}, + {174920000, 99362.4491066842}, {174930000, 99363.0408351463}, + {174940000, 99363.6301961193}, {174950000, 99364.224612155}, + {174960000, 99364.8258117378}, {174970000, 99365.4234949458}, + {174980000, 99366.0092190354}, {174990000, 99366.5871160875}, + {175000000, 99367.1697354623}, {175010000, 99367.7584597985}, + {175020000, 99368.3397746233}, {175030000, 99368.9091793407}, + {175040000, 99369.4771306273}, {175050000, 99370.0595373}, + {175060000, 99370.6538321181}, {175070000, 99371.2246227035}, + {175080000, 99371.7648012806}, {175090000, 99372.299345497}, + {175100000, 99372.8487417065}, {175110000, 99373.4091484926}, + {175120000, 99373.9689378472}, {175130000, 99374.5268120052}, + {175140000, 99375.0750911111}, {175150000, 99375.6112354337}, + {175160000, 99376.1453559132}, {175170000, 99376.6928337294}, + {175180000, 99377.2544910319}, {175190000, 99377.8109476615}, + {175200000, 99378.3552753552}, {175210000, 99378.9027644877}, + {175220000, 99379.4659502338}, {175230000, 99380.0407921211}, + {175240000, 99380.6150603726}, {175250000, 99381.1873897264}, + {175260000, 99381.7642021856}, {175270000, 99382.3476366624}, + {175280000, 99382.9309189453}, {175290000, 99383.5037398423}, + {175300000, 99384.0655553992}, {175310000, 99384.6292025956}, + {175320000, 99385.2000513405}, {175330000, 99385.7728286255}, + {175340000, 99386.3432037166}, {175350000, 99386.9132321617}, + {175360000, 99387.4891934295}, {175370000, 99388.0717635634}, + {175380000, 99388.6612123474}, {175390000, 99389.2576073519}, + {175400000, 99389.8506977518}, {175410000, 99390.4248614086}, + {175420000, 99390.9792869572}, {175430000, 99391.5333406978}, + {175440000, 99392.0940065553}, {175450000, 99392.666691429}, + {175460000, 99393.2558238087}, {175470000, 99393.859302278}, + {175480000, 99394.4708439424}, {175490000, 99395.0897099889}, + {175500000, 99395.6873284474}, {175510000, 99396.2541874429}, + {175520000, 99396.8075453887}, {175530000, 99397.3736534383}, + {175540000, 99397.9530269579}, {175550000, 99398.5332705328}, + {175560000, 99399.1115220747}, {175570000, 99399.6821302119}, + {175580000, 99400.2404619303}, {175590000, 99400.7907367241}, + {175600000, 99401.3458176252}, {175610000, 99401.9071246271}, + {175620000, 99402.475283586}, {175630000, 99403.0504824436}, + {175640000, 99403.6258224664}, {175650000, 99404.1907963256}, + {175660000, 99404.7448471965}, {175670000, 99405.300767554}, + {175680000, 99405.8639085623}, {175690000, 99406.4341768539}, + {175700000, 99407.011489501}, {175710000, 99407.5958184219}, + {175720000, 99408.1871503137}, {175730000, 99408.7854526888}, + {175740000, 99409.3765932541}, {175750000, 99409.9558561688}, + {175760000, 99410.5298199494}, {175770000, 99411.1084905366}, + {175780000, 99411.6924224519}, {175790000, 99412.276215922}, + {175800000, 99412.8576037977}, {175810000, 99413.4414891931}, + {175820000, 99414.0318953045}, {175830000, 99414.6288997246}, + {175840000, 99415.2328082422}, {175850000, 99415.8436245169}, + {175860000, 99416.4401633042}, {175870000, 99417.0153669554}, + {175880000, 99417.5760223901}, {175890000, 99418.1324376677}, + {175900000, 99418.685227756}, {175910000, 99419.2349960749}, + {175920000, 99419.7819688277}, {175930000, 99420.3261893014}, + {175940000, 99420.8676954642}, {175950000, 99421.408622185}, + {175960000, 99421.9555306079}, {175970000, 99422.5091303154}, + {175980000, 99423.0697630884}, {175990000, 99423.6375206972}, + {176000000, 99424.2120354345}, {176010000, 99424.7927646635}, + {176020000, 99425.3796478633}, {176030000, 99425.9591913219}, + {176040000, 99426.5258902582}, {176050000, 99427.0850197128}, + {176060000, 99427.6409222191}, {176070000, 99428.195840235}, + {176080000, 99428.756635372}, {176090000, 99429.324049971}, + {176100000, 99429.8984030731}, {176110000, 99430.4797789217}, + {176120000, 99431.0645472985}, {176130000, 99431.6471829335}, + {176140000, 99432.2273768929}, {176150000, 99432.789450676}, + {176160000, 99433.3281385891}, {176170000, 99433.8698095656}, + {176180000, 99434.4361357063}, {176190000, 99435.0189943751}, + {176200000, 99435.5936659249}, {176210000, 99436.1574185203}, + {176220000, 99436.7160234127}, {176230000, 99437.2714361844}, + {176240000, 99437.8238215749}, {176250000, 99438.3734226954}, + {176260000, 99438.9209774545}, {176270000, 99439.4738382289}, + {176280000, 99440.0334782487}, {176290000, 99440.6000646245}, + {176300000, 99441.1737286929}, {176310000, 99441.7523114391}, + {176320000, 99442.3292477651}, {176330000, 99442.9038098074}, + {176340000, 99443.4756577343}, {176350000, 99444.0446859847}, + {176360000, 99444.6075927302}, {176370000, 99445.1593280801}, + {176380000, 99445.6996530078}, {176390000, 99446.2573694088}, + {176400000, 99446.8428602544}, {176410000, 99447.4245340971}, + {176420000, 99447.976395284}, {176430000, 99448.5086034529}, + {176440000, 99449.0522062111}, {176450000, 99449.610636169}, + {176460000, 99450.1854681843}, {176470000, 99450.777177951}, + {176480000, 99451.3685258055}, {176490000, 99451.933228887}, + {176500000, 99452.4698951635}, {176510000, 99453.0117861793}, + {176520000, 99453.5700691481}, {176530000, 99454.1450333635}, + {176540000, 99454.7369021502}, {176550000, 99455.3392199151}, + {176560000, 99455.9322874169}, {176570000, 99456.5139383546}, + {176580000, 99457.0902355144}, {176590000, 99457.6632363112}, + {176600000, 99458.2297796813}, {176610000, 99458.785025068}, + {176620000, 99459.3287456494}, {176630000, 99459.8748767293}, + {176640000, 99460.4280738765}, {176650000, 99460.9831923967}, + {176660000, 99461.5359966828}, {176670000, 99462.0863994792}, + {176680000, 99462.634107712}, {176690000, 99463.1791004481}, + {176700000, 99463.7284386046}, {176710000, 99464.284487173}, + {176720000, 99464.8437874972}, {176730000, 99465.401070769}, + {176740000, 99465.9567600941}, {176750000, 99466.5178353572}, + {176760000, 99467.0856363138}, {176770000, 99467.6500206037}, + {176780000, 99468.2026442732}, {176790000, 99468.7476074783}, + {176800000, 99469.2974112028}, {176810000, 99469.8534347213}, + {176820000, 99470.4022521998}, {176830000, 99470.9393704881}, + {176840000, 99471.4713721816}, {176850000, 99472.0082878537}, + {176860000, 99472.5506744197}, {176870000, 99473.0856911423}, + {176880000, 99473.6080854206}, {176890000, 99474.1231164976}, + {176900000, 99474.6351241506}, {176910000, 99475.1484724531}, + {176920000, 99475.6765828187}, {176930000, 99476.2208946637}, + {176940000, 99476.7891026458}, {176950000, 99477.3837166431}, + {176960000, 99477.9809016368}, {176970000, 99478.5442953149}, + {176980000, 99479.0719538341}, {176990000, 99479.6005677917}, + {177000000, 99480.1455199223}, {177010000, 99480.6968145552}, + {177020000, 99481.2462200422}, {177030000, 99481.7935627795}, + {177040000, 99482.3382879377}, {177050000, 99482.8803448962}, + {177060000, 99483.4197106365}, {177070000, 99483.956386279}, + {177080000, 99484.4903852405}, {177090000, 99485.021720871}, + {177100000, 99485.550406454}, {177110000, 99486.0764552067}, + {177120000, 99486.5998802803}, {177130000, 99487.1206947603}, + {177140000, 99487.6389116674}, {177150000, 99488.1566706102}, + {177160000, 99488.6805402}, {177170000, 99489.2112298358}, + {177180000, 99489.7349642936}, {177190000, 99490.2471246635}, + {177200000, 99490.7545128656}, {177210000, 99491.2675043392}, + {177220000, 99491.7867567951}, {177230000, 99492.3133340755}, + {177240000, 99492.8474537187}, {177250000, 99493.3941107334}, + {177260000, 99493.9574101142}, {177270000, 99494.5395053312}, + {177280000, 99495.1472080531}, {177290000, 99495.7811686455}, + {177300000, 99496.4063635106}, {177310000, 99497.0110196242}, + {177320000, 99497.5873424292}, {177330000, 99498.1233521715}, + {177340000, 99498.6233545536}, {177350000, 99499.1373913529}, + {177360000, 99499.6755997507}, {177370000, 99500.2187945112}, + {177380000, 99500.7511632774}, {177390000, 99501.2787439869}, + {177400000, 99501.8200603245}, {177410000, 99502.3771295617}, + {177420000, 99502.9297627809}, {177430000, 99503.4711282187}, + {177440000, 99504.00081255}, {177450000, 99504.5181533646}, + {177460000, 99505.0259626228}, {177470000, 99505.5534383697}, + {177480000, 99506.1064761087}, {177490000, 99506.6651317866}, + {177500000, 99507.2129473829}, {177510000, 99507.7580839798}, + {177520000, 99508.3255864378}, {177530000, 99508.9181636892}, + {177540000, 99509.5018087213}, {177550000, 99510.0650733964}, + {177560000, 99510.6243002981}, {177570000, 99511.2044601082}, + {177580000, 99511.806903227}, {177590000, 99512.4217692878}, + {177600000, 99513.0454399491}, {177610000, 99513.6562028381}, + {177620000, 99514.2361569155}, {177630000, 99514.7913939787}, + {177640000, 99515.3403955005}, {177650000, 99515.8852623932}, + {177660000, 99516.4270100364}, {177670000, 99516.9659908722}, + {177680000, 99517.5055675998}, {177690000, 99518.0508820777}, + {177700000, 99518.6021826233}, {177710000, 99519.1455704906}, + {177720000, 99519.6765029757}, {177730000, 99520.2104200203}, + {177740000, 99520.7600874617}, {177750000, 99521.3193697835}, + {177760000, 99521.8694695663}, {177770000, 99522.4083173955}, + {177780000, 99522.9560946877}, {177790000, 99523.5195833656}, + {177800000, 99524.09202419}, {177810000, 99524.6631088456}, + {177820000, 99525.2321955003}, {177830000, 99525.798631175}, + {177840000, 99526.3622750784}, {177850000, 99526.923131775}, + {177860000, 99527.4812073966}, {177870000, 99528.0386310348}, + {177880000, 99528.6019536577}, {177890000, 99529.1718845216}, + {177900000, 99529.7487654735}, {177910000, 99530.332688983}, + {177920000, 99530.9200129312}, {177930000, 99531.5051790239}, + {177940000, 99532.0878749223}, {177950000, 99532.6678078025}, + {177960000, 99533.2448837393}, {177970000, 99533.8139344754}, + {177980000, 99534.3706979931}, {177990000, 99534.9172555721}, + {178000000, 99535.459911063}, {178010000, 99535.999389351}, + {178020000, 99536.5501270272}, {178030000, 99537.1169671838}, + {178040000, 99537.6797257658}, {178050000, 99538.2075104985}, + {178060000, 99538.6986903737}, {178070000, 99539.1773442166}, + {178080000, 99539.65161009}, {178090000, 99540.1483121525}, + {178100000, 99540.6895873043}, {178110000, 99541.2609164413}, + {178120000, 99541.8178936046}, {178130000, 99542.3555976466}, + {178140000, 99543.0336993969}, {178150000, 99543.9057119169}, + {178160000, 99544.8241698322}, {178170000, 99545.5635776691}, + {178180000, 99546.1116719909}, {178190000, 99546.5921458729}, + {178200000, 99547.0586644477}, {178210000, 99547.5173294184}, + {178220000, 99547.9731872546}, {178230000, 99548.4348505032}, + {178240000, 99548.928907211}, {178250000, 99549.4581986004}, + {178260000, 99549.9887870408}, {178270000, 99550.5091959256}, + {178280000, 99551.0123264424}, {178290000, 99551.4872711715}, + {178300000, 99551.933528613}, {178310000, 99552.3769077769}, + {178320000, 99552.826828669}, {178330000, 99553.2838603913}, + {178340000, 99553.748467584}, {178350000, 99554.2227439849}, + {178360000, 99554.7132479757}, {178370000, 99555.2206443954}, + {178380000, 99555.7241126369}, {178390000, 99556.2166274019}, + {178400000, 99556.7045643619}, {178410000, 99557.1976659318}, + {178420000, 99557.6964740217}, {178430000, 99558.1881967694}, + {178440000, 99558.6674751146}, {178450000, 99559.1344377999}, + {178460000, 99559.5892015977}, {178470000, 99560.0339325022}, + {178480000, 99560.4752054295}, {178490000, 99560.9137741749}, + {178500000, 99561.3640794235}, {178510000, 99561.8309718518}, + {178520000, 99562.3009229613}, {178530000, 99562.7532239501}, + {178540000, 99563.1867522402}, {178550000, 99563.6208282937}, + {178560000, 99564.0620645207}, {178570000, 99564.5004117884}, + {178580000, 99564.92756221}, {178590000, 99565.3497315008}, + {178600000, 99565.7860369037}, {178610000, 99566.2385631242}, + {178620000, 99566.6941881686}, {178630000, 99567.1484660508}, + {178640000, 99567.5977735738}, {178650000, 99568.0365489492}, + {178660000, 99568.4645178818}, {178670000, 99568.8877083625}, + {178680000, 99569.3082726217}, {178690000, 99569.7264874898}, + {178700000, 99570.1425838759}, {178710000, 99570.5586960837}, + {178720000, 99570.981406519}, {178730000, 99571.4114253243}, + {178740000, 99571.827977582}, {178750000, 99572.224073678}, + {178760000, 99572.6097894411}, {178770000, 99573.0005267031}, + {178780000, 99573.3971584243}, {178790000, 99573.7942084779}, + {178800000, 99574.1897402709}, {178810000, 99574.588656386}, + {178820000, 99574.9950181141}, {178830000, 99575.4067735316}, + {178840000, 99575.8176509399}, {178850000, 99576.2269497858}, + {178860000, 99576.620287337}, {178870000, 99576.9928464399}, + {178880000, 99577.3482944059}, {178890000, 99577.6922012135}, + {178900000, 99578.024945285}, {178910000, 99578.367667058}, + {178920000, 99578.729075313}, {178930000, 99579.0984407435}, + {178940000, 99579.4668731397}, {178950000, 99579.8341839463}, + {178960000, 99580.1997791443}, {178970000, 99580.5635995631}, + {178980000, 99580.9185808005}, {178990000, 99581.2623600917}, + {179000000, 99581.6017059184}, {179010000, 99581.9469806448}, + {179020000, 99582.2987606268}, {179030000, 99582.6437834049}, + {179040000, 99582.9772269375}, {179050000, 99583.3094302858}, + {179060000, 99583.6489549239}, {179070000, 99583.9959651026}, + {179080000, 99584.3510465535}, {179090000, 99584.7142293973}, + {179100000, 99585.0714456683}, {179110000, 99585.4179518992}, + {179120000, 99585.7605089056}, {179130000, 99586.1094686072}, + {179140000, 99586.4638818283}, {179150000, 99586.8025667508}, + {179160000, 99587.1205844904}, {179170000, 99587.4330407091}, + {179180000, 99587.752462219}, {179190000, 99588.0791095003}, + {179200000, 99588.4138638861}, {179210000, 99588.7567886235}, + {179220000, 99589.0938443923}, {179230000, 99589.4202895558}, + {179240000, 99589.7360982588}, {179250000, 99590.0412022029}, + {179260000, 99590.3356572352}, {179270000, 99590.6259645211}, + {179280000, 99590.9142766533}, {179290000, 99591.2060396811}, + {179300000, 99591.505765359}, {179310000, 99591.8092873823}, + {179320000, 99592.1037801642}, {179330000, 99592.3878422058}, + {179340000, 99592.6749055466}, {179350000, 99592.9695153139}, + {179360000, 99593.2683775028}, {179370000, 99593.5664547261}, + {179380000, 99593.8634569567}, {179390000, 99594.159115536}, + {179400000, 99594.4533176003}, {179410000, 99594.7460605466}, + {179420000, 99595.0373434313}, {179430000, 99595.3292877436}, + {179440000, 99595.628451512}, {179450000, 99595.9355398419}, + {179460000, 99596.2297847943}, {179470000, 99596.5041858922}, + {179480000, 99596.7724134503}, {179490000, 99597.0554226547}, + {179500000, 99597.3530492158}, {179510000, 99597.6452600342}, + {179520000, 99597.9271916695}, {179530000, 99598.2034699145}, + {179540000, 99598.4779479886}, {179550000, 99598.752834524}, + {179560000, 99599.03496273}, {179570000, 99599.3250690093}, + {179580000, 99599.6094429068}, {179590000, 99599.8834538596}, + {179600000, 99600.1469026807}, {179610000, 99600.3994552521}, + {179620000, 99600.6422197987}, {179630000, 99600.8896077994}, + {179640000, 99601.1449459534}, {179650000, 99601.3982868634}, + {179660000, 99601.6413860693}, {179670000, 99601.8783219786}, + {179680000, 99602.1216399248}, {179690000, 99602.3727224785}, + {179700000, 99602.6181441953}, {179710000, 99602.8533637052}, + {179720000, 99603.0887760722}, {179730000, 99603.3403290666}, + {179740000, 99603.6067735893}, {179750000, 99603.867402876}, + {179760000, 99604.1181738246}, {179770000, 99604.3687109382}, + {179780000, 99604.6269928631}, {179790000, 99604.8889500098}, + {179800000, 99605.1420381569}, {179810000, 99605.3848858606}, + {179820000, 99605.6379753403}, {179830000, 99605.9082297578}, + {179840000, 99606.1757300783}, {179850000, 99606.4099107196}, + {179860000, 99606.6091429879}, {179870000, 99606.8118894136}, + {179880000, 99607.0323358884}, {179890000, 99607.2709496931}, + {179900000, 99607.5281041919}, {179910000, 99607.7910339386}, + {179920000, 99608.0203298805}, {179930000, 99608.2117090053}, + {179940000, 99608.4054828924}, {179950000, 99608.6153355438}, + {179960000, 99608.8382977046}, {179970000, 99609.0698456065}, + {179980000, 99609.3096743076}, {179990000, 99609.5361147278}, + {180000000, 99609.7412835798}, {180010000, 99609.9460513594}, + {180020000, 99610.1677404184}, {180030000, 99610.4003303922}, + {180040000, 99610.6253213643}, {180050000, 99610.8406665161}, + {180060000, 99611.0524538681}, {180070000, 99611.2627629102}, + {180080000, 99611.4717499969}, {180090000, 99611.679651629}, + {180100000, 99611.8864867373}, {180110000, 99612.0922813893}, + {180120000, 99612.2970496363}, {180130000, 99612.4956537698}, + {180140000, 99612.6838347123}, {180150000, 99612.8657657819}, + {180160000, 99613.054301269}, {180170000, 99613.250858383}, + {180180000, 99613.4420278638}, {180190000, 99613.6232657219}, + {180200000, 99613.7945605141}, {180210000, 99613.9558677319}, + {180220000, 99614.1072316562}, {180230000, 99614.2780956152}, + {180240000, 99614.4784595728}, {180250000, 99614.6872462538}, + {180260000, 99614.8869550484}, {180270000, 99615.0772310888}, + {180280000, 99615.256876413}, {180290000, 99615.4258032458}, + {180300000, 99615.5980393585}, {180310000, 99615.7783459725}, + {180320000, 99615.9634518939}, {180330000, 99616.1483472133}, + {180340000, 99616.3327398422}, {180350000, 99616.516332984}, + {180360000, 99616.6990281341}, {180370000, 99616.8859520553}, + {180380000, 99617.0813615138}, {180390000, 99617.2810998091}, + {180400000, 99617.4723438656}, {180410000, 99617.6536883464}, + {180420000, 99617.8244939279}, {180430000, 99617.9845777117}, + {180440000, 99618.1375614146}, {180450000, 99618.2889918958}, + {180460000, 99618.4392042701}, {180470000, 99618.6039316138}, + {180480000, 99618.7883285396}, {180490000, 99618.9765123417}, + {180500000, 99619.1552816768}, {180510000, 99619.3264879693}, + {180520000, 99619.4957833698}, {180530000, 99619.663812337}, + {180540000, 99619.8308714057}, {180550000, 99619.9970646371}, + {180560000, 99620.1591597312}, {180570000, 99620.3121823954}, + {180580000, 99620.4558842249}, {180590000, 99620.6032855346}, + {180600000, 99620.759932968}, {180610000, 99620.9205891061}, + {180620000, 99621.0808984563}, {180630000, 99621.2407646535}, + {180640000, 99621.3998843053}, {180650000, 99621.558226554}, + {180660000, 99621.7157832022}, {180670000, 99621.8725540333}, + {180680000, 99622.0250604468}, {180690000, 99622.1679446685}, + {180700000, 99622.3014337497}, {180710000, 99622.4322198408}, + {180720000, 99622.5618693087}, {180730000, 99622.6957830166}, + {180740000, 99622.8384454742}, {180750000, 99622.9878107844}, + {180760000, 99623.137607684}, {180770000, 99623.2871281657}, + {180780000, 99623.4360350531}, {180790000, 99623.5842154737}, + {180800000, 99623.721734627}, {180810000, 99623.8332949592}, + {180820000, 99623.9181219427}, {180830000, 99624.0333529385}, + {180840000, 99624.1977955525}, {180850000, 99624.3750422273}, + {180860000, 99624.5348284396}, {180870000, 99624.6807660708}, + {180880000, 99624.8239053149}, {180890000, 99624.9655027206}, + {180900000, 99625.0920810515}, {180910000, 99625.1990975195}, + {180920000, 99625.3004129865}, {180930000, 99625.4173144494}, + {180940000, 99625.5501574891}, {180950000, 99625.6863418215}, + {180960000, 99625.8227716146}, {180970000, 99625.9538307244}, + {180980000, 99626.0748509806}, {180990000, 99626.192096436}, + {181000000, 99626.3249449113}, {181010000, 99626.4755091929}, + {181020000, 99626.616658777}, {181030000, 99626.7391804717}, + {181040000, 99626.8602321148}, {181050000, 99627.0061792508}, + {181060000, 99627.1751955549}, {181070000, 99627.332764891}, + {181080000, 99627.4718169513}, {181090000, 99627.6016233863}, + {181100000, 99627.7299056443}, {181110000, 99627.8568564392}, + {181120000, 99627.9830598478}, {181130000, 99628.1085849781}, + {181140000, 99628.2194119574}, {181150000, 99628.31080447}, + {181160000, 99628.3896915519}, {181170000, 99628.4666978351}, + {181180000, 99628.54245573}, {181190000, 99628.6175632764}, + {181200000, 99628.6922425907}, {181210000, 99628.7716711263}, + {181220000, 99628.8601525764}, {181230000, 99628.9556344131}, + {181240000, 99629.0518199313}, {181250000, 99629.1479966274}, + {181260000, 99629.2438380415}, {181270000, 99629.3392338635}, + {181280000, 99629.4341740227}, {181290000, 99629.5286417869}, + {181300000, 99629.6226383911}, {181310000, 99629.7235392128}, + {181320000, 99629.8344259968}, {181330000, 99629.9497927008}, + {181340000, 99630.0650547083}, {181350000, 99630.18221634}, + {181360000, 99630.3075187518}, {181370000, 99630.4416290718}, + {181380000, 99630.5708194888}, {181390000, 99630.6904213145}, + {181400000, 99630.8004372429}, {181410000, 99630.9008452311}, + {181420000, 99630.9916890696}, {181430000, 99631.0716545503}, + {181440000, 99631.1402930156}, {181450000, 99631.2136307198}, + {181460000, 99631.3049974587}, {181470000, 99631.4103937999}, + {181480000, 99631.517554476}, {181490000, 99631.6250898694}, + {181500000, 99631.7253347953}, {181510000, 99631.8156972908}, + {181520000, 99631.9030824167}, {181530000, 99631.9981166013}, + {181540000, 99632.10092984}, {181550000, 99632.2051844703}, + {181560000, 99632.3093870294}, {181570000, 99632.4132919595}, + {181580000, 99632.5166948711}, {181590000, 99632.6195946487}, + {181600000, 99632.7219824931}, {181610000, 99632.823859676}, + {181620000, 99632.9252287443}, {181630000, 99633.0260922322}, + {181640000, 99633.1264526614}, {181650000, 99633.2263125409}, + {181660000, 99633.3256743671}, {181670000, 99633.4392570481}, + {181680000, 99633.5732662374}, {181690000, 99633.7064208685}, + {181700000, 99633.8209874851}, {181710000, 99633.9229640995}, + {181720000, 99634.0308660139}, {181730000, 99634.1467546513}, + {181740000, 99634.2575461819}, {181750000, 99634.3587922658}, + {181760000, 99634.4473049447}, {181770000, 99634.5181396156}, + {181780000, 99634.5710883913}, {181790000, 99634.6177461111}, + {181800000, 99634.6630865186}, {181810000, 99634.7230802767}, + {181820000, 99634.8110243405}, {181830000, 99634.9228970445}, + {181840000, 99635.0464480029}, {181850000, 99635.1802443219}, + {181860000, 99635.3025223176}, {181870000, 99635.4058768961}, + {181880000, 99635.4970192211}, {181890000, 99635.5862518654}, + {181900000, 99635.6741897936}, {181910000, 99635.7538590256}, + {181920000, 99635.8227231286}, {181930000, 99635.8964944895}, + {181940000, 99635.9882786025}, {181950000, 99636.0940883302}, + {181960000, 99636.2016756949}, {181970000, 99636.3096518583}, + {181980000, 99636.4033363423}, {181990000, 99636.477755463}, + {182000000, 99636.5397994127}, {182010000, 99636.6000555191}, + {182020000, 99636.6591559424}, {182030000, 99636.7176677498}, + {182040000, 99636.7758336167}, {182050000, 99636.8285452061}, + {182060000, 99636.8715448293}, {182070000, 99636.9110948303}, + {182080000, 99636.9666541883}, {182090000, 99637.0403474603}, + {182100000, 99637.1190643153}, {182110000, 99637.1982977519}, + {182120000, 99637.2744235175}, {182130000, 99637.3418463167}, + {182140000, 99637.4002773285}, {182150000, 99637.4558015816}, + {182160000, 99637.5105347243}, {182170000, 99637.5647515573}, + {182180000, 99637.6186817733}, {182190000, 99637.6723304171}, + {182200000, 99637.7257102046}, {182210000, 99637.7788237593}, + {182220000, 99637.8386916109}, {182230000, 99637.907692548}, + {182240000, 99637.9788595384}, {182250000, 99638.0414588407}, + {182260000, 99638.0961974071}, {182270000, 99638.156896879}, + {182280000, 99638.2263892574}, {182290000, 99638.2999306265}, + {182300000, 99638.3735596942}, {182310000, 99638.4429668973}, + {182320000, 99638.4946911023}, {182330000, 99638.5272918264}, + {182340000, 99638.5612251007}, {182350000, 99638.6034931988}, + {182360000, 99638.6509870782}, {182370000, 99638.6989156}, + {182380000, 99638.7469930657}, {182390000, 99638.8025262224}, + {182400000, 99638.8681681153}, {182410000, 99638.9333500273}, + {182420000, 99638.9892437713}, {182430000, 99639.0398972798}, + {182440000, 99639.0978567299}, {182450000, 99639.1645052669}, + {182460000, 99639.2264415656}, {182470000, 99639.2790907948}, + {182480000, 99639.3257399245}, {182490000, 99639.3714393812}, + {182500000, 99639.4164911757}, {182510000, 99639.4688524921}, + {182520000, 99639.5312234939}, {182530000, 99639.5982267477}, + {182540000, 99639.6653665186}, {182550000, 99639.7346392142}, + {182560000, 99639.8122906337}, {182570000, 99639.8989888009}, + {182580000, 99639.9810155912}, {182590000, 99640.0536875291}, + {182600000, 99640.1202850788}, {182610000, 99640.1858484343}, + {182620000, 99640.2506794001}, {182630000, 99640.3227367266}, + {182640000, 99640.4046471761}, {182650000, 99640.4910627536}, + {182660000, 99640.5775177937}, {182670000, 99640.6639148554}, + {182680000, 99640.7499484042}, {182690000, 99640.8355854937}, + {182700000, 99640.9138034272}, {182710000, 99640.9822134229}, + {182720000, 99641.0371591189}, {182730000, 99641.0729621798}, + {182740000, 99641.092286898}, {182750000, 99641.1238807038}, + {182760000, 99641.1733591935}, {182770000, 99641.2261826998}, + {182780000, 99641.2702028652}, {182790000, 99641.3093739966}, + {182800000, 99641.3559706991}, {182810000, 99641.4113457873}, + {182820000, 99641.4620786155}, {182830000, 99641.5035802517}, + {182840000, 99641.539137755}, {182850000, 99641.5738063677}, + {182860000, 99641.607888585}, {182870000, 99641.6564134953}, + {182880000, 99641.7256142909}, {182890000, 99641.7994094972}, + {182900000, 99641.8643618113}, {182910000, 99641.9223095449}, + {182920000, 99641.9789084899}, {182930000, 99642.0348030774}, + {182940000, 99642.0832730307}, {182950000, 99642.1220371466}, + {182960000, 99642.1545616847}, {182970000, 99642.1861823414}, + {182980000, 99642.217218745}, {182990000, 99642.2479571583}, + {183000000, 99642.2785241697}, {183010000, 99642.3089304699}, + {183020000, 99642.339185118}, {183030000, 99642.3692888705}, + {183040000, 99642.3992424799}, {183050000, 99642.429046695}, + {183060000, 99642.458702261}, {183070000, 99642.4882099192}, + {183080000, 99642.5175704074}, {183090000, 99642.5467844595}, + {183100000, 99642.5758528059}, {183110000, 99642.6198869566}, + {183120000, 99642.6843837473}, {183130000, 99642.7431389117}, + {183140000, 99642.7742408538}, {183150000, 99642.7857247673}, + {183160000, 99642.8024289091}, {183170000, 99642.8271341229}, + {183180000, 99642.8540808871}, {183190000, 99642.8812829037}, + {183200000, 99642.9086034708}, {183210000, 99642.9358318085}, + {183220000, 99642.9618605424}, {183230000, 99642.9718445061}, + {183240000, 99642.9623763723}, {183250000, 99642.9589579744}, + {183260000, 99642.9829131776}, {183270000, 99643.0304160354}, + {183280000, 99643.0897760771}, {183290000, 99643.1596203779}, + {183300000, 99643.2322816941}, {183310000, 99643.3051163534}, + {183320000, 99643.3744173997}, {183330000, 99643.4344505262}, + {183340000, 99643.4848647803}, {183350000, 99643.5251170597}, + {183360000, 99643.5551350079}, {183370000, 99643.5852726197}, + {183380000, 99643.6241894522}, {183390000, 99643.6699553782}, + {183400000, 99643.7166191379}, {183410000, 99643.7635045354}, + {183420000, 99643.8102850349}, {183430000, 99643.8568484272}, + {183440000, 99643.9067050412}, {183450000, 99643.9652897875}, + {183460000, 99644.0322433967}, {183470000, 99644.1007456233}, + {183480000, 99644.1693828089}, {183490000, 99644.2327998011}, + {183500000, 99644.2865164794}, {183510000, 99644.3325629946}, + {183520000, 99644.3772020613}, {183530000, 99644.4211477336}, + {183540000, 99644.4717286791}, {183550000, 99644.5314413716}, + {183560000, 99644.5935854567}, {183570000, 99644.6478204052}, + {183580000, 99644.6935721019}, {183590000, 99644.721405928}, + {183600000, 99644.7278903371}, {183610000, 99644.7292514631}, + {183620000, 99644.7390806374}, {183630000, 99644.7576424737}, + {183640000, 99644.785857184}, {183650000, 99644.8237860983}, + {183660000, 99644.8574237756}, {183670000, 99644.8819643594}, + {183680000, 99644.9039667327}, {183690000, 99644.9335617771}, + {183700000, 99644.9713136772}, {183710000, 99644.995960583}, + {183720000, 99645.0004304445}, {183730000, 99645.000340234}, + {183740000, 99645.0087707436}, {183750000, 99645.0259755612}, + {183760000, 99645.0528444923}, {183770000, 99645.0894355716}, + {183780000, 99645.1357495275}, {183790000, 99645.1917549434}, + {183800000, 99645.2503676342}, {183810000, 99645.3006449634}, + {183820000, 99645.3424460666}, {183830000, 99645.3821131254}, + {183840000, 99645.4211318265}, {183850000, 99645.4597323248}, + {183860000, 99645.4981076756}, {183870000, 99645.536266256}, + {183880000, 99645.5742319316}, {183890000, 99645.6120082527}, + {183900000, 99645.6355667545}, {183910000, 99645.6401260429}, + {183920000, 99645.6358770122}, {183930000, 99645.6385471388}, + {183940000, 99645.6490351134}, {183950000, 99645.6466883784}, + {183960000, 99645.6241699329}, {183970000, 99645.6022795274}, + {183980000, 99645.5984548304}, {183990000, 99645.6046251314}, + {184000000, 99645.5956422908}, {184010000, 99645.5687292663}, + {184020000, 99645.5576938118}, {184030000, 99645.5741187847}, + {184040000, 99645.604694493}, {184050000, 99645.6288875646}, + {184060000, 99645.6455122588}, {184070000, 99645.6674532445}, + {184080000, 99645.6991319847}, {184090000, 99645.7302831024}, + {184100000, 99645.7523006924}, {184110000, 99645.7692180178}, + {184120000, 99645.7936015024}, {184130000, 99645.8268392909}, + {184140000, 99645.8555615544}, {184150000, 99645.875160159}, + {184160000, 99645.8856823186}, {184170000, 99645.8871759602}, + {184180000, 99645.8796862722}, {184190000, 99645.8837433082}, + {184200000, 99645.9082957188}, {184210000, 99645.9426005695}, + {184220000, 99645.9776435075}, {184230000, 99646.0090354508}, + {184240000, 99646.0230029197}, {184250000, 99646.0180652846}, + {184260000, 99646.014632096}, {184270000, 99646.019722223}, + {184280000, 99646.0236839037}, {184290000, 99646.0115820871}, + {184300000, 99645.9826064507}, {184310000, 99645.9559882295}, + {184320000, 99645.938840085}, {184330000, 99645.9314055138}, + {184340000, 99645.933881626}, {184350000, 99645.9483207388}, + {184360000, 99645.9812729902}, {184370000, 99646.0333973021}, + {184380000, 99646.0839662834}, {184390000, 99646.1258406329}, + {184400000, 99646.1556350051}, {184410000, 99646.1680786146}, + {184420000, 99646.1629402778}, {184430000, 99646.1517848017}, + {184440000, 99646.1396005088}, {184450000, 99646.1371982599}, + {184460000, 99646.1536340189}, {184470000, 99646.1848541936}, + {184480000, 99646.2182840093}, {184490000, 99646.2524890487}, + {184500000, 99646.2868019573}, {184510000, 99646.3209923579}, + {184520000, 99646.3583243278}, {184530000, 99646.4038563091}, + {184540000, 99646.4578498123}, {184550000, 99646.506577983}, + {184560000, 99646.5452992476}, {184570000, 99646.563768648}, + {184580000, 99646.5534128832}, {184590000, 99646.5267095845}, + {184600000, 99646.5225792583}, {184610000, 99646.5453263249}, + {184620000, 99646.5758704291}, {184630000, 99646.6076094875}, + {184640000, 99646.6367760426}, {184650000, 99646.6575291855}, + {184660000, 99646.669561441}, {184670000, 99646.6864362457}, + {184680000, 99646.7130437211}, {184690000, 99646.7340153054}, + {184700000, 99646.7364550665}, {184710000, 99646.7306180022}, + {184720000, 99646.7485470222}, {184730000, 99646.793763012}, + {184740000, 99646.8328117804}, {184750000, 99646.8541823532}, + {184760000, 99646.860989434}, {184770000, 99646.858015628}, + {184780000, 99646.8455908777}, {184790000, 99646.8453443141}, + {184800000, 99646.865257818}, {184810000, 99646.8947895275}, + {184820000, 99646.9250831305}, {184830000, 99646.9559438933}, + {184840000, 99646.9867677429}, {184850000, 99647.0174864863}, + {184860000, 99647.0410615994}, {184870000, 99647.0550864823}, + {184880000, 99647.066246858}, {184890000, 99647.0848873807}, + {184900000, 99647.1115874117}, {184910000, 99647.1335488942}, + {184920000, 99647.1454343371}, {184930000, 99647.1524504961}, + {184940000, 99647.1589769662}, {184950000, 99647.165113375}, + {184960000, 99647.171168097}, {184970000, 99647.1771764095}, + {184980000, 99647.1901536797}, {184990000, 99647.2124990821}, + {185000000, 99647.2407682693}, {185010000, 99647.2696442272}, + {185020000, 99647.2988082953}, {185030000, 99647.3128599109}, + {185040000, 99647.3061271915}, {185050000, 99647.2996793143}, + {185060000, 99647.3112014662}, {185070000, 99647.3347355127}, + {185080000, 99647.3517179065}, {185090000, 99647.3600757177}, + {185100000, 99647.3728765881}, {185110000, 99647.3946244015}, + {185120000, 99647.4151159073}, {185130000, 99647.4185339797}, + {185140000, 99647.405485161}, {185150000, 99647.3964391518}, + {185160000, 99647.3962113938}, {185170000, 99647.3951101237}, + {185180000, 99647.3849909408}, {185190000, 99647.3719688467}, + {185200000, 99647.3752717554}, {185210000, 99647.397008546}, + {185220000, 99647.4240697016}, {185230000, 99647.4519050726}, + {185240000, 99647.4768918152}, {185250000, 99647.4934070981}, + {185260000, 99647.5011561284}, {185270000, 99647.5063000759}, + {185280000, 99647.5109061665}, {185290000, 99647.5203596667}, + {185300000, 99647.5391826644}, {185310000, 99647.5674327543}, + {185320000, 99647.6053918591}, {185330000, 99647.6530489865}, + {185340000, 99647.6893911987}, {185350000, 99647.7071897643}, + {185360000, 99647.7163847332}, {185370000, 99647.7323578839}, + {185380000, 99647.755992538}, {185390000, 99647.7674725533}, + {185400000, 99647.7583627307}, {185410000, 99647.7445093596}, + {185420000, 99647.7392496134}, {185430000, 99647.7407448538}, + {185440000, 99647.7432992339}, {185450000, 99647.7462631507}, + {185460000, 99647.7563455123}, {185470000, 99647.7758428634}, + {185480000, 99647.7978614122}, {185490000, 99647.8117237441}, + {185500000, 99647.8177520939}, {185510000, 99647.8296842112}, + {185520000, 99647.8508281848}, {185530000, 99647.8712623546}, + {185540000, 99647.8826186917}, {185550000, 99647.8889020839}, + {185560000, 99647.9027037146}, {185570000, 99647.9254202852}, + {185580000, 99647.9436783311}, {185590000, 99647.9528682759}, + {185600000, 99647.956252944}, {185610000, 99647.9588776446}, + {185620000, 99647.9610705388}, {185630000, 99647.963159317}, + {185640000, 99647.9652210153}, {185650000, 99647.9672647965}, + {185660000, 99647.9692983844}, {185670000, 99647.9734125207}, + {185680000, 99647.9861888595}, {185690000, 99648.0083343326}, + {185700000, 99648.0331512529}, {185710000, 99648.0583150955}, + {185720000, 99648.0801224029}, {185730000, 99648.0928239912}, + {185740000, 99648.0968020335}, {185750000, 99648.0989205711}, + {185760000, 99648.1005538997}, {185770000, 99648.1121656684}, + {185780000, 99648.1425526097}, {185790000, 99648.1855749489}, + {185800000, 99648.2220813193}, {185810000, 99648.2499307764}, + {185820000, 99648.2681427256}, {185830000, 99648.2764089167}, + {185840000, 99648.275060164}, {185850000, 99648.2645828383}, + {185860000, 99648.2450487241}, {185870000, 99648.2301632108}, + {185880000, 99648.2252255546}, {185890000, 99648.2301834627}, + {185900000, 99648.244985311}, {185910000, 99648.2654365838}, + {185920000, 99648.278353563}, {185930000, 99648.2822723268}, + {185940000, 99648.2975103821}, {185950000, 99648.3310670375}, + {185960000, 99648.3664370485}, {185970000, 99648.3780215135}, + {185980000, 99648.364406553}, {185990000, 99648.3505081551}, + {186000000, 99648.3455519368}, {186010000, 99648.3397779246}, + {186020000, 99648.3249744267}, {186030000, 99648.3072696092}, + {186040000, 99648.3059079549}, {186050000, 99648.322998834}, + {186060000, 99648.3454412367}, {186070000, 99648.3686807773}, + {186080000, 99648.3891619978}, {186090000, 99648.4013567579}, + {186100000, 99648.4049739634}, {186110000, 99648.4202580034}, + {186120000, 99648.4559279304}, {186130000, 99648.4859767701}, + {186140000, 99648.4884993495}, {186150000, 99648.471484402}, + {186160000, 99648.4598173013}, {186170000, 99648.4562937851}, + {186180000, 99648.441171246}, {186190000, 99648.4076503769}, + {186200000, 99648.3657428849}, {186210000, 99648.3309701394}, + {186220000, 99648.3042250754}, {186230000, 99648.2876272478}, + {186240000, 99648.2818772879}, {186250000, 99648.2813585261}, + {186260000, 99648.2813295271}, {186270000, 99648.2816872685}, + {186280000, 99648.2821118691}, {186290000, 99648.2825667708}, + {186300000, 99648.290022394}, {186310000, 99648.3068736886}, + {186320000, 99648.3231138437}, {186330000, 99648.3232039406}, + {186340000, 99648.3062922637}, {186350000, 99648.2996256771}, + {186360000, 99648.3125721551}, {186370000, 99648.34001381}, + {186380000, 99648.3776280123}, {186390000, 99648.4190298312}, + {186400000, 99648.4441766997}, {186410000, 99648.4508683851}, + {186420000, 99648.4521145645}, {186430000, 99648.4524453451}, + {186440000, 99648.4521909099}, {186450000, 99648.4518622861}, + {186460000, 99648.4514903219}, {186470000, 99648.4511088248}, + {186480000, 99648.4507292305}, {186490000, 99648.4554595685}, + {186500000, 99648.4695991706}, {186510000, 99648.4869428112}, + {186520000, 99648.4880068858}, {186530000, 99648.4706546358}, + {186540000, 99648.4479437767}, {186550000, 99648.4244207956}, + {186560000, 99648.4036521893}, {186570000, 99648.3911832264}, + {186580000, 99648.3873059619}, {186590000, 99648.3937177438}, + {186600000, 99648.4111254917}, {186610000, 99648.4337783076}, + {186620000, 99648.4568215291}, {186630000, 99648.4780592171}, + {186640000, 99648.4905647238}, {186650000, 99648.4935914197}, + {186660000, 99648.5008119534}, {186670000, 99648.5169550665}, + {186680000, 99648.5353202571}, {186690000, 99648.545481915}, + {186700000, 99648.5473128533}, {186710000, 99648.5471744308}, + {186720000, 99648.5465691252}, {186730000, 99648.5508487598}, + {186740000, 99648.5645236968}, {186750000, 99648.5855705679}, + {186760000, 99648.6076963657}, {186770000, 99648.6301825079}, + {186780000, 99648.6596700897}, {186790000, 99648.6984434583}, + {186800000, 99648.7332099782}, {186810000, 99648.743300778}, + {186820000, 99648.7275959443}, {186830000, 99648.7273395143}, + {186840000, 99648.7563712104}, {186850000, 99648.7892221923}, + {186860000, 99648.8044074952}, {186870000, 99648.8077724387}, + {186880000, 99648.817599266}, {186890000, 99648.8359331738}, + {186900000, 99648.8497110413}, {186910000, 99648.8544096115}, + {186920000, 99648.8601861269}, {186930000, 99648.8828286411}, + {186940000, 99648.9213125478}, {186950000, 99648.9478298374}, + {186960000, 99648.9557223227}, {186970000, 99648.9597057371}, + {186980000, 99648.9722102342}, {186990000, 99648.9913995378}, + {187000000, 99649.0115624677}, {187010000, 99649.0320469036}, + {187020000, 99649.0525504124}, {187030000, 99649.0729678691}, + {187040000, 99649.0862720516}, {187050000, 99649.0815222545}, + {187060000, 99649.0594151551}, {187070000, 99649.0336241905}, + {187080000, 99649.007008257}, {187090000, 99648.9851751246}, + {187100000, 99648.9728511153}, {187110000, 99648.9680159663}, + {187120000, 99648.9643877135}, {187130000, 99648.9612484618}, + {187140000, 99648.9442873521}, {187150000, 99648.9085777499}, + {187160000, 99648.8675009796}, {187170000, 99648.8418374731}, + {187180000, 99648.8327572341}, {187190000, 99648.8289270426}, + {187200000, 99648.8260963018}, {187210000, 99648.828858425}, + {187220000, 99648.8410882568}, {187230000, 99648.8586685024}, + {187240000, 99648.8686727766}, {187250000, 99648.8696674427}, + {187260000, 99648.8679937482}, {187270000, 99648.865873592}, + {187280000, 99648.860247617}, {187290000, 99648.8463472304}, + {187300000, 99648.8239256938}, {187310000, 99648.8132863943}, + {187320000, 99648.8231986007}, {187330000, 99648.8378612965}, + {187340000, 99648.8439271887}, {187350000, 99648.8453093558}, + {187360000, 99648.8542973798}, {187370000, 99648.87225249}, + {187380000, 99648.8857962699}, {187390000, 99648.8902954612}, + {187400000, 99648.8857502368}, {187410000, 99648.8721354576}, + {187420000, 99648.8494921307}, {187430000, 99648.831645632}, + {187440000, 99648.8237229322}, {187450000, 99648.8307878076}, + {187460000, 99648.857105229}, {187470000, 99648.8922916188}, + {187480000, 99648.9036973538}, {187490000, 99648.8877218618}, + {187500000, 99648.8777261302}, {187510000, 99648.8852982959}, + {187520000, 99648.9006281711}, {187530000, 99648.9084780782}, + {187540000, 99648.9083979779}, {187550000, 99648.9064351608}, + {187560000, 99648.9040307449}, {187570000, 99648.9014223278}, + {187580000, 99648.8988107107}, {187590000, 99648.898281111}, + {187600000, 99648.9064319839}, {187610000, 99648.9239738818}, + {187620000, 99648.9442233682}, {187630000, 99648.9648426161}, + {187640000, 99648.97609123}, {187650000, 99648.9627919737}, + {187660000, 99648.9241511623}, {187670000, 99648.8904754925}, + {187680000, 99648.8766444502}, {187690000, 99648.8774949749}, + {187700000, 99648.888650671}, {187710000, 99648.905822109}, + {187720000, 99648.9155298331}, {187730000, 99648.9162760244}, + {187740000, 99648.9143698165}, {187750000, 99648.9120184202}, + {187760000, 99648.9126099212}, {187770000, 99648.9214274462}, + {187780000, 99648.9387492776}, {187790000, 99648.9589415477}, + {187800000, 99648.9795570999}, {187810000, 99649.000319156}, + {187820000, 99649.0209938704}, {187830000, 99649.0415781011}, + {187840000, 99649.0620609609}, {187850000, 99649.082441662}, + {187860000, 99649.0957347469}, {187870000, 99649.0995288834}, + {187880000, 99649.0939935975}, {187890000, 99649.0793665454}, + {187900000, 99649.0557045918}, {187910000, 99649.036820088}, + {187920000, 99649.0278690591}, {187930000, 99649.0237197413}, + {187940000, 99649.0200296046}, {187950000, 99649.0187859928}, + {187960000, 99649.0262908341}, {187970000, 99649.0432211545}, + {187980000, 99649.0558936009}, {187990000, 99649.0595386507}, + {188000000, 99649.0574174075}, {188010000, 99649.0545907743}, + {188020000, 99649.0513655671}, {188030000, 99649.0480185176}, + {188040000, 99649.0446701144}, {188050000, 99649.0413301207}, + {188060000, 99649.0380067853}, {188070000, 99649.0347000252}, + {188080000, 99649.0314097576}, {188090000, 99649.0281359002}, + {188100000, 99649.0248783713}, {188110000, 99649.0216370894}, + {188120000, 99649.0151332122}, {188130000, 99649.0002527914}, + {188140000, 99648.976728396}, {188150000, 99648.9659065577}, + {188160000, 99648.9752316598}, {188170000, 99648.9840358361}, + {188180000, 99648.97482357}, {188190000, 99648.9556052793}, + {188200000, 99648.9515995133}, {188210000, 99648.9656047158}, + {188220000, 99648.9708839064}, {188230000, 99648.958148026}, + {188240000, 99648.9374283462}, {188250000, 99648.9243198537}, + {188260000, 99648.9184775124}, {188270000, 99648.9063605905}, + {188280000, 99648.8851588049}, {188290000, 99648.8698240902}, + {188300000, 99648.8730092941}, {188310000, 99648.8886828462}, + {188320000, 99648.8979098483}, {188330000, 99648.8985671574}, + {188340000, 99648.9036785503}, {188350000, 99648.9177752376}, + {188360000, 99648.9343275252}, {188370000, 99648.9431672073}, + {188380000, 99648.9437196543}, {188390000, 99648.9416507426}, + {188400000, 99648.9390929412}, {188410000, 99648.9363096603}, + {188420000, 99648.9335240517}, {188430000, 99648.9328171773}, + {188440000, 99648.9407914862}, {188450000, 99648.9581588797}, + {188460000, 99648.9642592545}, {188470000, 99648.9519181862}, + {188480000, 99648.9278262058}, {188490000, 99648.9023759051}, + {188500000, 99648.8761979022}, {188510000, 99648.8498901511}, + {188520000, 99648.8236603661}, {188530000, 99648.8077391249}, + {188540000, 99648.8107792139}, {188550000, 99648.8287349095}, + {188560000, 99648.8489764993}, {188570000, 99648.8700587362}, + {188580000, 99648.8773379163}, {188590000, 99648.8657477048}, + {188600000, 99648.8454180202}, {188610000, 99648.8321095093}, + {188620000, 99648.8267359637}, {188630000, 99648.8237342285}, + {188640000, 99648.8212069813}, {188650000, 99648.8189212161}, + {188660000, 99648.8166792701}, {188670000, 99648.8165490709}, + {188680000, 99648.8251004396}, {188690000, 99648.8430420147}, + {188700000, 99648.8567145172}, {188710000, 99648.8613568762}, + {188720000, 99648.863726372}, {188730000, 99648.8743558843}, + {188740000, 99648.8931977255}, {188750000, 99648.913712974}, + {188760000, 99648.9345840553}, {188770000, 99648.9453683202}, + {188780000, 99648.937233293}, {188790000, 99648.9163018764}, + {188800000, 99648.9017943951}, {188810000, 99648.8958665261}, + {188820000, 99648.8924900029}, {188830000, 99648.8895525441}, + {188840000, 99648.8836758008}, {188850000, 99648.8695822507}, + {188860000, 99648.8469928881}, {188870000, 99648.8289556788}, + {188880000, 99648.8209763198}, {188890000, 99648.8178586208}, + {188900000, 99648.8151949576}, {188910000, 99648.8128937278}, + {188920000, 99648.8106688718}, {188930000, 99648.8084875272}, + {188940000, 99648.8063254991}, {188950000, 99648.8041742542}, + {188960000, 99648.7988195937}, {188970000, 99648.7852392724}, + {188980000, 99648.7631696844}, {188990000, 99648.7454699887}, + {189000000, 99648.7378816361}, {189010000, 99648.7300757303}, + {189020000, 99648.7132981768}, {189030000, 99648.6915582251}, + {189040000, 99648.6774947384}, {189050000, 99648.6725108474}, + {189060000, 99648.6632315669}, {189070000, 99648.6449879873}, + {189080000, 99648.6210561443}, {189090000, 99648.5965341478}, + {189100000, 99648.571731965}, {189110000, 99648.5544501135}, + {189120000, 99648.5475898872}, {189130000, 99648.5406754603}, + {189140000, 99648.5248173583}, {189150000, 99648.5060871913}, + {189160000, 99648.5037007278}, {189170000, 99648.5197719091}, + {189180000, 99648.5272585858}, {189190000, 99648.5167353913}, + {189200000, 99648.4981712674}, {189210000, 99648.4870919882}, + {189220000, 99648.4839600377}, {189230000, 99648.4827049766}, + {189240000, 99648.4818902999}, {189250000, 99648.4812968836}, + {189260000, 99648.480738846}, {189270000, 99648.4802088781}, + {189280000, 99648.4796841466}, {189290000, 99648.4791620323}, + {189300000, 99648.478642522}, {189310000, 99648.4781256027}, + {189320000, 99648.474109623}, {189330000, 99648.4611181921}, + {189340000, 99648.4408356597}, {189350000, 99648.4347777025}, + {189360000, 99648.4474026853}, {189370000, 99648.4639504744}, + {189380000, 99648.4718931234}, {189390000, 99648.4730519188}, + {189400000, 99648.4731337789}, {189410000, 99648.472793109}, + {189420000, 99648.4793099075}, {189430000, 99648.4952108505}, + {189440000, 99648.5170887209}, {189450000, 99648.5396414398}, + {189460000, 99648.5611663673}, {189470000, 99648.5666398537}, + {189480000, 99648.5529728607}, {189490000, 99648.5300683363}, + {189500000, 99648.5063364462}, {189510000, 99648.4840541613}, + {189520000, 99648.4704553109}, {189530000, 99648.466324515}, + {189540000, 99648.4650093904}, {189550000, 99648.4641717301}, + {189560000, 99648.4669014793}, {189570000, 99648.4780325037}, + {189580000, 99648.4978167184}, {189590000, 99648.5051017984}, + {189600000, 99648.4921906562}, {189610000, 99648.4644799211}, + {189620000, 99648.4265653538}, {189630000, 99648.3868676064}, + {189640000, 99648.3720955222}, {189650000, 99648.3851794153}, + {189660000, 99648.4064619566}, {189670000, 99648.4290342998}, + {189680000, 99648.4458400199}, {189690000, 99648.4458268538}, + {189700000, 99648.4284054947}, {189710000, 99648.3982328206}, + {189720000, 99648.3569373707}, {189730000, 99648.320556872}, + {189740000, 99648.3026969165}, {189750000, 99648.2994503297}, + {189760000, 99648.2985430741}, {189770000, 99648.2985659441}, + {189780000, 99648.3058372735}, {189790000, 99648.3225561928}, + {189800000, 99648.3418462999}, {189810000, 99648.3529703699}, + {189820000, 99648.3562985927}, {189830000, 99648.3655825591}, + {189840000, 99648.3840542418}, {189850000, 99648.396746908}, + {189860000, 99648.3909490423}, {189870000, 99648.3747404558}, + {189880000, 99648.3736538777}, {189890000, 99648.3905290407}, + {189900000, 99648.3986963568}, {189910000, 99648.3888319486}, + {189920000, 99648.3707363054}, {189930000, 99648.3596857081}, + {189940000, 99648.3565676655}, {189950000, 99648.3483289649}, + {189960000, 99648.3302552179}, {189970000, 99648.3074864054}, + {189980000, 99648.2843928744}, {189990000, 99648.2631397344}, + {190000000, 99648.2506194459}, {190010000, 99648.247578042}, + {190020000, 99648.2403669917}, {190030000, 99648.2242137457}, + {190040000, 99648.2056506193}, {190050000, 99648.1948776523}, + {190060000, 99648.1924739551}, {190070000, 99648.1849907916}, + {190080000, 99648.1677138865}, {190090000, 99648.1406792222}, + {190100000, 99648.1039244684}, {190110000, 99648.0636862587}, + {190120000, 99648.039748205}, {190130000, 99648.0342917243}, + {190140000, 99648.0343369901}, {190150000, 99648.0353076309}, + {190160000, 99648.036868525}, {190170000, 99648.0384972461}, + {190180000, 99648.0401618962}, {190190000, 99648.0345572282}, + {190200000, 99648.0184346809}, {190210000, 99647.9922019113}, + {190220000, 99647.9562126338}, {190230000, 99647.9167173673}, + {190240000, 99647.8935178327}, {190250000, 99647.8887961877}, + {190260000, 99647.896542041}, {190270000, 99647.9146075113}, + {190280000, 99647.932728452}, {190290000, 99647.934867052}, + {190300000, 99647.9201302521}, {190310000, 99647.9001138174}, + {190320000, 99647.8791817875}, {190330000, 99647.8629539726}, + {190340000, 99647.8562073243}, {190350000, 99647.8548638343}, + {190360000, 99647.8460216048}, {190370000, 99647.8282441928}, + {190380000, 99647.8148773157}, {190390000, 99647.8105865599}, + {190400000, 99647.8120980685}, {190410000, 99647.8143082765}, + {190420000, 99647.8169054065}, {190430000, 99647.8196361825}, + {190440000, 99647.822389435}, {190450000, 99647.8251455917}, + {190460000, 99647.827888002}, {190470000, 99647.8347465972}, + {190480000, 99647.8589096785}, {190490000, 99647.9018038983}, + {190500000, 99647.950098237}, {190510000, 99647.999093309}, + {190520000, 99648.0386628785}, {190530000, 99648.0529432522}, + {190540000, 99648.0410939573}, {190550000, 99648.021321542}, + {190560000, 99648.0001055629}, {190570000, 99647.9731642774}, + {190580000, 99647.9368596677}, {190590000, 99647.8994240286}, + {190600000, 99647.887009474}, {190610000, 99647.9024842942}, + {190620000, 99647.9261737078}, {190630000, 99647.9511412681}, + {190640000, 99647.9703647632}, {190650000, 99647.9728455024}, + {190660000, 99647.9579970604}, {190670000, 99647.9529304052}, + {190680000, 99647.9675305828}, {190690000, 99647.9915917874}, + {190700000, 99648.0164258486}, {190710000, 99648.0397772811}, + {190720000, 99648.0544519303}, {190730000, 99648.0596681957}, + {190740000, 99648.0550789053}, {190750000, 99648.0405937728}, + {190760000, 99648.0198110459}, {190770000, 99647.99834526}, + {190780000, 99647.9765395412}, {190790000, 99647.9697150297}, + {190800000, 99647.983621957}, {190810000, 99648.0075121281}, + {190820000, 99648.0322246311}, {190830000, 99648.0554952358}, + {190840000, 99648.0700929709}, {190850000, 99648.0752315325}, + {190860000, 99648.0845196272}, {190870000, 99648.1027233488}, + {190880000, 99648.1233837597}, {190890000, 99648.1364064816}, + {190900000, 99648.1412171009}, {190910000, 99648.1431617576}, + {190920000, 99648.1445904431}, {190930000, 99648.1406784799}, + {190940000, 99648.1273207523}, {190950000, 99648.1106712768}, + {190960000, 99648.1102786177}, {190970000, 99648.1282989345}, + {190980000, 99648.1517097638}, {190990000, 99648.1759130145}, + {191000000, 99648.1973351585}, {191010000, 99648.2103744004}, + {191020000, 99648.2147308507}, {191030000, 99648.2163243309}, + {191040000, 99648.2173930008}, {191050000, 99648.2131179334}, + {191060000, 99648.1993989125}, {191070000, 99648.1803234742}, + {191080000, 99648.1688411389}, {191090000, 99648.1663942329}, + {191100000, 99648.1596473291}, {191110000, 99648.1439234959}, + {191120000, 99648.1259262948}, {191130000, 99648.1161426887}, + {191140000, 99648.1136854829}, {191150000, 99648.09734968}, + {191160000, 99648.0621307962}, {191170000, 99648.0229157872}, + {191180000, 99647.9924013468}, {191190000, 99647.9667232656}, + {191200000, 99647.9335837491}, {191210000, 99647.891611397}, + {191220000, 99647.8541194445}, {191230000, 99647.8257764352}, + {191240000, 99647.8033363591}, {191250000, 99647.7817349291}, + {191260000, 99647.7606616047}, {191270000, 99647.7398141152}, + {191280000, 99647.7190882419}, {191290000, 99647.6934023458}, + {191300000, 99647.6584269422}, {191310000, 99647.6182312539}, + {191320000, 99647.5857080141}, {191330000, 99647.5622927268}, + {191340000, 99647.548647612}, {191350000, 99647.5449741065}, + {191360000, 99647.5444628642}, {191370000, 99647.5364638737}, + {191380000, 99647.5203674131}, {191390000, 99647.5015351436}, + {191400000, 99647.4823091698}, {191410000, 99647.4680249516}, + {191420000, 99647.4632284156}, {191430000, 99647.4638467999}, + {191440000, 99647.4569614414}, {191450000, 99647.4411322629}, + {191460000, 99647.4296888378}, {191470000, 99647.4273130669}, + {191480000, 99647.4238757851}, {191490000, 99647.4035038239}, + {191500000, 99647.367261754}, {191510000, 99647.3430195974}, + {191520000, 99647.3373784825}, {191530000, 99647.3458543049}, + {191540000, 99647.3646134768}, {191550000, 99647.393519485}, + {191560000, 99647.4322487853}, {191570000, 99647.4807211031}, + {191580000, 99647.5249552208}, {191590000, 99647.5600391874}, + {191600000, 99647.582322915}, {191610000, 99647.586050851}, + {191620000, 99647.5719251543}, {191630000, 99647.5536260617}, + {191640000, 99647.5344164573}, {191650000, 99647.5249809997}, + {191660000, 99647.5344233342}, {191670000, 99647.5566763573}, + {191680000, 99647.5725225553}, {191690000, 99647.5797974044}, + {191700000, 99647.5914699695}, {191710000, 99647.612095105}, + {191720000, 99647.6349172453}, {191730000, 99647.6493582329}, + {191740000, 99647.6561767544}, {191750000, 99647.6692180138}, + {191760000, 99647.6912390964}, {191770000, 99647.7175717697}, + {191780000, 99647.7442276528}, {191790000, 99647.7690449851}, + {191800000, 99647.7851149644}, {191810000, 99647.791688355}, + {191820000, 99647.7954189381}, {191830000, 99647.7986600097}, + {191840000, 99647.7951118108}, {191850000, 99647.7748845762}, + {191860000, 99647.7374567152}, {191870000, 99647.709543569}, + {191880000, 99647.7014888093}, {191890000, 99647.7030684501}, + {191900000, 99647.7055333354}, {191910000, 99647.7066296837}, + {191920000, 99647.699151218}, {191930000, 99647.6823135287}, + {191940000, 99647.6766691059}, {191950000, 99647.6894715267}, + {191960000, 99647.7043258662}, {191970000, 99647.6955275604}, + {191980000, 99647.6616262241}, {191990000, 99647.6273617082}, + {192000000, 99647.6021091867}, {192010000, 99647.5812837342}, + {192020000, 99647.5609680085}, {192030000, 99647.5452019674}, + {192040000, 99647.5469261128}, {192050000, 99647.5675397911}, + {192060000, 99647.5728027067}, {192070000, 99647.5506826139}, + {192080000, 99647.5175002501}, {192090000, 99647.4988179511}, + {192100000, 99647.4961203263}, {192110000, 99647.4916543511}, + {192120000, 99647.4776735076}, {192130000, 99647.4540621785}, + {192140000, 99647.4207282552}, {192150000, 99647.3818198741}, + {192160000, 99647.3505112792}, {192170000, 99647.3282721598}, + {192180000, 99647.3088127394}, {192190000, 99647.2899047286}, + {192200000, 99647.2713811787}, {192210000, 99647.2529808376}, + {192220000, 99647.2346872037}, {192230000, 99647.2240592365}, + {192240000, 99647.2238163001}, {192250000, 99647.2286031776}, + {192260000, 99647.233837164}, {192270000, 99647.239420157}, + {192280000, 99647.2450429795}, {192290000, 99647.2506701769}, + {192300000, 99647.2423509846}, {192310000, 99647.215207779}, + {192320000, 99647.1760682993}, {192330000, 99647.1356053136}, + {192340000, 99647.0944732246}, {192350000, 99647.0609008146}, + {192360000, 99647.0376893308}, {192370000, 99647.0195580318}, + {192380000, 99647.0019878603}, {192390000, 99646.9848768059}, + {192400000, 99646.967903879}, {192410000, 99646.9510318143}, + {192420000, 99646.9342481493}, {192430000, 99646.9175481932}, + {192440000, 99646.8976733711}, {192450000, 99646.8694982642}, + {192460000, 99646.8327497987}, {192470000, 99646.7935753738}, + {192480000, 99646.7540841309}, {192490000, 99646.7196088222}, + {192500000, 99646.6947058974}, {192510000, 99646.6815008162}, + {192520000, 99646.6869162503}, {192530000, 99646.7116605207}, + {192540000, 99646.7281189363}, {192550000, 99646.7265743491}, + {192560000, 99646.7135142269}, {192570000, 99646.6990913058}, + {192580000, 99646.6839298755}, {192590000, 99646.6685578957}, + {192600000, 99646.6532082185}, {192610000, 99646.6429896104}, + {192620000, 99646.6422722151}, {192630000, 99646.6469858416}, + {192640000, 99646.6441808789}, {192650000, 99646.6324117451}, + {192660000, 99646.6180240078}, {192670000, 99646.6032697514}, + {192680000, 99646.5883028084}, {192690000, 99646.5733640977}, + {192700000, 99646.558992474}, {192710000, 99646.5526295529}, + {192720000, 99646.5560162957}, {192730000, 99646.5641336877}, + {192740000, 99646.5726815581}, {192750000, 99646.5836211604}, + {192760000, 99646.6032476327}, {192770000, 99646.6322414929}, + {192780000, 99646.6430407074}, {192790000, 99646.6259583959}, + {192800000, 99646.5975837444}, {192810000, 99646.5839307738}, + {192820000, 99646.5865137969}, {192830000, 99646.5862720178}, + {192840000, 99646.5767099261}, {192850000, 99646.5728068169}, + {192860000, 99646.5873828203}, {192870000, 99646.6144617839}, + {192880000, 99646.6350553772}, {192890000, 99646.6470225865}, + {192900000, 99646.6563814955}, {192910000, 99646.6652716579}, + {192920000, 99646.6772666033}, {192930000, 99646.6979911719}, + {192940000, 99646.7263297347}, {192950000, 99646.7407873769}, + {192960000, 99646.7361761605}, {192970000, 99646.7273837381}, + {192980000, 99646.7271586333}, {192990000, 99646.7316308586}, + {193000000, 99646.7284665294}, {193010000, 99646.7162900646}, + {193020000, 99646.7154135059}, {193030000, 99646.7329824503}, + {193040000, 99646.7588695564}, {193050000, 99646.7771835576}, + {193060000, 99646.7875467714}, {193070000, 99646.7961284767}, + {193080000, 99646.8042397886}, {193090000, 99646.8070251571}, + {193100000, 99646.8003313581}, {193110000, 99646.7923377745}, + {193120000, 99646.8092079801}, {193130000, 99646.8538217099}, + {193140000, 99646.8717628045}, {193150000, 99646.8438466404}, + {193160000, 99646.7963295894}, {193170000, 99646.770417383}, + {193180000, 99646.7685206179}, {193190000, 99646.7742661932}, + {193200000, 99646.7814266583}, {193210000, 99646.794324187}, + {193220000, 99646.8166550833}, {193230000, 99646.8443469844}, + {193240000, 99646.8644256442}, {193250000, 99646.8754422097}, + {193260000, 99646.8767472787}, {193270000, 99646.868142077}, + {193280000, 99646.8564157496}, {193290000, 99646.8522285444}, + {193300000, 99646.8561949728}, {193310000, 99646.8629781059}, + {193320000, 99646.8702156092}, {193330000, 99646.8776603634}, + {193340000, 99646.8851004055}, {193350000, 99646.8904704379}, + {193360000, 99646.8871289345}, {193370000, 99646.8743550309}, + {193380000, 99646.865780611}, {193390000, 99646.8662271171}, + {193400000, 99646.8692072437}, {193410000, 99646.8645241541}, + {193420000, 99646.851591193}, {193430000, 99646.8360855827}, + {193440000, 99646.8201760789}, {193450000, 99646.8142538883}, + {193460000, 99646.8272081748}, {193470000, 99646.8570959644}, + {193480000, 99646.8978782201}, {193490000, 99646.9488164101}, + {193500000, 99646.9956589218}, {193510000, 99647.0333720116}, + {193520000, 99647.0583051483}, {193530000, 99647.064679224}, + {193540000, 99647.0531755693}, {193550000, 99647.0374655559}, + {193560000, 99647.0208317741}, {193570000, 99647.0037909516}, + {193580000, 99646.9867862843}, {193590000, 99646.9698282298}, + {193600000, 99646.9529508173}, {193610000, 99646.9361575812}, + {193620000, 99646.9194481017}, {193630000, 99646.9028219611}, + {193640000, 99646.8926789999}, {193650000, 99646.8991045979}, + {193660000, 99646.9226369153}, {193670000, 99646.9447596918}, + {193680000, 99646.9573194611}, {193690000, 99646.9702827763}, + {193700000, 99646.9921922244}, {193710000, 99647.0190847117}, + {193720000, 99647.0383150211}, {193730000, 99647.0484712579}, + {193740000, 99647.0489163121}, {193750000, 99647.0394553848}, + {193760000, 99647.0268733899}, {193770000, 99647.0218335838}, + {193780000, 99647.0249516638}, {193790000, 99647.0236074366}, + {193800000, 99647.0122377224}, {193810000, 99647.006181533}, + {193820000, 99647.0185989853}, {193830000, 99647.0414735803}, + {193840000, 99647.0491974486}, {193850000, 99647.0389080158}, + {193860000, 99647.0302531539}, {193870000, 99647.0301962732}, + {193880000, 99647.0324072237}, {193890000, 99647.0269265688}, + {193900000, 99647.0131813308}, {193910000, 99646.9968695922}, + {193920000, 99646.9801583107}, {193930000, 99646.9632901629}, + {193940000, 99646.9464735187}, {193950000, 99646.9317712745}, + {193960000, 99646.9258264626}, {193970000, 99646.9293603666}, + {193980000, 99646.9287463998}, {193990000, 99646.9191573342}, + {194000000, 99646.9070406083}, {194010000, 99646.9025395598}, + {194020000, 99646.906238767}, {194030000, 99646.9127721591}, + {194040000, 99646.9197611671}, {194050000, 99646.9168296175}, + {194060000, 99646.8950796025}, {194070000, 99646.8646555381}, + {194080000, 99646.8580132907}, {194090000, 99646.8787607234}, + {194100000, 99646.8798020989}, {194110000, 99646.844470941}, + {194120000, 99646.7891422382}, {194130000, 99646.7395382694}, + {194140000, 99646.6972050585}, {194150000, 99646.6572444371}, + {194160000, 99646.6178908806}, {194170000, 99646.5890690191}, + {194180000, 99646.5792888314}, {194190000, 99646.5866006974}, + {194200000, 99646.6049382082}, {194210000, 99646.6335587193}, + {194220000, 99646.6512344647}, {194230000, 99646.6504598706}, + {194240000, 99646.6378387146}, {194250000, 99646.6237334082}, + {194260000, 99646.608180328}, {194270000, 99646.5845326736}, + {194280000, 99646.551418682}, {194290000, 99646.5289612895}, + {194300000, 99646.5344433605}, {194310000, 99646.5578767728}, + {194320000, 99646.5673684687}, {194330000, 99646.5593293855}, + {194340000, 99646.5391402931}, {194350000, 99646.5087574036}, + {194360000, 99646.4751175647}, {194370000, 99646.4491424088}, + {194380000, 99646.4314649145}, {194390000, 99646.4239985205}, + {194400000, 99646.4274434293}, {194410000, 99646.4209860783}, + {194420000, 99646.386749686}, {194430000, 99646.3367695378}, + {194440000, 99646.3095409356}, {194450000, 99646.3093697752}, + {194460000, 99646.3172630292}, {194470000, 99646.3264480015}, + {194480000, 99646.3364498286}, {194490000, 99646.3465225967}, + {194500000, 99646.3566202933}, {194510000, 99646.3514505811}, + {194520000, 99646.3257783555}, {194530000, 99646.3054016312}, + {194540000, 99646.3124830881}, {194550000, 99646.3412360121}, + {194560000, 99646.3733081701}, {194570000, 99646.4065842466}, + {194580000, 99646.4331531066}, {194590000, 99646.4502216428}, + {194600000, 99646.4579077397}, {194610000, 99646.4563698457}, + {194620000, 99646.4456608377}, {194630000, 99646.4322511479}, + {194640000, 99646.418378661}, {194650000, 99646.409381033}, + {194660000, 99646.4098411903}, {194670000, 99646.4177745775}, + {194680000, 99646.4268630499}, {194690000, 99646.4363770397}, + {194700000, 99646.44599201}, {194710000, 99646.4555914606}, + {194720000, 99646.46865406}, {194730000, 99646.4906715905}, + {194740000, 99646.5205674744}, {194750000, 99646.544165546}, + {194760000, 99646.5586128346}, {194770000, 99646.5736194949}, + {194780000, 99646.597528348}, {194790000, 99646.6263962002}, + {194800000, 99646.6475918566}, {194810000, 99646.6597025159}, + {194820000, 99646.669052876}, {194830000, 99646.6779019622}, + {194840000, 99646.6800342756}, {194850000, 99646.6656269031}, + {194860000, 99646.6341547535}, {194870000, 99646.6113699012}, + {194880000, 99646.6086575656}, {194890000, 99646.6207482801}, + {194900000, 99646.6431043147}, {194910000, 99646.6714937082}, + {194920000, 99646.6923859071}, {194930000, 99646.7042652448}, + {194940000, 99646.706442128}, {194950000, 99646.6987006771}, + {194960000, 99646.6814384286}, {194970000, 99646.6552546064}, + {194980000, 99646.620227718}, {194990000, 99646.5966580558}, + {195000000, 99646.5936908803}, {195010000, 99646.600733461}, + {195020000, 99646.6086665175}, {195030000, 99646.6172951944}, + {195040000, 99646.6260003328}, {195050000, 99646.6347106826}, + {195060000, 99646.6225538859}, {195070000, 99646.5821593595}, + {195080000, 99646.5301812219}, {195090000, 99646.4928531484}, + {195100000, 99646.4717156447}, {195110000, 99646.455822476}, + {195120000, 99646.4409537206}, {195130000, 99646.4367501229}, + {195140000, 99646.4514980416}, {195150000, 99646.4770973569}, + {195160000, 99646.4876084341}, {195170000, 99646.4801269747}, + {195180000, 99646.4603611667}, {195190000, 99646.4303843199}, + {195200000, 99646.3939017275}, {195210000, 99646.3567385262}, + {195220000, 99646.3192811532}, {195230000, 99646.2819042341}, + {195240000, 99646.2446970624}, {195250000, 99646.2177811971}, + {195260000, 99646.2098674392}, {195270000, 99646.2169687934}, + {195280000, 99646.2264251602}, {195290000, 99646.2367761733}, + {195300000, 99646.2334687407}, {195310000, 99646.211360927}, + {195320000, 99646.177213625}, {195330000, 99646.141655225}, + {195340000, 99646.1060673393}, {195350000, 99646.078443708}, + {195360000, 99646.0604446413}, {195370000, 99646.0421370806}, + {195380000, 99646.0149762054}, {195390000, 99645.9828899843}, + {195400000, 99645.9584775067}, {195410000, 99645.9431487383}, + {195420000, 99645.9305967477}, {195430000, 99645.9185618484}, + {195440000, 99645.9103529083}, {195450000, 99645.9112047326}, + {195460000, 99645.9194703642}, {195470000, 99645.9136451097}, + {195480000, 99645.8892126052}, {195490000, 99645.8658799851}, + {195500000, 99645.8606202666}, {195510000, 99645.8696423431}, + {195520000, 99645.8808924534}, {195530000, 99645.8929794276}, + {195540000, 99645.898322115}, {195550000, 99645.8942365426}, + {195560000, 99645.8841125984}, {195570000, 99645.8732793139}, + {195580000, 99645.8620668703}, {195590000, 99645.8583020061}, + {195600000, 99645.8648635381}, {195610000, 99645.8713624839}, + {195620000, 99645.8688508552}, {195630000, 99645.8633211478}, + {195640000, 99645.8740446664}, {195650000, 99645.9031581377}, + {195660000, 99645.9168438777}, {195670000, 99645.9030824483}, + {195680000, 99645.8749622619}, {195690000, 99645.8531597335}, + {195700000, 99645.8389213495}, {195710000, 99645.826999221}, + {195720000, 99645.815577886}, {195730000, 99645.804427102}, + {195740000, 99645.7933481423}, {195750000, 99645.7843843684}, + {195760000, 99645.7841508337}, {195770000, 99645.7933675298}, + {195780000, 99645.798429299}, {195790000, 99645.7944865391}, + {195800000, 99645.7847701118}, {195810000, 99645.7743635907}, + {195820000, 99645.7630890213}, {195830000, 99645.7438576871}, + {195840000, 99645.7150043409}, {195850000, 99645.6967000216}, + {195860000, 99645.7063109743}, {195870000, 99645.7338812063}, + {195880000, 99645.7474958504}, {195890000, 99645.7435569665}, + {195900000, 99645.7413233265}, {195910000, 99645.7476731283}, + {195920000, 99645.753052057}, {195930000, 99645.7423604345}, + {195940000, 99645.7147444413}, {195950000, 99645.6969747122}, + {195960000, 99645.6989468712}, {195970000, 99645.7054502641}, + {195980000, 99645.7033651293}, {195990000, 99645.694496617}, + {196000000, 99645.6845918667}, {196010000, 99645.6743144475}, + {196020000, 99645.6709045626}, {196030000, 99645.6769281238}, + {196040000, 99645.6857462316}, {196050000, 99645.6868769165}, + {196060000, 99645.6797112402}, {196070000, 99645.6700464054}, + {196080000, 99645.6599518695}, {196090000, 99645.6446263142}, + {196100000, 99645.6199328515}, {196110000, 99645.5878539703}, + {196120000, 99645.5547352791}, {196130000, 99645.5213106864}, + {196140000, 99645.4948422516}, {196150000, 99645.4779074417}, + {196160000, 99645.4639422498}, {196170000, 99645.4425835588}, + {196180000, 99645.4132283675}, {196190000, 99645.3811279871}, + {196200000, 99645.3486802352}, {196210000, 99645.3211946668}, + {196220000, 99645.3032466209}, {196230000, 99645.2928538141}, + {196240000, 99645.2837063485}, {196250000, 99645.2750752034}, + {196260000, 99645.2666234298}, {196270000, 99645.258230019}, + {196280000, 99645.2466704123}, {196290000, 99645.2268401794}, + {196300000, 99645.1984639667}, {196310000, 99645.174908824}, + {196320000, 99645.1612935535}, {196330000, 99645.1576113972}, + {196340000, 99645.1638499219}, {196350000, 99645.1738389149}, + {196360000, 99645.1676905443}, {196370000, 99645.1431942402}, + {196380000, 99645.1271629342}, {196390000, 99645.1291681144}, + {196400000, 99645.139549034}, {196410000, 99645.1430514256}, + {196420000, 99645.1387675002}, {196430000, 99645.1390668722}, + {196440000, 99645.1494093979}, {196450000, 99645.1595449318}, + {196460000, 99645.1606238377}, {196470000, 99645.154537524}, + {196480000, 99645.1473466708}, {196490000, 99645.1397531296}, + {196500000, 99645.1320575579}, {196510000, 99645.1243677453}, + {196520000, 99645.1134607749}, {196530000, 99645.0942300043}, + {196540000, 99645.0663997054}, {196550000, 99645.058761606}, + {196560000, 99645.0815050351}, {196570000, 99645.1038283306}, + {196580000, 99645.0991382243}, {196590000, 99645.0771831245}, + {196600000, 99645.0692570677}, {196610000, 99645.0788885857}, + {196620000, 99645.0937518534}, {196630000, 99645.1094177549}, + {196640000, 99645.1255727073}, {196650000, 99645.1417222038}, + {196660000, 99645.1578357981}, {196670000, 99645.166398832}, + {196680000, 99645.1645441194}, {196690000, 99645.1626856241}, + {196700000, 99645.169814559}, {196710000, 99645.1799548532}, + {196720000, 99645.1738374739}, {196730000, 99645.1493233781}, + {196740000, 99645.1401984202}, {196750000, 99645.1585081517}, + {196760000, 99645.1879398646}, {196770000, 99645.2027269988}, + {196780000, 99645.2013503304}, {196790000, 99645.2023100819}, + {196800000, 99645.2126722361}, {196810000, 99645.2275792075}, + {196820000, 99645.242834054}, {196830000, 99645.2583507684}, + {196840000, 99645.2738541199}, {196850000, 99645.289312571}, + {196860000, 99645.2838940449}, {196870000, 99645.2502077188}, + {196880000, 99645.2047985756}, {196890000, 99645.1738224916}, + {196900000, 99645.158826152}, {196910000, 99645.1422192324}, + {196920000, 99645.1161689662}, {196930000, 99645.0956894276}, + {196940000, 99645.0937554676}, {196950000, 99645.1064873587}, + {196960000, 99645.1215016477}, {196970000, 99645.1373666533}, + {196980000, 99645.153433461}, {196990000, 99645.1694687696}, + {197000000, 99645.1822272831}, {197010000, 99645.1865667909}, + {197020000, 99645.1822098185}, {197030000, 99645.1750834773}, + {197040000, 99645.1674759261}, {197050000, 99645.164704971}, + {197060000, 99645.1713642755}, {197070000, 99645.1875121167}, + {197080000, 99645.21344348}, {197090000, 99645.2491490641}, + {197100000, 99645.2737896203}, {197110000, 99645.2799288904}, + {197120000, 99645.2741576199}, {197130000, 99645.2668737437}, + {197140000, 99645.2587705026}, {197150000, 99645.2505006406}, + {197160000, 99645.2422217925}, {197170000, 99645.2339608531}, + {197180000, 99645.2257411153}, {197190000, 99645.2175623735}, + {197200000, 99645.2094244234}, {197210000, 99645.2013270616}, + {197220000, 99645.1932700854}, {197230000, 99645.1852532936}, + {197240000, 99645.1740381325}, {197250000, 99645.1544886003}, + {197260000, 99645.1263267192}, {197270000, 99645.0956649062}, + {197280000, 99645.0646435396}, {197290000, 99645.0385683411}, + {197300000, 99645.022022456}, {197310000, 99645.0150710315}, + {197320000, 99645.0180329447}, {197330000, 99645.0309010888}, + {197340000, 99645.0466910571}, {197350000, 99645.0628893871}, + {197360000, 99645.0761353709}, {197370000, 99645.0811003637}, + {197380000, 99645.0774942491}, {197390000, 99645.0781663687}, + {197400000, 99645.0888298419}, {197410000, 99645.1043240504}, + {197420000, 99645.1201795222}, {197430000, 99645.1363066549}, + {197440000, 99645.1524186993}, {197450000, 99645.1684828034}, + {197460000, 99645.170607047}, {197470000, 99645.1538551906}, + {197480000, 99645.1318227639}, {197490000, 99645.1260156958}, + {197500000, 99645.1368074122}, {197510000, 99645.151496349}, + {197520000, 99645.1670299349}, {197530000, 99645.1728494847}, + {197540000, 99645.1598231323}, {197550000, 99645.1319052064}, + {197560000, 99645.1017344513}, {197570000, 99645.0707725711}, + {197580000, 99645.0465981692}, {197590000, 99645.0319109778}, + {197600000, 99645.0267703417}, {197610000, 99645.0312986475}, + {197620000, 99645.0439569275}, {197630000, 99645.0429093003}, + {197640000, 99645.0229653569}, {197650000, 99644.998878107}, + {197660000, 99644.9834184565}, {197670000, 99644.978874987}, + {197680000, 99644.9927820983}, {197690000, 99645.0259238391}, + {197700000, 99645.0577918066}, {197710000, 99645.0810257871}, + {197720000, 99645.095178756}, {197730000, 99645.0995156071}, + {197740000, 99645.0940229464}, {197750000, 99645.0786052126}, + {197760000, 99645.0532822117}, {197770000, 99645.0282089477}, + {197780000, 99645.0121740603}, {197790000, 99645.0073834346}, + {197800000, 99645.0211073435}, {197810000, 99645.0540992146}, + {197820000, 99645.0719639888}, {197830000, 99645.0623991118}, + {197840000, 99645.0384434345}, {197850000, 99645.0207135097}, + {197860000, 99645.0104545119}, {197870000, 99645.0175429796}, + {197880000, 99645.0458069975}, {197890000, 99645.0792727824}, + {197900000, 99645.1040955518}, {197910000, 99645.1200176755}, + {197920000, 99645.1261047174}, {197930000, 99645.1222927322}, + {197940000, 99645.1224584719}, {197950000, 99645.1315875774}, + {197960000, 99645.1368008277}, {197970000, 99645.1176805047}, + {197980000, 99645.0730784267}, {197990000, 99645.0503112285}, + {198000000, 99645.0675655059}, {198010000, 99645.1042735236}, + {198020000, 99645.1426006168}, {198030000, 99645.1821709189}, + {198040000, 99645.2217795756}, {198050000, 99645.26128794}, + {198060000, 99645.2936966478}, {198070000, 99645.3165110678}, + {198080000, 99645.3267650394}, {198090000, 99645.3197174265}, + {198100000, 99645.2951556576}, {198110000, 99645.257294358}, + {198120000, 99645.2080531393}, {198130000, 99645.1685206562}, + {198140000, 99645.1569641706}, {198150000, 99645.1675492117}, + {198160000, 99645.1816052097}, {198170000, 99645.1969709839}, + {198180000, 99645.2126861408}, {198190000, 99645.2284041731}, + {198200000, 99645.2440948935}, {198210000, 99645.2597103479}, + {198220000, 99645.27524792}, {198230000, 99645.283133812}, + {198240000, 99645.2806741748}, {198250000, 99645.2731778673}, + {198260000, 99645.2652483093}, {198270000, 99645.2590185075}, + {198280000, 99645.261433706}, {198290000, 99645.2732544751}, + {198300000, 99645.294790833}, {198310000, 99645.3261233317}, + {198320000, 99645.3539787314}, {198330000, 99645.3572971395}, + {198340000, 99645.3348896314}, {198350000, 99645.3199679769}, + {198360000, 99645.3241299014}, {198370000, 99645.3325452068}, + {198380000, 99645.3323451675}, {198390000, 99645.3294044785}, + {198400000, 99645.3427427398}, {198410000, 99645.374474122}, + {198420000, 99645.4046872199}, {198430000, 99645.4262259562}, + {198440000, 99645.4421537775}, {198450000, 99645.4573122852}, + {198460000, 99645.4720047915}, {198470000, 99645.4865093943}, + {198480000, 99645.5009240169}, {198490000, 99645.5152585308}, + {198500000, 99645.5295215509}, {198510000, 99645.543713434}, + {198520000, 99645.5578345347}, {198530000, 99645.5718852062}, + {198540000, 99645.5858657996}, {198550000, 99645.5997766645}, + {198560000, 99645.6104352929}, {198570000, 99645.6127803964}, + {198580000, 99645.6065370635}, {198590000, 99645.5755775972}, + {198600000, 99645.5127641744}, {198610000, 99645.4496917916}, + {198620000, 99645.413771002}, {198630000, 99645.4014098241}, + {198640000, 99645.4012107395}, {198650000, 99645.4118093834}, + {198660000, 99645.4256181209}, {198670000, 99645.43989373}, + {198680000, 99645.4510351491}, {198690000, 99645.4533170655}, + {198700000, 99645.4473849831}, {198710000, 99645.4473195288}, + {198720000, 99645.4564896085}, {198730000, 99645.4701498138}, + {198740000, 99645.4841803748}, {198750000, 99645.4964557358}, + {198760000, 99645.5000542217}, {198770000, 99645.4942181129}, + {198780000, 99645.485562764}, {198790000, 99645.4764799454}, + {198800000, 99645.4703700952}, {198810000, 99645.4726445365}, + {198820000, 99645.4836000661}, {198830000, 99645.4820821288}, + {198840000, 99645.4605028745}, {198850000, 99645.4392749324}, + {198860000, 99645.4361071505}, {198870000, 99645.4452026206}, + {198880000, 99645.4478521011}, {198890000, 99645.4419312057}, + {198900000, 99645.4403914342}, {198910000, 99645.4478838754}, + {198920000, 99645.4577770702}, {198930000, 99645.4595327886}, + {198940000, 99645.452942454}, {198950000, 99645.444371527}, + {198960000, 99645.4353913395}, {198970000, 99645.4212002631}, + {198980000, 99645.3976308988}, {198990000, 99645.3707241215}, + {199000000, 99645.3600833518}, {199010000, 99645.367892553}, + {199020000, 99645.3881566523}, {199030000, 99645.418676639}, + {199040000, 99645.4488374183}, {199050000, 99645.4617730996}, + {199060000, 99645.4570364021}, {199070000, 99645.4405826849}, + {199080000, 99645.4137332159}, {199090000, 99645.3868844213}, + {199100000, 99645.3690666493}, {199110000, 99645.3584175169}, + {199120000, 99645.3489627906}, {199130000, 99645.3400097647}, + {199140000, 99645.3312341028}, {199150000, 99645.3225184171}, + {199160000, 99645.3106503941}, {199170000, 99645.2905170615}, + {199180000, 99645.2618395916}, {199190000, 99645.2305092579}, + {199200000, 99645.1988181092}, {199210000, 99645.1720630604}, + {199220000, 99645.1548418907}, {199230000, 99645.145184841}, + {199240000, 99645.1367730302}, {199250000, 99645.1288738708}, + {199260000, 99645.1211512502}, {199270000, 99645.1134833557}, + {199280000, 99645.1058639029}, {199290000, 99645.0982830513}, + {199300000, 99645.0907400093}, {199310000, 99645.0904919717}, + {199320000, 99645.1007567863}, {199330000, 99645.1060707668}, + {199340000, 99645.092956535}, {199350000, 99645.0652714736}, + {199360000, 99645.0353925949}, {199370000, 99645.0047537621}, + {199380000, 99644.9878357243}, {199390000, 99644.9898187348}, + {199400000, 99644.9975160012}, {199410000, 99644.9899939017}, + {199420000, 99644.9660237792}, {199430000, 99644.9369231435}, + {199440000, 99644.9069896758}, {199450000, 99644.8867902596}, + {199460000, 99644.8855082576}, {199470000, 99644.8951491487}, + {199480000, 99644.8898091085}, {199490000, 99644.8665717988}, + {199500000, 99644.8449288377}, {199510000, 99644.8319174944}, + {199520000, 99644.8244876406}, {199530000, 99644.8178055932}, + {199540000, 99644.8115471072}, {199550000, 99644.8054097031}, + {199560000, 99644.7993195958}, {199570000, 99644.7983120137}, + {199580000, 99644.8067573419}, {199590000, 99644.8247066808}, + {199600000, 99644.852434092}, {199610000, 99644.8899280042}, + {199620000, 99644.9233178732}, {199630000, 99644.9476130008}, + {199640000, 99644.96283264}, {199650000, 99644.9689803309}, + {199660000, 99644.9660987123}, {199670000, 99644.9673591852}, + {199680000, 99644.9785775536}, {199690000, 99644.9946210922}, + {199700000, 99645.0110230995}, {199710000, 99645.0276944727}, + {199720000, 99645.044348174}, {199730000, 99645.0609512335}, + {199740000, 99645.0705481383}, {199750000, 99645.0706481124}, + {199760000, 99645.0646426662}, {199770000, 99645.0579067886}, + {199780000, 99645.0507781501}, {199790000, 99645.0363368296}, + {199800000, 99645.0114217029}, {199810000, 99644.986486017}, + {199820000, 99644.9706204404}, {199830000, 99644.96398569}, + {199840000, 99644.9672096088}, {199850000, 99644.9803210021}, + {199860000, 99644.996362509}, {199870000, 99645.012811123}, + {199880000, 99645.0262802149}, {199890000, 99645.0313754542}, + {199900000, 99645.0278005373}, {199910000, 99645.0140086385}, + {199920000, 99644.9894302542}, {199930000, 99644.9697013069}, + {199940000, 99644.9684329395}, {199950000, 99644.9797582479}, + {199960000, 99644.9846941608}, {199970000, 99644.9810819904}, + {199980000, 99644.9749052509}, {199990000, 99644.9683372491}, + {200000000, 99644.9613799365}}; diff --git a/src/tests/algorithms/ADA/ValueFollower.h b/src/tests/algorithms/ADA/ValueFollower.h new file mode 100644 index 0000000000000000000000000000000000000000..4b1b0ab765d2d0bd72fb08631c723e6427f7c6c9 --- /dev/null +++ b/src/tests/algorithms/ADA/ValueFollower.h @@ -0,0 +1,71 @@ +/* Copyright (c) 2022 Skyward Experimental Rocketry + * Author: Alberto Nidasio + * + * 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. + */ + +#pragma once + +#include <drivers/timer/TimestampTimer.h> +#include <sensors/SensorData.h> + +class ValueFollower +{ +public: + ValueFollower(Boardcore::PressureData *data, size_t length, + uint64_t timestampOffset = 0, float pressureOffset = 0) + : data(data), length(length), timestampOffset(timestampOffset), + pressureOffset(pressureOffset) + { + dataDuration = + data[length - 1].pressureTimestamp - data[0].pressureTimestamp; + } + + /** + * @brief Find the nearest data point with the specified timestamp. + */ + float findNext( + uint64_t timestamp = Boardcore::TimestampTimer::getTimestamp()) + { + timestamp = timestamp % dataDuration; + if (data[currentIndex].pressureTimestamp + timestampOffset > timestamp) + return data[currentIndex].pressure + pressureOffset; + + for (; currentIndex < length; currentIndex++) + if (data[currentIndex + 1].pressureTimestamp + timestampOffset > + timestamp) + return data[currentIndex].pressure + pressureOffset; + + return data[length - 1].pressure + pressureOffset; + } + + size_t getSize() { return length; } + + u_int64_t getDataDuration() { return dataDuration; } + +private: + Boardcore::PressureData *data; + size_t length; + + uint64_t timestampOffset; + float pressureOffset; + uint64_t dataDuration; // Duration of reference data + + size_t currentIndex = 0; +}; diff --git a/src/tests/algorithms/ADA/test-ada.cpp b/src/tests/algorithms/ADA/test-ada.cpp new file mode 100644 index 0000000000000000000000000000000000000000..36cefa542eeae2cd1be9acf891e12af3f5e96682 --- /dev/null +++ b/src/tests/algorithms/ADA/test-ada.cpp @@ -0,0 +1,99 @@ +/* Copyright (c) 2022 Skyward Experimental Rocketry + * Author: Alberto Nidasio + * + * 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. + */ + +#include <algorithms/ADA/ADA.h> +#include <miosix.h> +#include <scheduler/TaskScheduler.h> + +#include "EuRoC-pressure-logs.h" +#include "ValueFollower.h" + +using namespace miosix; +using namespace Boardcore; + +ValueFollower reference(euRoCLogs, sizeof(euRoCLogs) / sizeof(PressureData)); + +static constexpr float DEFAULT_REFERENCE_ALTITUDE = 160.0f; +static constexpr float DEFAULT_REFERENCE_PRESSURE = 100022.4f; +static constexpr float KALMAN_INITIAL_ACCELERATION = -500; +static constexpr float DEFAULT_REFERENCE_TEMPERATURE = 288.15f; + +uint64_t currentTimestamp = 0; +constexpr uint64_t DELTA_T = 50 * 1e3; // 50ms = 20Hz +constexpr float SAMPLING_PERIOD = 0.05; + +ADA *ada; + +void step() +{ + currentTimestamp += DELTA_T; + auto currentPressure = reference.findNext(currentTimestamp); + + ada->update(currentPressure); +} + +ReferenceValues getADAReferenceValues() +{ + return {DEFAULT_REFERENCE_ALTITUDE, DEFAULT_REFERENCE_PRESSURE, + DEFAULT_REFERENCE_TEMPERATURE}; +} + +ADA::KalmanFilter::KalmanConfig getADAKalmanConfig() +{ + ADA::KalmanFilter::MatrixNN F_INIT; + F_INIT << 1.0, SAMPLING_PERIOD, 0.5f * SAMPLING_PERIOD * SAMPLING_PERIOD, + // cppcheck-suppress constStatement + 0.0, 1.0, SAMPLING_PERIOD, 0.0, 0.0, 1.0; + ADA::KalmanFilter::MatrixPN H_INIT{1.0, 0.0, 0.0}; + ADA::KalmanFilter::MatrixNN P_INIT; + // cppcheck-suppress constStatement + P_INIT << 1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0; + ADA::KalmanFilter::MatrixNN Q_INIT; + // cppcheck-suppress constStatement + Q_INIT << 30.0, 0.0, 0.0, 0.0, 10.0, 0.0, 0.0, 0.0, 2.5f; + ADA::KalmanFilter::MatrixPP R_INIT{4000.0f}; + + return {F_INIT, + H_INIT, + Q_INIT, + R_INIT, + P_INIT, + ADA::KalmanFilter::CVectorN(DEFAULT_REFERENCE_PRESSURE, 0, + KALMAN_INITIAL_ACCELERATION)}; +} + +int main() +{ + ada = new ADA(getADAReferenceValues(), getADAKalmanConfig()); + + printf("Starting, data duration: %f\n", reference.getDataDuration() / 1e6); + + while (currentTimestamp < reference.getDataDuration()) + { + step(); + + printf("%f, %f\n", currentTimestamp / 1e6, ada->getState().aglAltitude); + } + + while (true) + Thread::sleep(1000); +} diff --git a/src/tests/algorithms/Kalman/test-kalman-eigen-benchmark.cpp b/src/tests/algorithms/Kalman/test-kalman-benchmark.cpp similarity index 81% rename from src/tests/algorithms/Kalman/test-kalman-eigen-benchmark.cpp rename to src/tests/algorithms/Kalman/test-kalman-benchmark.cpp index 7b47c1b28b1e716ed826ce55c6ae9787b6e9e106..52ca7e81c5ea91644604209d62d87c177f02ca6f 100644 --- a/src/tests/algorithms/Kalman/test-kalman-eigen-benchmark.cpp +++ b/src/tests/algorithms/Kalman/test-kalman-benchmark.cpp @@ -26,8 +26,7 @@ #define EIGEN_RUNTIME_NO_MALLOC #include <algorithms/Kalman/Kalman.h> -#include <drivers/timer/GeneralPurposeTimer.h> -#include <drivers/timer/TimerUtils.h> +#include <drivers/timer/TimestampTimer.h> #include <kernel/kernel.h> #include <util/util.h> #include <utils/SkyQuaternion/SkyQuaternion.h> @@ -44,9 +43,6 @@ int main() { printf("RUNNING...\n"); - // Timer for benchmarking purposes - GP32bitTimer timer{TIM5}; - const int n = 3; const int p = 1; @@ -83,8 +79,8 @@ int main() float lastTime = 0.0; // Variable to save the time of the last sample - timer.reset(); - timer.enable(); + uint64_t startTime = TimestampTimer::getTimestamp(); + bool apogeeDetected = false; printf("%d %d \n", TIME.size(), INPUT.size()); @@ -92,8 +88,6 @@ int main() { float time; // Current time as read from csv file float T; // Time elapsed between last sample and current one - uint32_t tick1; - uint32_t tick2; time = TIME[i]; T = time - lastTime; @@ -104,34 +98,23 @@ int main() y(0) = INPUT[i]; - tick1 = timer.readCounter(); - filter.predict(F); if (!filter.correct(y)) - { printf("Correction failed at iteration : %u \n", i); - } - - tick2 = timer.readCounter(); - - printf("%u : %f \n", i, - TimerUtils::toMilliSeconds(timer.getTimer(), tick2 - tick1)); - - // printf("%f, %f, %f;\n", filter.getState()(0), filter.getState()(1), - // filter.getState()(2)); - - // printf("%u \n", MemoryProfiling::getCurrentFreeStack()); lastTime = time; - if (filter.getState()(1) < 0) + if (filter.getState()(1) < 0 && !apogeeDetected) { printf("APOGEE DETECTED at iteration %u ! \n", i); + apogeeDetected = true; } } - // printf("Total time %d \n", timer.interval()); + uint64_t endTime = TimestampTimer::getTimestamp(); + printf("Total time %f \n", (endTime - startTime) / 1e6); - return 0; + while (true) + Thread::sleep(1000); } diff --git a/src/tests/algorithms/NAS/test-nas-parafoil.cpp b/src/tests/algorithms/NAS/test-nas-parafoil.cpp index 57fd167c839ec3bdef2d24c69417ddb7f118aab1..e9d0918bd32f791f95d86a1f7ff9fc40ae88b6b7 100644 --- a/src/tests/algorithms/NAS/test-nas-parafoil.cpp +++ b/src/tests/algorithms/NAS/test-nas-parafoil.cpp @@ -26,7 +26,7 @@ #include <miosix.h> #include <sensors/MPU9250/MPU9250.h> #include <sensors/SensorManager.h> -#include <sensors/UbloxGPS/UbloxGPS.h> +#include <sensors/UBXGPS/UBXGPSSerial.h> #include <utils/AeroUtils/AeroUtils.h> #include <utils/SkyQuaternion/SkyQuaternion.h> @@ -48,14 +48,15 @@ Vector2f startPos = Vector2f(45.501141, 9.156281); NAS* nas; SPIBus spi1(SPI1); -MPU9250* imu = nullptr; -UbloxGPS* gps = nullptr; +MPU9250* imu = nullptr; +UBXGPSSerial* gps = nullptr; int main() { init(); nas = new NAS(getEKConfig()); + nas->setReferenceValues({0, 0, 0, 110000, 20 + 273.5}); setInitialOrientation(); TaskScheduler scheduler; @@ -110,7 +111,7 @@ void init() imu = new MPU9250(spi1, sensors::mpu9250::cs::getPin()); imu->init(); - gps = new UbloxGPS(38400, 10, 2, "gps", 38400); + gps = new UBXGPSSerial(38400, 10, 2, "gps", 38400); gps->init(); gps->start(); @@ -162,7 +163,7 @@ void step() nas->correctAcc(acceleration); if (gpsData.fix) nas->correctGPS(gpsCorrection); - nas->correctBaro(100000, 110000, 20 + 273.5); + nas->correctBaro(100000); auto nasState = nas->getState(); Logger::getInstance().log(imuData); diff --git a/src/tests/algorithms/NAS/test-nas-stack.cpp b/src/tests/algorithms/NAS/test-nas-stack.cpp index e72a1c9830b63682cffff7968cbc27106b85a61f..5eaf14e31b0af562dcdc70b98cf9a6ff14a29107 100644 --- a/src/tests/algorithms/NAS/test-nas-stack.cpp +++ b/src/tests/algorithms/NAS/test-nas-stack.cpp @@ -27,7 +27,7 @@ #include <sensors/BMX160/BMX160.h> #include <sensors/MS5803/MS5803.h> #include <sensors/SensorManager.h> -#include <sensors/UbloxGPS/UbloxGPS.h> +#include <sensors/UBXGPS/UBXGPSSerial.h> #include <utils/AeroUtils/AeroUtils.h> #include <utils/Constants.h> #include <utils/SkyQuaternion/SkyQuaternion.h> @@ -50,9 +50,9 @@ Vector2f startPos = Vector2f(45.501141, 9.156281); NAS* nas; SPIBus spi1(SPI1); -BMX160* imu = nullptr; -UbloxGPS* gps = nullptr; -MS5803* baro = nullptr; +BMX160* imu = nullptr; +UBXGPSSerial* gps = nullptr; +MS5803* baro = nullptr; int main() { @@ -134,7 +134,7 @@ void init() new BMX160(spi1, sensors::bmx160::cs::getPin(), bmx_config, spiConfig); imu->init(); - gps = new UbloxGPS(921600, 10, 2, "gps", 38400); + gps = new UBXGPSSerial(921600, 10, 2, "gps", 38400); gps->init(); gps->start(); @@ -190,8 +190,7 @@ void step() nas->correctAcc(acceleration); if (gpsData.fix) nas->correctGPS(gpsCorrection); - nas->correctBaro(100000, Constants::MSL_PRESSURE, - Constants::MSL_TEMPERATURE); + nas->correctBaro(100000); auto nasState = nas->getState(); diff --git a/src/tests/algorithms/NAS/test-nas-with-triad.cpp b/src/tests/algorithms/NAS/test-nas-with-triad.cpp index 59baeb1d1e37a36035e2fe6208ec22617ea8ad2d..bb1e686a449746ac97d6faad99b405de2055303a 100644 --- a/src/tests/algorithms/NAS/test-nas-with-triad.cpp +++ b/src/tests/algorithms/NAS/test-nas-with-triad.cpp @@ -59,7 +59,7 @@ int main() nas = new NAS(getEKConfig()); // Logger::getInstance().start(); - TimestampTimer::getInstance().resetTimestamp(); + TimestampTimer::resetTimestamp(); sensorManager->start(); while (true) @@ -146,7 +146,7 @@ void bmxCallback() if (calibrating) { - if (TimestampTimer::getInstance().getTimestamp() < CALIBRATION_TIMEOUT) + if (TimestampTimer::getTimestamp() < CALIBRATION_TIMEOUT) { accMean = (accMean * meanCount + acceleration) / (meanCount + 1); magMean = (magMean * meanCount + acceleration) / (meanCount + 1); @@ -200,7 +200,7 @@ void bmxCallback() auto nasState = nas->getState(); - nasState.timestamp = TimestampTimer::getInstance().getTimestamp(); + nasState.timestamp = TimestampTimer::getTimestamp(); data.accelerationTimestamp = nasState.timestamp; data.magneticFieldTimestamp = nasState.timestamp; data.angularVelocityTimestamp = nasState.timestamp; diff --git a/src/tests/algorithms/NAS/test-tmp.cpp b/src/tests/algorithms/NAS/test-tmp.cpp deleted file mode 100644 index 39fcdbd511705c39361f2a926ef92c15ea662ff9..0000000000000000000000000000000000000000 --- a/src/tests/algorithms/NAS/test-tmp.cpp +++ /dev/null @@ -1,89 +0,0 @@ -/* Copyright (c) 2021 Skyward Experimental Rocketry - * Author: Alberto Nidasio - * - * 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. - */ - -#include <drivers/spi/SPIDriver.h> -#include <drivers/timer/TimestampTimer.h> -#include <miosix.h> -#include <sensors/BMX160/BMX160.h> -#include <sensors/MPU9250/MPU9250.h> -#include <utils/Debug.h> - -using namespace miosix; - -using namespace Boardcore; - -GpioPin mpuCs = GpioPin(GPIOG_BASE, 3); -SPIBus spi1(SPI1); - -MPU9250* mpu = nullptr; -BMX160* bmx = nullptr; - -void initBoard() -{ - // Chip select pin as output starting high - mpuCs.mode(miosix::Mode::OUTPUT); - mpuCs.high(); - - mpu = new MPU9250(spi1, mpuCs); - - SPIBusConfig spiConfig; - spiConfig.clockDivider = SPI::ClockDivider::DIV_8; - - BMX160Config bmxConfig; - bmxConfig.fifoMode = BMX160Config::FifoMode::HEADER; - bmxConfig.fifoWatermark = 80; - bmxConfig.fifoInterrupt = BMX160Config::FifoInterruptPin::PIN_INT1; - bmxConfig.temperatureDivider = 1; - bmxConfig.accelerometerRange = BMX160Config::AccelerometerRange::G_16; - bmxConfig.gyroscopeRange = BMX160Config::GyroscopeRange::DEG_1000; - bmxConfig.accelerometerDataRate = BMX160Config::OutputDataRate::HZ_100; - bmxConfig.gyroscopeDataRate = BMX160Config::OutputDataRate::HZ_100; - bmxConfig.magnetometerRate = BMX160Config::OutputDataRate::HZ_100; - bmxConfig.gyroscopeUnit = BMX160Config::GyroscopeMeasureUnit::RAD; - bmx = new BMX160(spi1, miosix::sensors::bmx160::cs::getPin(), bmxConfig, - spiConfig); - - mpu->init(); - bmx->init(); -} - -int main() -{ - initBoard(); - - auto lastTick = getTick(); - while (true) - { - mpu->sample(); - bmx->sample(); - auto mpuData = mpu->getLastSample(); - auto bmxData = bmx->getLastSample(); - - printf("%f,%f,%f,", mpuData.magneticFieldX, mpuData.magneticFieldY, - mpuData.magneticFieldZ); - printf("%f,%f,%f\n", bmxData.magneticFieldX, bmxData.magneticFieldY, - bmxData.magneticFieldZ); - - Thread::sleepUntil(lastTick + 20); - lastTick = getTick(); - } -} diff --git a/src/tests/catch/test-kalman-eigen.cpp b/src/tests/catch/test-kalman.cpp similarity index 100% rename from src/tests/catch/test-kalman-eigen.cpp rename to src/tests/catch/test-kalman.cpp diff --git a/src/tests/catch/test-packetqueue.cpp b/src/tests/catch/test-packetqueue.cpp index e0cf2865ac8da3f9dbc691dbcd583c2aaa79ec03..0b7eecdc0ce2cab70fcb60650b12d5ee9712e092 100644 --- a/src/tests/catch/test-packetqueue.cpp +++ b/src/tests/catch/test-packetqueue.cpp @@ -86,8 +86,7 @@ TEST_CASE("Packet tests") REQUIRE(p.append(messageBase, 5)); uint64_t ts = p.getTimestamp(); - REQUIRE(Boardcore::TimestampTimer::getInstance().getTimestamp() - ts < - 5); + REQUIRE(Boardcore::TimestampTimer::getTimestamp() - ts < 5); REQUIRE(p.dump(buf) == 5); COMPARE(buf, BUF_LEN, "01234"); diff --git a/src/tests/catch/xbee/test-xbee-parser.cpp b/src/tests/catch/xbee/test-xbee-parser.cpp index 924d96851e8970f3729ef57d13f65de28ae78be1..26867ab7acd2037a74f063e06089dd0d52c61e2f 100644 --- a/src/tests/catch/xbee/test-xbee-parser.cpp +++ b/src/tests/catch/xbee/test-xbee-parser.cpp @@ -71,9 +71,7 @@ void printu64(uint64_t v) uint8_t* p = reinterpret_cast<uint8_t*>(&v); for (int i = 0; i < 8; i++) - { printf("%02X ", p[i]); - } printf("\n"); } diff --git a/src/tests/drivers/canbus/SimpleCanManager.h b/src/tests/drivers/canbus/CanDriver/SimpleCanManager.h similarity index 95% rename from src/tests/drivers/canbus/SimpleCanManager.h rename to src/tests/drivers/canbus/CanDriver/SimpleCanManager.h index f7ff5a59d5c65a83500948b128f2f0714c344701..141c5a60e2fe12c72607cd171f35231313874559 100644 --- a/src/tests/drivers/canbus/SimpleCanManager.h +++ b/src/tests/drivers/canbus/CanDriver/SimpleCanManager.h @@ -21,16 +21,16 @@ */ #pragma once + +#include <ActiveObject.h> +#include <drivers/canbus/CanDriver/BusLoadEstimation.h> +#include <drivers/canbus/CanDriver/CanDriver.h> #include <miosix.h> +#include <utils/collections/SyncCircularBuffer.h> #include <cstdlib> #include <functional> -#include "ActiveObject.h" -#include "drivers/canbus/BusLoadEstimation.h" -#include "drivers/canbus/Canbus.h" -#include "utils/collections/SyncCircularBuffer.h" - using std::function; class SimpleCanManager diff --git a/src/tests/drivers/canbus/test-canbus-2way.cpp b/src/tests/drivers/canbus/CanDriver/test-can-2way.cpp similarity index 96% rename from src/tests/drivers/canbus/test-canbus-2way.cpp rename to src/tests/drivers/canbus/CanDriver/test-can-2way.cpp index 91b69f5c2b9589fc67bfe5c843f0ed3eadad35b9..1a22bdfc874f306cfa4222838a19cd6b7ac02628 100644 --- a/src/tests/drivers/canbus/test-canbus-2way.cpp +++ b/src/tests/drivers/canbus/CanDriver/test-can-2way.cpp @@ -25,17 +25,17 @@ // considered lost. It may also receive requests from other canbus devices, to // which it will respond +#include <ActiveObject.h> +#include <diagnostic/PrintLogger.h> +#include <drivers/canbus/CanDriver/BusLoadEstimation.h> +#include <drivers/canbus/CanDriver/CanDriver.h> #include <utils/Debug.h> #include <utils/Stats/Stats.h> +#include <utils/collections/CircularBuffer.h> #include <string> -#include "ActiveObject.h" #include "SimpleCanManager.h" -#include "diagnostic/PrintLogger.h" -#include "drivers/canbus/BusLoadEstimation.h" -#include "drivers/canbus/Canbus.h" -#include "utils/collections/CircularBuffer.h" constexpr uint32_t BAUD_RATE = 500 * 1000; constexpr float SAMPLE_POINT = 87.5f / 100.0f; diff --git a/src/tests/drivers/canbus/test-canbus-filters.cpp b/src/tests/drivers/canbus/CanDriver/test-can-filters.cpp similarity index 97% rename from src/tests/drivers/canbus/test-canbus-filters.cpp rename to src/tests/drivers/canbus/CanDriver/test-can-filters.cpp index 64c8868840454afd28abcb7506592713ceb08095..b6c3f6b667ffcac3ff1021d99634f5430ec08b78 100644 --- a/src/tests/drivers/canbus/test-canbus-filters.cpp +++ b/src/tests/drivers/canbus/CanDriver/test-can-filters.cpp @@ -22,8 +22,8 @@ #include <ActiveObject.h> #include <diagnostic/PrintLogger.h> -#include <drivers/canbus/BusLoadEstimation.h> -#include <drivers/canbus/Canbus.h> +#include <drivers/canbus/CanDriver/BusLoadEstimation.h> +#include <drivers/canbus/CanDriver/CanDriver.h> #include <string> diff --git a/src/tests/drivers/canbus/test-canbus-loopback.cpp b/src/tests/drivers/canbus/CanDriver/test-can-loopback.cpp similarity index 96% rename from src/tests/drivers/canbus/test-canbus-loopback.cpp rename to src/tests/drivers/canbus/CanDriver/test-can-loopback.cpp index d01ac89a1eee286837069dde8cbd8c8eef46e28e..06559020e6eaee2e933d2ce66696ec2a1c5baf44 100644 --- a/src/tests/drivers/canbus/test-canbus-loopback.cpp +++ b/src/tests/drivers/canbus/CanDriver/test-can-loopback.cpp @@ -20,12 +20,12 @@ * THE SOFTWARE. */ -#include <string> +#include <ActiveObject.h> +#include <diagnostic/PrintLogger.h> +#include <drivers/canbus/CanDriver/BusLoadEstimation.h> +#include <drivers/canbus/CanDriver/CanDriver.h> -#include "ActiveObject.h" -#include "diagnostic/PrintLogger.h" -#include "drivers/canbus/BusLoadEstimation.h" -#include "drivers/canbus/Canbus.h" +#include <string> using std::string; using namespace Boardcore; diff --git a/src/tests/drivers/canbus/CanProtocol/test-can-protocol.cpp b/src/tests/drivers/canbus/CanProtocol/test-can-protocol.cpp new file mode 100644 index 0000000000000000000000000000000000000000..bc1bc8b1c29e69fef80e53a7038a222cd0f2cb10 --- /dev/null +++ b/src/tests/drivers/canbus/CanProtocol/test-can-protocol.cpp @@ -0,0 +1,88 @@ +/* Copyright (c) 2022 Skyward Experimental Rocketry + * Author: Federico Mandelli + * + * 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. + */ + +#include <drivers/canbus/CanProtocol/CanProtocol.h> +#include <drivers/timer/TimestampTimer.h> +#include <scheduler/TaskScheduler.h> + +using namespace std; +using namespace miosix; +using namespace Boardcore; +using namespace Canbus; + +void print(const CanMessage& msg) +{ + printf("Received packet:\n"); + printf("\tpriority: %d\n", msg.getPriority()); + printf("\tprimary type: %d\n", msg.getPrimaryType()); + printf("\tsource: %d\n", msg.getSource()); + printf("\tdestination: %d\n", msg.getDestination()); + printf("\tsecondary type: %d\n", msg.getSecondaryType()); + printf("\n"); +} + +int main() +{ + // Prepare the cab driver + CanbusDriver::CanbusConfig config; + config.loopback = true; + CanbusDriver::AutoBitTiming bitTiming; + bitTiming.baudRate = 500 * 1000; + bitTiming.samplePoint = 87.5f / 100.0f; + CanbusDriver* driver = new CanbusDriver(CAN1, config, bitTiming); + + // Prepare the can driver + CanProtocol protocol(driver, print); + + // Add a filter to allow every message + Mask32FilterBank f2(0, 0, 1, 1, 0, 0, 0); + driver->addFilter(f2); + driver->init(); + + // Start the protocol + protocol.start(); + + CanMessage msg1; + msg1.id = 0x200; + msg1.length = 2; + msg1.payload[0] = 0xffffffffffffffff; + msg1.payload[1] = 0x0123456789ABCDEF; + + TaskScheduler scheduler; + + scheduler.addTask([&]() { protocol.enqueueMsg(msg1); }, 1000); + scheduler.addTask( + [&]() + { + PitotData data{TimestampTimer::getTimestamp(), 23}; + + protocol.enqueueData(0xF, 0xA, 0x1, 0x2, 0xB, data); + }, + 2000); + + scheduler.start(); + + printf("Started\n"); + + while (true) + Thread::sleep(1000); +} diff --git a/src/tests/drivers/sx1278/test-sx1278-bench.cpp b/src/tests/drivers/sx1278/test-sx1278-bench.cpp index 31db75f4f5c47aa0a847be004e403718df858116..8850e9c14af2fac4599c9e6778f059c262cfed14 100644 --- a/src/tests/drivers/sx1278/test-sx1278-bench.cpp +++ b/src/tests/drivers/sx1278/test-sx1278-bench.cpp @@ -25,50 +25,72 @@ #include <thread> -#include "test-sx1278-core.h" - using namespace Boardcore; using namespace miosix; -/** - * 0 -> RX - * 1 -> TX - * - * Connection diagram: - * sx1278[0]:nss -> stm32:pa1 - * sx1278[0]:dio0 -> stm32:pc15 - * sx1278[0]:mosi -> stm32:pc12 (SPI3_MOSI) - * sx1278[0]:miso -> stm32:pc11 (SPI3_MISO) - * sx1278[0]:sck -> stm32:pc10 (SPI3_SCK) - - * sx1278[1]:nss -> stm32:pa2 - * sx1278[1]:dio0 -> stm32:pc0 - * sx1278[1]:mosi -> stm32:pb15 (SPI2_MOSI) - * sx1278[1]:miso -> stm32:pb14 (SPI2_MISO) - * sx1278[1]:sck -> stm32:pb13 (SPI2_SCK) - */ +struct Stats; + +const char *stringFromErr(SX1278::Error err) +{ + switch (err) + { + case SX1278::Error::BAD_VALUE: + return "Error::BAD_VALUE"; + + case SX1278::Error::BAD_VERSION: + return "Error::BAD_VERSION"; -SPIBus bus0(SPI3); -SPIBus bus1(SPI2); + default: + return "<unknown>"; + } +} -GpioPin sck0(GPIOC_BASE, 10); -GpioPin miso0(GPIOC_BASE, 11); -GpioPin mosi0(GPIOC_BASE, 12); -GpioPin cs0(GPIOA_BASE, 1); -GpioPin dio0(GPIOC_BASE, 15); +// Simple xorshift RNG +uint32_t xorshift32() +{ + // https://xkcd.com/221/ + static uint32_t STATE = 0x08104444; -GpioPin sck1(GPIOB_BASE, 13); -GpioPin miso1(GPIOB_BASE, 14); -GpioPin mosi1(GPIOB_BASE, 15); -GpioPin cs1(GPIOA_BASE, 2); -GpioPin dio1(GPIOC_BASE, 0); + uint32_t x = STATE; + x ^= x << 13; + x ^= x >> 17; + x ^= x << 5; -struct Stats; + return STATE = x; +} + +#if defined _BOARD_STM32F429ZI_SKYWARD_GS +#include "interfaces-impl/hwmapping.h" + +#if 1 // use ra01 +using cs = peripherals::ra01::cs; +using dio0 = peripherals::ra01::dio0; +#else +using cs = peripherals::sx127x::cs; +using dio0 = peripherals::sx127x::dio0; +#endif -const char *stringFromErr(SX1278::Error err); -const char *stringFromRxBw(SX1278::RxBw rx_bw); +using sck = interfaces::spi4::sck; +using miso = interfaces::spi4::miso; +using mosi = interfaces::spi4::mosi; -void printStats(Stats stats); +#define SX1278_SPI SPI4 + +#elif defined _BOARD_STM32F429ZI_SKYWARD_DEATHST_V3 +#include "interfaces-impl/hwmapping.h" + +using cs = sensors::sx127x::cs; +using dio0 = sensors::sx127x::dio0; + +using sck = interfaces::spi5::sck; +using miso = interfaces::spi5::miso; +using mosi = interfaces::spi5::mosi; + +#define SX1278_SPI SPI5 + +#else +#error "Target not supported" +#endif /// Status informations. struct Stats @@ -91,37 +113,52 @@ struct Stats } } + void print() const + { + // Prints are REALLY slow, so take a COPY of stats, so we can print an + // instant in time. + Stats stats_now = *this; + + printf("stats.last_recv_packet = %d\n", stats_now.last_recv_packet); + printf("stats.corrupted_packets = %d\n", stats_now.corrupted_packets); + printf("stats.send_count = %d\n", stats_now.send_count); + printf("stats.recv_count = %d\n", stats_now.recv_count); + printf("stats.recv_errors = %d\n", stats_now.recv_errors); + printf("stats.packet_loss = %.2f %%\n", + stats_now.packet_loss() * 100.0f); + } + } stats; -SX1278 *sx1278[2] = {nullptr, nullptr}; +SX1278 *sx1278 = nullptr; + +// Payload size in 32bit blocks +constexpr size_t PAYLOAD_SIZE = 14; struct Msg { - int idx; - int dummy_1; - int dummy_2; - int dummy_3; - - const static int DUMMY_1 = 0xdeadbeef; - const static int DUMMY_2 = 0xbeefdead; - const static int DUMMY_3 = 0x1234abcd; + uint32_t idx; + uint32_t payload[PAYLOAD_SIZE]; }; -void recvLoop(int idx) +void recvLoop() { while (1) { Msg msg; memset(&msg, 0, sizeof(msg)); - int len = sx1278[idx]->receive((uint8_t *)&msg, sizeof(msg)); + int len = sx1278->receive((uint8_t *)&msg, sizeof(msg)); + + uint32_t acc = 0; + for (size_t i = 0; i < PAYLOAD_SIZE; i++) + acc ^= msg.payload[i]; if (len != sizeof(msg)) { stats.recv_errors++; } - else if (msg.dummy_1 != Msg::DUMMY_1 || msg.dummy_2 != Msg::DUMMY_2 || - msg.dummy_3 != Msg::DUMMY_3) + else if (acc != 0) { stats.recv_errors++; stats.corrupted_packets++; @@ -134,19 +171,26 @@ void recvLoop(int idx) } } -void sendLoop(int idx) +void sendLoop() { while (1) { int next_idx = stats.send_count + 1; Msg msg; - msg.idx = next_idx; - msg.dummy_1 = Msg::DUMMY_1; - msg.dummy_2 = Msg::DUMMY_2; - msg.dummy_3 = Msg::DUMMY_3; + msg.idx = next_idx; - sx1278[idx]->send((uint8_t *)&msg, sizeof(msg)); + // Setup the buffer so that the xor of the full thing is 0 + uint32_t acc = 0; + for (size_t i = 0; i < PAYLOAD_SIZE - 1; i++) + { + // Fill only the lower 8bit to simulate a lot of zeroes + msg.payload[i] = xorshift32() & 0xff; + acc ^= msg.payload[i]; + } + msg.payload[PAYLOAD_SIZE - 1] = acc; + + sx1278->send((uint8_t *)&msg, sizeof(msg)); stats.send_count = next_idx; } } @@ -154,116 +198,55 @@ void sendLoop(int idx) /// Get current time long long now() { return miosix::getTick() * 1000 / miosix::TICK_FREQ; } -void __attribute__((used)) EXTI15_IRQHandlerImpl() -{ - if (sx1278[0]) - sx1278[0]->handleDioIRQ(); -} - -void __attribute__((used)) EXTI0_IRQHandlerImpl() -{ - if (sx1278[1]) - sx1278[1]->handleDioIRQ(); -} - -/// Initialize stm32f407g board (sx1278[0] only) -void initBoard0() +#if defined _BOARD_STM32F429ZI_SKYWARD_GS +void __attribute__((used)) EXTI6_IRQHandlerImpl() +#elif defined _BOARD_STM32F429ZI_SKYWARD_DEATHST_V3 +void __attribute__((used)) EXTI10_IRQHandlerImpl() +#else +#error "Target not supported" +#endif { - { - miosix::FastInterruptDisableLock dLock; - - // Enable SPI3 - RCC->APB1ENR |= RCC_APB1ENR_SPI3EN; - RCC_SYNC(); - - // Setup SPI pins - sck0.mode(miosix::Mode::ALTERNATE); - sck0.alternateFunction(6); - miso0.mode(miosix::Mode::ALTERNATE); - miso0.alternateFunction(6); - mosi0.mode(miosix::Mode::ALTERNATE); - mosi0.alternateFunction(6); - - cs0.mode(miosix::Mode::OUTPUT); - dio0.mode(miosix::Mode::INPUT); - } - - cs0.high(); - enableExternalInterrupt(dio0.getPort(), dio0.getNumber(), - InterruptTrigger::RISING_EDGE); + if (sx1278) + sx1278->handleDioIRQ(); } -/// Initialize stm32f407g board (sx1278[1] only) -void initBoard1() +void initBoard() { - { - miosix::FastInterruptDisableLock dLock; - - // Enable SPI2 - RCC->APB1ENR |= RCC_APB1ENR_SPI2EN; - RCC_SYNC(); - - sck1.mode(miosix::Mode::ALTERNATE); - sck1.alternateFunction(5); - miso1.mode(miosix::Mode::ALTERNATE); - miso1.alternateFunction(5); - mosi1.mode(miosix::Mode::ALTERNATE); - mosi1.alternateFunction(5); - - cs1.mode(miosix::Mode::OUTPUT); - dio1.mode(miosix::Mode::INPUT); - } - - cs1.high(); - enableExternalInterrupt(dio1.getPort(), dio1.getNumber(), - InterruptTrigger::RISING_EDGE); +#if defined _BOARD_STM32F429ZI_SKYWARD_GS + enableExternalInterrupt(GPIOF_BASE, 6, InterruptTrigger::RISING_EDGE); +#elif defined _BOARD_STM32F429ZI_SKYWARD_DEATHST_V3 + enableExternalInterrupt(GPIOF_BASE, 10, InterruptTrigger::RISING_EDGE); +#else +#error "Target not supported" +#endif } int main() { -#ifndef DISABLE_RX - initBoard0(); -#endif -#ifndef DISABLE_TX - initBoard1(); -#endif + initBoard(); // Run default configuration SX1278::Config config; SX1278::Error err; - // Configure them -#ifndef DISABLE_RX - sx1278[0] = new SX1278(bus0, cs0); + SPIBus bus(SX1278_SPI); + GpioPin cs = cs::getPin(); - printf("\n[sx1278] Configuring sx1278[0]...\n"); - printConfig(config); - if ((err = sx1278[0]->init(config)) != SX1278::Error::NONE) - { - printf("[sx1278] sx1278[0]->init error: %s\n", stringFromErr(err)); - return -1; - } -#endif - -#ifndef DISABLE_TX - sx1278[1] = new SX1278(bus1, cs1); + sx1278 = new SX1278(bus, cs); - printf("\n[sx1278] Configuring sx1278[1]...\n"); - printConfig(config); - if ((err = sx1278[1]->init(config)) != SX1278::Error::NONE) + printf("\n[sx1278] Configuring sx1278...\n"); + if ((err = sx1278->init(config)) != SX1278::Error::NONE) { - printf("[sx1278] sx1278[1]->init error: %s\n", stringFromErr(err)); + printf("[sx1278] sx1278->init error: %s\n", stringFromErr(err)); return -1; } -#endif // Run background threads #ifndef DISABLE_RX - std::thread recv([]() { recvLoop(0); }); + std::thread recv([]() { recvLoop(); }); #endif #ifndef DISABLE_TX - miosix::Thread::sleep(500); - std::thread send([]() { sendLoop(1); }); + std::thread send([]() { sendLoop(); }); #endif // Finish! @@ -285,7 +268,7 @@ int main() ((float)elapsed / 1000.0f); printf("\n[sx1278] Stats:\n"); - printStats(stats); + stats.print(); printf("tx_bitrate: %.2f kb/s\n", tx_bitrate / 1000.0f); printf("rx_bitrate: %.2f kb/s\n", rx_bitrate / 1000.0f); @@ -294,16 +277,3 @@ int main() return 0; } - -void printStats(Stats stats) -{ - // Prints are REALLY slow, so take a COPY of stats, so we can print an - // instant in time. - - printf("stats.last_recv_packet = %d\n", stats.last_recv_packet); - printf("stats.corrupted_packets = %d\n", stats.corrupted_packets); - printf("stats.send_count = %d\n", stats.send_count); - printf("stats.recv_count = %d\n", stats.recv_count); - printf("stats.recv_errors = %d\n", stats.recv_errors); - printf("stats.packet_loss = %.2f %%\n", stats.packet_loss() * 100.0f); -} diff --git a/src/tests/drivers/sx1278/test-sx1278-bidir.cpp b/src/tests/drivers/sx1278/test-sx1278-bidir.cpp index c0cc885bf6c9b84693700cb808e3909f81779045..174474ae654548c7d46dfc3909907fb31839eba3 100644 --- a/src/tests/drivers/sx1278/test-sx1278-bidir.cpp +++ b/src/tests/drivers/sx1278/test-sx1278-bidir.cpp @@ -21,179 +21,146 @@ */ #include <drivers/interrupt/external_interrupts.h> +#include <miosix.h> #include <radio/SX1278/SX1278.h> #include <cstring> #include <thread> -#include "test-sx1278-core.h" - using namespace Boardcore; using namespace miosix; -/** - * Connection diagram: - * sx1278[0]:nss -> stm32:pa1 - * sx1278[0]:dio0 -> stm32:pc15 - * sx1278[0]:mosi -> stm32:pc12 (SPI3_MOSI) - * sx1278[0]:miso -> stm32:pc11 (SPI3_MISO) - * sx1278[0]:sck -> stm32:pc10 (SPI3_SCK) - - * sx1278[1]:nss -> stm32:pa2 - * sx1278[1]:dio0 -> stm32:pc0 - * sx1278[1]:mosi -> stm32:pb15 (SPI2_MOSI) - * sx1278[1]:miso -> stm32:pb14 (SPI2_MISO) - * sx1278[1]:sck -> stm32:pb13 (SPI2_SCK) - */ +const char *stringFromErr(SX1278::Error err) +{ + switch (err) + { + case SX1278::Error::BAD_VALUE: + return "Error::BAD_VALUE"; -SPIBus bus0(SPI3); -SPIBus bus1(SPI2); + case SX1278::Error::BAD_VERSION: + return "Error::BAD_VERSION"; -GpioPin sck0(GPIOC_BASE, 10); -GpioPin miso0(GPIOC_BASE, 11); -GpioPin mosi0(GPIOC_BASE, 12); -GpioPin cs0(GPIOA_BASE, 1); -GpioPin dio0(GPIOC_BASE, 15); + default: + return "<unknown>"; + } +} -GpioPin sck1(GPIOB_BASE, 13); -GpioPin miso1(GPIOB_BASE, 14); -GpioPin mosi1(GPIOB_BASE, 15); -GpioPin cs1(GPIOA_BASE, 2); -GpioPin dio1(GPIOC_BASE, 0); +#if defined _BOARD_STM32F429ZI_SKYWARD_GS +#include "interfaces-impl/hwmapping.h" -SX1278 *sx1278[2] = {nullptr, nullptr}; +#if 1 // use ra01 +using cs = peripherals::ra01::cs; +using dio0 = peripherals::ra01::dio0; +#else +using cs = peripherals::sx127x::cs; +using dio0 = peripherals::sx127x::dio0; +#endif -void __attribute__((used)) EXTI15_IRQHandlerImpl() -{ - if (sx1278[0]) - sx1278[0]->handleDioIRQ(); -} +using sck = interfaces::spi4::sck; +using miso = interfaces::spi4::miso; +using mosi = interfaces::spi4::mosi; -void __attribute__((used)) EXTI0_IRQHandlerImpl() -{ - if (sx1278[1]) - sx1278[1]->handleDioIRQ(); -} +#define SX1278_SPI SPI4 -/// Initialize stm32f407g board (sx1278[0] only) -void initBoard0() -{ - { - miosix::FastInterruptDisableLock dLock; - - // Enable SPI3 - RCC->APB1ENR |= RCC_APB1ENR_SPI3EN; - RCC_SYNC(); - - // Setup SPI pins - sck0.mode(miosix::Mode::ALTERNATE); - sck0.alternateFunction(6); - miso0.mode(miosix::Mode::ALTERNATE); - miso0.alternateFunction(6); - mosi0.mode(miosix::Mode::ALTERNATE); - mosi0.alternateFunction(6); - - cs0.mode(miosix::Mode::OUTPUT); - dio0.mode(miosix::Mode::INPUT); - } +#elif defined _BOARD_STM32F429ZI_SKYWARD_DEATHST_V3 +#include "interfaces-impl/hwmapping.h" - cs0.high(); - enableExternalInterrupt(dio0.getPort(), dio0.getNumber(), - InterruptTrigger::RISING_EDGE); -} +using cs = sensors::sx127x::cs; +using dio0 = sensors::sx127x::dio0; -/// Initialize stm32f407g board (sx1278[1] only) -void initBoard1() -{ - { - miosix::FastInterruptDisableLock dLock; +using sck = interfaces::spi5::sck; +using miso = interfaces::spi5::miso; +using mosi = interfaces::spi5::mosi; - // Enable SPI2 - RCC->APB1ENR |= RCC_APB1ENR_SPI2EN; - RCC_SYNC(); +#define SX1278_SPI SPI5 - sck1.mode(miosix::Mode::ALTERNATE); - sck1.alternateFunction(5); - miso1.mode(miosix::Mode::ALTERNATE); - miso1.alternateFunction(5); - mosi1.mode(miosix::Mode::ALTERNATE); - mosi1.alternateFunction(5); +#else +#error "Target not supported" +#endif - cs1.mode(miosix::Mode::OUTPUT); - dio1.mode(miosix::Mode::INPUT); - } +SX1278 *sx1278 = nullptr; - cs1.high(); - enableExternalInterrupt(dio1.getPort(), dio1.getNumber(), - InterruptTrigger::RISING_EDGE); +#if defined _BOARD_STM32F429ZI_SKYWARD_GS +void __attribute__((used)) EXTI6_IRQHandlerImpl() +#elif defined _BOARD_STM32F429ZI_SKYWARD_DEATHST_V3 +void __attribute__((used)) EXTI10_IRQHandlerImpl() +#else +#error "Target not supported" +#endif +{ + if (sx1278) + sx1278->handleDioIRQ(); +} + +void initBoard() +{ +#if defined _BOARD_STM32F429ZI_SKYWARD_GS + enableExternalInterrupt(GPIOF_BASE, 6, InterruptTrigger::RISING_EDGE); +#elif defined _BOARD_STM32F429ZI_SKYWARD_DEATHST_V3 + enableExternalInterrupt(GPIOF_BASE, 10, InterruptTrigger::RISING_EDGE); +#else +#error "Target not supported" +#endif } -void recvLoop(int idx) +void recvLoop() { - char buf[256]; + char buf[64]; while (1) { - if (sx1278[idx]->receive((uint8_t *)buf, sizeof(buf)) != -1) + ssize_t res = + sx1278->receive(reinterpret_cast<uint8_t *>(buf), sizeof(buf)); + if (res != -1) { // Make sure there is a terminator somewhere - buf[255] = 0; - printf("[sx1278 @ %p] Received '%s'\n", sx1278[idx], buf); + buf[res] = 0; + printf("[sx1278] Received '%s'\n", buf); } } } -void sendLoop(int idx, int interval, char *data) +void sendLoop(int interval, const char *data) { + char buf[64]; + strncpy(buf, data, sizeof(buf) - 1); + while (1) { miosix::Thread::sleep(interval); - sx1278[idx]->send((uint8_t *)data, strlen(data) + 1); - printf("[sx1278 @ %p] Sent '%s'\n", sx1278[idx], data); + sx1278->send(reinterpret_cast<uint8_t *>(buf), strlen(buf) + 1); + printf("[sx1278] Sent '%s'\n", buf); } } int main() { - initBoard0(); - initBoard1(); + initBoard(); // Run default configuration SX1278::Config config; SX1278::Error err; - // Configure them - sx1278[0] = new SX1278(bus0, cs0); + SPIBus bus(SX1278_SPI); + GpioPin cs = cs::getPin(); - printf("\n[sx1278] Configuring sx1278[0]...\n"); - printConfig(config); - if ((err = sx1278[0]->init(config)) != SX1278::Error::NONE) - { - printf("[sx1278] sx1278[0]->init error: %s\n", stringFromErr(err)); - return -1; - } + sx1278 = new SX1278(bus, cs); - sx1278[1] = new SX1278(bus1, cs1); - - printf("\n[sx1278] Configuring sx1278[1]...\n"); - printConfig(config); - if ((err = sx1278[1]->init(config)) != SX1278::Error::NONE) + printf("\n[sx1278] Configuring sx1278...\n"); + if ((err = sx1278->init(config)) != SX1278::Error::NONE) { - printf("[sx1278] sx1278[1]->init error: %s\n", stringFromErr(err)); + printf("[sx1278] sx1278->init error: %s\n", stringFromErr(err)); return -1; } // Spawn all threads - std::thread send0( - [=]() { sendLoop(0, 1000, const_cast<char *>("Hi from sx1278[0]!")); }); - std::thread send1( - [=]() { sendLoop(1, 3333, const_cast<char *>("Hi from sx1278[1]!")); }); - - std::thread recv0([]() { recvLoop(0); }); - std::thread recv1([]() { recvLoop(1); }); + std::thread send([]() { sendLoop(1000, "Sample radio message"); }); + std::thread recv([]() { recvLoop(); }); printf("\n[sx1278] Initialization complete!\n"); + // sx1278->debugDumpRegisters(); + while (1) miosix::Thread::wait(); diff --git a/src/tests/drivers/test-internal-temp.cpp b/src/tests/drivers/test-internal-temp.cpp new file mode 100644 index 0000000000000000000000000000000000000000..23fd7844a83f5ae4978d26f092253f76067814e3 --- /dev/null +++ b/src/tests/drivers/test-internal-temp.cpp @@ -0,0 +1,44 @@ +/* Copyright (c) 2022 Skyward Experimental Rocketry + * Authors: Giulia Ghirardini + * + * 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. + */ + +#include <drivers/adc/InternalTemp.h> +#include <drivers/timer/TimestampTimer.h> +#include <miosix.h> +#include <utils/ClockUtils.h> + +using namespace Boardcore; + +int main() +{ + ADC->CCR |= ADC_CCR_ADCPRE_0 | ADC_CCR_ADCPRE_1; + + InternalTemp temp(InternalADC::CYCLES_480, 3.0); + temp.init(); + + for (;;) + { + temp.sample(); + printf("Temperature: %2.3f\n", temp.getLastSample().temperature); + + miosix::delayMs(1000); + } +} diff --git a/src/tests/drivers/test-mavlink.cpp b/src/tests/drivers/test-mavlink.cpp index 38b3c0d0672fc4f4828a34e316a309018e3d16ea..2f4883c1335bed4c243a00a5d9ba63aaf208fc28 100644 --- a/src/tests/drivers/test-mavlink.cpp +++ b/src/tests/drivers/test-mavlink.cpp @@ -52,7 +52,8 @@ MavDriver* mavlink; */ int main() { - transceiver = new SerialTransceiver(); + STM32SerialWrapper serial(USART1, USARTInterface::Baudrate::B19200); + transceiver = new SerialTransceiver(serial); mavlink = new MavDriver(transceiver, nullptr, silenceAfterSend, maxPktAge); mavlink->start(); diff --git a/src/tests/drivers/timer/test-timestamptimer.cpp b/src/tests/drivers/timer/test-timestamptimer.cpp index f265e13f6975fe8678e4b5d3e324d4f0a71e5969..3ba13168412061eafaff618405be23b7e1ecc240 100644 --- a/src/tests/drivers/timer/test-timestamptimer.cpp +++ b/src/tests/drivers/timer/test-timestamptimer.cpp @@ -35,9 +35,6 @@ void testTimerUtils(TIM_TypeDef *timer); int main() { - // Force the timestamptimer to init - (void)TimestampTimer::getInstance(); - testTimerUtils(TIM2); printf("Initialization should be complete\n"); @@ -48,7 +45,7 @@ int main() { long long prevTick = getTick(); - uint64_t timestamp = TimestampTimer::getInstance().getTimestamp(); + uint64_t timestamp = TimestampTimer::getTimestamp(); // cppcheck-suppress invalidPrintfArgType_uint printf("%12llu us, %12.3f ms, %12.6f s, %12lld tick \n", timestamp, @@ -59,13 +56,13 @@ int main() printf("Now resetting the TimestampTimer\n"); - TimestampTimer::getInstance().resetTimestamp(); + TimestampTimer::resetTimestamp(); while (true) { long long prevTick = getTick(); - uint64_t timestamp = TimestampTimer::getInstance().getTimestamp(); + uint64_t timestamp = TimestampTimer::getTimestamp(); // cppcheck-suppress invalidPrintfArgType_uint printf("%12llu us, %12.3f ms, %12.6f s, %12lld tick \n", timestamp, diff --git a/src/tests/drivers/usart/test-usart.cpp b/src/tests/drivers/usart/test-usart.cpp index ce99d3d5a5a764b696598f8b0bf2c1ef49eccd7f..728f374b30b12b02fcbcc97fd55f33f73054ce86 100644 --- a/src/tests/drivers/usart/test-usart.cpp +++ b/src/tests/drivers/usart/test-usart.cpp @@ -136,6 +136,22 @@ bool testCommunicationSequential(USARTInterface *src, USARTInterface *dst) */ int main() { + // Init serial port pins + u1rx2::getPin().mode(miosix::Mode::ALTERNATE); + u1rx2::getPin().alternateFunction(7); + u1tx1::getPin().mode(miosix::Mode::ALTERNATE); + u1tx1::getPin().alternateFunction(7); + + u2rx1::getPin().mode(miosix::Mode::ALTERNATE); + u2rx1::getPin().alternateFunction(7); + u2tx1::getPin().mode(miosix::Mode::ALTERNATE); + u2tx1::getPin().alternateFunction(7); + + // u4rx1::getPin().mode(miosix::Mode::ALTERNATE); + // u4rx1::getPin().alternateFunction(8); + // u4tx1::getPin().mode(miosix::Mode::ALTERNATE); + // u4tx1::getPin().alternateFunction(8); + bool testPassed = true; printf("*** SERIAL 3 WORKING!\n"); for (unsigned int iBaud = 0; @@ -145,12 +161,10 @@ int main() printf("\n\n########################### %d\n", (int)baudrate); // declaring the usart peripherals - STM32SerialWrapper usartx(USART1, baudrate, u1rx2::getPin(), - u1tx1::getPin()); + STM32SerialWrapper usartx(USART1, baudrate); usartx.init(); - USART usarty(UART4, baudrate); - // usarty.initPins(u5tx::getPin(), 8, u5rx::getPin(), 8); + STM32SerialWrapper usarty(USART2, baudrate); // usarty.setOversampling(false); // usarty.setStopBits(1); // usarty.setWordLength(USART::WordLength::BIT8); diff --git a/src/tests/drivers/xbee/gui/StatusScreen.h b/src/tests/drivers/xbee/gui/StatusScreen.h index b397715e0d772a8261ddfbb42f127b320ac9b848..1c7a40b5c196ffe7ab85fbe6e87eddaa8265dc79 100644 --- a/src/tests/drivers/xbee/gui/StatusScreen.h +++ b/src/tests/drivers/xbee/gui/StatusScreen.h @@ -188,7 +188,7 @@ struct StatusScreen void updateLogStatus(Logger& logger) { - LoggerStats stats = logger.getLoggerStats(); + LoggerStats stats = logger.getStats(); if (logger.getCurrentLogNumber() >= 0) { @@ -221,7 +221,7 @@ struct StatusScreen } tvLogBufWritten.setText(to_string(stats.buffersWritten)); - tvLogBufTtw.setText(to_string(stats.writeTime) + " ms"); + tvLogBufTtw.setText(to_string(stats.averageWriteTime) + " ms"); } void updateXbeeStatus(DataRateResult resRcv, DataRateResult resSnd, diff --git a/src/tests/drivers/xbee/test-xbee-bidir.cpp b/src/tests/drivers/xbee/test-xbee-bidir.cpp index f5ee9c1c121701988718040165c105f9c211bbf3..27a1af9e77be308f06b9ee63e20ceb8c0c887367 100644 --- a/src/tests/drivers/xbee/test-xbee-bidir.cpp +++ b/src/tests/drivers/xbee/test-xbee-bidir.cpp @@ -218,7 +218,7 @@ int main() RxData rxd = trans->getReceiver().getRxData(); logger.log(xbeeDriver->getStatus()); - logger.log(logger.getLoggerStats()); + logger.log(logger.getStats()); long long tick = getTick(); unsigned int h = tick / (1000 * 3600); diff --git a/src/tests/drivers/xbee/test-xbee-gui.cpp b/src/tests/drivers/xbee/test-xbee-gui.cpp index 407f90a1dd4c9682e45c5aa504388544b83ea0b0..bc0d694aa9c2b460f7304bdb4d213ea7c169235b 100644 --- a/src/tests/drivers/xbee/test-xbee-gui.cpp +++ b/src/tests/drivers/xbee/test-xbee-gui.cpp @@ -208,7 +208,7 @@ int main() break; } - logger.log(logger.getLoggerStats()); + logger.log(logger.getStats()); Thread::sleepUntil(start + 500); } } diff --git a/src/tests/logger/test-logger.cpp b/src/tests/logger/test-logger.cpp index 53dca34bd42b869cab946038858bd2dce2be53aa..a22753780bcfb70d7ef88080e3474cc7cd4898fe 100644 --- a/src/tests/logger/test-logger.cpp +++ b/src/tests/logger/test-logger.cpp @@ -22,14 +22,14 @@ #include "test-logger.h" -#include <diagnostic/CpuMeter.h> +#include <diagnostic/CpuMeter/CpuMeter.h> #include <logger/Logger.h> using namespace Boardcore; using namespace std; using namespace miosix; -void logthread(void*) +void logThread(void*) { Logger& log = Logger::getInstance(); const int period = 5; @@ -45,18 +45,18 @@ void logthread(void*) } } -void printutil(void*) +void printUtil(void*) { for (;;) { Thread::sleep(1000); - printf("cpu: %5.1f\n", averageCpuUtilization()); + printf("cpu: %5.1f\n", CpuMeter::getCpuStats().mean); } } int main() { - Thread::create(printutil, 4096); + Thread::create(printUtil, 4096); Logger& log = Logger::getInstance(); log.start(); @@ -64,7 +64,7 @@ int main() puts("type enter to start test"); getchar(); - Thread::create(logthread, 4096); + Thread::create(logThread, 4096); puts("type enter to stop test"); getchar(); diff --git a/src/tests/radio/test-mavlinkdriver.cpp b/src/tests/radio/test-mavlinkdriver.cpp new file mode 100644 index 0000000000000000000000000000000000000000..c7d14b5108f9304be08b6284a6efd3404a8e0e32 --- /dev/null +++ b/src/tests/radio/test-mavlinkdriver.cpp @@ -0,0 +1,73 @@ +/* Copyright (c) 2022 Skyward Experimental Rocketry + * Author: Alberto Nidasio + * + * 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. + */ + +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wcast-align" +#pragma GCC diagnostic ignored "-Waddress-of-packed-member" +#pragma GCC diagnostic ignored "-Wmaybe-uninitialized" +#include <mavlink_lib/pyxis/mavlink.h> +#pragma GCC diagnostic pop + +#include <drivers/usart/USART.h> +#include <miosix.h> +#include <radio/MavlinkDriver/MavlinkDriver.h> +#include <radio/SerialTransceiver/SerialTransceiver.h> +#include <scheduler/TaskScheduler.h> + +using namespace miosix; +using namespace Boardcore; + +USART usart(USART2, USARTInterface::Baudrate::B115200); +SerialTransceiver transceiver(usart); +MavlinkDriver<20, 10> mavlink(&transceiver); + +void payloadGenerator(); + +int main() +{ + u2rx1::mode(Mode::ALTERNATE); + u2rx1::alternateFunction(7); + u2tx1::mode(Mode::ALTERNATE); + u2tx1::alternateFunction(7); + + TaskScheduler scheduler; + scheduler.addTask(payloadGenerator, 2000); + scheduler.start(); + + usart.init(); + mavlink.start(); + + while (true) + Thread::sleep(1000); +} + +void payloadGenerator() +{ + // uint8_t msg[] = "012345678"; + // mavlink.enqueueRaw(msg, 9); + // printf("Added 9 bytes: %s\n", msg); + + // Create a mavlink packet + mavlink_message_t ackMsg; + mavlink_msg_ack_tm_pack(0x01, 0x23, &ackMsg, 0x45, 0x67); + mavlink.enqueueMsg(ackMsg); +} diff --git a/src/tests/sensors/calibration/test-calibration-benchmark.cpp b/src/tests/sensors/calibration/test-calibration-benchmark.cpp index 1ed6b0f81de257186fd9c1c858b8648fce157998..7b84019d9fdbf06512c5bd4f24c1f67b2c96bb72 100644 --- a/src/tests/sensors/calibration/test-calibration-benchmark.cpp +++ b/src/tests/sensors/calibration/test-calibration-benchmark.cpp @@ -28,7 +28,7 @@ /* Expressed in Hertz: valid values: 1 <= frequency <= 1000 */ #define SAMPLE_FREQUENCY_LOAD_TEST 1000 -#include <diagnostic/CpuMeter.h> +#include <diagnostic/CpuMeter/CpuMeter.h> #include <drivers/spi/SPIDriver.h> #include <miosix.h> #include <sensors/LIS3DSH/LIS3DSH.h> @@ -101,7 +101,7 @@ int main() if (elapsed > 500) { elapsed = 0; - TRACE("Average CPU usage: %f %%\n", averageCpuUtilization()); + TRACE("Average CPU usage: %f %%\n", CpuMeter::getCpuStats().mean); } } } diff --git a/src/tests/sensors/calibration/test-calibration-stats.cpp b/src/tests/sensors/calibration/test-calibration-stats.cpp index 40aa29ad31fb57621dc67c00d6c83193c4b6d30b..4fee619509453ac66db22b0a01756dbecbf49dc4 100644 --- a/src/tests/sensors/calibration/test-calibration-stats.cpp +++ b/src/tests/sensors/calibration/test-calibration-stats.cpp @@ -128,7 +128,7 @@ int main() const char* yLabel = humanFriendlyDirection[(uint8_t)orientations[i].yAxis]; - printf(" %d. X towards %s, Y towards %s (%d samples)", i, + printf(" %d. X towards %s, Y towards %s (%ld samples)", i, xLabel, yLabel, xAxis[i].getStats().nSamples); if (selected == i) @@ -146,7 +146,7 @@ int main() printf("Current orientation is: X towards %s, Y towards %s\n", xLabel, yLabel); - printf("You took %d samples for each axis on this orientation.\n", + printf("You took %ld samples for each axis on this orientation.\n", xAxis[selected].getStats().nSamples); } else if (!strncmp("onext", input, 5)) @@ -292,7 +292,7 @@ int main() } else if (!strncmp("samples", input, 7)) { - printf("Taken %d samples on the current orientation.\n", + printf("Taken %ld samples on the current orientation.\n", xAxis[selected].getStats().nSamples); } else diff --git a/src/tests/sensors/test-bmx160-with-correction.cpp b/src/tests/sensors/test-bmx160-with-correction.cpp index 32c0363c182d739ca6e7e98b1715f5660c8bfaf6..37be463625c7e92e7a8b1a41db500a9087ab4df7 100644 --- a/src/tests/sensors/test-bmx160-with-correction.cpp +++ b/src/tests/sensors/test-bmx160-with-correction.cpp @@ -40,8 +40,7 @@ void __attribute__((used)) EXTI5_IRQHandlerImpl() { if (bmx160) { - bmx160->IRQupdateTimestamp( - TimestampTimer::getInstance().getTimestamp()); + bmx160->IRQupdateTimestamp(TimestampTimer::getTimestamp()); } } @@ -118,11 +117,9 @@ int main() miosix::Thread *samplingThread = miosix::Thread::create(bmx160Sample, 2048, miosix::MAIN_PRIORITY, nullptr, miosix::Thread::JOINABLE); - if (!bmx160WithCorrection.calibrate()) - { - TRACE("Calibration failed!\n"); - return -1; - } + bmx160WithCorrection.startCalibration(); + miosix::Thread::sleep(2000); + bmx160WithCorrection.stopCalibration(); stopSamplingThread = true; samplingThread->join(); TRACE("Calibration completed\n"); diff --git a/src/tests/sensors/test-bmx160.cpp b/src/tests/sensors/test-bmx160.cpp index ad3e567dff0f9769c7d01c2049972f0916a656bf..36e04b7046e9a0b9384fc4a3d36cfb10cf5d9fd1 100644 --- a/src/tests/sensors/test-bmx160.cpp +++ b/src/tests/sensors/test-bmx160.cpp @@ -40,7 +40,7 @@ uint32_t tick = 0; void __attribute__((used)) EXTI5_IRQHandlerImpl() { - tick = TimestampTimer::getInstance().getTimestamp(); + tick = TimestampTimer::getTimestamp(); if (sensor) { sensor->IRQupdateTimestamp(tick); @@ -95,7 +95,7 @@ int main() continue; } - uint64_t now = TimestampTimer::getInstance().getTimestamp(); + uint64_t now = TimestampTimer::getTimestamp(); printf("Tick: %.4f s, Now: %.4f s\n", tick / 1000000.0f, now / 1000000.0f); diff --git a/src/tests/sensors/test-l3gd20-fifo.cpp b/src/tests/sensors/test-l3gd20-fifo.cpp index 2b6d46286f8df3ff7f3b620eb4e0a04860642da4..24e2c4d3a723adef7581539f2e6fe8e2ae4160b9 100644 --- a/src/tests/sensors/test-l3gd20-fifo.cpp +++ b/src/tests/sensors/test-l3gd20-fifo.cpp @@ -48,7 +48,7 @@ * togheter with other useful data. */ -#include <diagnostic/CpuMeter.h> +#include <diagnostic/CpuMeter/CpuMeter.h> #include <drivers/interrupt/external_interrupts.h> #include <drivers/spi/SPIDriver.h> #include <drivers/timer/GeneralPurposeTimer.h> @@ -113,7 +113,7 @@ volatile uint64_t watermarkDelta; // Tick delta between the last 2 watermark void __attribute__((used)) EXTI2_IRQHandlerImpl() { // Current high resolution tick - uint64_t currentTimestamp = TimestampTimer::getInstance().getTimestamp(); + uint64_t currentTimestamp = TimestampTimer::getTimestamp(); watermarkDelta = currentTimestamp - lastWatermarkTick; lastWatermarkTick = currentTimestamp; @@ -169,11 +169,11 @@ int main() long lastTick = miosix::getTick(); // Read the fifo - uint64_t update = TimestampTimer::getInstance().getTimestamp(); + uint64_t update = TimestampTimer::getTimestamp(); gyro->sample(); // Measure how long we take to read the fifo - update = TimestampTimer::getInstance().getTimestamp() - update; + update = TimestampTimer::getTimestamp() - update; uint8_t level = gyro->getLastFifoSize(); // Current number of samples in the FIFO @@ -190,10 +190,10 @@ int main() fifo[i], level, TimerUtils::toIntMicroSeconds( - TimestampTimer::getInstance().getTimer(), watermarkDelta), - averageCpuUtilization(), + TimestampTimer::timestampTimer.getTimer(), watermarkDelta), + CpuMeter::getCpuStats().mean, TimerUtils::toIntMicroSeconds( - TimestampTimer::getInstance().getTimer(), update)}; + TimestampTimer::timestampTimer.getTimer(), update)}; // Stop if we have enough data if (dataCounter >= NUM_SAMPLES) diff --git a/src/tests/sensors/test-l3gd20.cpp b/src/tests/sensors/test-l3gd20.cpp index bca767afdb5bab63386df2dbfbe4fafeaa4aa92d..33d4134e2bafa831286fdcc00b63d9005d17afd7 100644 --- a/src/tests/sensors/test-l3gd20.cpp +++ b/src/tests/sensors/test-l3gd20.cpp @@ -28,7 +28,7 @@ * CSV format. */ -#include <diagnostic/CpuMeter.h> +#include <diagnostic/CpuMeter/CpuMeter.h> #include <drivers/interrupt/external_interrupts.h> #include <drivers/spi/SPIDriver.h> #include <drivers/timer/TimestampTimer.h> @@ -83,7 +83,7 @@ uint32_t sampleDelta; // Tick delta between the last 2 watermark void __attribute__((used)) EXTI2_IRQHandlerImpl() { // Current high resolution tick - uint64_t currentTimestamp = TimestampTimer::getInstance().getTimestamp(); + uint64_t currentTimestamp = TimestampTimer::getTimestamp(); sampleDelta = currentTimestamp - lastSampleTick; lastSampleTick = currentTimestamp; @@ -148,7 +148,7 @@ int main() // Store the sample in the array, togheter with other useful data data[dataCounter++] = {d.angularVelocityTimestamp, sampleDelta, d, - averageCpuUtilization()}; + CpuMeter::getCpuStats().mean}; // Wait until SAMPLE_PERIOD milliseconds from the start of this // iteration have passed (SAMPLE_PERIOD = 1000 / SAMPLE_RATE) @@ -164,7 +164,7 @@ int main() 0, data[i].timestamp, TimerUtils::toIntMicroSeconds( - TimestampTimer::getInstance().getTimer(), data[i].sampleDelta), + TimestampTimer::timestampTimer.getTimer(), data[i].sampleDelta), (data[i].timestamp - data[i - 1].timestamp), data[i].data.angularVelocityX, data[i].data.angularVelocityY, diff --git a/src/tests/sensors/test-ms5803.cpp b/src/tests/sensors/test-ms5803.cpp index 4c00318899a0fd596e002c0baa3e350203ecd876..811dfcc18b85d682ded91bf65de0286a70174526 100644 --- a/src/tests/sensors/test-ms5803.cpp +++ b/src/tests/sensors/test-ms5803.cpp @@ -37,6 +37,8 @@ int main() { // Sample temperature every 10 pressure samples SPIBus spiBus(SPI1); + SPIBusConfig config; + config.clockDivider = SPI::ClockDivider::DIV_32; MS5803 sensor(spiBus, miosix::sensors::ms5803::cs::getPin(), {}, 10); Thread::sleep(100); @@ -57,6 +59,6 @@ int main() printf("%llu,%f,%llu,%f\n", data.pressureTimestamp, data.pressure, data.temperatureTimestamp, data.temperature); - Thread::sleep(10); + Thread::sleep(20); } } diff --git a/src/tests/sensors/test-ubloxgps.cpp b/src/tests/sensors/test-ubxgps-serial.cpp similarity index 94% rename from src/tests/sensors/test-ubloxgps.cpp rename to src/tests/sensors/test-ubxgps-serial.cpp index 24b6cc092a73e531765fbbe4897a29133a827014..ae33c9048af377e01fe712c215d50a4f41dfef4b 100644 --- a/src/tests/sensors/test-ubloxgps.cpp +++ b/src/tests/sensors/test-ubxgps-serial.cpp @@ -22,7 +22,7 @@ #include <drivers/timer/TimestampTimer.h> #include <miosix.h> -#include <sensors/UbloxGPS/UbloxGPS.h> +#include <sensors/UBXGPS/UBXGPSSerial.h> #include <utils/Debug.h> #include <cstdio> @@ -34,13 +34,11 @@ using namespace miosix; int main() { - (void)TimestampTimer::getInstance(); - printf("Welcome to the ublox test\n"); // Keep GPS baud rate at default for easier testing - UbloxGPS gps(921600, RATE, 2, "gps", 38400); - UbloxGPSData dataGPS; + UBXGPSSerial gps(38400, RATE, 2, "gps", 9600); + UBXGPSData dataGPS; printf("Gps allocated\n"); // Init the gps diff --git a/src/tests/sensors/test-ubxgps-spi.cpp b/src/tests/sensors/test-ubxgps-spi.cpp new file mode 100644 index 0000000000000000000000000000000000000000..3fcecde01e161e98c8e01a1aa2021d8e4e4775dc --- /dev/null +++ b/src/tests/sensors/test-ubxgps-spi.cpp @@ -0,0 +1,82 @@ +/* Copyright (c) 2022 Skyward Experimental Rocketry + * Authors: Davide Bonomini, Davide Mor, Alberto Nidasio, Damiano Amatruda + * + * 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. + */ + +#include <sensors/UBXGPS/UBXGPSSpi.h> +#include <utils/Debug.h> + +using namespace miosix; +using namespace Boardcore; + +int main() +{ +#ifdef _BOARD_STM32F429ZI_SKYWARD_DEATHST_X + SPIBus spiBus(SPI2); + GpioPin spiCs(GPIOG_BASE, 3); + GpioPin spiSck(GPIOB_BASE, 13); + GpioPin spiMiso(GPIOB_BASE, 14); + GpioPin spiMosi(GPIOB_BASE, 15); +#else + SPIBus spiBus(SPI1); + GpioPin spiCs(GPIOA_BASE, 3); + GpioPin spiSck(GPIOA_BASE, 5); + GpioPin spiMiso(GPIOA_BASE, 6); + GpioPin spiMosi(GPIOA_BASE, 7); +#endif + + spiCs.mode(Mode::OUTPUT); + spiCs.high(); + spiSck.mode(Mode::ALTERNATE); + spiSck.alternateFunction(5); + spiMiso.mode(Mode::ALTERNATE); + spiMiso.alternateFunction(5); + spiMosi.mode(Mode::ALTERNATE); + spiMosi.alternateFunction(5); + + UBXGPSSpi gps{spiBus, spiCs}; + + TRACE("Initializing UBXGPSSpi...\n"); + + while (!gps.init()) + { + TRACE("Init failed! (code: %d)\n", gps.getLastError()); + + TRACE("Retrying in 10 seconds...\n"); + miosix::Thread::sleep(10000); + } + + while (true) + { + gps.sample(); + GPSData sample __attribute__((unused)) = gps.getLastSample(); + + TRACE( + "timestamp: %4.3f, lat: %f, lon: %f, height: %4.1f, velN: %3.2f, " + "velE: %3.2f, velD: %3.2f, speed: %3.2f, track %3.1f, pDOP: %f, " + "nsat: %2d, fix: %2d\n", + (float)sample.gpsTimestamp / 1000000, sample.latitude, + sample.longitude, sample.height, sample.velocityNorth, + sample.velocityEast, sample.velocityDown, sample.speed, + sample.track, sample.positionDOP, sample.satellites, sample.fix); + + Thread::sleep(1000 / gps.getSampleRate()); + } +} diff --git a/src/tests/test-pinobserver.cpp b/src/tests/test-pinobserver.cpp index 1fe87708a4f27d22bf72f4d84455860331c34b0e..9856200ef36e72da7b604ae2d496a830ee3dc912 100644 --- a/src/tests/test-pinobserver.cpp +++ b/src/tests/test-pinobserver.cpp @@ -21,10 +21,14 @@ */ #include <miosix.h> -#include <utils/PinObserver.h> +#include <utils/PinObserver/PinObserver.h> + +#include <functional> using namespace Boardcore; using namespace miosix; +using namespace std; +using namespace std::placeholders; static constexpr unsigned int POLL_INTERVAL = 20; @@ -35,60 +39,38 @@ static constexpr unsigned char PIN1_PIN = 5; static constexpr unsigned int PIN2_PORT = GPIOE_BASE; static constexpr unsigned char PIN2_PIN = 6; -void onStateChange(unsigned int p, unsigned char n, int state) +void onTransition(GpioPin pin, PinTransition transition) { - if (p == BTN_PORT && n == BTN_PIN) - { - printf("BTN state change: %d\n", state); - } - if (p == PIN1_PORT && n == PIN1_PIN) - { - printf("PIN1 state change: %d\n", state); - } - if (p == PIN2_PORT && n == PIN2_PIN) - { - printf("PIN2 state change: %d\n", state); - } -} + if (pin.getPort() == BTN_PORT && pin.getNumber() == BTN_PIN) + printf("BTN transition: "); + if (pin.getPort() == PIN1_PORT && pin.getNumber() == PIN1_PIN) + printf("PIN1 transition: "); + if (pin.getPort() == PIN2_PORT && pin.getNumber() == PIN2_PIN) + printf("PIN2 transition: "); -void onTransition(unsigned int p, unsigned char n) -{ - if (p == BTN_PORT && n == BTN_PIN) - { - printf("BTN transition.\n"); - } - if (p == PIN1_PORT && n == PIN1_PIN) - { - printf("PIN1 transition.\n"); - } - if (p == PIN2_PORT && n == PIN2_PIN) - { - printf("PIN2 transition.\n"); - } + if (transition == PinTransition::FALLING_EDGE) + printf("FALLING_EDGE\n"); + else + printf("RISING_EDGE\n"); } int main() { - GpioPin(BTN_PORT, BTN_PIN).mode(Mode::INPUT); - GpioPin(PIN1_PORT, PIN1_PIN).mode(Mode::INPUT_PULL_DOWN); - GpioPin(PIN2_PORT, PIN2_PIN).mode(Mode::INPUT_PULL_UP); - - PinObserver observer; - - observer.observePin(BTN_PORT, BTN_PIN, PinObserver::Transition::RISING_EDGE, - &onTransition, 1, onStateChange); + auto btn = GpioPin(BTN_PORT, BTN_PIN); + auto pin1 = GpioPin(PIN1_PORT, PIN1_PIN); + auto pin2 = GpioPin(PIN2_PORT, PIN2_PIN); - observer.observePin(PIN1_PORT, PIN1_PIN, - PinObserver::Transition::FALLING_EDGE, &onTransition, - 1000 / POLL_INTERVAL, onStateChange); + btn.mode(Mode::INPUT); + pin1.mode(Mode::INPUT_PULL_DOWN); + pin2.mode(Mode::INPUT_PULL_UP); - observer.observePin(PIN2_PORT, PIN2_PIN, - PinObserver::Transition::RISING_EDGE, &onTransition, - 1000 / POLL_INTERVAL, onStateChange); + PinObserver::getInstance().registerPinCallback( + btn, std::bind(onTransition, btn, _1), 10); + PinObserver::getInstance().registerPinCallback( + pin1, std::bind(onTransition, pin1, _1), 10); + PinObserver::getInstance().registerPinCallback( + pin2, std::bind(onTransition, pin2, _1), 10); - observer.start(); - for (;;) - { + while (true) Thread::sleep(10000); - } } diff --git a/src/tests/test-sensormanager.cpp b/src/tests/test-sensormanager.cpp index 1a8b06648b7c60c46f31c461c5485285622577d1..011941abbc470c0586eecd68afa4d1e7ff4f70c3 100644 --- a/src/tests/test-sensormanager.cpp +++ b/src/tests/test-sensormanager.cpp @@ -44,8 +44,8 @@ struct MySensorData : public PressureData, public TemperatureData MySensorData() : PressureData{0, 0.0}, TemperatureData{0, 0.0} {} MySensorData(float p, float t) - : PressureData{TimestampTimer::getInstance().getTimestamp(), p}, - TemperatureData{TimestampTimer::getInstance().getTimestamp(), t} + : PressureData{TimestampTimer::getTimestamp(), p}, + TemperatureData{TimestampTimer::getTimestamp(), t} { } }; @@ -97,20 +97,16 @@ struct MySensorDataFIFO : public AccelerometerData, public GyroscopeData { MySensorDataFIFO() - : AccelerometerData{TimestampTimer::getInstance().getTimestamp(), 0.0, - 0.0, 0.0}, - GyroscopeData{TimestampTimer::getInstance().getTimestamp(), 0.0, 0.0, - 0.0} + : AccelerometerData{TimestampTimer::getTimestamp(), 0.0, 0.0, 0.0}, + GyroscopeData{TimestampTimer::getTimestamp(), 0.0, 0.0, 0.0} { } MySensorDataFIFO(AccelerometerData acc, GyroscopeData gyro) - : AccelerometerData{TimestampTimer::getInstance().getTimestamp(), - acc.accelerationX, acc.accelerationY, - acc.accelerationZ}, - GyroscopeData{TimestampTimer::getInstance().getTimestamp(), - gyro.angularVelocityX, gyro.angularVelocityY, - gyro.angularVelocityZ} + : AccelerometerData{TimestampTimer::getTimestamp(), acc.accelerationX, + acc.accelerationY, acc.accelerationZ}, + GyroscopeData{TimestampTimer::getTimestamp(), gyro.angularVelocityX, + gyro.angularVelocityY, gyro.angularVelocityZ} { } }; @@ -127,10 +123,9 @@ public: { for (uint32_t i = 0; i < fifoSize; i++) { - AccelerometerData acc{TimestampTimer::getInstance().getTimestamp(), - 0.5, 0.5, 0.5}; - GyroscopeData gyro{TimestampTimer::getInstance().getTimestamp(), - 0.5, 0.5, 0.5}; + AccelerometerData acc{TimestampTimer::getTimestamp(), 0.5, 0.5, + 0.5}; + GyroscopeData gyro{TimestampTimer::getTimestamp(), 0.5, 0.5, 0.5}; lastFifo[i] = MySensorDataFIFO{acc, gyro}; diff --git a/src/tests/utils/test-syncpacketqueue.cpp b/src/tests/utils/test-syncpacketqueue.cpp new file mode 100644 index 0000000000000000000000000000000000000000..13bb3a1f33e63b90f4d4acc6cb97b20196bc425c --- /dev/null +++ b/src/tests/utils/test-syncpacketqueue.cpp @@ -0,0 +1,71 @@ +/* Copyright (c) 2022 Skyward Experimental Rocketry + * Author: Alberto Nidasio + * + * 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. + */ + +#include <miosix.h> +#include <scheduler/TaskScheduler.h> +#include <utils/collections/SyncPacketQueue.h> + +using namespace miosix; +using namespace Boardcore; + +SyncPacketQueue<20, 10> queue; + +void payloadGenerator(); + +int main() +{ + TaskScheduler scheduler; + scheduler.addTask(payloadGenerator, 1000); + scheduler.start(); + + while (true) + { + queue.waitUntilNotEmpty(); + auto packet = queue.get(); + + if (packet.isReady()) + { + queue.pop(); + + uint8_t packetContent[20]; + size_t size = packet.dump(packetContent); + + printf("[%.2f] ", TimestampTimer::getTimestamp() / 1e6); + + for (size_t i = 0; i < size; i++) + printf("%c", packetContent[i]); + + printf(" size: %zu\n", size); + } + else + { + Thread::sleep(50); + } + } +} + +void payloadGenerator() +{ + uint8_t msg[] = "012345678"; + queue.put(msg, 9); + printf("Filled queue with 9 bytes: %s\n", msg); +}