Compare commits

...

41 Commits

Author SHA1 Message Date
Daniel Agar d5876ab0d2 ekf2: stop gps yaw fusion on numerical error 2024-07-11 12:25:14 -04:00
Daniel Agar 467f96f2a4 ekf2: stop airspeed fusion on numerical error 2024-07-11 12:23:15 -04:00
Daniel Agar 4263fa9ee4 ekf2: stop flow fusion on numerical error 2024-07-11 12:22:26 -04:00
Daniel Agar b425253a54 ekf2: stop mag fusion on numerical error 2024-07-11 12:19:50 -04:00
Claudio Chies 33be5d8356 Survey - fix of survey tracking problem on steep slopes (#23371)
* initial working

* incoperated review
2024-07-11 14:54:22 +02:00
Daniel Agar 9124a7b471 ekf2: add IMU delta_ang_dt/delta_vel_dt safety constrain before pushing into buffer 2024-07-10 21:20:47 -04:00
Daniel Agar ac77049c47 ekf2: directly use IMU sample to find corresponding aid source sample
- I think this helps make it clear we're using a sensor sample
   corresponding with a particular IMU sample
2024-07-10 21:20:47 -04:00
Daniel Agar f93dc61770 ekf2: use bias corrected angular velocity
- avoid unnecessarily storing _ang_rate_delayed_raw
2024-07-10 21:20:47 -04:00
Julian Oes 20137bea40 boards: add console build for Cube Orange(+)
This adds a build variant which enables the serial console, and
therefore disables the ADSB receiver.
2024-07-10 21:14:08 -04:00
Claudio Chies 57e303b11b bugfix for failing actions 2024-07-10 21:12:55 -04:00
PX4 BuildBot e0ea91fc27 Update submodule gz to latest Thu Jul 11 00:39:09 UTC 2024
- gz in PX4/Firmware (2c3401dc83): https://github.com/PX4/PX4-gazebo-models/commit/881558c8c274d0d9f21970de24333122e050b561
    - gz current upstream: https://github.com/PX4/PX4-gazebo-models/commit/312cd002ff9602644efef58eef93e447c10dcbe8
    - Changes: https://github.com/PX4/PX4-gazebo-models/compare/881558c8c274d0d9f21970de24333122e050b561...312cd002ff9602644efef58eef93e447c10dcbe8

    312cd00 2024-07-08 chfriedrich98 - Add rover ackermann model (#46)
2024-07-10 21:05:57 -04:00
chfriedrich98 c391509c23 ackermann: add SITL airframe 2024-07-10 21:04:59 -04:00
Matthias Grob 2c3401dc83 uORB: SubscriptionInterval fix timestamp wrapping when initializing less than the interval time after boot (#23384)
* SubscriptionInterval: ensure _last_update is never before timer start
2024-07-10 12:43:31 -04:00
Daniel Agar 75bb339d94 ekf2: remove warning events logging
- some of these warning flags aren't even being used, and most of the rest we can figure out from other sources
2024-07-10 10:43:55 -04:00
Daniel Agar c29b4ff87e ekf2: apply astyle formatting and enforce 2024-07-10 10:43:55 -04:00
chfriedrich98 3fe609f769 exclude 4017 from v5x to save flash 2024-07-10 12:06:48 +02:00
chfriedrich98 03ff837c50 ackermann: new features and improvements
added return mode support, slew rates for actuators, new ackermann specific message, improved cornering slow down effect and fixed logging issue.
2024-07-10 12:06:48 +02:00
Daniel Agar 223397c20e ekf2: always add accel/gyro bias process noise
- continue adding accel/gyro bias process noise even if inhibited
2024-07-10 11:49:01 +02:00
Marco Hauswirth 419652b9fe EKF2: Spoofing GPS check (#23366)
* estimator gps check fail flag for spoofing

* warn whenever spoofing state changes to true, use default hysteresis to completely stop fusion

* dont introduce more GPS namings, GNSS instead

* flash: exclude mantis for cuav_x7pro
2024-07-09 16:31:11 +02:00
Daniel Agar 62ff39a669 ekf2: EV vel (body) update last fuse timestamps
- these are set by the NED fuseVelocity() helper so also need to be set in the body frame velocity case
2024-07-09 10:16:12 -04:00
Daniel Agar 5d08b97fd7 ekf2: add vehicle_local_position dist_bottom_var 2024-07-09 10:10:01 -04:00
Daniel Agar 3e3b886b5d ekf2: add terrain estimator_status_flags 2024-07-09 10:10:01 -04:00
Daniel Agar 64a6971bdb ekf2: only limit opt flow HAGL if range only terrain
- increase HALG limit from 75%->90% of sensor max
2024-07-09 10:10:01 -04:00
Daniel Agar c56f84fe8a ekf2: range, check if terrain valid for reset on fusion timeout 2024-07-09 10:10:01 -04:00
Daniel Agar e52025cc20 ekf2: optical flow fusion timeout only reset if quality is good 2024-07-09 10:10:01 -04:00
Daniel Agar 6be06ecbb3 ekf2: optical flow failing also reset terrain if needed 2024-07-09 10:10:01 -04:00
Daniel Agar ea8f14b883 ekf2: optical flow logic, timeout if bad_tilt, etc
- previously we could get stuck with optical flow still technically
   active (_control_status.flags.opt_flow=true), but nothing being
updated due to excessive tilt, etc
2024-07-09 10:10:01 -04:00
Daniel Agar 8bf15b01c4 ekf2: optical flow don't compute innovation variance twice
- collapse updateOptFlow() and startFlowFusion() to avoid recomputing H
 - this is a relatively expensive call we can easily avoid with the
   right structure
2024-07-09 10:10:01 -04:00
Daniel Agar f709ed409d ekf2: optical flow stop reset all flags 2024-07-09 10:10:01 -04:00
Daniel Agar 9dfd82ab06 ekf2: optical flow remove _flow_data_ready flag 2024-07-09 10:10:01 -04:00
Daniel Agar 7047f9441c ekf2: fix calcOptFlowBodyRateComp() gyro bias
- adjust flow sample gyro_rate immediately after popping from ring
   buffer
 - always update flow gyro bias (calcOptFlowBodyRateComp()) regardless
   of flow quality or magnitude
2024-07-09 10:10:01 -04:00
Daniel Agar 4d324da9f8 ekf2: update flow aid src status every sample 2024-07-09 10:10:01 -04:00
Daniel Agar bcd666b3f8 ekf2: fix optical flow start logic
- remove fallthrough that enables flow regardless of success
 - add appropriate start messages for each case
2024-07-09 10:10:01 -04:00
Daniel Agar bf4e564b23 ekf2: resetTerrainToFlow() reset aid src status appropriately 2024-07-09 10:10:01 -04:00
Daniel Agar ced609daa8 ekf2: flow fusion start require valid fusion 2024-07-09 10:10:01 -04:00
Daniel Agar 1df8f3f9d2 ekf2: resetFlowFusion() reset aid src status appropriately 2024-07-09 10:10:01 -04:00
Roman Bapst 8221940b60 Added pitot tube icing detection (#23206)
* lib: add FilteredDerivative class

* AirspeedValidator: add first principle check

- filters throttle, pitch and airspeed rate, and triggers
if the airspeed rate is negative even though the vehicle
is pitching down and giving high throttle.
Check has to fail for duration defined by ASPD_FP_T_WINDOW
to trigger an airspeed failure.

* AirspeedValidator: define constants for first principle check

* FilteredDerivative: set initialised to false if sample interval is invalid

* airspeed_selector: improved comment

* increase IAS derivative filter time constant from 4 to 5

* use legacy parameter handling for FW_PSP_OFF

* handle FW_THR_MAX as well

* ROMFS/airframes: exclude some airframes for v6x and v4pro to save flash on them

---------

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
Signed-off-by: RomanBapst <bapstroman@gmail.com>
Co-authored-by: Silvan Fuhrer <silvan@auterion.com>
2024-07-09 11:16:40 +02:00
Julian Oes a35cecece4 gnss: add missing include
Breaks CLion otherwise.
2024-07-08 20:38:40 -04:00
Peter van der Perk 6bd81f38a6 imxrt dshot timing fix (#23365)
* imxrt: Change PLL settings for more accurate dshot timing
* Update NuttX submodule
2024-07-08 12:57:15 -04:00
Silvan Fuhrer 77709c2948 FW Position control: clean up param descriptions
Mostly to save flash, but also to improve generally.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2024-07-08 16:44:09 +02:00
Claudio Chies aed0fd41cf SIH - change how LAT and LON is used for Takeoff location (#23363)
change how lat long is used for SIH
2024-07-08 14:51:08 +02:00
100 changed files with 2194 additions and 1014 deletions
@@ -11,6 +11,8 @@ on:
jobs:
build:
runs-on: ubuntu-latest
env:
ACTIONS_ALLOW_USE_UNSECURE_NODE_VERSION: true
strategy:
fail-fast: false
matrix:
@@ -11,6 +11,8 @@ on:
jobs:
build:
runs-on: ubuntu-latest
env:
ACTIONS_ALLOW_USE_UNSECURE_NODE_VERSION: true
strategy:
fail-fast: false
matrix:
@@ -0,0 +1,47 @@
#!/bin/sh
# @name Rover Ackermann
# @type Rover
# @class Rover
. ${R}etc/init.d/rc.rover_ackermann_defaults
PX4_SIMULATOR=${PX4_SIMULATOR:=gz}
PX4_GZ_WORLD=${PX4_GZ_WORLD:=rover}
PX4_SIM_MODEL=${PX4_SIM_MODEL:=rover_ackermann}
param set-default SIM_GZ_EN 1 # Gazebo bridge
# Rover parameters
param set-default NAV_ACC_RAD 0.5
param set-default RA_ACC_RAD_GAIN 2
param set-default RA_ACC_RAD_MAX 3
param set-default RA_LOOKAHD_GAIN 1
param set-default RA_LOOKAHD_MAX 10
param set-default RA_LOOKAHD_MIN 1
param set-default RA_MAX_ACCEL 1.5
param set-default RA_MAX_JERK 15
param set-default RA_MAX_SPEED 3
param set-default RA_MAX_STR_ANG 0.5236
param set-default RA_MAX_STR_RATE 360
param set-default RA_MISS_VEL_DEF 3
param set-default RA_MISS_VEL_GAIN 5
param set-default RA_MISS_VEL_MIN 1
param set-default RA_SPEED_I 0.01
param set-default RA_SPEED_P 2
param set-default RA_WHEEL_BASE 0.321
# Simulated sensors
param set-default SENS_EN_GPSSIM 1
param set-default SENS_EN_BAROSIM 0
param set-default SENS_EN_MAGSIM 1
param set-default SENS_EN_ARSPDSIM 0
# Wheels
param set-default SIM_GZ_WH_FUNC1 101
param set-default SIM_GZ_WH_MIN1 0
param set-default SIM_GZ_WH_MAX1 200
param set-default SIM_GZ_WH_DIS1 100
# Steering
param set-default SIM_GZ_SV_FUNC1 201
param set-default SIM_GZ_SV_REV 1
@@ -83,6 +83,7 @@ px4_add_romfs_files(
4009_gz_r1_rover
4010_gz_x500_mono_cam
4011_gz_lawnmower
4012_gz_rover_ackermann
6011_gazebo-classic_typhoon_h480
6011_gazebo-classic_typhoon_h480.post
@@ -15,6 +15,9 @@ if [ "$PX4_SIMULATOR" = "sihsim" ] || [ "$(param show -q SYS_AUTOSTART)" -eq "0"
if [ -n "${PX4_HOME_LON}" ]; then
param set SIH_LOC_LON0 ${PX4_HOME_LON}
fi
if [ -n "${PX4_HOME_ALT}" ]; then
param set SIH_LOC_H0 ${PX4_HOME_ALT}
fi
if simulator_sih start; then
@@ -6,6 +6,7 @@
# @class Copter
#
# @board px4_fmu-v2 exclude
# @board px4_fmu-v5x exclude
# @board bitcraze_crazyflie exclude
#
# @maintainer Iain Galloway <iain.galloway@nxp.com>
@@ -7,6 +7,8 @@
#
# @maintainer
# @board px4_fmu-v2 exclude
# @board cuav_x7pro exclude
# @board px4_fmu-v4pro exclude
# @board px4_fmu-v5x exclude
# @board px4_fmu-v6x exclude
#
@@ -12,6 +12,7 @@
# @board px4_fmu-v4pro exclude
# @board px4_fmu-v5 exclude
# @board px4_fmu-v5x exclude
# @board px4_fmu-v6x exclude
# @board bitcraze_crazyflie exclude
# @board cuav_x7pro exclude
#
@@ -10,6 +10,7 @@
# @board px4_fmu-v4pro exclude
# @board px4_fmu-v5 exclude
# @board px4_fmu-v5x exclude
# @board px4_fmu-v6x exclude
# @board bitcraze_crazyflie exclude
# @board cuav_x7pro exclude
#
@@ -8,6 +8,7 @@
# @maintainer Oleg Kalachev <okalachev@gmail.com>
#
# @board px4_fmu-v2 exclude
# @board px4_fmu-v4pro exclude
# @board bitcraze_crazyflie exclude
#
@@ -1,9 +1,6 @@
#!/bin/sh
# Standard apps for a ackermann drive rover.
# Start the attitude and position estimator.
ekf2 start &
# Start rover ackermann drive controller.
rover_ackermann start
+2 -1
View File
@@ -18,7 +18,8 @@ exec find boards msg src platforms test \
-path src/lib/events/libevents -prune -o \
-path src/lib/parameters/uthash -prune -o \
-path src/lib/wind_estimator/python/generated -prune -o \
-path src/modules/ekf2/EKF -prune -o \
-path src/modules/ekf2/EKF/python/ekf_derivation/generated -prune -o \
-path src/modules/ekf2/EKF/yaw_estimator/derivation/generated -prune -o \
-path src/modules/gyro_fft/CMSIS_5 -prune -o \
-path src/modules/mavlink/mavlink -prune -o \
-path test/mavsdk_tests/catch2 -prune -o \
@@ -0,0 +1 @@
# Same as default, only defconfig is different
@@ -0,0 +1,257 @@
#
# This file is autogenerated: PLEASE DO NOT EDIT IT.
#
# You can use "make menuconfig" to make any modifications to the installed .config file.
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
# modifications.
#
# CONFIG_DISABLE_ENVIRON is not set
# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
# CONFIG_DISABLE_PTHREAD is not set
# CONFIG_MMCSD_HAVE_CARDDETECT is not set
# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set
# CONFIG_MMCSD_MMCSUPPORT is not set
# CONFIG_MMCSD_SPI is not set
# CONFIG_NSH_DISABLEBG is not set
# CONFIG_NSH_DISABLESCRIPT is not set
# CONFIG_NSH_DISABLE_CAT is not set
# CONFIG_NSH_DISABLE_CD is not set
# CONFIG_NSH_DISABLE_CP is not set
# CONFIG_NSH_DISABLE_DATE is not set
# CONFIG_NSH_DISABLE_DF is not set
# CONFIG_NSH_DISABLE_ECHO is not set
# CONFIG_NSH_DISABLE_ENV is not set
# CONFIG_NSH_DISABLE_EXEC is not set
# CONFIG_NSH_DISABLE_EXIT is not set
# CONFIG_NSH_DISABLE_EXPORT is not set
# CONFIG_NSH_DISABLE_FREE is not set
# CONFIG_NSH_DISABLE_GET is not set
# CONFIG_NSH_DISABLE_HELP is not set
# CONFIG_NSH_DISABLE_ITEF is not set
# CONFIG_NSH_DISABLE_KILL is not set
# CONFIG_NSH_DISABLE_LOOPS is not set
# CONFIG_NSH_DISABLE_LS is not set
# CONFIG_NSH_DISABLE_MKDIR is not set
# CONFIG_NSH_DISABLE_MKFATFS is not set
# CONFIG_NSH_DISABLE_MOUNT is not set
# CONFIG_NSH_DISABLE_MV is not set
# CONFIG_NSH_DISABLE_PS is not set
# CONFIG_NSH_DISABLE_PSSTACKUSAGE is not set
# CONFIG_NSH_DISABLE_PWD is not set
# CONFIG_NSH_DISABLE_RM is not set
# CONFIG_NSH_DISABLE_RMDIR is not set
# CONFIG_NSH_DISABLE_SEMICOLON is not set
# CONFIG_NSH_DISABLE_SET is not set
# CONFIG_NSH_DISABLE_SLEEP is not set
# CONFIG_NSH_DISABLE_SOURCE is not set
# CONFIG_NSH_DISABLE_TEST is not set
# CONFIG_NSH_DISABLE_TIME is not set
# CONFIG_NSH_DISABLE_UMOUNT is not set
# CONFIG_NSH_DISABLE_UNSET is not set
# CONFIG_NSH_DISABLE_USLEEP is not set
CONFIG_ARCH="arm"
CONFIG_ARCH_BOARD_CUSTOM=y
CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/cubepilot/cubeorange/nuttx-config"
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
CONFIG_ARCH_CHIP="stm32h7"
CONFIG_ARCH_CHIP_STM32H743ZI=y
CONFIG_ARCH_CHIP_STM32H7=y
CONFIG_ARCH_INTERRUPTSTACK=768
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARMV7M_BASEPRI_WAR=y
CONFIG_ARMV7M_DCACHE=y
CONFIG_ARMV7M_DTCM=y
CONFIG_ARMV7M_ICACHE=y
CONFIG_ARMV7M_MEMCPY=y
CONFIG_ARMV7M_USEBASEPRI=y
CONFIG_ARM_MPU_EARLY_RESET=y
CONFIG_BOARDCTL_RESET=y
CONFIG_BOARD_ASSERT_RESET_VALUE=0
CONFIG_BOARD_CRASHDUMP=y
CONFIG_BOARD_LOOPSPERMSEC=79954
CONFIG_BOARD_RESET_ON_ASSERT=2
CONFIG_BUILTIN=y
CONFIG_CDCACM=y
CONFIG_CDCACM_IFLOWCONTROL=y
CONFIG_CDCACM_PRODUCTID=0x1016
CONFIG_CDCACM_PRODUCTSTR="CubeOrange"
CONFIG_CDCACM_RXBUFSIZE=600
CONFIG_CDCACM_TXBUFSIZE=12000
CONFIG_CDCACM_VENDORID=0x2DAE
CONFIG_CDCACM_VENDORSTR="CubePilot"
CONFIG_DEBUG_FULLOPT=y
CONFIG_DEBUG_HARDFAULT_ALERT=y
CONFIG_DEBUG_SYMBOLS=y
CONFIG_DEBUG_TCBINFO=y
CONFIG_DEFAULT_SMALL=y
CONFIG_DEV_FIFO_SIZE=0
CONFIG_DEV_PIPE_MAXSIZE=1024
CONFIG_DEV_PIPE_SIZE=70
CONFIG_EXPERIMENTAL=y
CONFIG_FAT_DMAMEMORY=y
CONFIG_FAT_LCNAMES=y
CONFIG_FAT_LFN=y
CONFIG_FAT_LFN_ALIAS_HASH=y
CONFIG_FDCLONE_STDIO=y
CONFIG_FS_BINFS=y
CONFIG_FS_CROMFS=y
CONFIG_FS_FAT=y
CONFIG_FS_FATTIME=y
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64
CONFIG_FS_PROCFS_REGISTER=y
CONFIG_FS_ROMFS=y
CONFIG_GRAN=y
CONFIG_GRAN_INTR=y
CONFIG_HAVE_CXX=y
CONFIG_HAVE_CXXINITIALIZE=y
CONFIG_I2C=y
CONFIG_I2C_RESET=y
CONFIG_IDLETHREAD_STACKSIZE=750
CONFIG_INIT_ENTRYPOINT="nsh_main"
CONFIG_INIT_STACKSIZE=3194
CONFIG_LIBC_FLOATINGPOINT=y
CONFIG_LIBC_LONG_LONG=y
CONFIG_LIBC_MAX_EXITFUNS=1
CONFIG_LIBC_STRERROR=y
CONFIG_MEMSET_64BIT=y
CONFIG_MEMSET_OPTSPEED=y
CONFIG_MMCSD=y
CONFIG_MMCSD_SDIO=y
CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y
CONFIG_MM_REGIONS=4
CONFIG_MTD=y
CONFIG_MTD_BYTE_WRITE=y
CONFIG_MTD_PARTITION=y
CONFIG_MTD_PROGMEM=y
CONFIG_MTD_RAMTRON=y
CONFIG_NAME_MAX=40
CONFIG_NSH_ARCHINIT=y
CONFIG_NSH_ARGCAT=y
CONFIG_NSH_BUILTIN_APPS=y
CONFIG_NSH_CMDPARMS=y
CONFIG_NSH_CROMFSETC=y
CONFIG_NSH_LINELEN=128
CONFIG_NSH_MAXARGUMENTS=15
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_VARS=y
CONFIG_OTG_ID_GPIO_DISABLE=y
CONFIG_PIPES=y
CONFIG_PREALLOC_TIMERS=50
CONFIG_PRIORITY_INHERITANCE=y
CONFIG_PTHREAD_MUTEX_ROBUST=y
CONFIG_PTHREAD_STACK_MIN=512
CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5
CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5
CONFIG_RAMTRON_SETSPEED=y
CONFIG_RAM_SIZE=245760
CONFIG_RAM_START=0x20010000
CONFIG_RAW_BINARY=y
CONFIG_READLINE_CMD_HISTORY=y
CONFIG_READLINE_TABCOMPLETION=y
CONFIG_RTC_DATETIME=y
CONFIG_SCHED_HPWORK=y
CONFIG_SCHED_HPWORKPRIORITY=249
CONFIG_SCHED_HPWORKSTACKSIZE=1280
CONFIG_SCHED_INSTRUMENTATION=y
CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y
CONFIG_SCHED_INSTRUMENTATION_SWITCH=y
CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SDMMC1_SDIO_PULLUP=y
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y
CONFIG_SIG_SIGUSR1_ACTION=y
CONFIG_SIG_SIGUSR2_ACTION=y
CONFIG_SIG_SIGWORK=4
CONFIG_STACK_COLORATION=y
CONFIG_START_DAY=30
CONFIG_START_MONTH=11
CONFIG_STDIO_BUFFER_SIZE=256
CONFIG_STM32H7_ADC1=y
CONFIG_STM32H7_ADC3=y
CONFIG_STM32H7_BBSRAM=y
CONFIG_STM32H7_BBSRAM_FILES=5
CONFIG_STM32H7_BKPSRAM=y
CONFIG_STM32H7_DMA1=y
CONFIG_STM32H7_DMA2=y
CONFIG_STM32H7_DMACAPABLE=y
CONFIG_STM32H7_FLOWCONTROL_BROKEN=y
CONFIG_STM32H7_I2C1=y
CONFIG_STM32H7_I2C2=y
CONFIG_STM32H7_I2C_DYNTIMEO=y
CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10
CONFIG_STM32H7_OTGFS=y
CONFIG_STM32H7_PROGMEM=y
CONFIG_STM32H7_RTC=y
CONFIG_STM32H7_RTC_HSECLOCK=y
CONFIG_STM32H7_RTC_MAGIC_REG=1
CONFIG_STM32H7_SAVE_CRASHDUMP=y
CONFIG_STM32H7_SDMMC1=y
CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y
CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y
CONFIG_STM32H7_SPI1=y
CONFIG_STM32H7_SPI1_DMA=y
CONFIG_STM32H7_SPI1_DMA_BUFFER=1024
CONFIG_STM32H7_SPI2=y
CONFIG_STM32H7_SPI4=y
CONFIG_STM32H7_SPI4_DMA=y
CONFIG_STM32H7_SPI4_DMA_BUFFER=1024
CONFIG_STM32H7_TIM1=y
CONFIG_STM32H7_TIM3=y
CONFIG_STM32H7_TIM4=y
CONFIG_STM32H7_UART4=y
CONFIG_STM32H7_UART7=y
CONFIG_STM32H7_UART8=y
CONFIG_STM32H7_USART2=y
CONFIG_STM32H7_USART3=y
CONFIG_STM32H7_USART6=y
CONFIG_STM32H7_USART_BREAKS=y
CONFIG_STM32H7_USART_INVERT=y
CONFIG_STM32H7_USART_SINGLEWIRE=y
CONFIG_STM32H7_USART_SWAP=y
CONFIG_SYSTEM_CDCACM=y
CONFIG_SYSTEM_NSH=y
CONFIG_TASK_NAME_SIZE=24
CONFIG_TTY_SIGINT=y
CONFIG_TTY_SIGINT_CHAR=0x03
CONFIG_TTY_SIGTSTP=y
CONFIG_UART4_BAUD=57600
CONFIG_UART4_RXBUFSIZE=600
CONFIG_UART4_TXBUFSIZE=1500
CONFIG_UART7_BAUD=57600
CONFIG_UART7_RXBUFSIZE=600
CONFIG_UART7_SERIAL_CONSOLE=y
CONFIG_UART7_TXBUFSIZE=1500
CONFIG_UART8_BAUD=57600
CONFIG_UART8_RXBUFSIZE=600
CONFIG_UART8_TXBUFSIZE=1500
CONFIG_USART2_BAUD=57600
CONFIG_USART2_IFLOWCONTROL=y
CONFIG_USART2_OFLOWCONTROL=y
CONFIG_USART2_RXBUFSIZE=600
CONFIG_USART2_TXBUFSIZE=1500
CONFIG_USART3_BAUD=57600
CONFIG_USART3_IFLOWCONTROL=y
CONFIG_USART3_OFLOWCONTROL=y
CONFIG_USART3_RXBUFSIZE=600
CONFIG_USART3_TXBUFSIZE=3000
CONFIG_USART6_BAUD=57600
CONFIG_USART6_RXBUFSIZE=600
CONFIG_USART6_TXBUFSIZE=1500
CONFIG_USBDEV=y
CONFIG_USBDEV_BUSPOWERED=y
CONFIG_USBDEV_MAXPOWER=500
CONFIG_USEC_PER_TICK=1000
CONFIG_WATCHDOG=y
@@ -0,0 +1 @@
# Same as default, only defconfig is different
@@ -0,0 +1,259 @@
#
# This file is autogenerated: PLEASE DO NOT EDIT IT.
#
# You can use "make menuconfig" to make any modifications to the installed .config file.
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
# modifications.
#
# CONFIG_DISABLE_ENVIRON is not set
# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
# CONFIG_DISABLE_PTHREAD is not set
# CONFIG_MMCSD_HAVE_CARDDETECT is not set
# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set
# CONFIG_MMCSD_MMCSUPPORT is not set
# CONFIG_MMCSD_SPI is not set
# CONFIG_NSH_DISABLEBG is not set
# CONFIG_NSH_DISABLESCRIPT is not set
# CONFIG_NSH_DISABLE_CAT is not set
# CONFIG_NSH_DISABLE_CD is not set
# CONFIG_NSH_DISABLE_CP is not set
# CONFIG_NSH_DISABLE_DATE is not set
# CONFIG_NSH_DISABLE_DF is not set
# CONFIG_NSH_DISABLE_ECHO is not set
# CONFIG_NSH_DISABLE_ENV is not set
# CONFIG_NSH_DISABLE_EXEC is not set
# CONFIG_NSH_DISABLE_EXIT is not set
# CONFIG_NSH_DISABLE_EXPORT is not set
# CONFIG_NSH_DISABLE_FREE is not set
# CONFIG_NSH_DISABLE_GET is not set
# CONFIG_NSH_DISABLE_HELP is not set
# CONFIG_NSH_DISABLE_ITEF is not set
# CONFIG_NSH_DISABLE_KILL is not set
# CONFIG_NSH_DISABLE_LOOPS is not set
# CONFIG_NSH_DISABLE_LS is not set
# CONFIG_NSH_DISABLE_MKDIR is not set
# CONFIG_NSH_DISABLE_MKFATFS is not set
# CONFIG_NSH_DISABLE_MOUNT is not set
# CONFIG_NSH_DISABLE_MV is not set
# CONFIG_NSH_DISABLE_PS is not set
# CONFIG_NSH_DISABLE_PSSTACKUSAGE is not set
# CONFIG_NSH_DISABLE_PWD is not set
# CONFIG_NSH_DISABLE_RM is not set
# CONFIG_NSH_DISABLE_RMDIR is not set
# CONFIG_NSH_DISABLE_SEMICOLON is not set
# CONFIG_NSH_DISABLE_SET is not set
# CONFIG_NSH_DISABLE_SLEEP is not set
# CONFIG_NSH_DISABLE_SOURCE is not set
# CONFIG_NSH_DISABLE_TEST is not set
# CONFIG_NSH_DISABLE_TIME is not set
# CONFIG_NSH_DISABLE_UMOUNT is not set
# CONFIG_NSH_DISABLE_UNSET is not set
# CONFIG_NSH_DISABLE_USLEEP is not set
CONFIG_ARCH="arm"
CONFIG_ARCH_BOARD_CUSTOM=y
CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/cubepilot/cubeorangeplus/nuttx-config"
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
CONFIG_ARCH_CHIP="stm32h7"
CONFIG_ARCH_CHIP_STM32H747XI=y
CONFIG_ARCH_CHIP_STM32H7=y
CONFIG_ARCH_INTERRUPTSTACK=768
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARMV7M_BASEPRI_WAR=y
CONFIG_ARMV7M_DCACHE=y
CONFIG_ARMV7M_DTCM=y
CONFIG_ARMV7M_ICACHE=y
CONFIG_ARMV7M_MEMCPY=y
CONFIG_ARMV7M_USEBASEPRI=y
CONFIG_ARM_MPU_EARLY_RESET=y
CONFIG_BOARDCTL_RESET=y
CONFIG_BOARD_ASSERT_RESET_VALUE=0
CONFIG_BOARD_CRASHDUMP=y
CONFIG_BOARD_LOOPSPERMSEC=79954
CONFIG_BOARD_RESET_ON_ASSERT=2
CONFIG_BUILTIN=y
CONFIG_CDCACM=y
CONFIG_CDCACM_IFLOWCONTROL=y
CONFIG_CDCACM_PRODUCTID=0x1058
CONFIG_CDCACM_PRODUCTSTR="CubeOrange+"
CONFIG_CDCACM_RXBUFSIZE=600
CONFIG_CDCACM_TXBUFSIZE=12000
CONFIG_CDCACM_VENDORID=0x2DAE
CONFIG_CDCACM_VENDORSTR="CubePilot"
CONFIG_DEBUG_FULLOPT=y
CONFIG_DEBUG_HARDFAULT_ALERT=y
CONFIG_DEBUG_SYMBOLS=y
CONFIG_DEBUG_TCBINFO=y
CONFIG_DEFAULT_SMALL=y
CONFIG_DEV_FIFO_SIZE=0
CONFIG_DEV_PIPE_MAXSIZE=1024
CONFIG_DEV_PIPE_SIZE=70
CONFIG_EXPERIMENTAL=y
CONFIG_FAT_DMAMEMORY=y
CONFIG_FAT_LCNAMES=y
CONFIG_FAT_LFN=y
CONFIG_FAT_LFN_ALIAS_HASH=y
CONFIG_FDCLONE_STDIO=y
CONFIG_FS_BINFS=y
CONFIG_FS_CROMFS=y
CONFIG_FS_FAT=y
CONFIG_FS_FATTIME=y
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64
CONFIG_FS_PROCFS_REGISTER=y
CONFIG_FS_ROMFS=y
CONFIG_GRAN=y
CONFIG_GRAN_INTR=y
CONFIG_HAVE_CXX=y
CONFIG_HAVE_CXXINITIALIZE=y
CONFIG_I2C=y
CONFIG_I2C_RESET=y
CONFIG_IDLETHREAD_STACKSIZE=750
CONFIG_INIT_ENTRYPOINT="nsh_main"
CONFIG_INIT_STACKSIZE=3194
CONFIG_LIBC_FLOATINGPOINT=y
CONFIG_LIBC_LONG_LONG=y
CONFIG_LIBC_MAX_EXITFUNS=1
CONFIG_LIBC_STRERROR=y
CONFIG_MEMSET_64BIT=y
CONFIG_MEMSET_OPTSPEED=y
CONFIG_MMCSD=y
CONFIG_MMCSD_SDIO=y
CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y
CONFIG_MM_REGIONS=4
CONFIG_MTD=y
CONFIG_MTD_BYTE_WRITE=y
CONFIG_MTD_PARTITION=y
CONFIG_MTD_PROGMEM=y
CONFIG_MTD_RAMTRON=y
CONFIG_NAME_MAX=40
CONFIG_NSH_ARCHINIT=y
CONFIG_NSH_ARGCAT=y
CONFIG_NSH_BUILTIN_APPS=y
CONFIG_NSH_CMDPARMS=y
CONFIG_NSH_CROMFSETC=y
CONFIG_NSH_LINELEN=128
CONFIG_NSH_MAXARGUMENTS=15
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_VARS=y
CONFIG_OTG_ID_GPIO_DISABLE=y
CONFIG_PIPES=y
CONFIG_PREALLOC_TIMERS=50
CONFIG_PRIORITY_INHERITANCE=y
CONFIG_PTHREAD_MUTEX_ROBUST=y
CONFIG_PTHREAD_STACK_MIN=512
CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5
CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5
CONFIG_RAMTRON_SETSPEED=y
CONFIG_RAM_SIZE=245760
CONFIG_RAM_START=0x20010000
CONFIG_RAW_BINARY=y
CONFIG_READLINE_CMD_HISTORY=y
CONFIG_READLINE_TABCOMPLETION=y
CONFIG_RTC_DATETIME=y
CONFIG_SCHED_HPWORK=y
CONFIG_SCHED_HPWORKPRIORITY=249
CONFIG_SCHED_HPWORKSTACKSIZE=1280
CONFIG_SCHED_INSTRUMENTATION=y
CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y
CONFIG_SCHED_INSTRUMENTATION_SWITCH=y
CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SDMMC1_SDIO_PULLUP=y
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y
CONFIG_SIG_SIGUSR1_ACTION=y
CONFIG_SIG_SIGUSR2_ACTION=y
CONFIG_SIG_SIGWORK=4
CONFIG_STACK_COLORATION=y
CONFIG_START_DAY=30
CONFIG_START_MONTH=11
CONFIG_STDIO_BUFFER_SIZE=256
CONFIG_STM32H7_ADC1=y
CONFIG_STM32H7_ADC3=y
CONFIG_STM32H7_BBSRAM=y
CONFIG_STM32H7_BBSRAM_FILES=5
CONFIG_STM32H7_BKPSRAM=y
CONFIG_STM32H7_DMA1=y
CONFIG_STM32H7_DMA2=y
CONFIG_STM32H7_DMACAPABLE=y
CONFIG_STM32H7_FLOWCONTROL_BROKEN=y
CONFIG_STM32H7_I2C1=y
CONFIG_STM32H7_I2C2=y
CONFIG_STM32H7_I2C4=y
CONFIG_STM32H7_I2C_DYNTIMEO=y
CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10
CONFIG_STM32H7_OTGFS=y
CONFIG_STM32H7_PROGMEM=y
CONFIG_STM32H7_PWR_DIRECT_SMPS_SUPPLY=y
CONFIG_STM32H7_RTC=y
CONFIG_STM32H7_RTC_HSECLOCK=y
CONFIG_STM32H7_RTC_MAGIC_REG=1
CONFIG_STM32H7_SAVE_CRASHDUMP=y
CONFIG_STM32H7_SDMMC1=y
CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y
CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y
CONFIG_STM32H7_SPI1=y
CONFIG_STM32H7_SPI1_DMA=y
CONFIG_STM32H7_SPI1_DMA_BUFFER=1024
CONFIG_STM32H7_SPI2=y
CONFIG_STM32H7_SPI4=y
CONFIG_STM32H7_SPI4_DMA=y
CONFIG_STM32H7_SPI4_DMA_BUFFER=1024
CONFIG_STM32H7_TIM1=y
CONFIG_STM32H7_TIM3=y
CONFIG_STM32H7_TIM4=y
CONFIG_STM32H7_UART4=y
CONFIG_STM32H7_UART7=y
CONFIG_STM32H7_UART8=y
CONFIG_STM32H7_USART2=y
CONFIG_STM32H7_USART3=y
CONFIG_STM32H7_USART6=y
CONFIG_STM32H7_USART_BREAKS=y
CONFIG_STM32H7_USART_INVERT=y
CONFIG_STM32H7_USART_SINGLEWIRE=y
CONFIG_STM32H7_USART_SWAP=y
CONFIG_SYSTEM_CDCACM=y
CONFIG_SYSTEM_NSH=y
CONFIG_TASK_NAME_SIZE=24
CONFIG_TTY_SIGINT=y
CONFIG_TTY_SIGINT_CHAR=0x03
CONFIG_TTY_SIGTSTP=y
CONFIG_UART4_BAUD=57600
CONFIG_UART4_RXBUFSIZE=600
CONFIG_UART4_TXBUFSIZE=1500
CONFIG_UART7_BAUD=57600
CONFIG_UART7_RXBUFSIZE=600
CONFIG_UART7_SERIAL_CONSOLE=y
CONFIG_UART7_TXBUFSIZE=1500
CONFIG_UART8_BAUD=57600
CONFIG_UART8_RXBUFSIZE=600
CONFIG_UART8_TXBUFSIZE=1500
CONFIG_USART2_BAUD=57600
CONFIG_USART2_IFLOWCONTROL=y
CONFIG_USART2_OFLOWCONTROL=y
CONFIG_USART2_RXBUFSIZE=600
CONFIG_USART2_TXBUFSIZE=1500
CONFIG_USART3_BAUD=57600
CONFIG_USART3_IFLOWCONTROL=y
CONFIG_USART3_OFLOWCONTROL=y
CONFIG_USART3_RXBUFSIZE=600
CONFIG_USART3_TXBUFSIZE=3000
CONFIG_USART6_BAUD=57600
CONFIG_USART6_RXBUFSIZE=600
CONFIG_USART6_TXBUFSIZE=1500
CONFIG_USBDEV=y
CONFIG_USBDEV_BUSPOWERED=y
CONFIG_USBDEV_MAXPOWER=500
CONFIG_USEC_PER_TICK=1000
CONFIG_WATCHDOG=y
@@ -52,6 +52,7 @@
#define IMXRT_IPG_PODF_DIVIDER 5
#define BOARD_GPT_FREQUENCY 24000000
#define BOARD_XTAL_FREQUENCY 24000000
#define BOARD_FLEXIO_PREQ 108000000
/* SDIO *********************************************************************/
+6 -6
View File
@@ -114,11 +114,11 @@ const struct clock_configuration_s g_initial_clkconfig = {
.div = 1,
.mux = ACMP_CLK_ROOT_OSC_RC_48M_DIV2,
},
.flexio1_clk_root = /* 240 / 2 = 120Mhz */
.flexio1_clk_root = /* 432 / 4 = 108Mhz */
{
.enable = 1,
.div = 2,
.mux = FLEXIO1_CLK_ROOT_SYS_PLL3_DIV2,
.div = 4,
.mux = FLEXIO1_CLK_ROOT_SYS_PLL2_PFD3,
},
.flexio2_clk_root =
{
@@ -492,9 +492,9 @@ const struct clock_configuration_s g_initial_clkconfig = {
.mfd = 268435455,
.ss_enable = 0,
.pfd0 = 27, /* (528 * 18) / 27 = 352 MHz */
.pfd1 = 16, /* (528 * 16) / 16 = 594 MHz */
.pfd2 = 24, /* (528 * 24) / 27 = 396 MHz */
.pfd3 = 32, /* (528 * 32) / 27 = 297 MHz */
.pfd1 = 16, /* (528 * 18) / 16 = 594 MHz */
.pfd2 = 24, /* (528 * 18) / 24 = 396 MHz */
.pfd3 = 22, /* (528 * 18) / 22 = 216 MHz */
},
.sys_pll3 =
{
+4
View File
@@ -10,3 +10,7 @@ float32 true_ground_minus_wind_m_s # TAS calculated from groundspeed - windspe
bool airspeed_sensor_measurement_valid # True if data from at least one airspeed sensor is declared valid.
int8 selected_airspeed_index # 1-3: airspeed sensor index, 0: groundspeed-windspeed, -1: airspeed invalid
float32 airspeed_derivative_filtered # filtered indicated airspeed derivative [m/s/s]
float32 throttle_filtered # filtered fixed-wing throttle [-]
float32 pitch_filtered # filtered pitch [rad]
+1
View File
@@ -180,6 +180,7 @@ set(msg_files
RegisterExtComponentReply.msg
RegisterExtComponentRequest.msg
RoverAckermannGuidanceStatus.msg
RoverAckermannStatus.msg
Rpm.msg
RtlStatus.msg
RtlTimeEstimate.msg
-15
View File
@@ -20,18 +20,3 @@ bool reset_hgt_to_baro # 13 - true when the vertical position s
bool reset_hgt_to_gps # 14 - true when the vertical position state is reset to the gps measurement
bool reset_hgt_to_rng # 15 - true when the vertical position state is reset to the rng measurement
bool reset_hgt_to_ev # 16 - true when the vertical position state is reset to the ev measurement
# warning events
uint32 warning_event_changes # number of warning event changes
bool gps_quality_poor # 0 - true when the gps is failing quality checks
bool gps_fusion_timout # 1 - true when the gps data has not been used to correct the state estimates for a significant time period
bool gps_data_stopped # 2 - true when the gps data has stopped for a significant time period
bool gps_data_stopped_using_alternate # 3 - true when the gps data has stopped for a significant time period but the filter is able to use other sources of data to maintain navigation
bool height_sensor_timeout # 4 - true when the height sensor has not been used to correct the state estimates for a significant time period
bool stopping_navigation # 5 - true when the filter has insufficient data to estimate velocity and position and is falling back to an attitude, height and height rate mode of operation
bool invalid_accel_bias_cov_reset # 6 - true when the filter has detected bad acceerometer bias state esitmstes and has reset the corresponding covariance matrix elements
bool bad_yaw_using_gps_course # 7 - true when the filter has detected an invalid yaw estimate and has reset the yaw angle to the GPS ground course
bool stopping_mag_use # 8 - true when the filter has detected bad magnetometer data and is stopping further use of the magnetometer data
bool vision_data_stopped # 9 - true when the vision system data has stopped for a significant time period
bool emergency_yaw_reset_mag_stopped # 10 - true when the filter has detected bad magnetometer data, has reset the yaw to anothter source of data and has stopped further use of the magnetometer data
bool emergency_yaw_reset_gps_yaw_stopped # 11 - true when the filter has detected bad GNSS yaw data, has reset the yaw to anothter source of data and has stopped further use of the GNSS yaw data
+1
View File
@@ -13,6 +13,7 @@ bool check_fail_max_horz_drift # 6 : maximum allowed horizontal position drift
bool check_fail_max_vert_drift # 7 : maximum allowed vertical position drift fail - requires stationary vehicle
bool check_fail_max_horz_spd_err # 8 : maximum allowed horizontal speed fail - requires stationary vehicle
bool check_fail_max_vert_spd_err # 9 : maximum allowed vertical velocity discrepancy fail
bool check_fail_spoofed_gps # 10 : GPS signal is spoofed
float32 position_drift_rate_horizontal_m_s # Horizontal position rate magnitude (m/s)
float32 position_drift_rate_vertical_m_s # Vertical position rate magnitude (m/s)
+1
View File
@@ -15,6 +15,7 @@ uint8 GPS_CHECK_FAIL_MAX_HORZ_DRIFT = 6 # 6 : maximum allowed horizontal positi
uint8 GPS_CHECK_FAIL_MAX_VERT_DRIFT = 7 # 7 : maximum allowed vertical position drift fail - requires stationary vehicle
uint8 GPS_CHECK_FAIL_MAX_HORZ_SPD_ERR = 8 # 8 : maximum allowed horizontal speed fail - requires stationary vehicle
uint8 GPS_CHECK_FAIL_MAX_VERT_SPD_ERR = 9 # 9 : maximum allowed vertical velocity discrepancy fail
uint8 GPS_CHECK_FAIL_SPOOFED = 10 # 10 : GPS signal is spoofed
uint64 control_mode_flags # Bitmask to indicate EKF logic state
uint8 CS_TILT_ALIGN = 0 # 0 - true if the filter tilt alignment is complete
+2
View File
@@ -43,6 +43,8 @@ bool cs_mag # 35 - true if 3-axis magnetometer measurement f
bool cs_ev_yaw_fault # 36 - true when the EV heading has been declared faulty and is no longer being used
bool cs_mag_heading_consistent # 37 - true when the heading obtained from mag data is declared consistent with the filter
bool cs_aux_gpos # 38 - true if auxiliary global position measurement fusion is intended
bool cs_rng_terrain # 39 - true if we are fusing range finder data for terrain
bool cs_opt_flow_terrain # 40 - true if we are fusing flow data for terrain
# fault status
uint32 fault_status_changes # number of filter fault status (fs) changes
+5 -6
View File
@@ -1,10 +1,9 @@
uint64 timestamp # time since system start (microseconds)
float32 actual_speed # [m/s] Rover ground speed
float32 desired_speed # [m/s] Rover desired ground speed
float32 lookahead_distance # [m] Lookahead distance of pure the pursuit controller
float32 heading_error # [deg] Heading error of the pure pursuit controller
float32 pid_throttle_integral # [-1, 1] Integral of the PID for the normalized throttle to control the rover speed during missions
float32 crosstrack_error # [m] Shortest distance from the vehicle to the path
float32 desired_speed # [m/s] Rover desired ground speed
float32 lookahead_distance # [m] Lookahead distance of pure the pursuit controller
float32 heading_error # [deg] Heading error of the pure pursuit controller
float32 pid_throttle_integral # [-1, 1] Integral of the PID for the normalized throttle to control the rover speed during missions
float32 crosstrack_error # [m] Shortest distance from the vehicle to the path
# TOPICS rover_ackermann_guidance_status
+7
View File
@@ -0,0 +1,7 @@
uint64 timestamp # time since system start (microseconds)
float32 throttle_setpoint # [-1, 1] Normalized throttle setpoint
float32 steering_setpoint # [-1, 1] Normalized steering setpoint
float32 actual_speed # [m/s] Rover ground speed
# TOPICS rover_ackermann_status
+1
View File
@@ -56,6 +56,7 @@ float32 ref_alt # Reference altitude AMSL, (metres)
# Distance to surface
float32 dist_bottom # Distance from from bottom surface to ground, (metres)
float32 dist_bottom_var # terrain estimate variance (m^2)
bool dist_bottom_valid # true if distance to bottom surface is valid
uint8 dist_bottom_sensor_bitfield # bitfield indicating what type of sensor is used to estimate dist_bottom
uint8 DIST_BOTTOM_SENSOR_NONE = 0
+11 -3
View File
@@ -125,8 +125,16 @@ public:
{
if (_subscription.copy(dst)) {
const hrt_abstime now = hrt_absolute_time();
// shift last update time forward, but don't let it get further behind than the interval
_last_update = math::constrain(_last_update + _interval_us, now - _interval_us, now);
// make sure we don't set a timestamp before the timer started counting (now - _interval_us would wrap because it's unsigned)
if (now > _interval_us) {
// shift last update time forward, but don't let it get further behind than the interval
_last_update = math::constrain(_last_update + _interval_us, now - _interval_us, now);
} else {
_last_update = now;
}
return true;
}
@@ -160,7 +168,7 @@ public:
protected:
Subscription _subscription;
uint64_t _last_update{0}; // last update in microseconds
uint64_t _last_update{0}; // last subscription update in microseconds
uint32_t _interval_us{0}; // maximum update interval in microseconds
};
@@ -46,7 +46,6 @@
#include "arm_internal.h"
#define FLEXIO_BASE IMXRT_FLEXIO1_BASE
#define FLEXIO_PREQ 120000000
#define DSHOT_TIMERS FLEXIO_SHIFTBUFNIS_COUNT
#define DSHOT_THROTTLE_POSITION 5u
#define DSHOT_TELEMETRY_POSITION 4u
@@ -305,8 +304,8 @@ static int flexio_irq_handler(int irq, void *context, void *arg)
int up_dshot_init(uint32_t channel_mask, unsigned dshot_pwm_freq, bool enable_bidirectional_dshot)
{
/* Calculate dshot timings based on dshot_pwm_freq */
dshot_tcmp = 0x2F00 | (((FLEXIO_PREQ / (dshot_pwm_freq * 3) / 2)) & 0xFF);
bdshot_tcmp = 0x2900 | (((FLEXIO_PREQ / (dshot_pwm_freq * 5 / 4) / 2) - 1) & 0xFF);
dshot_tcmp = 0x2F00 | (((BOARD_FLEXIO_PREQ / (dshot_pwm_freq * 3) / 2) - 1) & 0xFF);
bdshot_tcmp = 0x2900 | (((BOARD_FLEXIO_PREQ / (dshot_pwm_freq * 5 / 4) / 2) - 3) & 0xFF);
/* Clock FlexIO peripheral */
imxrt_clockall_flexio1();
+2
View File
@@ -39,6 +39,8 @@
#pragma once
#include <stdint.h>
namespace septentrio
{
@@ -131,7 +131,6 @@ private:
(ParamFloat<px4::params::WEIGHT_GROSS>) _param_weight_gross,
(ParamFloat<px4::params::FW_SERVICE_CEIL>) _param_service_ceiling,
(ParamFloat<px4::params::FW_THR_TRIM>) _param_fw_thr_trim,
(ParamFloat<px4::params::FW_THR_IDLE>) _param_fw_thr_idle,
(ParamFloat<px4::params::FW_THR_MAX>) _param_fw_thr_max,
(ParamFloat<px4::params::FW_THR_MIN>) _param_fw_thr_min,
(ParamFloat<px4::params::FW_THR_ASPD_MIN>) _param_fw_thr_aspd_min,
+1
View File
@@ -33,6 +33,7 @@
px4_add_library(mathlib
math/test/test.cpp
math/filter/FilteredDerivative.hpp
math/filter/LowPassFilter2p.hpp
math/filter/MedianFilter.hpp
math/filter/NotchFilter.hpp
@@ -0,0 +1,114 @@
/****************************************************************************
*
* Copyright (c) 2024 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file FilteredDerivative.hpp
*
* @brief Derivative function passed through a first order "alpha" IIR digital filter
*
* @author Silvan Fuhrer <silvan@auterion.com>
*/
#pragma once
// #include <float.h>
// #include <mathlib/math/Functions.hpp>
#include <mathlib/math/filter/AlphaFilter.hpp>
using namespace math;
template <typename T>
class FilteredDerivative
{
public:
FilteredDerivative() = default;
~FilteredDerivative() = default;
/**
* Set filter parameters for time abstraction
*
* Both parameters have to be provided in the same units.
*
* @param sample_interval interval between two samples
* @param time_constant filter time constant determining convergence
*/
void setParameters(float sample_interval, float time_constant)
{
_alpha_filter.setParameters(sample_interval, time_constant);
_sample_interval = sample_interval;
}
/**
* Set filter state to an initial value
*
* @param sample new initial value
*/
void reset(const T &sample)
{
_alpha_filter.reset(sample);
_initialized = false;
}
/**
* Add a new raw value to the filter
*
* @return retrieve the filtered result
*/
const T &update(const T &sample)
{
if (_initialized) {
if (_sample_interval > FLT_EPSILON) {
_alpha_filter.update((sample - _previous_sample) / _sample_interval);
} else {
_initialized = false;
}
} else {
// don't update in the first iteration
_initialized = true;
}
_previous_sample = sample;
return _alpha_filter.getState();
}
const T &getState() const { return _alpha_filter.getState(); }
private:
AlphaFilter<T> _alpha_filter;
float _sample_interval{0.f};
T _previous_sample{0.f};
bool _initialized{false};
};
@@ -60,6 +60,8 @@ AirspeedValidator::update_airspeed_validator(const airspeed_validator_update_dat
check_load_factor(input_data.accel_z);
check_airspeed_innovation(input_data.timestamp, input_data.vel_test_ratio, input_data.mag_test_ratio,
input_data.ground_velocity, input_data.gnss_valid);
check_first_principle(input_data.timestamp, input_data.fixed_wing_tecs_throttle,
input_data.fixed_wing_tecs_throttle_trim, input_data.tecs_timestamp, input_data.q_att);
update_airspeed_valid_status(input_data.timestamp);
}
@@ -277,16 +279,76 @@ AirspeedValidator::check_load_factor(float accel_z)
}
}
void
AirspeedValidator::check_first_principle(const uint64_t timestamp, const float throttle_fw, const float throttle_trim,
const uint64_t tecs_timestamp, const Quatf &att_q)
{
if (! _first_principle_check_enabled) {
_first_principle_check_failed = false;
_time_last_first_principle_check_passing = timestamp;
return;
}
const float pitch = matrix::Eulerf(att_q).theta();
const hrt_abstime tecs_dt = timestamp - tecs_timestamp; // return if TECS data is old (TECS not running)
if (!_in_fixed_wing_flight || tecs_dt > 500_ms || !PX4_ISFINITE(_IAS) || !PX4_ISFINITE(throttle_fw)
|| !PX4_ISFINITE(throttle_trim) || !PX4_ISFINITE(pitch)) {
// do not do anything in that case
return;
}
const float dt = static_cast<float>(timestamp - _time_last_first_principle_check) / 1_s;
_time_last_first_principle_check = timestamp;
// update filters
if (dt < FLT_EPSILON || dt > 1.f) {
// reset if dt is too large
_IAS_derivative.reset(0.f);
_throttle_filtered.reset(throttle_fw);
_pitch_filtered.reset(pitch);
_time_last_first_principle_check_passing = timestamp;
} else {
// update filters, with different time constant
_IAS_derivative.setParameters(dt, 5.f);
_throttle_filtered.setParameters(dt, 0.5f);
_pitch_filtered.setParameters(dt, 1.5f);
_IAS_derivative.update(_IAS);
_throttle_filtered.update(throttle_fw);
_pitch_filtered.update(pitch);
}
// declare high throttle if more than 5% above trim
const float high_throttle_threshold = math::min(throttle_trim + kHighThrottleDelta, _param_throttle_max);
const bool high_throttle = _throttle_filtered.getState() > high_throttle_threshold;
const bool pitching_down = _pitch_filtered.getState() < _param_psp_off;
// check if the airspeed derivative is too low given the throttle and pitch
const bool check_failing = _IAS_derivative.getState() < kIASDerivateThreshold && high_throttle && pitching_down;
if (!check_failing) {
_time_last_first_principle_check_passing = timestamp;
_first_principle_check_failed = false;
}
if (timestamp - _time_last_first_principle_check_passing > _aspd_fp_t_window * 1_s) {
// only update the test_failed flag once the timeout since first principle check failing is over
_first_principle_check_failed = check_failing;
}
}
void
AirspeedValidator::update_airspeed_valid_status(const uint64_t timestamp)
{
if (_data_stuck_test_failed || _innovations_check_failed || _load_factor_check_failed) {
if (_data_stuck_test_failed || _innovations_check_failed || _load_factor_check_failed
|| _first_principle_check_failed) {
// at least one check (data stuck, innovation or load factor) failed, so record timestamp
_time_checks_failed = timestamp;
} else if (! _data_stuck_test_failed && !_innovations_check_failed
&& !_load_factor_check_failed) {
&& !_load_factor_check_failed && !_first_principle_check_failed) {
// all checks(data stuck, innovation and load factor) must pass to declare airspeed good
_time_checks_passed = timestamp;
}
@@ -41,6 +41,8 @@
#include <airspeed/airspeed.h>
#include <lib/wind_estimator/WindEstimator.hpp>
#include <uORB/topics/airspeed_wind.h>
#include <lib/mathlib/math/filter/AlphaFilter.hpp>
#include <lib/mathlib/math/filter/FilteredDerivative.hpp>
using matrix::Dcmf;
@@ -66,6 +68,9 @@ struct airspeed_validator_update_data {
float vel_test_ratio;
float mag_test_ratio;
bool in_fixed_wing_flight;
float fixed_wing_tecs_throttle;
float fixed_wing_tecs_throttle_trim;
uint64_t tecs_timestamp;
};
class AirspeedValidator
@@ -83,6 +88,9 @@ public:
float get_TAS() { return _TAS; }
bool get_airspeed_valid() { return _airspeed_valid; }
float get_CAS_scale_validated() {return _CAS_scale_validated;}
float get_airspeed_derivative() { return _IAS_derivative.getState(); }
float get_throttle_filtered() { return _throttle_filtered.getState(); }
float get_pitch_filtered() { return _pitch_filtered.getState(); }
airspeed_wind_s get_wind_estimator_states(uint64_t timestamp);
@@ -118,6 +126,10 @@ public:
void set_enable_data_stuck_check(bool enable) { _data_stuck_check_enabled = enable; }
void set_enable_innovation_check(bool enable) { _innovation_check_enabled = enable; }
void set_enable_load_factor_check(bool enable) { _load_factor_check_enabled = enable; }
void set_enable_first_principle_check(bool enable) { _first_principle_check_enabled = enable; }
void set_psp_off_param(float psp_off_param) { _param_psp_off = psp_off_param; }
void set_throttle_max_param(float throttle_max_param) { _param_throttle_max = throttle_max_param; }
void set_fp_t_window(float t_window) { _aspd_fp_t_window = t_window; }
private:
@@ -127,10 +139,17 @@ private:
bool _data_stuck_check_enabled{false};
bool _innovation_check_enabled{false};
bool _load_factor_check_enabled{false};
bool _first_principle_check_enabled{false};
// airspeed scale validity check
static constexpr int SCALE_CHECK_SAMPLES = 12; ///< take samples from 12 segments (every 360/12=30°)
static constexpr float kHighThrottleDelta =
0.05f; ///< throttle delta above trim throttle required to consider throttle high
static constexpr float kIASDerivateThreshold =
0.1f; ///< threshold for IAS derivative to detect airspeed failure. Failure is
// detected if in a high throttle and low pitch situation and the filtered IAS derivative is below this threshold
// general states
bool _in_fixed_wing_flight{false}; ///< variable to bypass innovation and load factor checks
float _IAS{0.0f}; ///< indicated airsped in m/s
@@ -158,6 +177,17 @@ private:
float _airspeed_stall{8.0f}; ///< stall speed of aircraft used for load factor check
float _load_factor_ratio{0.5f}; ///< ratio of maximum load factor predicted by stall speed to measured load factor
// first principle check
bool _first_principle_check_failed{false}; ///< first principle check has detected failure
float _aspd_fp_t_window{0.f}; ///< time window for first principle check
FilteredDerivative<float> _IAS_derivative; ///< indicated airspeed derivative for first principle check
AlphaFilter<float> _throttle_filtered; ///< filtered throttle for first principle check
AlphaFilter<float> _pitch_filtered; ///< filtered pitch for first principle check
hrt_abstime _time_last_first_principle_check{0}; ///< time airspeed first principle was last checked (uSec)
hrt_abstime _time_last_first_principle_check_passing{0}; ///< time airspeed first principle was last passing (uSec)
float _param_psp_off{0.0f}; ///< parameter pitch in level flight [rad]
float _param_throttle_max{0.0f}; ///< parameter maximum throttle value
// states of airspeed valid declaration
bool _airspeed_valid{true}; ///< airspeed valid (pitot or groundspeed-windspeed)
float _checks_fail_delay{2.f}; ///< delay for airspeed invalid declaration after single check failure (Sec)
@@ -185,6 +215,8 @@ private:
void check_airspeed_innovation(uint64_t timestamp, float estimator_status_vel_test_ratio,
float estimator_status_mag_test_ratio, const matrix::Vector3f &vI, bool gnss_valid);
void check_load_factor(float accel_z);
void check_first_principle(const uint64_t timestamp, const float throttle, const float throttle_trim,
const uint64_t tecs_timestamp, const Quatf &att_q);
void update_airspeed_valid_status(const uint64_t timestamp);
void reset();
void reset_CAS_scale_check();
@@ -57,6 +57,7 @@
#include <uORB/topics/position_setpoint.h>
#include <uORB/Publication.hpp>
#include <uORB/PublicationMulti.hpp>
#include <uORB/topics/tecs_status.h>
#include <uORB/topics/vehicle_acceleration.h>
#include <uORB/topics/vehicle_air_data.h>
#include <uORB/topics/vehicle_attitude.h>
@@ -112,6 +113,7 @@ private:
uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s};
uORB::Subscription _tecs_status_sub{ORB_ID(tecs_status)};
uORB::Subscription _estimator_selector_status_sub{ORB_ID(estimator_selector_status)};
uORB::Subscription _estimator_status_sub{ORB_ID(estimator_status)};
uORB::Subscription _vehicle_acceleration_sub{ORB_ID(vehicle_acceleration)};
@@ -125,6 +127,7 @@ private:
uORB::SubscriptionMultiArray<airspeed_s, MAX_NUM_AIRSPEED_SENSORS> _airspeed_subs{ORB_ID::airspeed};
tecs_status_s _tecs_status {};
estimator_status_s _estimator_status {};
vehicle_acceleration_s _accel {};
vehicle_air_data_s _vehicle_air_data {};
@@ -162,9 +165,16 @@ private:
CHECK_TYPE_ONLY_DATA_MISSING_BIT = (1 << 0),
CHECK_TYPE_DATA_STUCK_BIT = (1 << 1),
CHECK_TYPE_INNOVATION_BIT = (1 << 2),
CHECK_TYPE_LOAD_FACTOR_BIT = (1 << 3)
CHECK_TYPE_LOAD_FACTOR_BIT = (1 << 3),
CHECK_TYPE_FIRST_PRINCIPLE_BIT = (1 << 4)
};
param_t _param_handle_pitch_sp_offset{PARAM_INVALID};
float _param_pitch_sp_offset{0.0f};
param_t _param_handle_fw_thr_max{PARAM_INVALID};
float _param_fw_thr_max{0.0f};
DEFINE_PARAMETERS(
(ParamFloat<px4::params::ASPD_WIND_NSD>) _param_aspd_wind_nsd,
(ParamFloat<px4::params::ASPD_SCALE_NSD>) _param_aspd_scale_nsd,
@@ -185,8 +195,12 @@ private:
(ParamFloat<px4::params::ASPD_FS_T_STOP>) _checks_fail_delay, /**< delay to declare airspeed invalid */
(ParamFloat<px4::params::ASPD_FS_T_START>) _checks_clear_delay, /**< delay to declare airspeed valid again */
(ParamFloat<px4::params::ASPD_WERR_THR>) _param_wind_sigma_max_synth_tas,
(ParamFloat<px4::params::ASPD_FP_T_WINDOW>) _aspd_fp_t_window,
// external parameters
(ParamFloat<px4::params::FW_AIRSPD_STALL>) _param_fw_airspd_stall,
(ParamFloat<px4::params::ASPD_WERR_THR>) _param_wind_sigma_max_synth_tas
(ParamFloat<px4::params::FW_AIRSPD_TRIM>) _param_fw_airspd_trim
)
void init(); /**< initialization of the airspeed validator instances */
@@ -203,6 +217,8 @@ AirspeedModule::AirspeedModule():
ModuleParams(nullptr),
ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::nav_and_controllers)
{
_param_handle_pitch_sp_offset = param_find("FW_PSP_OFF");
_param_handle_fw_thr_max = param_find("FW_THR_MAX");
// initialise parameters
update_params();
@@ -355,6 +371,9 @@ AirspeedModule::Run()
input_data.accel_z = _accel.xyz[2];
input_data.vel_test_ratio = _estimator_status.vel_test_ratio;
input_data.mag_test_ratio = _estimator_status.mag_test_ratio;
input_data.tecs_timestamp = _tecs_status.timestamp;
input_data.fixed_wing_tecs_throttle = _tecs_status.throttle_sp;
input_data.fixed_wing_tecs_throttle_trim = _tecs_status.throttle_trim;
// iterate through all airspeed sensors, poll new data from them and update their validators
for (int i = 0; i < _number_of_airspeed_sensors; i++) {
@@ -442,6 +461,14 @@ void AirspeedModule::update_params()
{
updateParams();
if (_param_handle_pitch_sp_offset != PARAM_INVALID) {
param_get(_param_handle_pitch_sp_offset, &_param_pitch_sp_offset);
}
if (_param_handle_fw_thr_max != PARAM_INVALID) {
param_get(_param_handle_fw_thr_max, &_param_fw_thr_max);
}
_param_airspeed_scale[0] = _param_airspeed_scale_1.get();
_param_airspeed_scale[1] = _param_airspeed_scale_2.get();
_param_airspeed_scale[2] = _param_airspeed_scale_3.get();
@@ -476,6 +503,11 @@ void AirspeedModule::update_params()
CheckTypeBits::CHECK_TYPE_INNOVATION_BIT);
_airspeed_validator[i].set_enable_load_factor_check(_param_airspeed_checks_on.get() &
CheckTypeBits::CHECK_TYPE_LOAD_FACTOR_BIT);
_airspeed_validator[i].set_enable_first_principle_check(_param_airspeed_checks_on.get() &
CheckTypeBits::CHECK_TYPE_FIRST_PRINCIPLE_BIT);
_airspeed_validator[i].set_psp_off_param(math::radians(_param_pitch_sp_offset));
_airspeed_validator[i].set_throttle_max_param(_param_fw_thr_max);
_airspeed_validator[i].set_fp_t_window(_aspd_fp_t_window.get());
}
}
@@ -501,6 +533,8 @@ void AirspeedModule::poll_topics()
_vehicle_local_position_sub.update(&_vehicle_local_position);
_position_setpoint_sub.update(&_position_setpoint);
_tecs_status_sub.update(&_tecs_status);
if (_vehicle_attitude_sub.updated()) {
vehicle_attitude_s vehicle_attitude;
_vehicle_attitude_sub.update(&vehicle_attitude);
@@ -661,6 +695,11 @@ void AirspeedModule::select_airspeed_and_publish()
airspeed_validated.airspeed_sensor_measurement_valid = false;
airspeed_validated.selected_airspeed_index = _valid_airspeed_index;
airspeed_validated.airspeed_derivative_filtered = _airspeed_validator[_valid_airspeed_index -
1].get_airspeed_derivative();
airspeed_validated.throttle_filtered = _airspeed_validator[_valid_airspeed_index - 1].get_throttle_filtered();
airspeed_validated.pitch_filtered = _airspeed_validator[_valid_airspeed_index - 1].get_pitch_filtered();
switch (_valid_airspeed_index) {
case airspeed_index::DISABLED_INDEX:
break;
@@ -149,11 +149,12 @@ PARAM_DEFINE_INT32(ASPD_PRIMARY, 1);
* Controls which checks are run to check airspeed data for validity. Only applied if ASPD_PRIMARY > 0.
*
* @min 0
* @max 15
* @max 31
* @bit 0 Only data missing check (triggers if more than 1s no data)
* @bit 1 Data stuck (triggers if data is exactly constant for 2s in FW mode)
* @bit 2 Innovation check (see ASPD_FS_INNOV)
* @bit 3 Load factor check (triggers if measurement is below stall speed)
* @bit 4 First principle check (airspeed change vs. throttle and pitch)
* @group Airspeed Validator
*/
PARAM_DEFINE_INT32(ASPD_DO_CHECKS, 7);
@@ -239,3 +240,19 @@ PARAM_DEFINE_FLOAT(ASPD_FS_T_START, -1.f);
* @group Airspeed Validator
*/
PARAM_DEFINE_FLOAT(ASPD_WERR_THR, 0.55f);
/**
* First principle airspeed check time window
*
* Window for comparing airspeed change to throttle and pitch change.
* Triggers when the airspeed change within this window is negative while throttle increases
* and the vehicle pitches down.
* Is meant to catch degrading airspeed blockages as can happen when flying through icing conditions.
* Relies on FW_THR_TRIM being set accurately.
*
* @unit s
* @min 0
* @decimal 1
* @group Airspeed Validator
*/
PARAM_DEFINE_FLOAT(ASPD_FP_T_WINDOW, 2.0f);
@@ -318,6 +318,22 @@ void EstimatorChecks::checkEstimatorStatus(const Context &context, Report &repor
_gps_was_fused = ekf_gps_fusion;
if (estimator_status.gps_check_fail_flags & (1 << estimator_status_s::GPS_CHECK_FAIL_SPOOFED)) {
if (!_gnss_spoofed) {
_gnss_spoofed = true;
if (reporter.mavlink_log_pub()) {
mavlink_log_critical(reporter.mavlink_log_pub(), "GNSS signal spoofed\t");
}
events::send(events::ID("check_estimator_gnss_warning_spoofing"), {events::Log::Alert, events::LogInternal::Info},
"GNSS signal spoofed");
}
} else {
_gnss_spoofed = false;
}
if (!context.isArmed() && ekf_gps_check_fail) {
NavModes required_groups_gps = required_groups;
events::Log log_level = events::Log::Error;
@@ -450,6 +466,18 @@ void EstimatorChecks::checkEstimatorStatus(const Context &context, Report &repor
events::ID("check_estimator_gps_vert_speed_drift_too_high"),
log_level, "GPS Vertical Speed Drift too high");
} else if (estimator_status.gps_check_fail_flags & (1 << estimator_status_s::GPS_CHECK_FAIL_SPOOFED)) {
message = "Preflight%s: GPS signal spoofed";
/* EVENT
* @description
* <profile name="dev">
* This check can be configured via <param>EKF2_GPS_CHECK</param> parameter.
* </profile>
*/
reporter.armingCheckFailure(required_groups_gps, health_component_t::gps,
events::ID("check_estimator_gps_spoofed"),
log_level, "GPS signal spoofed");
} else {
if (!ekf_gps_fusion) {
// Likely cause unknown
@@ -64,7 +64,6 @@ private:
void checkSensorBias(const Context &context, Report &reporter, NavModes required_groups);
void checkEstimatorStatusFlags(const Context &context, Report &reporter, const estimator_status_s &estimator_status,
const vehicle_local_position_s &lpos);
void checkGps(const Context &context, Report &reporter, const sensor_gps_s &vehicle_gps_position) const;
void lowPositionAccuracy(const Context &context, Report &reporter, const vehicle_local_position_s &lpos) const;
void setModeRequirementFlags(const Context &context, bool pre_flt_fail_innov_heading, bool pre_flt_fail_innov_vel_horiz,
@@ -102,6 +101,7 @@ private:
bool _position_reliant_on_optical_flow{false};
bool _gps_was_fused{false};
bool _gnss_spoofed{false};
bool _nav_failure_imminent_warned{false};
@@ -89,7 +89,8 @@ void Ekf::controlAirDataFusion(const imuSample &imu_delayed)
updateAirspeed(airspeed_sample, _aid_src_airspeed);
_innov_check_fail_status.flags.reject_airspeed = _aid_src_airspeed.innovation_rejected; // TODO: remove this redundant flag
_innov_check_fail_status.flags.reject_airspeed =
_aid_src_airspeed.innovation_rejected; // TODO: remove this redundant flag
const bool continuing_conditions_passing = _control_status.flags.in_air
&& _control_status.flags.fixed_wing
@@ -155,12 +156,12 @@ void Ekf::updateAirspeed(const airspeedSample &airspeed_sample, estimator_aid_so
&innov, &innov_var);
updateAidSourceStatus(aid_src,
airspeed_sample.time_us, // sample timestamp
airspeed_sample.true_airspeed, // observation
R, // observation variance
innov, // innovation
innov_var, // innovation variance
math::max(_params.tas_innov_gate, 1.f)); // innovation gate
airspeed_sample.time_us, // sample timestamp
airspeed_sample.true_airspeed, // observation
R, // observation variance
innov, // innovation
innov_var, // innovation variance
math::max(_params.tas_innov_gate, 1.f)); // innovation gate
}
void Ekf::fuseAirspeed(const airspeedSample &airspeed_sample, estimator_aid_source1d_s &aid_src)
@@ -193,6 +194,8 @@ void Ekf::fuseAirspeed(const airspeedSample &airspeed_sample, estimator_aid_sour
_fault_status.flags.bad_airspeed = true;
stopAirspeedFusion();
return;
}
@@ -85,12 +85,12 @@ void AuxGlobalPosition::update(Ekf &ekf, const estimator::imuSample &imu_delayed
const Vector2f pos_obs_var(pos_var, pos_var);
ekf.updateAidSourceStatus(aid_src,
sample.time_us, // sample timestamp
position, // observation
pos_obs_var, // observation variance
Vector2f(ekf.state().pos) - position, // innovation
Vector2f(ekf.getPositionVariance()) + pos_obs_var, // innovation variance
math::max(_param_ekf2_agp_gate.get(), 1.f)); // innovation gate
sample.time_us, // sample timestamp
position, // observation
pos_obs_var, // observation variance
Vector2f(ekf.state().pos) - position, // innovation
Vector2f(ekf.getPositionVariance()) + pos_obs_var, // innovation variance
math::max(_param_ekf2_agp_gate.get(), 1.f)); // innovation gate
}
const bool starting_conditions = PX4_ISFINITE(sample.latitude) && PX4_ISFINITE(sample.longitude)
@@ -96,8 +96,8 @@ private:
uint64_t _time_last_buffer_push{0};
enum class Ctrl : uint8_t {
HPOS = (1<<0),
VPOS = (1<<1)
HPOS = (1 << 0),
VPOS = (1 << 1)
};
enum class State {
@@ -33,20 +33,20 @@
#include "ekf.h"
void Ekf::controlAuxVelFusion()
void Ekf::controlAuxVelFusion(const imuSample &imu_sample)
{
if (_auxvel_buffer) {
auxVelSample sample;
if (_auxvel_buffer->pop_first_older_than(_time_delayed_us, &sample)) {
if (_auxvel_buffer->pop_first_older_than(imu_sample.time_us, &sample)) {
updateAidSourceStatus(_aid_src_aux_vel,
sample.time_us, // sample timestamp
sample.vel, // observation
sample.velVar, // observation variance
Vector2f(_state.vel.xy()) - sample.vel, // innovation
Vector2f(getStateVariance<State::vel>()) + sample.velVar, // innovation variance
math::max(_params.auxvel_gate, 1.f)); // innovation gate
sample.time_us, // sample timestamp
sample.vel, // observation
sample.velVar, // observation variance
Vector2f(_state.vel.xy()) - sample.vel, // innovation
Vector2f(getStateVariance<State::vel>()) + sample.velVar, // innovation variance
math::max(_params.auxvel_gate, 1.f)); // innovation gate
if (isHorizontalAidingActive()) {
fuseHorizontalVelocity(_aid_src_aux_vel);
@@ -38,7 +38,7 @@
#include "ekf.h"
void Ekf::controlBaroHeightFusion()
void Ekf::controlBaroHeightFusion(const imuSample &imu_sample)
{
static constexpr const char *HGT_SRC_NAME = "baro";
@@ -49,10 +49,10 @@ void Ekf::controlBaroHeightFusion()
baroSample baro_sample;
if (_baro_buffer && _baro_buffer->pop_first_older_than(_time_delayed_us, &baro_sample)) {
if (_baro_buffer && _baro_buffer->pop_first_older_than(imu_sample.time_us, &baro_sample)) {
#if defined(CONFIG_EKF2_BARO_COMPENSATION)
const float measurement = compensateBaroForDynamicPressure(baro_sample.hgt);
const float measurement = compensateBaroForDynamicPressure(imu_sample, baro_sample.hgt);
#else
const float measurement = baro_sample.hgt;
#endif
@@ -137,7 +137,7 @@ void Ekf::controlBaroHeightFusion()
// reset vertical velocity
resetVerticalVelocityToZero();
aid_src.time_last_fuse = _time_delayed_us;
aid_src.time_last_fuse = imu_sample.time_us;
} else if (is_fusion_failing) {
// Some other height source is still working
@@ -166,7 +166,7 @@ void Ekf::controlBaroHeightFusion()
bias_est.setBias(_state.pos(2) + _baro_lpf.getState());
}
aid_src.time_last_fuse = _time_delayed_us;
aid_src.time_last_fuse = imu_sample.time_us;
bias_est.setFusionActive();
_control_status.flags.baro_hgt = true;
}
@@ -195,7 +195,7 @@ void Ekf::stopBaroHgtFusion()
}
#if defined(CONFIG_EKF2_BARO_COMPENSATION)
float Ekf::compensateBaroForDynamicPressure(const float baro_alt_uncompensated) const
float Ekf::compensateBaroForDynamicPressure(const imuSample &imu_sample, const float baro_alt_uncompensated) const
{
if (_control_status.flags.wind && local_position_is_valid()) {
// calculate static pressure error = Pmeas - Ptruth
@@ -203,7 +203,8 @@ float Ekf::compensateBaroForDynamicPressure(const float baro_alt_uncompensated)
// negative X and Y directions. Used to correct baro data for positional errors
// Calculate airspeed in body frame
const Vector3f vel_imu_rel_body_ned = _R_to_earth * (_ang_rate_delayed_raw % _params.imu_pos_body);
const Vector3f angular_velocity = (imu_sample.delta_ang / imu_sample.delta_ang_dt) - _state.gyro_bias;
const Vector3f vel_imu_rel_body_ned = _R_to_earth * (angular_velocity % _params.imu_pos_body);
const Vector3f velocity_earth = _state.vel - vel_imu_rel_body_ned;
const Vector3f wind_velocity_earth(_state.wind_vel(0), _state.wind_vel(1), 0.0f);
@@ -169,12 +169,12 @@ void Ekf::fuseDrag(const dragSample &drag_sample)
}
updateAidSourceStatus(_aid_src_drag,
drag_sample.time_us, // sample timestamp
observation, // observation
observation_variance, // observation variance
innovation, // innovation
innovation_variance, // innovation variance
innov_gate); // innovation gate
drag_sample.time_us, // sample timestamp
observation, // observation
observation_variance, // observation variance
innovation, // innovation
innovation_variance, // innovation variance
innov_gate); // innovation gate
if (fused[0] && fused[1]) {
_aid_src_drag.fused = true;
@@ -38,7 +38,7 @@
#include "ekf.h"
void Ekf::controlExternalVisionFusion()
void Ekf::controlExternalVisionFusion(const imuSample &imu_sample)
{
_ev_pos_b_est.predict(_dt_ekf_avg);
_ev_hgt_b_est.predict(_dt_ekf_avg);
@@ -46,7 +46,7 @@ void Ekf::controlExternalVisionFusion()
// Check for new external vision data
extVisionSample ev_sample;
if (_ext_vision_buffer && _ext_vision_buffer->pop_first_older_than(_time_delayed_us, &ev_sample)) {
if (_ext_vision_buffer && _ext_vision_buffer->pop_first_older_than(imu_sample.time_us, &ev_sample)) {
bool ev_reset = (ev_sample.reset_counter != _ev_sample_prev.reset_counter);
@@ -55,15 +55,18 @@ void Ekf::controlExternalVisionFusion()
const bool starting_conditions_passing = quality_sufficient
&& ((ev_sample.time_us - _ev_sample_prev.time_us) < EV_MAX_INTERVAL)
&& ((_params.ev_quality_minimum <= 0) || (_ev_sample_prev.quality >= _params.ev_quality_minimum)) // previous quality sufficient
&& ((_params.ev_quality_minimum <= 0) || (_ext_vision_buffer->get_newest().quality >= _params.ev_quality_minimum)) // newest quality sufficient
&& ((_params.ev_quality_minimum <= 0)
|| (_ev_sample_prev.quality >= _params.ev_quality_minimum)) // previous quality sufficient
&& ((_params.ev_quality_minimum <= 0)
|| (_ext_vision_buffer->get_newest().quality >= _params.ev_quality_minimum)) // newest quality sufficient
&& isNewestSampleRecent(_time_last_ext_vision_buffer_push, EV_MAX_INTERVAL);
updateEvAttitudeErrorFilter(ev_sample, ev_reset);
controlEvYawFusion(ev_sample, starting_conditions_passing, ev_reset, quality_sufficient, _aid_src_ev_yaw);
controlEvVelFusion(ev_sample, starting_conditions_passing, ev_reset, quality_sufficient, _aid_src_ev_vel);
controlEvPosFusion(ev_sample, starting_conditions_passing, ev_reset, quality_sufficient, _aid_src_ev_pos);
controlEvHeightFusion(ev_sample, starting_conditions_passing, ev_reset, quality_sufficient, _aid_src_ev_hgt);
controlEvYawFusion(imu_sample, ev_sample, starting_conditions_passing, ev_reset, quality_sufficient, _aid_src_ev_yaw);
controlEvVelFusion(imu_sample, ev_sample, starting_conditions_passing, ev_reset, quality_sufficient, _aid_src_ev_vel);
controlEvPosFusion(imu_sample, ev_sample, starting_conditions_passing, ev_reset, quality_sufficient, _aid_src_ev_pos);
controlEvHeightFusion(imu_sample, ev_sample, starting_conditions_passing, ev_reset, quality_sufficient,
_aid_src_ev_hgt);
if (quality_sufficient) {
_ev_sample_prev = ev_sample;
@@ -81,7 +84,6 @@ void Ekf::controlExternalVisionFusion()
_ev_q_error_initialized = false;
_warning_events.flags.vision_data_stopped = true;
ECL_WARN("vision data stopped");
}
}
@@ -38,8 +38,9 @@
#include "ekf.h"
void Ekf::controlEvHeightFusion(const extVisionSample &ev_sample, const bool common_starting_conditions_passing,
const bool ev_reset, const bool quality_sufficient, estimator_aid_source1d_s &aid_src)
void Ekf::controlEvHeightFusion(const imuSample &imu_sample, const extVisionSample &ev_sample,
const bool common_starting_conditions_passing, const bool ev_reset, const bool quality_sufficient,
estimator_aid_source1d_s &aid_src)
{
static constexpr const char *AID_SRC_NAME = "EV height";
@@ -77,10 +78,12 @@ void Ekf::controlEvHeightFusion(const extVisionSample &ev_sample, const bool com
float measurement_var = math::max(pos_cov(2, 2), sq(_params.ev_pos_noise), sq(0.01f));
#if defined(CONFIG_EKF2_GNSS)
// increase minimum variance if GPS active
if (_control_status.flags.gps_hgt) {
measurement_var = math::max(measurement_var, sq(_params.gps_pos_noise));
}
#endif // CONFIG_EKF2_GNSS
const bool measurement_valid = PX4_ISFINITE(measurement) && PX4_ISFINITE(measurement_var);
@@ -150,7 +153,8 @@ void Ekf::controlEvHeightFusion(const extVisionSample &ev_sample, const bool com
if (ev_sample.vel.isAllFinite() && (_params.ev_ctrl & static_cast<int32_t>(EvCtrl::VEL))) {
// correct velocity for offset relative to IMU
const Vector3f vel_offset_body = _ang_rate_delayed_raw % pos_offset_body;
const Vector3f angular_velocity = (imu_sample.delta_ang / imu_sample.delta_ang_dt) - _state.gyro_bias;
const Vector3f vel_offset_body = angular_velocity % pos_offset_body;
const Vector3f vel_offset_earth = _R_to_earth * vel_offset_body;
switch (ev_sample.vel_frame) {
@@ -41,8 +41,9 @@
static constexpr const char *EV_AID_SRC_NAME = "EV position";
void Ekf::controlEvPosFusion(const extVisionSample &ev_sample, const bool common_starting_conditions_passing,
const bool ev_reset, const bool quality_sufficient, estimator_aid_source2d_s &aid_src)
void Ekf::controlEvPosFusion(const imuSample &imu_sample, const extVisionSample &ev_sample,
const bool common_starting_conditions_passing, const bool ev_reset, const bool quality_sufficient,
estimator_aid_source2d_s &aid_src)
{
const bool yaw_alignment_changed = (!_control_status_prev.flags.ev_yaw && _control_status.flags.ev_yaw)
|| (_control_status_prev.flags.yaw_align != _control_status.flags.yaw_align);
@@ -161,12 +162,12 @@ void Ekf::controlEvPosFusion(const extVisionSample &ev_sample, const bool common
const Vector2f pos_obs_var = measurement_var + _ev_pos_b_est.getBiasVar();
updateAidSourceStatus(aid_src,
ev_sample.time_us, // sample timestamp
position, // observation
pos_obs_var, // observation variance
Vector2f(_state.pos) - position, // innovation
Vector2f(getStateVariance<State::pos>()) + pos_obs_var, // innovation variance
math::max(_params.ev_pos_innov_gate, 1.f)); // innovation gate
ev_sample.time_us, // sample timestamp
position, // observation
pos_obs_var, // observation variance
Vector2f(_state.pos) - position, // innovation
Vector2f(getStateVariance<State::pos>()) + pos_obs_var, // innovation variance
math::max(_params.ev_pos_innov_gate, 1.f)); // innovation gate
// update the bias estimator before updating the main filter but after
// using its current state to compute the vertical position innovation
@@ -205,7 +206,8 @@ void Ekf::controlEvPosFusion(const extVisionSample &ev_sample, const bool common
}
}
void Ekf::startEvPosFusion(const Vector2f &measurement, const Vector2f &measurement_var, estimator_aid_source2d_s &aid_src)
void Ekf::startEvPosFusion(const Vector2f &measurement, const Vector2f &measurement_var,
estimator_aid_source2d_s &aid_src)
{
// activate fusion
// TODO: (_params.position_sensor_ref == PositionSensor::EV)
@@ -229,7 +231,8 @@ void Ekf::startEvPosFusion(const Vector2f &measurement, const Vector2f &measurem
_control_status.flags.ev_pos = true;
}
void Ekf::updateEvPosFusion(const Vector2f &measurement, const Vector2f &measurement_var, bool quality_sufficient, bool reset, estimator_aid_source2d_s &aid_src)
void Ekf::updateEvPosFusion(const Vector2f &measurement, const Vector2f &measurement_var, bool quality_sufficient,
bool reset, estimator_aid_source2d_s &aid_src)
{
if (reset) {
@@ -41,8 +41,9 @@
#include <ekf_derivation/generated/compute_ev_body_vel_hy.h>
#include <ekf_derivation/generated/compute_ev_body_vel_hz.h>
void Ekf::controlEvVelFusion(const extVisionSample &ev_sample, const bool common_starting_conditions_passing,
const bool ev_reset, const bool quality_sufficient, estimator_aid_source3d_s &aid_src)
void Ekf::controlEvVelFusion(const imuSample &imu_sample, const extVisionSample &ev_sample,
const bool common_starting_conditions_passing, const bool ev_reset, const bool quality_sufficient,
estimator_aid_source3d_s &aid_src)
{
static constexpr const char *AID_SRC_NAME = "EV velocity";
@@ -55,8 +56,9 @@ void Ekf::controlEvVelFusion(const extVisionSample &ev_sample, const bool common
&& ev_sample.vel.isAllFinite();
// correct velocity for offset relative to IMU
const Vector3f angular_velocity = imu_sample.delta_ang / imu_sample.delta_ang_dt - _state.gyro_bias;
const Vector3f pos_offset_body = _params.ev_pos_body - _params.imu_pos_body;
const Vector3f vel_offset_body = _ang_rate_delayed_raw % pos_offset_body;
const Vector3f vel_offset_body = angular_velocity % pos_offset_body;
const Vector3f vel_offset_earth = _R_to_earth * vel_offset_body;
// rotate measurement into correct earth frame if required
@@ -292,6 +294,11 @@ bool Ekf::fuseEvVelocity(estimator_aid_source3d_s &aid_src, const extVisionSampl
}
if (aid_src.fused) {
_time_last_hor_vel_fuse = _time_delayed_us;
_time_last_ver_vel_fuse = _time_delayed_us;
}
aid_src.timestamp_sample = current_aid_src.timestamp_sample;
return !aid_src.innovation_rejected;
@@ -38,8 +38,9 @@
#include "ekf.h"
void Ekf::controlEvYawFusion(const extVisionSample &ev_sample, const bool common_starting_conditions_passing,
const bool ev_reset, const bool quality_sufficient, estimator_aid_source1d_s &aid_src)
void Ekf::controlEvYawFusion(const imuSample &imu_sample, const extVisionSample &ev_sample,
const bool common_starting_conditions_passing, const bool ev_reset, const bool quality_sufficient,
estimator_aid_source1d_s &aid_src)
{
static constexpr const char *AID_SRC_NAME = "EV yaw";
@@ -53,12 +54,12 @@ void Ekf::controlEvYawFusion(const extVisionSample &ev_sample, const bool common
computeYawInnovVarAndH(obs_var, innov_var, H_YAW);
updateAidSourceStatus(aid_src,
ev_sample.time_us, // sample timestamp
obs, // observation
obs_var, // observation variance
innov, // innovation
innov_var, // innovation variance
math::max(_params.heading_innov_gate, 1.f)); // innovation gate
ev_sample.time_us, // sample timestamp
obs, // observation
obs_var, // observation variance
innov, // innovation
innov_var, // innovation variance
math::max(_params.heading_innov_gate, 1.f)); // innovation gate
if (ev_reset) {
_control_status.flags.ev_yaw_fault = false;
@@ -191,9 +192,11 @@ void Ekf::controlEvYawFusion(const extVisionSample &ev_sample, const bool common
void Ekf::stopEvYawFusion()
{
#if defined(CONFIG_EKF2_EXTERNAL_VISION)
if (_control_status.flags.ev_yaw) {
_control_status.flags.ev_yaw = false;
}
#endif // CONFIG_EKF2_EXTERNAL_VISION
}
@@ -68,17 +68,17 @@ void Ekf::controlFakePosFusion()
const float innov_gate = 3.f;
updateAidSourceStatus(aid_src,
_time_delayed_us,
position, // observation
obs_var, // observation variance
Vector2f(_state.pos) - position, // innovation
Vector2f(getStateVariance<State::pos>()) + obs_var, // innovation variance
innov_gate); // innovation gate
_time_delayed_us,
position, // observation
obs_var, // observation variance
Vector2f(_state.pos) - position, // innovation
Vector2f(getStateVariance<State::pos>()) + obs_var, // innovation variance
innov_gate); // innovation gate
const bool enable_conditions_passing = !isHorizontalAidingActive()
&& ((getTiltVariance() > sq(math::radians(3.f))) || _control_status.flags.vehicle_at_rest)
&& (!(_params.imu_ctrl & static_cast<int32_t>(ImuCtrl::GravityVector)) || _control_status.flags.vehicle_at_rest)
&& _horizontal_deadreckon_time_exceeded;
&& ((getTiltVariance() > sq(math::radians(3.f))) || _control_status.flags.vehicle_at_rest)
&& (!(_params.imu_ctrl & static_cast<int32_t>(ImuCtrl::GravityVector)) || _control_status.flags.vehicle_at_rest)
&& _horizontal_deadreckon_time_exceeded;
if (_control_status.flags.fake_pos) {
if (enable_conditions_passing) {
@@ -109,7 +109,6 @@ void Ekf::controlFakePosFusion()
if (_control_status.flags.tilt_align) {
// The fake position fusion is not started for initial alignement
_warning_events.flags.stopping_navigation = true;
ECL_WARN("stopping navigation");
}
}
@@ -48,15 +48,16 @@
#include <mathlib/mathlib.h>
// GPS pre-flight check bit locations
#define MASK_GPS_NSATS (1<<0)
#define MASK_GPS_PDOP (1<<1)
#define MASK_GPS_HACC (1<<2)
#define MASK_GPS_VACC (1<<3)
#define MASK_GPS_SACC (1<<4)
#define MASK_GPS_HDRIFT (1<<5)
#define MASK_GPS_VDRIFT (1<<6)
#define MASK_GPS_HSPD (1<<7)
#define MASK_GPS_VSPD (1<<8)
#define MASK_GPS_NSATS (1<<0)
#define MASK_GPS_PDOP (1<<1)
#define MASK_GPS_HACC (1<<2)
#define MASK_GPS_VACC (1<<3)
#define MASK_GPS_SACC (1<<4)
#define MASK_GPS_HDRIFT (1<<5)
#define MASK_GPS_VDRIFT (1<<6)
#define MASK_GPS_HSPD (1<<7)
#define MASK_GPS_VSPD (1<<8)
#define MASK_GPS_SPOOFED (1<<9)
void Ekf::collect_gps(const gnssSample &gps)
{
@@ -125,6 +126,7 @@ void Ekf::collect_gps(const gnssSample &gps)
_wmm_gps_time_last_set = _time_delayed_us;
}
}
#endif // CONFIG_EKF2_MAGNETOMETER
_earth_rate_NED = calcEarthRateNED((float)math::radians(gps.lat));
@@ -136,6 +138,8 @@ void Ekf::collect_gps(const gnssSample &gps)
bool Ekf::runGnssChecks(const gnssSample &gps)
{
_gps_check_fail_status.flags.spoofed = gps.spoofed;
// Check the fix type
_gps_check_fail_status.flags.fix = (gps.fix_type < 3);
@@ -154,7 +158,8 @@ bool Ekf::runGnssChecks(const gnssSample &gps)
// Calculate time lapsed since last update, limit to prevent numerical errors and calculate a lowpass filter coefficient
constexpr float filt_time_const = 10.0f;
const float dt = math::constrain(float(int64_t(gps.time_us) - int64_t(_gps_pos_prev.getProjectionReferenceTimestamp())) * 1e-6f, 0.001f, filt_time_const);
const float dt = math::constrain(float(int64_t(gps.time_us) - int64_t(_gps_pos_prev.getProjectionReferenceTimestamp()))
* 1e-6f, 0.001f, filt_time_const);
const float filter_coef = dt / filt_time_const;
// The following checks are only valid when the vehicle is at rest
@@ -240,7 +245,8 @@ bool Ekf::runGnssChecks(const gnssSample &gps)
(_gps_check_fail_status.flags.hdrift && (_params.gps_check_mask & MASK_GPS_HDRIFT)) ||
(_gps_check_fail_status.flags.vdrift && (_params.gps_check_mask & MASK_GPS_VDRIFT)) ||
(_gps_check_fail_status.flags.hspeed && (_params.gps_check_mask & MASK_GPS_HSPD)) ||
(_gps_check_fail_status.flags.vspeed && (_params.gps_check_mask & MASK_GPS_VSPD))
(_gps_check_fail_status.flags.vspeed && (_params.gps_check_mask & MASK_GPS_VSPD)) ||
(_gps_check_fail_status.flags.spoofed && (_params.gps_check_mask & MASK_GPS_SPOOFED))
) {
_last_gps_fail_us = _time_delayed_us;
return false;
@@ -78,7 +78,6 @@ void Ekf::controlGpsFusion(const imuSample &imu_delayed)
if (_control_status.flags.gps && isTimedOut(_last_gps_pass_us, _params.reset_timeout_max)) {
stopGpsFusion();
_warning_events.flags.gps_quality_poor = true;
ECL_WARN("GPS quality poor - stopping use");
}
}
@@ -87,12 +86,11 @@ void Ekf::controlGpsFusion(const imuSample &imu_delayed)
updateGnssPos(gnss_sample, _aid_src_gnss_pos);
}
updateGnssVel(gnss_sample, _aid_src_gnss_vel);
updateGnssVel(imu_delayed, gnss_sample, _aid_src_gnss_vel);
} else if (_control_status.flags.gps) {
if (!isNewestSampleRecent(_time_last_gps_buffer_push, _params.reset_timeout_max)) {
stopGpsFusion();
_warning_events.flags.gps_data_stopped = true;
ECL_WARN("GPS data stopped");
}
}
@@ -175,12 +173,13 @@ void Ekf::controlGpsFusion(const imuSample &imu_delayed)
}
}
void Ekf::updateGnssVel(const gnssSample &gnss_sample, estimator_aid_source3d_s &aid_src)
void Ekf::updateGnssVel(const imuSample &imu_sample, const gnssSample &gnss_sample, estimator_aid_source3d_s &aid_src)
{
// correct velocity for offset relative to IMU
const Vector3f pos_offset_body = _params.gps_pos_body - _params.imu_pos_body;
const Vector3f vel_offset_body = _ang_rate_delayed_raw % pos_offset_body;
const Vector3f angular_velocity = imu_sample.delta_ang / imu_sample.delta_ang_dt - _state.gyro_bias;
const Vector3f vel_offset_body = angular_velocity % pos_offset_body;
const Vector3f vel_offset_earth = _R_to_earth * vel_offset_body;
const Vector3f velocity = gnss_sample.vel - vel_offset_earth;
@@ -190,12 +189,12 @@ void Ekf::updateGnssVel(const gnssSample &gnss_sample, estimator_aid_source3d_s
const float innovation_gate = math::max(_params.gps_vel_innov_gate, 1.f);
updateAidSourceStatus(aid_src,
gnss_sample.time_us, // sample timestamp
velocity, // observation
vel_obs_var, // observation variance
_state.vel - velocity, // innovation
getVelocityVariance() + vel_obs_var, // innovation variance
innovation_gate); // innovation gate
gnss_sample.time_us, // sample timestamp
velocity, // observation
vel_obs_var, // observation variance
_state.vel - velocity, // innovation
getVelocityVariance() + vel_obs_var, // innovation variance
innovation_gate); // innovation gate
// vz special case if there is bad vertical acceleration data, then don't reject measurement if GNSS reports velocity accuracy is acceptable,
// but limit innovation to prevent spikes that could destabilise the filter
@@ -228,12 +227,12 @@ void Ekf::updateGnssPos(const gnssSample &gnss_sample, estimator_aid_source2d_s
const Vector2f pos_obs_var(pos_var, pos_var);
updateAidSourceStatus(aid_src,
gnss_sample.time_us, // sample timestamp
position, // observation
pos_obs_var, // observation variance
Vector2f(_state.pos) - position, // innovation
Vector2f(getStateVariance<State::pos>()) + pos_obs_var, // innovation variance
math::max(_params.gps_pos_innov_gate, 1.f)); // innovation gate
gnss_sample.time_us, // sample timestamp
position, // observation
pos_obs_var, // observation variance
Vector2f(_state.pos) - position, // innovation
Vector2f(getStateVariance<State::pos>()) + pos_obs_var, // innovation variance
math::max(_params.gps_pos_innov_gate, 1.f)); // innovation gate
}
void Ekf::controlGnssYawEstimator(estimator_aid_source3d_s &aid_src_vel)
@@ -276,14 +275,12 @@ bool Ekf::tryYawEmergencyReset()
// stop using the magnetometer in the main EKF otherwise its fusion could drag the yaw around
// and cause another navigation failure
_control_status.flags.mag_fault = true;
_warning_events.flags.emergency_yaw_reset_mag_stopped = true;
}
#if defined(CONFIG_EKF2_GNSS_YAW)
if (_control_status.flags.gps_yaw) {
_control_status.flags.gps_yaw_fault = true;
_warning_events.flags.emergency_yaw_reset_gps_yaw_stopped = true;
}
#endif // CONFIG_EKF2_GNSS_YAW
@@ -62,12 +62,12 @@ void Ekf::updateGpsYaw(const gnssSample &gps_sample)
&heading_pred, &heading_innov_var, &H);
updateAidSourceStatus(_aid_src_gnss_yaw,
gps_sample.time_us, // sample timestamp
measured_hdg, // observation
R_YAW, // observation variance
wrap_pi(heading_pred - measured_hdg), // innovation
heading_innov_var, // innovation variance
math::max(_params.heading_innov_gate, 1.f)); // innovation gate
gps_sample.time_us, // sample timestamp
measured_hdg, // observation
R_YAW, // observation variance
wrap_pi(heading_pred - measured_hdg), // innovation
heading_innov_var, // innovation variance
math::max(_params.heading_innov_gate, 1.f)); // innovation gate
}
void Ekf::fuseGpsYaw(float antenna_yaw_offset)
@@ -100,6 +100,7 @@ void Ekf::fuseGpsYaw(float antenna_yaw_offset)
// we reinitialise the covariance matrix and abort this fusion step
initialiseCovariance();
ECL_ERR("GPS yaw numerical error - covariance reset");
stopGpsYawFusion();
return;
}
@@ -54,7 +54,8 @@ void Ekf::controlGravityFusion(const imuSample &imu)
const float upper_accel_limit = CONSTANTS_ONE_G * 1.1f;
const float lower_accel_limit = CONSTANTS_ONE_G * 0.9f;
const bool accel_lpf_norm_good = (_accel_magnitude_filt > lower_accel_limit) && (_accel_magnitude_filt < upper_accel_limit);
const bool accel_lpf_norm_good = (_accel_magnitude_filt > lower_accel_limit)
&& (_accel_magnitude_filt < upper_accel_limit);
// fuse gravity observation if our overall acceleration isn't too big
_control_status.flags.gravity_vector = (_params.imu_ctrl & static_cast<int32_t>(ImuCtrl::GravityVector))
@@ -70,12 +71,12 @@ void Ekf::controlGravityFusion(const imuSample &imu)
// fill estimator aid source status
updateAidSourceStatus(_aid_src_gravity,
imu.time_us, // sample timestamp
measurement, // observation
Vector3f{measurement_var, measurement_var, measurement_var}, // observation variance
innovation, // innovation
innovation_variance, // innovation variance
0.25f); // innovation gate
imu.time_us, // sample timestamp
measurement, // observation
Vector3f{measurement_var, measurement_var, measurement_var}, // observation variance
innovation, // innovation
innovation_variance, // innovation variance
0.25f); // innovation gate
bool fused[3] {false, false, false};
@@ -90,14 +91,16 @@ void Ekf::controlGravityFusion(const imuSample &imu)
sym::ComputeGravityYInnovVarAndH(state_vector, P, measurement_var, &_aid_src_gravity.innovation_variance[index], &H);
// recalculate innovation using the updated state
_aid_src_gravity.innovation[index] = _state.quat_nominal.rotateVectorInverse(Vector3f(0.f, 0.f, -1.f))(index) - measurement(index);
_aid_src_gravity.innovation[index] = _state.quat_nominal.rotateVectorInverse(Vector3f(0.f, 0.f,
-1.f))(index) - measurement(index);
} else if (index == 2) {
// recalculate innovation variance because state covariances have changed due to previous fusion (linearise using the same initial state for all axes)
sym::ComputeGravityZInnovVarAndH(state_vector, P, measurement_var, &_aid_src_gravity.innovation_variance[index], &H);
// recalculate innovation using the updated state
_aid_src_gravity.innovation[index] = _state.quat_nominal.rotateVectorInverse(Vector3f(0.f, 0.f, -1.f))(index) - measurement(index);
_aid_src_gravity.innovation[index] = _state.quat_nominal.rotateVectorInverse(Vector3f(0.f, 0.f,
-1.f))(index) - measurement(index);
}
VectorState K = P * H / _aid_src_gravity.innovation_variance[index];
@@ -105,7 +108,8 @@ void Ekf::controlGravityFusion(const imuSample &imu)
const bool accel_clipping = imu.delta_vel_clipping[0] || imu.delta_vel_clipping[1] || imu.delta_vel_clipping[2];
if (_control_status.flags.gravity_vector && !_aid_src_gravity.innovation_rejected && !accel_clipping) {
fused[index] = measurementUpdate(K, H, _aid_src_gravity.observation_variance[index], _aid_src_gravity.innovation[index]);
fused[index] = measurementUpdate(K, H, _aid_src_gravity.observation_variance[index],
_aid_src_gravity.innovation[index]);
}
}
@@ -41,7 +41,7 @@
#include <ekf_derivation/generated/compute_mag_innov_innov_var_and_hx.h>
void Ekf::controlMagFusion()
void Ekf::controlMagFusion(const imuSample &imu_sample)
{
static constexpr const char *AID_SRC_NAME = "mag";
estimator_aid_source3d_s &aid_src = _aid_src_mag;
@@ -59,7 +59,7 @@ void Ekf::controlMagFusion()
magSample mag_sample;
if (_mag_buffer && _mag_buffer->pop_first_older_than(_time_delayed_us, &mag_sample)) {
if (_mag_buffer && _mag_buffer->pop_first_older_than(imu_sample.time_us, &mag_sample)) {
if (mag_sample.reset || (_mag_counter == 0)) {
// sensor or calibration has changed, reset low pass filter
@@ -109,12 +109,12 @@ void Ekf::controlMagFusion()
sym::ComputeMagInnovInnovVarAndHx(_state.vector(), P, mag_sample.mag, R_MAG, FLT_EPSILON, &mag_innov, &innov_var, &H);
updateAidSourceStatus(aid_src,
mag_sample.time_us, // sample timestamp
mag_sample.mag, // observation
Vector3f(R_MAG, R_MAG, R_MAG), // observation variance
mag_innov, // innovation
innov_var, // innovation variance
math::max(_params.mag_innov_gate, 1.f)); // innovation gate
mag_sample.time_us, // sample timestamp
mag_sample.mag, // observation
Vector3f(R_MAG, R_MAG, R_MAG), // observation variance
mag_innov, // innovation
innov_var, // innovation variance
math::max(_params.mag_innov_gate, 1.f)); // innovation gate
// Perform an innovation consistency check and report the result
_innov_check_fail_status.flags.reject_mag_x = (aid_src.test_ratio[0] > 1.f);
@@ -134,7 +134,8 @@ void Ekf::controlMagFusion()
&& checkMagField(mag_sample.mag)
&& (_mag_counter > 3) // wait until we have more than a few samples through the filter
&& (_control_status.flags.yaw_align == _control_status_prev.flags.yaw_align) // no yaw alignment change this frame
&& (_state_reset_status.reset_count.quat == _state_reset_count_prev.quat) // don't allow starting on same frame as yaw reset
&& (_state_reset_status.reset_count.quat ==
_state_reset_count_prev.quat) // don't allow starting on same frame as yaw reset
&& isNewestSampleRecent(_time_last_mag_buffer_push, MAG_MAX_INTERVAL);
checkMagHeadingConsistency(mag_sample);
@@ -145,22 +146,22 @@ void Ekf::controlMagFusion()
{
const bool mag_consistent_or_no_ne_aiding = _control_status.flags.mag_heading_consistent || !using_ne_aiding;
const bool common_conditions_passing = _control_status.flags.mag
&& ((_control_status.flags.yaw_align && mag_consistent_or_no_ne_aiding)
|| (!_control_status.flags.ev_yaw && !_control_status.flags.yaw_align))
&& !_control_status.flags.mag_fault
&& !_control_status.flags.mag_field_disturbed
&& !_control_status.flags.ev_yaw
&& !_control_status.flags.gps_yaw;
const bool mag_consistent_or_no_ne_aiding = _control_status.flags.mag_heading_consistent || !using_ne_aiding;
const bool common_conditions_passing = _control_status.flags.mag
&& ((_control_status.flags.yaw_align && mag_consistent_or_no_ne_aiding)
|| (!_control_status.flags.ev_yaw && !_control_status.flags.yaw_align))
&& !_control_status.flags.mag_fault
&& !_control_status.flags.mag_field_disturbed
&& !_control_status.flags.ev_yaw
&& !_control_status.flags.gps_yaw;
_control_status.flags.mag_3D = common_conditions_passing
&& (_params.mag_fusion_type == MagFuseType::AUTO)
&& _control_status.flags.mag_aligned_in_flight;
_control_status.flags.mag_3D = common_conditions_passing
&& (_params.mag_fusion_type == MagFuseType::AUTO)
&& _control_status.flags.mag_aligned_in_flight;
_control_status.flags.mag_hdg = common_conditions_passing
&& ((_params.mag_fusion_type == MagFuseType::HEADING)
|| (_params.mag_fusion_type == MagFuseType::AUTO && !_control_status.flags.mag_3D));
_control_status.flags.mag_hdg = common_conditions_passing
&& ((_params.mag_fusion_type == MagFuseType::HEADING)
|| (_params.mag_fusion_type == MagFuseType::AUTO && !_control_status.flags.mag_3D));
}
// TODO: allow clearing mag_fault if mag_3d is good?
@@ -184,7 +185,7 @@ void Ekf::controlMagFusion()
if (mag_sample.reset || checkHaglYawResetReq() || (wmm_updated && no_ne_aiding_or_pre_takeoff)) {
ECL_INFO("reset to %s", AID_SRC_NAME);
resetMagStates(_mag_lpf.getState(), _control_status.flags.mag_hdg || _control_status.flags.mag_3D);
aid_src.time_last_fuse = _time_delayed_us;
aid_src.time_last_fuse = imu_sample.time_us;
} else {
// The normal sequence is to fuse the magnetometer data first before fusing
@@ -212,7 +213,7 @@ void Ekf::controlMagFusion()
if (no_ne_aiding_or_pre_takeoff) {
ECL_WARN("%s fusion failing, resetting", AID_SRC_NAME);
resetMagStates(_mag_lpf.getState(), _control_status.flags.mag_hdg || _control_status.flags.mag_3D);
aid_src.time_last_fuse = _time_delayed_us;
aid_src.time_last_fuse = imu_sample.time_us;
} else {
ECL_WARN("stopping %s, fusion failing", AID_SRC_NAME);
@@ -241,7 +242,7 @@ void Ekf::controlMagFusion()
bool reset_heading = !_control_status.flags.yaw_align;
resetMagStates(_mag_lpf.getState(), reset_heading);
aid_src.time_last_fuse = _time_delayed_us;
aid_src.time_last_fuse = imu_sample.time_us;
if (reset_heading) {
_control_status.flags.yaw_align = true;
@@ -50,7 +50,8 @@
#include <mathlib/mathlib.h>
bool Ekf::fuseMag(const Vector3f &mag, const float R_MAG, VectorState &H, estimator_aid_source3d_s &aid_src, bool update_all_states, bool update_tilt)
bool Ekf::fuseMag(const Vector3f &mag, const float R_MAG, VectorState &H, estimator_aid_source3d_s &aid_src,
bool update_all_states, bool update_tilt)
{
// if any axis failed, abort the mag fusion
if (aid_src.innovation_rejected) {
@@ -72,7 +73,8 @@ bool Ekf::fuseMag(const Vector3f &mag, const float R_MAG, VectorState &H, estima
sym::ComputeMagYInnovVarAndH(state_vector, P, R_MAG, FLT_EPSILON, &aid_src.innovation_variance[index], &H);
// recalculate innovation using the updated state
aid_src.innovation[index] = _state.quat_nominal.rotateVectorInverse(_state.mag_I)(index) + _state.mag_B(index) - mag(index);
aid_src.innovation[index] = _state.quat_nominal.rotateVectorInverse(_state.mag_I)(index) + _state.mag_B(index) - mag(
index);
} else if (index == 2) {
// we do not fuse synthesized magnetomter measurements when doing 3D fusion
@@ -85,7 +87,8 @@ bool Ekf::fuseMag(const Vector3f &mag, const float R_MAG, VectorState &H, estima
sym::ComputeMagZInnovVarAndH(state_vector, P, R_MAG, FLT_EPSILON, &aid_src.innovation_variance[index], &H);
// recalculate innovation using the updated state
aid_src.innovation[index] = _state.quat_nominal.rotateVectorInverse(_state.mag_I)(index) + _state.mag_B(index) - mag(index);
aid_src.innovation[index] = _state.quat_nominal.rotateVectorInverse(_state.mag_I)(index) + _state.mag_B(index) - mag(
index);
}
if (aid_src.innovation_variance[index] < R_MAG) {
@@ -98,6 +101,8 @@ bool Ekf::fuseMag(const Vector3f &mag, const float R_MAG, VectorState &H, estima
resetMagCov();
stopMagFusion();
return false;
}
@@ -171,7 +176,8 @@ bool Ekf::fuseDeclination(float decl_sigma)
float decl_pred;
float innovation_variance;
sym::ComputeMagDeclinationPredInnovVarAndH(_state.vector(), P, R_DECL, FLT_EPSILON, &decl_pred, &innovation_variance, &H);
sym::ComputeMagDeclinationPredInnovVarAndH(_state.vector(), P, R_DECL, FLT_EPSILON, &decl_pred, &innovation_variance,
&H);
const float innovation = wrap_pi(decl_pred - decl_measurement);
@@ -38,45 +38,80 @@
#include "ekf.h"
#include <ekf_derivation/generated/compute_flow_xy_innov_var_and_hx.h>
void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed)
{
if (_flow_buffer) {
_flow_data_ready = _flow_buffer->pop_first_older_than(imu_delayed.time_us, &_flow_sample_delayed);
if (!_flow_buffer || (_params.flow_ctrl != 1)) {
stopFlowFusion();
return;
}
VectorState H;
// New optical flow data is available and is ready to be fused when the midpoint of the sample falls behind the fusion time horizon
if (_flow_data_ready) {
if (_flow_buffer->pop_first_older_than(imu_delayed.time_us, &_flow_sample_delayed)) {
// flow gyro has opposite sign convention
_ref_body_rate = -(imu_delayed.delta_ang / imu_delayed.delta_ang_dt - getGyroBias());
// ensure valid flow sample gyro rate before proceeding
if (!PX4_ISFINITE(_flow_sample_delayed.gyro_rate(0)) || !PX4_ISFINITE(_flow_sample_delayed.gyro_rate(1))) {
_flow_sample_delayed.gyro_rate = _ref_body_rate;
} else if (!PX4_ISFINITE(_flow_sample_delayed.gyro_rate(2))) {
// Some flow modules only provide X ind Y angular rates. If this is the case, complete the vector with our own Z gyro
_flow_sample_delayed.gyro_rate(2) = _ref_body_rate(2);
}
const flowSample &flow_sample = _flow_sample_delayed;
const int32_t min_quality = _control_status.flags.in_air
? _params.flow_qual_min
: _params.flow_qual_min_gnd;
const bool is_quality_good = (_flow_sample_delayed.quality >= min_quality);
const bool is_magnitude_good = _flow_sample_delayed.flow_rate.isAllFinite()
&& !_flow_sample_delayed.flow_rate.longerThan(_flow_max_rate);
const bool is_quality_good = (flow_sample.quality >= min_quality);
const bool is_magnitude_good = flow_sample.flow_rate.isAllFinite()
&& !flow_sample.flow_rate.longerThan(_flow_max_rate);
bool is_tilt_good = true;
#if defined(CONFIG_EKF2_RANGE_FINDER)
is_tilt_good = (_R_to_earth(2, 2) > _params.range_cos_max_tilt);
#endif // CONFIG_EKF2_RANGE_FINDER
if (is_quality_good
&& is_magnitude_good
&& is_tilt_good) {
// compensate for body motion to give a LOS rate
calcOptFlowBodyRateComp(imu_delayed);
_flow_rate_compensated = _flow_sample_delayed.flow_rate - _flow_sample_delayed.gyro_rate.xy();
calcOptFlowBodyRateComp(flow_sample);
} else {
// don't use this flow data and wait for the next data to arrive
_flow_data_ready = false;
_flow_rate_compensated.setZero();
}
}
// calculate optical LOS rates using optical flow rates that have had the body angular rate contribution removed
// correct for gyro bias errors in the data used to do the motion compensation
// Note the sign convention used: A positive LOS rate is a RH rotation of the scene about that axis.
const Vector3f flow_gyro_corrected = flow_sample.gyro_rate - _flow_gyro_bias;
const Vector2f flow_compensated = flow_sample.flow_rate - flow_gyro_corrected.xy();
// calculate the optical flow observation variance
const float R_LOS = calcOptFlowMeasVar(flow_sample);
Vector2f innov_var;
sym::ComputeFlowXyInnovVarAndHx(_state.vector(), P, R_LOS, FLT_EPSILON, &innov_var, &H);
// run the innovation consistency check and record result
updateAidSourceStatus(_aid_src_optical_flow,
flow_sample.time_us, // sample timestamp
flow_compensated, // observation
Vector2f{R_LOS, R_LOS}, // observation variance
predictFlow(flow_gyro_corrected) - flow_compensated, // innovation
innov_var, // innovation variance
math::max(_params.flow_innov_gate, 1.f)); // innovation gate
// logging
_flow_rate_compensated = flow_compensated;
// compute the velocities in body and local frames from corrected optical flow measurement for logging only
const float range = predictFlowRange();
_flow_vel_body(0) = -flow_compensated(1) * range;
_flow_vel_body(1) = flow_compensated(0) * range;
_flow_vel_ne = Vector2f(_R_to_earth * Vector3f(_flow_vel_body(0), _flow_vel_body(1), 0.f));
if (_flow_data_ready) {
updateOptFlow(_aid_src_optical_flow);
// Check if we are in-air and require optical flow to control position drift
bool is_flow_required = _control_status.flags.in_air
@@ -90,20 +125,30 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed)
&& is_within_max_sensor_dist;
const bool starting_conditions_passing = continuing_conditions_passing
&& is_quality_good
&& is_magnitude_good
&& is_tilt_good
&& isTimedOut(_aid_src_optical_flow.time_last_fuse, (uint64_t)2e6); // Prevent rapid switching
// If the height is relative to the ground, terrain height cannot be observed.
_hagl_sensor_status.flags.flow = _control_status.flags.opt_flow && !(_height_sensor_ref == HeightSensor::RANGE);
_control_status.flags.opt_flow_terrain = _control_status.flags.opt_flow && !(_height_sensor_ref == HeightSensor::RANGE);
if (_control_status.flags.opt_flow) {
if (continuing_conditions_passing) {
fuseOptFlow(_hagl_sensor_status.flags.flow);
if (is_quality_good && is_magnitude_good && is_tilt_good) {
fuseOptFlow(H, _control_status.flags.opt_flow_terrain);
}
// handle the case when we have optical flow, are reliant on it, but have not been using it for an extended period
if (isTimedOut(_aid_src_optical_flow.time_last_fuse, _params.no_aid_timeout_max)) {
if (is_flow_required) {
if (is_flow_required && is_quality_good) {
resetFlowFusion();
if (_control_status.flags.opt_flow_terrain && !isTerrainEstimateValid()) {
resetTerrainToFlow();
}
} else {
stopFlowFusion();
}
@@ -115,7 +160,34 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed)
} else {
if (starting_conditions_passing) {
startFlowFusion();
// If the height is relative to the ground, terrain height cannot be observed.
_control_status.flags.opt_flow_terrain = (_height_sensor_ref != HeightSensor::RANGE);
if (isHorizontalAidingActive()) {
if (fuseOptFlow(H, _control_status.flags.opt_flow_terrain)) {
ECL_INFO("starting optical flow");
_control_status.flags.opt_flow = true;
} else if (_control_status.flags.opt_flow_terrain && !_control_status.flags.rng_terrain) {
ECL_INFO("starting optical flow, resetting terrain");
resetTerrainToFlow();
_control_status.flags.opt_flow = true;
}
} else {
if (isTerrainEstimateValid() || (_height_sensor_ref == HeightSensor::RANGE)) {
ECL_INFO("starting optical flow, resetting");
resetFlowFusion();
_control_status.flags.opt_flow = true;
} else if (_control_status.flags.opt_flow_terrain) {
ECL_INFO("starting optical flow, resetting terrain");
resetTerrainToFlow();
_control_status.flags.opt_flow = true;
}
}
_control_status.flags.opt_flow_terrain = _control_status.flags.opt_flow && !(_height_sensor_ref == HeightSensor::RANGE);
}
}
@@ -124,41 +196,6 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed)
}
}
void Ekf::startFlowFusion()
{
ECL_INFO("starting optical flow fusion");
if (_height_sensor_ref != HeightSensor::RANGE) {
// If the height is relative to the ground, terrain height cannot be observed.
_hagl_sensor_status.flags.flow = true;
}
if (isHorizontalAidingActive()) {
if (!_aid_src_optical_flow.innovation_rejected) {
ECL_INFO("starting optical flow no reset");
fuseOptFlow(_hagl_sensor_status.flags.flow);
} else if (_hagl_sensor_status.flags.flow && !_hagl_sensor_status.flags.range_finder) {
resetTerrainToFlow();
} else {
ECL_INFO("optical flow fusion failed to start");
_control_status.flags.opt_flow = false;
_hagl_sensor_status.flags.flow = false;
}
} else {
if (isTerrainEstimateValid() || (_height_sensor_ref == HeightSensor::RANGE)) {
resetFlowFusion();
} else if (_hagl_sensor_status.flags.flow) {
resetTerrainToFlow();
}
}
_control_status.flags.opt_flow = true; // needs to be here because of isHorizontalAidingActive
}
void Ekf::resetFlowFusion()
{
ECL_INFO("reset velocity to flow");
@@ -171,11 +208,10 @@ void Ekf::resetFlowFusion()
resetHorizontalPositionTo(Vector2f(0.f, 0.f), 0.f);
}
updateOptFlow(_aid_src_optical_flow);
resetAidSourceStatusZeroInnovation(_aid_src_optical_flow);
_innov_check_fail_status.flags.reject_optflow_X = false;
_innov_check_fail_status.flags.reject_optflow_Y = false;
_aid_src_optical_flow.time_last_fuse = _time_delayed_us;
}
void Ekf::resetTerrainToFlow()
@@ -186,10 +222,10 @@ void Ekf::resetTerrainToFlow()
P.uncorrelateCovarianceSetVariance<State::terrain.dof>(State::terrain.idx, 100.f);
_terrain_vpos_reset_counter++;
resetAidSourceStatusZeroInnovation(_aid_src_optical_flow);
_innov_check_fail_status.flags.reject_optflow_X = false;
_innov_check_fail_status.flags.reject_optflow_Y = false;
_aid_src_optical_flow.time_last_fuse = _time_delayed_us;
}
void Ekf::stopFlowFusion()
@@ -197,29 +233,19 @@ void Ekf::stopFlowFusion()
if (_control_status.flags.opt_flow) {
ECL_INFO("stopping optical flow fusion");
_control_status.flags.opt_flow = false;
_hagl_sensor_status.flags.flow = false;
_control_status.flags.opt_flow_terrain = false;
_fault_status.flags.bad_optflow_X = false;
_fault_status.flags.bad_optflow_Y = false;
_innov_check_fail_status.flags.reject_optflow_X = false;
_innov_check_fail_status.flags.reject_optflow_Y = false;
}
}
void Ekf::calcOptFlowBodyRateComp(const imuSample &imu_delayed)
void Ekf::calcOptFlowBodyRateComp(const flowSample &flow_sample)
{
if (imu_delayed.delta_ang_dt > FLT_EPSILON) {
_ref_body_rate = -imu_delayed.delta_ang / imu_delayed.delta_ang_dt -
getGyroBias(); // flow gyro has opposite sign convention
} else {
_ref_body_rate.zero();
}
if (!PX4_ISFINITE(_flow_sample_delayed.gyro_rate(0)) || !PX4_ISFINITE(_flow_sample_delayed.gyro_rate(1))) {
_flow_sample_delayed.gyro_rate = _ref_body_rate;
} else if (!PX4_ISFINITE(_flow_sample_delayed.gyro_rate(2))) {
// Some flow modules only provide X ind Y angular rates. If this is the case, complete the vector with our own Z gyro
_flow_sample_delayed.gyro_rate(2) = _ref_body_rate(2);
}
// calculate the bias estimate using a combined LPF and spike filter
_flow_gyro_bias = _flow_gyro_bias * 0.99f + matrix::constrain(_flow_sample_delayed.gyro_rate - _ref_body_rate, -0.1f,
0.1f) * 0.01f;
// calculate the bias estimate using a combined LPF and spike filter
_flow_gyro_bias = 0.99f * _flow_gyro_bias
+ 0.01f * matrix::constrain(flow_sample.gyro_rate - _ref_body_rate, -0.1f, 0.1f);
}
@@ -42,95 +42,42 @@
#include <ekf_derivation/generated/compute_flow_xy_innov_var_and_hx.h>
#include <ekf_derivation/generated/compute_flow_y_innov_var_and_h.h>
void Ekf::updateOptFlow(estimator_aid_source2d_s &aid_src)
bool Ekf::fuseOptFlow(VectorState &H, const bool update_terrain)
{
const Vector2f vel_body = predictFlowVelBody();
const float range = predictFlowRange();
// calculate optical LOS rates using optical flow rates that have had the body angular rate contribution removed
// correct for gyro bias errors in the data used to do the motion compensation
// Note the sign convention used: A positive LOS rate is a RH rotation of the scene about that axis.
const Vector2f opt_flow_rate = _flow_rate_compensated;
// compute the velocities in body and local frames from corrected optical flow measurement for logging only
_flow_vel_body(0) = -opt_flow_rate(1) * range;
_flow_vel_body(1) = opt_flow_rate(0) * range;
_flow_vel_ne = Vector2f(_R_to_earth * Vector3f(_flow_vel_body(0), _flow_vel_body(1), 0.f));
Vector2f innovation{
(vel_body(1) / range) - opt_flow_rate(0),
(-vel_body(0) / range) - opt_flow_rate(1)
};
// calculate the optical flow observation variance
const float R_LOS = calcOptFlowMeasVar(_flow_sample_delayed);
Vector2f innov_var;
VectorState H;
sym::ComputeFlowXyInnovVarAndHx(_state.vector(), P, R_LOS, FLT_EPSILON, &innov_var, &H);
// run the innovation consistency check and record result
updateAidSourceStatus(aid_src,
_flow_sample_delayed.time_us, // sample timestamp
opt_flow_rate, // observation
Vector2f{R_LOS, R_LOS}, // observation variance
innovation, // innovation
innov_var, // innovation variance
math::max(_params.flow_innov_gate, 1.f)); // innovation gate
}
void Ekf::fuseOptFlow(const bool update_terrain)
{
const float R_LOS = _aid_src_optical_flow.observation_variance[0];
// calculate the height above the ground of the optical flow camera. Since earth frame is NED
// a positive offset in earth frame leads to a smaller height above the ground.
float range = predictFlowRange();
const auto state_vector = _state.vector();
Vector2f innov_var;
VectorState H;
sym::ComputeFlowXyInnovVarAndHx(state_vector, P, R_LOS, FLT_EPSILON, &innov_var, &H);
innov_var.copyTo(_aid_src_optical_flow.innovation_variance);
if ((innov_var(0) < R_LOS) || (innov_var(1) < R_LOS)) {
// we need to reinitialise the covariance matrix and abort this fusion step
ECL_ERR("Opt flow error - covariance reset");
initialiseCovariance();
return;
}
_innov_check_fail_status.flags.reject_optflow_X = (_aid_src_optical_flow.test_ratio[0] > 1.f);
_innov_check_fail_status.flags.reject_optflow_Y = (_aid_src_optical_flow.test_ratio[1] > 1.f);
// if either axis fails we abort the fusion
if (_aid_src_optical_flow.innovation_rejected) {
return;
return false;
}
bool fused[2] {false, false};
// fuse observation axes sequentially
for (uint8_t index = 0; index <= 1; index++) {
if (_aid_src_optical_flow.innovation_variance[index] < _aid_src_optical_flow.observation_variance[index]) {
// we need to reinitialise the covariance matrix and abort this fusion step
ECL_ERR("Opt flow error - covariance reset");
initialiseCovariance();
stopFlowFusion();
return false;
}
if (index == 0) {
// everything was already computed above
} else if (index == 1) {
// recalculate innovation variance because state covariances have changed due to previous fusion (linearise using the same initial state for all axes)
const float R_LOS = _aid_src_optical_flow.observation_variance[1];
sym::ComputeFlowYInnovVarAndH(state_vector, P, R_LOS, FLT_EPSILON, &_aid_src_optical_flow.innovation_variance[1], &H);
// recalculate the innovation using the updated state
const Vector2f vel_body = predictFlowVelBody();
range = predictFlowRange();
_aid_src_optical_flow.innovation[1] = (-vel_body(0) / range) - _aid_src_optical_flow.observation[1];
if (_aid_src_optical_flow.innovation_variance[1] < R_LOS) {
// we need to reinitialise the covariance matrix and abort this fusion step
ECL_ERR("Opt flow error - covariance reset");
initialiseCovariance();
return;
}
const Vector3f flow_gyro_corrected = _flow_sample_delayed.gyro_rate - _flow_gyro_bias;
_aid_src_optical_flow.innovation[1] = predictFlow(flow_gyro_corrected)(1) - _aid_src_optical_flow.observation[1];
}
VectorState Kfusion = P * H / _aid_src_optical_flow.innovation_variance[index];
@@ -139,7 +86,8 @@ void Ekf::fuseOptFlow(const bool update_terrain)
Kfusion(State::terrain.idx) = 0.f;
}
if (measurementUpdate(Kfusion, H, _aid_src_optical_flow.observation_variance[index], _aid_src_optical_flow.innovation[index])) {
if (measurementUpdate(Kfusion, H, _aid_src_optical_flow.observation_variance[index],
_aid_src_optical_flow.innovation[index])) {
fused[index] = true;
}
}
@@ -150,10 +98,14 @@ void Ekf::fuseOptFlow(const bool update_terrain)
if (fused[0] && fused[1]) {
_aid_src_optical_flow.time_last_fuse = _time_delayed_us;
_aid_src_optical_flow.fused = true;
return true;
}
return false;
}
float Ekf::predictFlowRange()
float Ekf::predictFlowRange() const
{
// calculate the sensor position relative to the IMU
const Vector3f pos_offset_body = _params.flow_pos_body - _params.imu_pos_body;
@@ -176,24 +128,28 @@ float Ekf::predictFlowRange()
return flow_range;
}
Vector2f Ekf::predictFlowVelBody()
Vector2f Ekf::predictFlow(const Vector3f &flow_gyro) const
{
// calculate the sensor position relative to the IMU
const Vector3f pos_offset_body = _params.flow_pos_body - _params.imu_pos_body;
// calculate the velocity of the sensor relative to the imu in body frame
// Note: _flow_sample_delayed.gyro_rate is the negative of the body angular velocity, thus use minus sign
const Vector3f vel_rel_imu_body = Vector3f(-(_flow_sample_delayed.gyro_rate - _flow_gyro_bias)) % pos_offset_body;
// Note: flow gyro is the negative of the body angular velocity, thus use minus sign
const Vector3f vel_rel_imu_body = -flow_gyro % pos_offset_body;
// calculate the velocity of the sensor in the earth frame
const Vector3f vel_rel_earth = _state.vel + _R_to_earth * vel_rel_imu_body;
// rotate into body frame
return _state.quat_nominal.rotateVectorInverse(vel_rel_earth).xy();
const Vector2f vel_body = _state.quat_nominal.rotateVectorInverse(vel_rel_earth).xy();
// calculate range from focal point to centre of image
const float range = predictFlowRange();
return Vector2f(vel_body(1) / range, -vel_body(0) / range);
}
// calculate the measurement variance for the optical flow sensor (rad/sec)^2
float Ekf::calcOptFlowMeasVar(const flowSample &flow_sample)
float Ekf::calcOptFlowMeasVar(const flowSample &flow_sample) const
{
// calculate the observation noise variance - scaling noise linearly across flow quality range
const float R_LOS_best = fmaxf(_params.flow_noise, 0.05f);
@@ -39,7 +39,7 @@
#include "ekf.h"
#include "ekf_derivation/generated/compute_hagl_innov_var.h"
void Ekf::controlRangeHaglFusion()
void Ekf::controlRangeHaglFusion(const imuSample &imu_sample)
{
static constexpr const char *HGT_SRC_NAME = "RNG";
@@ -47,7 +47,7 @@ void Ekf::controlRangeHaglFusion()
if (_range_buffer) {
// Get range data from buffer and check validity
rng_data_ready = _range_buffer->pop_first_older_than(_time_delayed_us, _range_sensor.getSampleAddress());
rng_data_ready = _range_buffer->pop_first_older_than(imu_sample.time_us, _range_sensor.getSampleAddress());
_range_sensor.setDataReadiness(rng_data_ready);
// update range sensor angle parameters in case they have changed
@@ -55,7 +55,7 @@ void Ekf::controlRangeHaglFusion()
_range_sensor.setCosMaxTilt(_params.range_cos_max_tilt);
_range_sensor.setQualityHysteresis(_params.range_valid_quality_s);
_range_sensor.runChecks(_time_delayed_us, _R_to_earth);
_range_sensor.runChecks(imu_sample.time_us, _R_to_earth);
if (_range_sensor.isDataHealthy()) {
// correct the range data for position offset relative to the IMU
@@ -72,7 +72,7 @@ void Ekf::controlRangeHaglFusion()
_rng_consistency_check.setGate(_params.range_kin_consistency_gate);
_rng_consistency_check.update(_range_sensor.getDistBottom(), math::max(var, 0.001f), _state.vel(2),
P(State::vel.idx + 2, State::vel.idx + 2), horizontal_motion, _time_delayed_us);
P(State::vel.idx + 2, State::vel.idx + 2), horizontal_motion, imu_sample.time_us);
}
} else {
@@ -101,22 +101,22 @@ void Ekf::controlRangeHaglFusion()
const bool measurement_valid = PX4_ISFINITE(aid_src.observation) && PX4_ISFINITE(aid_src.observation_variance);
const bool continuing_conditions_passing = ((_params.rng_ctrl == static_cast<int32_t>(RngCtrl::ENABLED))
|| (_params.rng_ctrl == static_cast<int32_t>(RngCtrl::CONDITIONAL)))
&& _control_status.flags.tilt_align
&& measurement_valid
&& _range_sensor.isDataHealthy()
&& _rng_consistency_check.isKinematicallyConsistent();
|| (_params.rng_ctrl == static_cast<int32_t>(RngCtrl::CONDITIONAL)))
&& _control_status.flags.tilt_align
&& measurement_valid
&& _range_sensor.isDataHealthy()
&& _rng_consistency_check.isKinematicallyConsistent();
const bool starting_conditions_passing = continuing_conditions_passing
&& isNewestSampleRecent(_time_last_range_buffer_push, 2 * estimator::sensor::RNG_MAX_INTERVAL)
&& _range_sensor.isRegularlySendingData();
const bool do_conditional_range_aid = (_hagl_sensor_status.flags.range_finder || _control_status.flags.rng_hgt)
const bool do_conditional_range_aid = (_control_status.flags.rng_terrain || _control_status.flags.rng_hgt)
&& (_params.rng_ctrl == static_cast<int32_t>(RngCtrl::CONDITIONAL))
&& isConditionalRangeAidSuitable();
const bool do_range_aid = (_hagl_sensor_status.flags.range_finder || _control_status.flags.rng_hgt)
const bool do_range_aid = (_control_status.flags.rng_terrain || _control_status.flags.rng_hgt)
&& (_params.rng_ctrl == static_cast<int32_t>(RngCtrl::ENABLED));
if (_control_status.flags.rng_hgt) {
@@ -135,7 +135,7 @@ void Ekf::controlRangeHaglFusion()
_control_status.flags.rng_hgt = true;
stopRngTerrFusion();
if (!_hagl_sensor_status.flags.flow && aid_src.innovation_rejected) {
if (!_control_status.flags.opt_flow_terrain && aid_src.innovation_rejected) {
resetTerrainToRng(aid_src);
}
@@ -151,7 +151,7 @@ void Ekf::controlRangeHaglFusion()
_control_status.flags.rng_hgt = true;
stopRngTerrFusion();
aid_src.time_last_fuse = _time_delayed_us;
aid_src.time_last_fuse = imu_sample.time_us;
}
} else {
@@ -159,17 +159,17 @@ void Ekf::controlRangeHaglFusion()
ECL_INFO("starting %s height fusion", HGT_SRC_NAME);
_control_status.flags.rng_hgt = true;
if (!_hagl_sensor_status.flags.flow && aid_src.innovation_rejected) {
if (!_control_status.flags.opt_flow_terrain && aid_src.innovation_rejected) {
resetTerrainToRng(aid_src);
}
}
}
}
if (_control_status.flags.rng_hgt || _hagl_sensor_status.flags.range_finder) {
if (_control_status.flags.rng_hgt || _control_status.flags.rng_terrain) {
if (continuing_conditions_passing) {
fuseHaglRng(aid_src, _control_status.flags.rng_hgt, _hagl_sensor_status.flags.range_finder);
fuseHaglRng(aid_src, _control_status.flags.rng_hgt, _control_status.flags.rng_terrain);
const bool is_fusion_failing = isTimedOut(aid_src.time_last_fuse, _params.hgt_fusion_timeout_max);
@@ -183,11 +183,11 @@ void Ekf::controlRangeHaglFusion()
// reset vertical velocity
resetVerticalVelocityToZero();
aid_src.time_last_fuse = _time_delayed_us;
aid_src.time_last_fuse = imu_sample.time_us;
} else if (is_fusion_failing) {
// Some other height source is still working
if (_hagl_sensor_status.flags.flow) {
if (_control_status.flags.opt_flow_terrain && isTerrainEstimateValid()) {
ECL_WARN("stopping %s fusion, fusion failing", HGT_SRC_NAME);
stopRngHgtFusion();
stopRngTerrFusion();
@@ -205,10 +205,10 @@ void Ekf::controlRangeHaglFusion()
} else {
if (starting_conditions_passing) {
if (_hagl_sensor_status.flags.flow) {
if (_control_status.flags.opt_flow_terrain) {
if (!aid_src.innovation_rejected) {
_hagl_sensor_status.flags.range_finder = true;
fuseHaglRng(aid_src, _control_status.flags.rng_hgt, _hagl_sensor_status.flags.range_finder);
_control_status.flags.rng_terrain = true;
fuseHaglRng(aid_src, _control_status.flags.rng_hgt, _control_status.flags.rng_terrain);
}
} else {
@@ -216,12 +216,12 @@ void Ekf::controlRangeHaglFusion()
resetTerrainToRng(aid_src);
}
_hagl_sensor_status.flags.range_finder = true;
_control_status.flags.rng_terrain = true;
}
}
}
} else if ((_control_status.flags.rng_hgt || _hagl_sensor_status.flags.range_finder)
} else if ((_control_status.flags.rng_hgt || _control_status.flags.rng_terrain)
&& !isNewestSampleRecent(_time_last_range_buffer_push, 2 * estimator::sensor::RNG_MAX_INTERVAL)) {
// No data anymore. Stop until it comes back.
ECL_WARN("stopping %s fusion, no data", HGT_SRC_NAME);
@@ -260,10 +260,10 @@ void Ekf::updateRangeHagl(estimator_aid_source1d_s &aid_src)
float Ekf::getRngVar() const
{
return fmaxf(
P(State::pos.idx + 2, State::pos.idx + 2)
+ sq(_params.range_noise)
+ sq(_params.range_noise_scaler * _range_sensor.getRange()),
0.f);
P(State::pos.idx + 2, State::pos.idx + 2)
+ sq(_params.range_noise)
+ sq(_params.range_noise_scaler * _range_sensor.getRange()),
0.f);
}
void Ekf::resetTerrainToRng(estimator_aid_source1d_s &aid_src)
@@ -317,5 +317,5 @@ void Ekf::stopRngHgtFusion()
void Ekf::stopRngTerrFusion()
{
_hagl_sensor_status.flags.range_finder = false;
_control_status.flags.rng_terrain = false;
}
@@ -56,7 +56,8 @@ struct rangeSample {
int8_t quality{}; ///< Signal quality in percent (0...100%), where 0 = invalid signal, 100 = perfect signal, and -1 = unknown signal quality.
};
static constexpr uint64_t RNG_MAX_INTERVAL = 200e3; ///< Maximum allowable time interval between range finder measurements (uSec)
static constexpr uint64_t RNG_MAX_INTERVAL =
200e3; ///< Maximum allowable time interval between range finder measurements (uSec)
class SensorRangeFinder : public Sensor
{
@@ -88,12 +88,12 @@ void Ekf::updateSideslip(estimator_aid_source1d_s &aid_src) const
sym::ComputeSideslipInnovAndInnovVar(_state.vector(), P, R, FLT_EPSILON, &innov, &innov_var);
updateAidSourceStatus(aid_src,
_time_delayed_us, // sample timestamp
observation, // observation
R, // observation variance
innov, // innovation
innov_var, // innovation variance
math::max(_params.beta_innov_gate, 1.f)); // innovation gate
_time_delayed_us, // sample timestamp
observation, // observation
R, // observation variance
innov, // innovation
innov_var, // innovation variance
math::max(_params.beta_innov_gate, 1.f)); // innovation gate
}
void Ekf::fuseSideslip(estimator_aid_source1d_s &sideslip)
@@ -44,7 +44,7 @@ void Ekf::controlZeroInnovationHeadingUpdate()
|| _control_status.flags.ev_yaw || _control_status.flags.gps_yaw;
// fuse zero innovation at a limited rate if the yaw variance is too large
if(!yaw_aiding
if (!yaw_aiding
&& isTimedOut(_time_last_heading_fuse, (uint64_t)200'000)) {
// Use an observation variance larger than usual but small enough
@@ -60,7 +60,8 @@ void Ekf::controlZeroInnovationHeadingUpdate()
computeYawInnovVarAndH(obs_var, aid_src_status.innovation_variance, H_YAW);
if (!_control_status.flags.tilt_align || (aid_src_status.innovation_variance - obs_var) > sq(_params.mag_heading_noise)) {
if (!_control_status.flags.tilt_align
|| (aid_src_status.innovation_variance - obs_var) > sq(_params.mag_heading_noise)) {
// The yaw variance is too large, fuse fake measurement
fuseYaw(aid_src_status, H_YAW);
}
+87 -81
View File
@@ -66,18 +66,26 @@ using math::Utilities::sq;
using math::Utilities::updateYawInRotMat;
// maximum sensor intervals in usec
static constexpr uint64_t BARO_MAX_INTERVAL = 200e3; ///< Maximum allowable time interval between pressure altitude measurements (uSec)
static constexpr uint64_t EV_MAX_INTERVAL = 200e3; ///< Maximum allowable time interval between external vision system measurements (uSec)
static constexpr uint64_t GNSS_MAX_INTERVAL = 500e3; ///< Maximum allowable time interval between GNSS measurements (uSec)
static constexpr uint64_t GNSS_YAW_MAX_INTERVAL = 1500e3; ///< Maximum allowable time interval between GNSS yaw measurements (uSec)
static constexpr uint64_t MAG_MAX_INTERVAL = 500e3; ///< Maximum allowable time interval between magnetic field measurements (uSec)
static constexpr uint64_t BARO_MAX_INTERVAL =
200e3; ///< Maximum allowable time interval between pressure altitude measurements (uSec)
static constexpr uint64_t EV_MAX_INTERVAL =
200e3; ///< Maximum allowable time interval between external vision system measurements (uSec)
static constexpr uint64_t GNSS_MAX_INTERVAL =
500e3; ///< Maximum allowable time interval between GNSS measurements (uSec)
static constexpr uint64_t GNSS_YAW_MAX_INTERVAL =
1500e3; ///< Maximum allowable time interval between GNSS yaw measurements (uSec)
static constexpr uint64_t MAG_MAX_INTERVAL =
500e3; ///< Maximum allowable time interval between magnetic field measurements (uSec)
// bad accelerometer detection and mitigation
static constexpr uint64_t BADACC_PROBATION = 10e6; ///< Period of time that accel data declared bad must continuously pass checks to be declared good again (uSec)
static constexpr float BADACC_BIAS_PNOISE = 4.9f; ///< The delta velocity process noise is set to this when accel data is declared bad (m/sec**2)
static constexpr uint64_t BADACC_PROBATION =
10e6; ///< Period of time that accel data declared bad must continuously pass checks to be declared good again (uSec)
static constexpr float BADACC_BIAS_PNOISE =
4.9f; ///< The delta velocity process noise is set to this when accel data is declared bad (m/sec**2)
// ground effect compensation
static constexpr uint64_t GNDEFFECT_TIMEOUT = 10e6; ///< Maximum period of time that ground effect protection will be active after it was last turned on (uSec)
static constexpr uint64_t GNDEFFECT_TIMEOUT =
10e6; ///< Maximum period of time that ground effect protection will be active after it was last turned on (uSec)
enum class PositionFrame : uint8_t {
LOCAL_FRAME_NED = 0,
@@ -93,8 +101,8 @@ enum class VelocityFrame : uint8_t {
#if defined(CONFIG_EKF2_MAGNETOMETER)
enum GeoDeclinationMask : uint8_t {
// Bit locations for mag_declination_source
USE_GEO_DECL = (1<<0), ///< set to true to use the declination from the geo library when the GPS position becomes available, set to false to always use the EKF2_MAG_DECL value
SAVE_GEO_DECL = (1<<1) ///< set to true to set the EKF2_MAG_DECL parameter to the value returned by the geo library
USE_GEO_DECL = (1 << 0), ///< set to true to use the declination from the geo library when the GPS position becomes available, set to false to always use the EKF2_MAG_DECL value
SAVE_GEO_DECL = (1 << 1) ///< set to true to set the EKF2_MAG_DECL parameter to the value returned by the geo library
};
enum MagFuseType : uint8_t {
@@ -128,16 +136,16 @@ enum class PositionSensor : uint8_t {
};
enum class ImuCtrl : uint8_t {
GyroBias = (1<<0),
AccelBias = (1<<1),
GravityVector = (1<<2),
GyroBias = (1 << 0),
AccelBias = (1 << 1),
GravityVector = (1 << 2),
};
enum class GnssCtrl : uint8_t {
HPOS = (1<<0),
VPOS = (1<<1),
VEL = (1<<2),
YAW = (1<<3)
HPOS = (1 << 0),
VPOS = (1 << 1),
VEL = (1 << 2),
YAW = (1 << 3)
};
enum class RngCtrl : uint8_t {
@@ -147,10 +155,10 @@ enum class RngCtrl : uint8_t {
};
enum class EvCtrl : uint8_t {
HPOS = (1<<0),
VPOS = (1<<1),
VEL = (1<<2),
YAW = (1<<3)
HPOS = (1 << 0),
VPOS = (1 << 1),
VEL = (1 << 2),
YAW = (1 << 3)
};
enum class MagCheckMask : uint8_t {
@@ -183,6 +191,7 @@ struct gnssSample {
float yaw{}; ///< yaw angle. NaN if not set (used for dual antenna GPS), (rad, [-PI, PI])
float yaw_acc{}; ///< 1-std yaw error (rad)
float yaw_offset{}; ///< Heading/Yaw offset for dual antenna GPS - refer to description for GPS_YAW_OFFSET
bool spoofed{}; ///< true if GNSS data is spoofed
};
struct magSample {
@@ -270,7 +279,7 @@ struct parameters {
float accel_bias_p_noise{1.0e-2f}; ///< process noise for IMU accelerometer bias prediction (m/sec**3)
#if defined(CONFIG_EKF2_WIND)
const float initial_wind_uncertainty{1.0f}; ///< 1-sigma initial uncertainty in wind velocity (m/sec)
const float initial_wind_uncertainty {1.0f}; ///< 1-sigma initial uncertainty in wind velocity (m/sec)
float wind_vel_nsd{1.0e-2f}; ///< process noise spectral density for wind velocity prediction (m/sec**2/sqrt(Hz))
const float wind_vel_nsd_scaler{0.5f}; ///< scaling of wind process noise with vertical velocity
#endif // CONFIG_EKF2_WIND
@@ -281,7 +290,7 @@ struct parameters {
float initial_tilt_err{0.1f}; ///< 1-sigma tilt error after initial alignment using gravity vector (rad)
#if defined(CONFIG_EKF2_BAROMETER)
int32_t baro_ctrl{1};
int32_t baro_ctrl {1};
float baro_delay_ms{0.0f}; ///< barometer height measurement delay relative to the IMU (mSec)
float baro_noise{2.0f}; ///< observation noise for barometric height fusion (m)
float baro_bias_nsd{0.13f}; ///< process noise for barometric height bias estimation (m/s/sqrt(Hz))
@@ -304,7 +313,7 @@ struct parameters {
#endif // CONFIG_EKF2_BAROMETER
#if defined(CONFIG_EKF2_GNSS)
int32_t gnss_ctrl{static_cast<int32_t>(GnssCtrl::HPOS) | static_cast<int32_t>(GnssCtrl::VEL)};
int32_t gnss_ctrl {static_cast<int32_t>(GnssCtrl::HPOS) | static_cast<int32_t>(GnssCtrl::VEL)};
float gps_delay_ms{110.0f}; ///< GPS measurement delay relative to the IMU (mSec)
Vector3f gps_pos_body{}; ///< xyz position of the GPS antenna in body frame (m)
@@ -345,7 +354,7 @@ struct parameters {
float mag_heading_noise{3.0e-1f}; ///< measurement noise used for simple heading fusion (rad)
#if defined(CONFIG_EKF2_MAGNETOMETER)
float mag_delay_ms{0.0f}; ///< magnetometer measurement delay relative to the IMU (mSec)
float mag_delay_ms {0.0f}; ///< magnetometer measurement delay relative to the IMU (mSec)
float mage_p_noise{1.0e-3f}; ///< process noise for earth magnetic field prediction (Gauss/sec)
float magb_p_noise{1.0e-4f}; ///< process noise for body magnetic field prediction (Gauss/sec)
@@ -382,13 +391,13 @@ struct parameters {
#endif // CONFIG_EKF2_SIDESLIP
#if defined(CONFIG_EKF2_TERRAIN)
float terrain_p_noise{5.0f}; ///< process noise for terrain offset (m/sec)
float terrain_p_noise {5.0f}; ///< process noise for terrain offset (m/sec)
float terrain_gradient{0.5f}; ///< gradient of terrain used to estimate process noise due to changing position (m/m)
const float terrain_timeout{10.f}; ///< maximum time for invalid bottom distance measurements before resetting terrain estimate (s)
#endif // CONFIG_EKF2_TERRAIN
#if defined(CONFIG_EKF2_TERRAIN) || defined(CONFIG_EKF2_OPTICAL_FLOW) || defined(CONFIG_EKF2_RANGE_FINDER)
float rng_gnd_clearance{0.1f}; ///< minimum valid value for range when on ground (m)
float rng_gnd_clearance {0.1f}; ///< minimum valid value for range when on ground (m)
#endif // CONFIG_EKF2_TERRAIN || CONFIG_EKF2_OPTICAL_FLOW || CONFIG_EKF2_RANGE_FINDER
#if defined(CONFIG_EKF2_RANGE_FINDER)
@@ -432,7 +441,7 @@ struct parameters {
#endif // CONFIG_EKF2_GRAVITY_FUSION
#if defined(CONFIG_EKF2_OPTICAL_FLOW)
int32_t flow_ctrl{0};
int32_t flow_ctrl {0};
float flow_delay_ms{5.0f}; ///< optical flow measurement delay relative to the IMU (mSec) - this is to the middle of the optical flow integration interval
// optical flow fusion
@@ -493,7 +502,8 @@ union fault_status_u {
bool bad_hdg : 1; ///< 3 - true if the fusion of the heading angle has encountered a numerical error
bool bad_mag_decl : 1; ///< 4 - true if the fusion of the magnetic declination has encountered a numerical error
bool bad_airspeed : 1; ///< 5 - true if fusion of the airspeed has encountered a numerical error
bool bad_sideslip : 1; ///< 6 - true if fusion of the synthetic sideslip constraint has encountered a numerical error
bool bad_sideslip :
1; ///< 6 - true if fusion of the synthetic sideslip constraint has encountered a numerical error
bool bad_optflow_X : 1; ///< 7 - true if fusion of the optical flow X axis has encountered a numerical error
bool bad_optflow_Y : 1; ///< 8 - true if fusion of the optical flow Y axis has encountered a numerical error
bool bad_acc_bias : 1; ///< 9 - true if bad delta velocity bias estimates have been detected
@@ -536,6 +546,7 @@ union gps_check_fail_status_u {
uint16_t vdrift : 1; ///< 7 - true if vertical drift is excessive (can only be used when stationary on ground)
uint16_t hspeed : 1; ///< 8 - true if horizontal speed is excessive (can only be used when stationary on ground)
uint16_t vspeed : 1; ///< 9 - true if vertical speed error is excessive
uint16_t spoofed: 1; ///< 10 - true if the GNSS data is spoofed
} flags;
uint16_t value;
};
@@ -553,7 +564,8 @@ union filter_control_status_u {
uint64_t in_air : 1; ///< 7 - true when the vehicle is airborne
uint64_t wind : 1; ///< 8 - true when wind velocity is being estimated
uint64_t baro_hgt : 1; ///< 9 - true when baro height is being fused as a primary height reference
uint64_t rng_hgt : 1; ///< 10 - true when range finder height is being fused as a primary height reference
uint64_t rng_hgt :
1; ///< 10 - true when range finder height is being fused as a primary height reference
uint64_t gps_hgt : 1; ///< 11 - true when GPS height is being fused as a primary height reference
uint64_t ev_pos : 1; ///< 12 - true when local position data fusion from external vision is intended
uint64_t ev_yaw : 1; ///< 13 - true when yaw data from external vision measurements fusion is intended
@@ -561,27 +573,41 @@ union filter_control_status_u {
uint64_t fuse_beta : 1; ///< 15 - true when synthetic sideslip measurements are being fused
uint64_t mag_field_disturbed : 1; ///< 16 - true when the mag field does not match the expected strength
uint64_t fixed_wing : 1; ///< 17 - true when the vehicle is operating as a fixed wing vehicle
uint64_t mag_fault : 1; ///< 18 - true when the magnetometer has been declared faulty and is no longer being used
uint64_t mag_fault :
1; ///< 18 - true when the magnetometer has been declared faulty and is no longer being used
uint64_t fuse_aspd : 1; ///< 19 - true when airspeed measurements are being fused
uint64_t gnd_effect : 1; ///< 20 - true when protection from ground effect induced static pressure rise is active
uint64_t rng_stuck : 1; ///< 21 - true when rng data wasn't ready for more than 10s and new rng values haven't changed enough
uint64_t gps_yaw : 1; ///< 22 - true when yaw (not ground course) data fusion from a GPS receiver is intended
uint64_t gnd_effect :
1; ///< 20 - true when protection from ground effect induced static pressure rise is active
uint64_t rng_stuck :
1; ///< 21 - true when rng data wasn't ready for more than 10s and new rng values haven't changed enough
uint64_t gps_yaw :
1; ///< 22 - true when yaw (not ground course) data fusion from a GPS receiver is intended
uint64_t mag_aligned_in_flight : 1; ///< 23 - true when the in-flight mag field alignment has been completed
uint64_t ev_vel : 1; ///< 24 - true when local frame velocity data fusion from external vision measurements is intended
uint64_t synthetic_mag_z : 1; ///< 25 - true when we are using a synthesized measurement for the magnetometer Z component
uint64_t ev_vel :
1; ///< 24 - true when local frame velocity data fusion from external vision measurements is intended
uint64_t synthetic_mag_z :
1; ///< 25 - true when we are using a synthesized measurement for the magnetometer Z component
uint64_t vehicle_at_rest : 1; ///< 26 - true when the vehicle is at rest
uint64_t gps_yaw_fault : 1; ///< 27 - true when the GNSS heading has been declared faulty and is no longer being used
uint64_t rng_fault : 1; ///< 28 - true when the range finder has been declared faulty and is no longer being used
uint64_t inertial_dead_reckoning : 1; ///< 29 - true if we are no longer fusing measurements that constrain horizontal velocity drift
uint64_t gps_yaw_fault :
1; ///< 27 - true when the GNSS heading has been declared faulty and is no longer being used
uint64_t rng_fault :
1; ///< 28 - true when the range finder has been declared faulty and is no longer being used
uint64_t inertial_dead_reckoning :
1; ///< 29 - true if we are no longer fusing measurements that constrain horizontal velocity drift
uint64_t wind_dead_reckoning : 1; ///< 30 - true if we are navigationg reliant on wind relative measurements
uint64_t rng_kin_consistent : 1; ///< 31 - true when the range finder kinematic consistency check is passing
uint64_t fake_pos : 1; ///< 32 - true when fake position measurements are being fused
uint64_t fake_hgt : 1; ///< 33 - true when fake height measurements are being fused
uint64_t gravity_vector : 1; ///< 34 - true when gravity vector measurements are being fused
uint64_t mag : 1; ///< 35 - true if 3-axis magnetometer measurement fusion (mag states only) is intended
uint64_t ev_yaw_fault : 1; ///< 36 - true when the EV heading has been declared faulty and is no longer being used
uint64_t mag_heading_consistent : 1; ///< 37 - true when the heading obtained from mag data is declared consistent with the filter
uint64_t aux_gpos : 1;
uint64_t mag :
1; ///< 35 - true if 3-axis magnetometer measurement fusion (mag states only) is intended
uint64_t ev_yaw_fault :
1; ///< 36 - true when the EV heading has been declared faulty and is no longer being used
uint64_t mag_heading_consistent :
1; ///< 37 - true when the heading obtained from mag data is declared consistent with the filter
uint64_t aux_gpos : 1; ///< 38 - true if auxiliary global position measurement fusion is intended
uint64_t rng_terrain : 1; ///< 39 - true if we are fusing range finder data for terrain
uint64_t opt_flow_terrain : 1; ///< 40 - true if we are fusing flow data for terrain
} flags;
uint64_t value;
@@ -597,25 +623,18 @@ union ekf_solution_status_u {
uint16_t pos_horiz_abs : 1; ///< 4 - True if the horizontal position (absolute) estimate is good
uint16_t pos_vert_abs : 1; ///< 5 - True if the vertical position (absolute) estimate is good
uint16_t pos_vert_agl : 1; ///< 6 - True if the vertical position (above ground) estimate is good
uint16_t const_pos_mode : 1; ///< 7 - True if the EKF is in a constant position mode and is not using external measurements (eg GPS or optical flow)
uint16_t pred_pos_horiz_rel : 1; ///< 8 - True if the EKF has sufficient data to enter a mode that will provide a (relative) position estimate
uint16_t pred_pos_horiz_abs : 1; ///< 9 - True if the EKF has sufficient data to enter a mode that will provide a (absolute) position estimate
uint16_t const_pos_mode :
1; ///< 7 - True if the EKF is in a constant position mode and is not using external measurements (eg GPS or optical flow)
uint16_t pred_pos_horiz_rel :
1; ///< 8 - True if the EKF has sufficient data to enter a mode that will provide a (relative) position estimate
uint16_t pred_pos_horiz_abs :
1; ///< 9 - True if the EKF has sufficient data to enter a mode that will provide a (absolute) position estimate
uint16_t gps_glitch : 1; ///< 10 - True if the EKF has detected a GPS glitch
uint16_t accel_error : 1; ///< 11 - True if the EKF has detected bad accelerometer data
} flags;
uint16_t value;
};
#if defined(CONFIG_EKF2_TERRAIN)
union terrain_fusion_status_u {
struct {
bool range_finder : 1; ///< 0 - true if we are fusing range finder data
bool flow : 1; ///< 1 - true if we are fusing flow data
} flags;
uint8_t value;
};
#endif // CONFIG_EKF2_TERRAIN
// define structure used to communicate information events
union information_event_status_u {
struct {
@@ -627,35 +646,22 @@ union information_event_status_u {
bool reset_pos_to_last_known : 1; ///< 5 - true when the position states are reset to the last known position
bool reset_pos_to_gps : 1; ///< 6 - true when the position states are reset to the gps measurement
bool reset_pos_to_vision : 1; ///< 7 - true when the position states are reset to the vision system measurement
bool starting_gps_fusion : 1; ///< 8 - true when the filter starts using gps measurements to correct the state estimates
bool starting_vision_pos_fusion : 1; ///< 9 - true when the filter starts using vision system position measurements to correct the state estimates
bool starting_vision_vel_fusion : 1; ///< 10 - true when the filter starts using vision system velocity measurements to correct the state estimates
bool starting_vision_yaw_fusion : 1; ///< 11 - true when the filter starts using vision system yaw measurements to correct the state estimates
bool yaw_aligned_to_imu_gps : 1; ///< 12 - true when the filter resets the yaw to an estimate derived from IMU and GPS data
bool starting_gps_fusion :
1; ///< 8 - true when the filter starts using gps measurements to correct the state estimates
bool starting_vision_pos_fusion :
1; ///< 9 - true when the filter starts using vision system position measurements to correct the state estimates
bool starting_vision_vel_fusion :
1; ///< 10 - true when the filter starts using vision system velocity measurements to correct the state estimates
bool starting_vision_yaw_fusion :
1; ///< 11 - true when the filter starts using vision system yaw measurements to correct the state estimates
bool yaw_aligned_to_imu_gps :
1; ///< 12 - true when the filter resets the yaw to an estimate derived from IMU and GPS data
bool reset_hgt_to_baro : 1; ///< 13 - true when the vertical position state is reset to the baro measurement
bool reset_hgt_to_gps : 1; ///< 14 - true when the vertical position state is reset to the gps measurement
bool reset_hgt_to_rng : 1; ///< 15 - true when the vertical position state is reset to the rng measurement
bool reset_hgt_to_ev : 1; ///< 16 - true when the vertical position state is reset to the ev measurement
bool reset_pos_to_ext_obs : 1; ///< 17 - true when horizontal position was reset to an external observation while deadreckoning
} flags;
uint32_t value;
};
// define structure used to communicate information events
union warning_event_status_u {
struct {
bool gps_quality_poor : 1; ///< 0 - true when the gps is failing quality checks
bool gps_fusion_timout : 1; ///< 1 - true when the gps data has not been used to correct the state estimates for a significant time period
bool gps_data_stopped : 1; ///< 2 - true when the gps data has stopped for a significant time period
bool gps_data_stopped_using_alternate : 1; ///< 3 - true when the gps data has stopped for a significant time period but the filter is able to use other sources of data to maintain navigation
bool height_sensor_timeout : 1; ///< 4 - true when the height sensor has not been used to correct the state estimates for a significant time period
bool stopping_navigation : 1; ///< 5 - true when the filter has insufficient data to estimate velocity and position and is falling back to an attitude, height and height rate mode of operation
bool invalid_accel_bias_cov_reset : 1; ///< 6 - true when the filter has detected bad acceerometer bias state estimates and has reset the corresponding covariance matrix elements
bool bad_yaw_using_gps_course : 1; ///< 7 - true when the filter has detected an invalid yaw estimate and has reset the yaw angle to the GPS ground course
bool stopping_mag_use : 1; ///< 8 - true when the filter has detected bad magnetometer data and is stopping further use of the magnetometer data
bool vision_data_stopped : 1; ///< 9 - true when the vision system data has stopped for a significant time period
bool emergency_yaw_reset_mag_stopped : 1; ///< 10 - true when the filter has detected bad magnetometer data, has reset the yaw to anothter source of data and has stopped further use of the magnetometer data
bool emergency_yaw_reset_gps_yaw_stopped: 1; ///< 11 - true when the filter has detected bad GNSS yaw data, has reset the yaw to anothter source of data and has stopped further use of the GNSS yaw data
bool reset_pos_to_ext_obs :
1; ///< 17 - true when horizontal position was reset to an external observation while deadreckoning
} flags;
uint32_t value;
};
+3 -3
View File
@@ -102,7 +102,7 @@ void Ekf::controlFusionModes(const imuSample &imu_delayed)
#if defined(CONFIG_EKF2_MAGNETOMETER)
// control use of observations for aiding
controlMagFusion();
controlMagFusion(imu_delayed);
#endif // CONFIG_EKF2_MAGNETOMETER
#if defined(CONFIG_EKF2_OPTICAL_FLOW)
@@ -137,12 +137,12 @@ void Ekf::controlFusionModes(const imuSample &imu_delayed)
#if defined(CONFIG_EKF2_EXTERNAL_VISION)
// Additional data odometry data from an external estimator can be fused.
controlExternalVisionFusion();
controlExternalVisionFusion(imu_delayed);
#endif // CONFIG_EKF2_EXTERNAL_VISION
#if defined(CONFIG_EKF2_AUXVEL)
// Additional horizontal velocity data from an auxiliary sensor can be fused
controlAuxVelFusion();
controlAuxVelFusion(imu_delayed);
#endif // CONFIG_EKF2_AUXVEL
//
#if defined(CONFIG_EKF2_TERRAIN)
+22 -8
View File
@@ -76,14 +76,17 @@ void Ekf::initialiseCovariance()
if (_control_status.flags.gps_hgt) {
z_pos_var = sq(fmaxf(1.5f * _params.gps_pos_noise, 0.01f));
}
#else
const float xy_pos_var = sq(fmaxf(_params.pos_noaid_noise, 0.01f));
#endif
#if defined(CONFIG_EKF2_RANGE_FINDER)
if (_control_status.flags.rng_hgt) {
z_pos_var = sq(fmaxf(_params.range_noise, 0.01f));
}
#endif // CONFIG_EKF2_RANGE_FINDER
P.uncorrelateCovarianceSetVariance<State::pos.dof>(State::pos.idx, Vector3f(xy_pos_var, xy_pos_var, z_pos_var));
@@ -131,14 +134,14 @@ void Ekf::predictCovariance(const imuSample &imu_delayed)
// calculate variances and upper diagonal covariances for quaternion, velocity, position and gyro bias states
P = sym::PredictCovariance(_state.vector(), P,
imu_delayed.delta_vel / math::max(imu_delayed.delta_vel_dt, FLT_EPSILON), accel_var,
imu_delayed.delta_ang / math::max(imu_delayed.delta_ang_dt, FLT_EPSILON), gyro_var,
imu_delayed.delta_vel / imu_delayed.delta_vel_dt, accel_var,
imu_delayed.delta_ang / imu_delayed.delta_ang_dt, gyro_var,
dt);
// Construct the process noise variance diagonal for those states with a stationary process model
// These are kinematic states and their error growth is controlled separately by the IMU noise variances
// gyro bias: add process noise unless state is inhibited
// gyro bias: add process noise
{
const float gyro_bias_sig = dt * math::constrain(_params.gyro_bias_p_noise, 0.f, 1.f);
const float gyro_bias_process_noise = sq(gyro_bias_sig);
@@ -146,13 +149,13 @@ void Ekf::predictCovariance(const imuSample &imu_delayed)
for (unsigned index = 0; index < State::gyro_bias.dof; index++) {
const unsigned i = State::gyro_bias.idx + index;
if (!_gyro_bias_inhibit[index]) {
if (P(i, i) < gyro_var) {
P(i, i) += gyro_bias_process_noise;
}
}
}
// accel bias: add process noise unless state is inhibited
// accel bias: add process noise
{
const float accel_bias_sig = dt * math::constrain(_params.accel_bias_p_noise, 0.f, 1.f);
const float accel_bias_process_noise = sq(accel_bias_sig);
@@ -160,7 +163,7 @@ void Ekf::predictCovariance(const imuSample &imu_delayed)
for (unsigned index = 0; index < State::accel_bias.dof; index++) {
const unsigned i = State::accel_bias.idx + index;
if (!_accel_bias_inhibit[index]) {
if (P(i, i) < accel_var(index)) {
P(i, i) += accel_bias_process_noise;
}
}
@@ -191,13 +194,16 @@ void Ekf::predictCovariance(const imuSample &imu_delayed)
P(i, i) += mag_B_process_noise;
}
}
#endif // CONFIG_EKF2_MAGNETOMETER
#if defined(CONFIG_EKF2_WIND)
if (_control_status.flags.wind) {
// wind vel: add process noise
float wind_vel_nsd_scaled = math::constrain(_params.wind_vel_nsd, 0.f, 1.f) * (1.f + _params.wind_vel_nsd_scaler * fabsf(_height_rate_lpf));
float wind_vel_nsd_scaled = math::constrain(_params.wind_vel_nsd, 0.f,
1.f) * (1.f + _params.wind_vel_nsd_scaler * fabsf(_height_rate_lpf));
float wind_vel_process_noise = sq(wind_vel_nsd_scaled) * dt;
for (unsigned index = 0; index < State::wind_vel.dof; index++) {
@@ -205,18 +211,22 @@ void Ekf::predictCovariance(const imuSample &imu_delayed)
P(i, i) += wind_vel_process_noise;
}
}
#endif // CONFIG_EKF2_WIND
#if defined(CONFIG_EKF2_TERRAIN)
if (_height_sensor_ref != HeightSensor::RANGE) {
// predict the state variance growth where the state is the vertical position of the terrain underneath the vehicle
// process noise due to errors in vehicle height estimate
float terrain_process_noise = sq(imu_delayed.delta_vel_dt * _params.terrain_p_noise);
// process noise due to terrain gradient
terrain_process_noise += sq(imu_delayed.delta_vel_dt * _params.terrain_gradient) * (sq(_state.vel(0)) + sq(_state.vel(1)));
terrain_process_noise += sq(imu_delayed.delta_vel_dt * _params.terrain_gradient) * (sq(_state.vel(0)) + sq(_state.vel(
1)));
P(State::terrain.idx, State::terrain.idx) += terrain_process_noise;
}
#endif // CONFIG_EKF2_TERRAIN
// covariance matrix is symmetrical, so copy upper half to lower half
@@ -244,16 +254,20 @@ void Ekf::constrainStateVariances()
constrainStateVarLimitRatio(State::accel_bias, kAccelBiasVarianceMin, 1.f);
#if defined(CONFIG_EKF2_MAGNETOMETER)
if (_control_status.flags.mag) {
constrainStateVarLimitRatio(State::mag_I, kMagVarianceMin, 1.f);
constrainStateVarLimitRatio(State::mag_B, kMagVarianceMin, 1.f);
}
#endif // CONFIG_EKF2_MAGNETOMETER
#if defined(CONFIG_EKF2_WIND)
if (_control_status.flags.wind) {
constrainStateVarLimitRatio(State::wind_vel, 1e-6f, 1e6f);
}
#endif // CONFIG_EKF2_WIND
#if defined(CONFIG_EKF2_TERRAIN)
+24 -22
View File
@@ -89,8 +89,6 @@ void Ekf::reset()
_control_status.flags.in_air = true;
_control_status_prev.flags.in_air = true;
_ang_rate_delayed_raw.zero();
_fault_status.value = 0;
_innov_check_fail_status.value = 0;
@@ -168,7 +166,8 @@ bool Ekf::update()
// control fusion of observation data
controlFusionModes(imu_sample_delayed);
_output_predictor.correctOutputStates(imu_sample_delayed.time_us, _state.quat_nominal, _state.vel, _state.pos, _state.gyro_bias, _state.accel_bias);
_output_predictor.correctOutputStates(imu_sample_delayed.time_us, _state.quat_nominal, _state.vel, _state.pos,
_state.gyro_bias, _state.accel_bias);
return true;
}
@@ -263,13 +262,6 @@ void Ekf::predictState(const imuSample &imu_delayed)
_state.vel = matrix::constrain(_state.vel, -1000.f, 1000.f);
_state.pos = matrix::constrain(_state.pos, -1.e6f, 1.e6f);
// some calculations elsewhere in code require a raw angular rate vector so calculate here to avoid duplication
// protect against possible small timesteps resulting from timing slip on previous frame that can drive spikes into the rate
// due to insufficient averaging
if (imu_delayed.delta_ang_dt > 0.25f * _dt_ekf_avg) {
_ang_rate_delayed_raw = imu_delayed.delta_ang / imu_delayed.delta_ang_dt;
}
// calculate a filtered horizontal acceleration with a 1 sec time constant
// this are used for manoeuvre detection elsewhere
@@ -281,7 +273,8 @@ void Ekf::predictState(const imuSample &imu_delayed)
_height_rate_lpf = _height_rate_lpf * (1.0f - alpha_height_rate_lpf) + _state.vel(2) * alpha_height_rate_lpf;
}
bool Ekf::resetGlobalPosToExternalObservation(double lat_deg, double lon_deg, float accuracy, uint64_t timestamp_observation)
bool Ekf::resetGlobalPosToExternalObservation(double lat_deg, double lon_deg, float accuracy,
uint64_t timestamp_observation)
{
if (!_pos_ref.isInitialized()) {
ECL_WARN("unable to reset global position, position reference not initialized");
@@ -315,7 +308,7 @@ bool Ekf::resetGlobalPosToExternalObservation(double lat_deg, double lon_deg, fl
const float sq_gate = sq(5.f); // magic hardcoded gate
const Vector2f test_ratio{sq(innov(0)) / (sq_gate * innov_var(0)),
sq(innov(1)) / (sq_gate * innov_var(1))};
sq(innov(1)) / (sq_gate * innov_var(1))};
const bool innov_rejected = (test_ratio.max() > 1.f);
@@ -331,8 +324,8 @@ bool Ekf::resetGlobalPosToExternalObservation(double lat_deg, double lon_deg, fl
} else {
if (fuseDirectStateMeasurement(innov(0), innov_var(0), obs_var, State::pos.idx + 0)
&& fuseDirectStateMeasurement(innov(1), innov_var(1), obs_var, State::pos.idx + 1)
) {
&& fuseDirectStateMeasurement(innov(1), innov_var(1), obs_var, State::pos.idx + 1)
) {
ECL_INFO("fused external observation as position measurement");
_time_last_hor_pos_fuse = _time_delayed_us;
_last_known_pos.xy() = _state.pos.xy();
@@ -366,40 +359,49 @@ void Ekf::print_status()
printf("\nStates: (%.4f seconds ago)\n", (_time_latest_us - _time_delayed_us) * 1e-6);
printf("Orientation (%d-%d): [%.3f, %.3f, %.3f, %.3f] (Euler [%.1f, %.1f, %.1f] deg) var: [%.1e, %.1e, %.1e]\n",
State::quat_nominal.idx, State::quat_nominal.idx + State::quat_nominal.dof - 1,
(double)_state.quat_nominal(0), (double)_state.quat_nominal(1), (double)_state.quat_nominal(2), (double)_state.quat_nominal(3),
(double)math::degrees(matrix::Eulerf(_state.quat_nominal).phi()), (double)math::degrees(matrix::Eulerf(_state.quat_nominal).theta()), (double)math::degrees(matrix::Eulerf(_state.quat_nominal).psi()),
(double)getStateVariance<State::quat_nominal>()(0), (double)getStateVariance<State::quat_nominal>()(1), (double)getStateVariance<State::quat_nominal>()(2)
(double)_state.quat_nominal(0), (double)_state.quat_nominal(1), (double)_state.quat_nominal(2),
(double)_state.quat_nominal(3),
(double)math::degrees(matrix::Eulerf(_state.quat_nominal).phi()),
(double)math::degrees(matrix::Eulerf(_state.quat_nominal).theta()),
(double)math::degrees(matrix::Eulerf(_state.quat_nominal).psi()),
(double)getStateVariance<State::quat_nominal>()(0), (double)getStateVariance<State::quat_nominal>()(1),
(double)getStateVariance<State::quat_nominal>()(2)
);
printf("Velocity (%d-%d): [%.3f, %.3f, %.3f] var: [%.1e, %.1e, %.1e]\n",
State::vel.idx, State::vel.idx + State::vel.dof - 1,
(double)_state.vel(0), (double)_state.vel(1), (double)_state.vel(2),
(double)getStateVariance<State::vel>()(0), (double)getStateVariance<State::vel>()(1), (double)getStateVariance<State::vel>()(2)
(double)getStateVariance<State::vel>()(0), (double)getStateVariance<State::vel>()(1),
(double)getStateVariance<State::vel>()(2)
);
printf("Position (%d-%d): [%.3f, %.3f, %.3f] var: [%.1e, %.1e, %.1e]\n",
State::pos.idx, State::pos.idx + State::pos.dof - 1,
(double)_state.pos(0), (double)_state.pos(1), (double)_state.pos(2),
(double)getStateVariance<State::pos>()(0), (double)getStateVariance<State::pos>()(1), (double)getStateVariance<State::pos>()(2)
(double)getStateVariance<State::pos>()(0), (double)getStateVariance<State::pos>()(1),
(double)getStateVariance<State::pos>()(2)
);
printf("Gyro Bias (%d-%d): [%.6f, %.6f, %.6f] var: [%.1e, %.1e, %.1e]\n",
State::gyro_bias.idx, State::gyro_bias.idx + State::gyro_bias.dof - 1,
(double)_state.gyro_bias(0), (double)_state.gyro_bias(1), (double)_state.gyro_bias(2),
(double)getStateVariance<State::gyro_bias>()(0), (double)getStateVariance<State::gyro_bias>()(1), (double)getStateVariance<State::gyro_bias>()(2)
(double)getStateVariance<State::gyro_bias>()(0), (double)getStateVariance<State::gyro_bias>()(1),
(double)getStateVariance<State::gyro_bias>()(2)
);
printf("Accel Bias (%d-%d): [%.6f, %.6f, %.6f] var: [%.1e, %.1e, %.1e]\n",
State::accel_bias.idx, State::accel_bias.idx + State::accel_bias.dof - 1,
(double)_state.accel_bias(0), (double)_state.accel_bias(1), (double)_state.accel_bias(2),
(double)getStateVariance<State::accel_bias>()(0), (double)getStateVariance<State::accel_bias>()(1), (double)getStateVariance<State::accel_bias>()(2)
(double)getStateVariance<State::accel_bias>()(0), (double)getStateVariance<State::accel_bias>()(1),
(double)getStateVariance<State::accel_bias>()(2)
);
#if defined(CONFIG_EKF2_MAGNETOMETER)
printf("Magnetic Field (%d-%d): [%.3f, %.3f, %.3f] var: [%.1e, %.1e, %.1e]\n",
State::mag_I.idx, State::mag_I.idx + State::mag_I.dof - 1,
(double)_state.mag_I(0), (double)_state.mag_I(1), (double)_state.mag_I(2),
(double)getStateVariance<State::mag_I>()(0), (double)getStateVariance<State::mag_I>()(1), (double)getStateVariance<State::mag_I>()(2)
(double)getStateVariance<State::mag_I>()(0), (double)getStateVariance<State::mag_I>()(1),
(double)getStateVariance<State::mag_I>()(2)
);
printf("Magnetic Bias (%d-%d): [%.3f, %.3f, %.3f] var: [%.1e, %.1e, %.1e]\n",
+72 -44
View File
@@ -100,8 +100,6 @@ public:
// terrain estimate
bool isTerrainEstimateValid() const;
uint8_t getTerrainEstimateSensorBitfield() const { return _hagl_sensor_status.value; }
// get the estimated terrain vertical position relative to the NED origin
float getTerrainVertPos() const { return _state.terrain; };
float getHagl() const { return _state.terrain - _state.pos(2); }
@@ -134,27 +132,33 @@ public:
const Vector3f getFlowGyro() const { return _flow_sample_delayed.gyro_rate; }
const Vector3f &getFlowGyroBias() const { return _flow_gyro_bias; }
const Vector3f &getRefBodyRate() const { return _ref_body_rate; }
const Vector3f &getFlowRefBodyRate() const { return _ref_body_rate; }
#endif // CONFIG_EKF2_OPTICAL_FLOW
float getHeadingInnov() const
{
#if defined(CONFIG_EKF2_MAGNETOMETER)
if (_control_status.flags.mag_hdg || _control_status.flags.mag_3D) {
return Vector3f(_aid_src_mag.innovation).max();
}
#endif // CONFIG_EKF2_MAGNETOMETER
#if defined(CONFIG_EKF2_GNSS_YAW)
if (_control_status.flags.gps_yaw) {
return _aid_src_gnss_yaw.innovation;
}
#endif // CONFIG_EKF2_GNSS_YAW
#if defined(CONFIG_EKF2_EXTERNAL_VISION)
if (_control_status.flags.ev_yaw) {
return _aid_src_ev_yaw.innovation;
}
#endif // CONFIG_EKF2_EXTERNAL_VISION
return 0.f;
@@ -163,21 +167,27 @@ public:
float getHeadingInnovVar() const
{
#if defined(CONFIG_EKF2_MAGNETOMETER)
if (_control_status.flags.mag_hdg || _control_status.flags.mag_3D) {
return Vector3f(_aid_src_mag.innovation_variance).max();
}
#endif // CONFIG_EKF2_MAGNETOMETER
#if defined(CONFIG_EKF2_GNSS_YAW)
if (_control_status.flags.gps_yaw) {
return _aid_src_gnss_yaw.innovation_variance;
}
#endif // CONFIG_EKF2_GNSS_YAW
#if defined(CONFIG_EKF2_EXTERNAL_VISION)
if (_control_status.flags.ev_yaw) {
return _aid_src_ev_yaw.innovation_variance;
}
#endif // CONFIG_EKF2_EXTERNAL_VISION
return 0.f;
@@ -186,21 +196,27 @@ public:
float getHeadingInnovRatio() const
{
#if defined(CONFIG_EKF2_MAGNETOMETER)
if (_control_status.flags.mag_hdg || _control_status.flags.mag_3D) {
return Vector3f(_aid_src_mag.test_ratio).max();
}
#endif // CONFIG_EKF2_MAGNETOMETER
#if defined(CONFIG_EKF2_GNSS_YAW)
if (_control_status.flags.gps_yaw) {
return _aid_src_gnss_yaw.test_ratio;
}
#endif // CONFIG_EKF2_GNSS_YAW
#if defined(CONFIG_EKF2_EXTERNAL_VISION)
if (_control_status.flags.ev_yaw) {
return _aid_src_ev_yaw.test_ratio;
}
#endif // CONFIG_EKF2_EXTERNAL_VISION
return 0.f;
@@ -492,6 +508,7 @@ public:
P(j, i) = P(i, j);
}
}
#endif
constrainStateVariances();
@@ -501,7 +518,8 @@ public:
return true;
}
bool resetGlobalPosToExternalObservation(double lat_deg, double lon_deg, float accuracy, uint64_t timestamp_observation);
bool resetGlobalPosToExternalObservation(double lat_deg, double lon_deg, float accuracy,
uint64_t timestamp_observation);
void updateParameters();
@@ -548,8 +566,6 @@ private:
StateResets _state_reset_status{}; ///< reset event monitoring structure containing velocity, position, height and yaw reset information
StateResetCounts _state_reset_count_prev{};
Vector3f _ang_rate_delayed_raw{}; ///< uncorrected angular rate vector at fusion time horizon (rad/sec)
StateSample _state{}; ///< state struct of the ekf running at the delayed time horizon
bool _filter_initialised{false}; ///< true when the EKF sttes and covariances been initialised
@@ -578,23 +594,22 @@ private:
SquareMatrixState P{}; ///< state covariance matrix
#if defined(CONFIG_EKF2_DRAG_FUSION)
estimator_aid_source2d_s _aid_src_drag{};
estimator_aid_source2d_s _aid_src_drag {};
#endif // CONFIG_EKF2_DRAG_FUSION
#if defined(CONFIG_EKF2_TERRAIN)
// Terrain height state estimation
uint8_t _terrain_vpos_reset_counter{0}; ///< number of times _terrain_vpos has been reset
terrain_fusion_status_u _hagl_sensor_status{}; ///< Struct indicating type of sensor used to estimate height above ground
float _last_on_ground_posD{0.0f}; ///< last vertical position when the in_air status was false (m)
#endif // CONFIG_EKF2_TERRAIN
#if defined(CONFIG_EKF2_RANGE_FINDER)
estimator_aid_source1d_s _aid_src_rng_hgt{};
estimator_aid_source1d_s _aid_src_rng_hgt {};
#endif // CONFIG_EKF2_RANGE_FINDER
#if defined(CONFIG_EKF2_OPTICAL_FLOW)
estimator_aid_source2d_s _aid_src_optical_flow{};
estimator_aid_source2d_s _aid_src_optical_flow {};
// optical flow processing
Vector3f _flow_gyro_bias{}; ///< bias errors in optical flow sensor rate gyro outputs (rad/sec)
@@ -603,22 +618,20 @@ private:
Vector3f _ref_body_rate{};
Vector2f _flow_rate_compensated{}; ///< measured angular rate of the image about the X and Y body axes after removal of body rotation (rad/s), RH rotation is positive
bool _flow_data_ready{false}; ///< true when the leading edge of the optical flow integration period has fallen behind the fusion time horizon
#endif // CONFIG_EKF2_OPTICAL_FLOW
#if defined(CONFIG_EKF2_AIRSPEED)
estimator_aid_source1d_s _aid_src_airspeed{};
estimator_aid_source1d_s _aid_src_airspeed {};
#endif // CONFIG_EKF2_AIRSPEED
#if defined(CONFIG_EKF2_SIDESLIP)
estimator_aid_source1d_s _aid_src_sideslip{};
estimator_aid_source1d_s _aid_src_sideslip {};
#endif // CONFIG_EKF2_SIDESLIP
estimator_aid_source2d_s _aid_src_fake_pos{};
estimator_aid_source1d_s _aid_src_fake_hgt{};
#if defined(CONFIG_EKF2_EXTERNAL_VISION)
estimator_aid_source1d_s _aid_src_ev_hgt{};
estimator_aid_source1d_s _aid_src_ev_hgt {};
estimator_aid_source2d_s _aid_src_ev_pos{};
estimator_aid_source3d_s _aid_src_ev_vel{};
estimator_aid_source1d_s _aid_src_ev_yaw{};
@@ -629,7 +642,7 @@ private:
#endif // CONFIG_EKF2_EXTERNAL_VISION
#if defined(CONFIG_EKF2_GNSS)
bool _gps_data_ready{false}; ///< true when new GPS data has fallen behind the fusion time horizon and is available to be fused
bool _gps_data_ready {false}; ///< true when new GPS data has fallen behind the fusion time horizon and is available to be fused
// variables used for the GPS quality checks
Vector3f _gps_pos_deriv_filt{}; ///< GPS NED position derivative (m/sec)
@@ -652,16 +665,16 @@ private:
estimator_aid_source3d_s _aid_src_gnss_vel{};
# if defined(CONFIG_EKF2_GNSS_YAW)
estimator_aid_source1d_s _aid_src_gnss_yaw{};
estimator_aid_source1d_s _aid_src_gnss_yaw {};
# endif // CONFIG_EKF2_GNSS_YAW
#endif // CONFIG_EKF2_GNSS
#if defined(CONFIG_EKF2_GRAVITY_FUSION)
estimator_aid_source3d_s _aid_src_gravity{};
estimator_aid_source3d_s _aid_src_gravity {};
#endif // CONFIG_EKF2_GRAVITY_FUSION
#if defined(CONFIG_EKF2_AUXVEL)
estimator_aid_source2d_s _aid_src_aux_vel{};
estimator_aid_source2d_s _aid_src_aux_vel {};
#endif // CONFIG_EKF2_AUXVEL
// Variables used by the initial filter alignment
@@ -670,7 +683,7 @@ private:
AlphaFilter<Vector3f> _gyro_lpf{0.1f}; ///< filtered gyro measurement used for alignment excessive movement check (rad/sec)
#if defined(CONFIG_EKF2_BAROMETER)
estimator_aid_source1d_s _aid_src_baro_hgt{};
estimator_aid_source1d_s _aid_src_baro_hgt {};
// Variables used to perform in flight resets and switch between height sources
AlphaFilter<float> _baro_lpf{0.1f}; ///< filtered barometric height measurement (m)
@@ -734,7 +747,8 @@ private:
#if defined(CONFIG_EKF2_MAGNETOMETER)
// ekf sequential fusion of magnetometer measurements
bool fuseMag(const Vector3f &mag, const float R_MAG, VectorState &H, estimator_aid_source3d_s &aid_src, bool update_all_states = false, bool update_tilt = false);
bool fuseMag(const Vector3f &mag, const float R_MAG, VectorState &H, estimator_aid_source3d_s &aid_src,
bool update_all_states = false, bool update_tilt = false);
// fuse magnetometer declination measurement
// argument passed in is the declination uncertainty in radians
@@ -795,7 +809,8 @@ private:
void resetVerticalVelocityToZero();
// horizontal and vertical position aid source
void updateVerticalPositionAidStatus(estimator_aid_source1d_s &aid_src, const uint64_t &time_us, const float observation, const float observation_variance, const float innovation_gate = 1.f) const;
void updateVerticalPositionAidStatus(estimator_aid_source1d_s &aid_src, const uint64_t &time_us,
const float observation, const float observation_variance, const float innovation_gate = 1.f) const;
// horizontal and vertical position fusion
bool fuseHorizontalPosition(estimator_aid_source2d_s &pos_aid_src);
@@ -826,7 +841,7 @@ private:
#if defined(CONFIG_EKF2_RANGE_FINDER)
// range height
void controlRangeHaglFusion();
void controlRangeHaglFusion(const imuSample &imu_delayed);
bool isConditionalRangeAidSuitable();
void stopRngHgtFusion();
void stopRngTerrFusion();
@@ -835,24 +850,24 @@ private:
#if defined(CONFIG_EKF2_OPTICAL_FLOW)
// control fusion of optical flow observations
void controlOpticalFlowFusion(const imuSample &imu_delayed);
void startFlowFusion();
void resetFlowFusion();
void stopFlowFusion();
void updateOnGroundMotionForOpticalFlowChecks();
void resetOnGroundMotionForOpticalFlowChecks();
// calculate the measurement variance for the optical flow sensor
float calcOptFlowMeasVar(const flowSample &flow_sample);
// calculate the measurement variance for the optical flow sensor (rad/sec)^2
float calcOptFlowMeasVar(const flowSample &flow_sample) const;
// calculate optical flow body angular rate compensation
void calcOptFlowBodyRateComp(const imuSample &imu_delayed);
void calcOptFlowBodyRateComp(const flowSample &flow_sample);
float predictFlowRange() const;
Vector2f predictFlow(const Vector3f &flow_gyro) const;
// fuse optical flow line of sight rate measurements
void updateOptFlow(estimator_aid_source2d_s &aid_src);
void fuseOptFlow(bool update_terrain);
float predictFlowRange();
Vector2f predictFlowVelBody();
bool fuseOptFlow(VectorState &H, bool update_terrain);
#endif // CONFIG_EKF2_OPTICAL_FLOW
#if defined(CONFIG_EKF2_MAGNETOMETER)
@@ -875,6 +890,7 @@ private:
}
#if defined(CONFIG_EKF2_MAGNETOMETER)
if (!_control_status.flags.mag) {
for (unsigned i = 0; i < State::mag_I.dof; i++) {
K(State::mag_I.idx + i) = 0.f;
@@ -886,14 +902,17 @@ private:
K(State::mag_B.idx + i) = 0.f;
}
}
#endif // CONFIG_EKF2_MAGNETOMETER
#if defined(CONFIG_EKF2_WIND)
if (!_control_status.flags.wind) {
for (unsigned i = 0; i < State::wind_vel.dof; i++) {
K(State::wind_vel.idx + i) = 0.f;
}
}
#endif // CONFIG_EKF2_WIND
}
@@ -915,17 +934,26 @@ private:
#if defined(CONFIG_EKF2_EXTERNAL_VISION)
// control fusion of external vision observations
void controlExternalVisionFusion();
void controlExternalVisionFusion(const imuSample &imu_sample);
void updateEvAttitudeErrorFilter(extVisionSample &ev_sample, bool ev_reset);
void controlEvHeightFusion(const extVisionSample &ev_sample, const bool common_starting_conditions_passing, const bool ev_reset, const bool quality_sufficient, estimator_aid_source1d_s &aid_src);
void controlEvPosFusion(const extVisionSample &ev_sample, const bool common_starting_conditions_passing, const bool ev_reset, const bool quality_sufficient, estimator_aid_source2d_s &aid_src);
void controlEvVelFusion(const extVisionSample &ev_sample, const bool common_starting_conditions_passing, const bool ev_reset, const bool quality_sufficient, estimator_aid_source3d_s &aid_src);
void controlEvYawFusion(const extVisionSample &ev_sample, const bool common_starting_conditions_passing, const bool ev_reset, const bool quality_sufficient, estimator_aid_source1d_s &aid_src);
void controlEvHeightFusion(const imuSample &imu_sample, const extVisionSample &ev_sample,
const bool common_starting_conditions_passing, const bool ev_reset, const bool quality_sufficient,
estimator_aid_source1d_s &aid_src);
void controlEvPosFusion(const imuSample &imu_sample, const extVisionSample &ev_sample,
const bool common_starting_conditions_passing, const bool ev_reset, const bool quality_sufficient,
estimator_aid_source2d_s &aid_src);
void controlEvVelFusion(const imuSample &imu_sample, const extVisionSample &ev_sample,
const bool common_starting_conditions_passing, const bool ev_reset, const bool quality_sufficient,
estimator_aid_source3d_s &aid_src);
void controlEvYawFusion(const imuSample &imu_sample, const extVisionSample &ev_sample,
const bool common_starting_conditions_passing, const bool ev_reset, const bool quality_sufficient,
estimator_aid_source1d_s &aid_src);
void resetVelocityToEV(const Vector3f &measurement, const Vector3f &measurement_var, const VelocityFrame &vel_frame);
Vector3f rotateVarianceToEkf(const Vector3f &measurement_var);
void startEvPosFusion(const Vector2f &measurement, const Vector2f &measurement_var, estimator_aid_source2d_s &aid_src);
void updateEvPosFusion(const Vector2f &measurement, const Vector2f &measurement_var, bool quality_sufficient, bool reset, estimator_aid_source2d_s &aid_src);
void updateEvPosFusion(const Vector2f &measurement, const Vector2f &measurement_var, bool quality_sufficient,
bool reset, estimator_aid_source2d_s &aid_src);
void stopEvPosFusion();
void stopEvHgtFusion();
void stopEvVelFusion();
@@ -942,7 +970,7 @@ private:
// control fusion of GPS observations
void controlGpsFusion(const imuSample &imu_delayed);
void stopGpsFusion();
void updateGnssVel(const gnssSample &gnss_sample, estimator_aid_source3d_s &aid_src);
void updateGnssVel(const imuSample &imu_sample, const gnssSample &gnss_sample, estimator_aid_source3d_s &aid_src);
void updateGnssPos(const gnssSample &gnss_sample, estimator_aid_source2d_s &aid_src);
void controlGnssYawEstimator(estimator_aid_source3d_s &aid_src_vel);
bool tryYawEmergencyReset();
@@ -991,7 +1019,7 @@ private:
#if defined(CONFIG_EKF2_MAGNETOMETER)
// control fusion of magnetometer observations
void controlMagFusion();
void controlMagFusion(const imuSample &imu_sample);
bool checkHaglYawResetReq() const;
@@ -1024,7 +1052,7 @@ private:
#if defined(CONFIG_EKF2_AUXVEL)
// control fusion of auxiliary velocity observations
void controlAuxVelFusion();
void controlAuxVelFusion(const imuSample &imu_sample);
void stopAuxVelFusion();
#endif // CONFIG_EKF2_AUXVEL
@@ -1037,13 +1065,13 @@ private:
void checkHeightSensorRefFallback();
#if defined(CONFIG_EKF2_BAROMETER)
void controlBaroHeightFusion();
void controlBaroHeightFusion(const imuSample &imu_sample);
void stopBaroHgtFusion();
void updateGroundEffect();
# if defined(CONFIG_EKF2_BARO_COMPENSATION)
float compensateBaroForDynamicPressure(float baro_alt_uncompensated) const;
float compensateBaroForDynamicPressure(const imuSample &imu_sample, float baro_alt_uncompensated) const;
# endif // CONFIG_EKF2_BARO_COMPENSATION
#endif // CONFIG_EKF2_BAROMETER
@@ -1096,7 +1124,7 @@ private:
PositionSensor _position_sensor_ref{PositionSensor::GNSS};
#if defined(CONFIG_EKF2_EXTERNAL_VISION)
HeightBiasEstimator _ev_hgt_b_est{HeightSensor::EV, _height_sensor_ref};
HeightBiasEstimator _ev_hgt_b_est {HeightSensor::EV, _height_sensor_ref};
PositionBiasEstimator _ev_pos_b_est{PositionSensor::EV, _position_sensor_ref};
AlphaFilter<Quatf> _ev_q_error_filt{0.001f};
bool _ev_q_error_initialized{false};
@@ -1302,7 +1330,7 @@ private:
ZeroVelocityUpdate _zero_velocity_update{};
#if defined(CONFIG_EKF2_AUX_GLOBAL_POSITION) && defined(MODULE_NAME)
AuxGlobalPosition _aux_global_position{};
AuxGlobalPosition _aux_global_position {};
#endif // CONFIG_EKF2_AUX_GLOBAL_POSITION
};
+122 -44
View File
@@ -72,13 +72,14 @@ bool Ekf::getEkfGlobalOrigin(uint64_t &origin_time, double &latitude, double &lo
return _NED_origin_initialised;
}
bool Ekf::setEkfGlobalOrigin(const double latitude, const double longitude, const float altitude, const float eph, const float epv)
bool Ekf::setEkfGlobalOrigin(const double latitude, const double longitude, const float altitude, const float eph,
const float epv)
{
// sanity check valid latitude/longitude and altitude anywhere between the Mariana Trench and edge of Space
if (PX4_ISFINITE(latitude) && (abs(latitude) <= 90)
&& PX4_ISFINITE(longitude) && (abs(longitude) <= 180)
&& PX4_ISFINITE(altitude) && (altitude > -12'000.f) && (altitude < 100'000.f)
) {
&& PX4_ISFINITE(longitude) && (abs(longitude) <= 180)
&& PX4_ISFINITE(altitude) && (altitude > -12'000.f) && (altitude < 100'000.f)
) {
bool current_pos_available = false;
double current_lat = static_cast<double>(NAN);
double current_lon = static_cast<double>(NAN);
@@ -107,6 +108,7 @@ bool Ekf::setEkfGlobalOrigin(const double latitude, const double longitude, cons
_wmm_gps_time_last_set = _time_delayed_us;
}
#endif // CONFIG_EKF2_MAGNETOMETER
_gpos_origin_eph = eph;
@@ -176,15 +178,19 @@ void Ekf::get_ekf_lpos_accuracy(float *ekf_eph, float *ekf_epv) const
// and using state variances for accuracy reporting is overly optimistic in these situations
if (_horizontal_deadreckon_time_exceeded) {
#if defined(CONFIG_EKF2_GNSS)
if (_control_status.flags.gps) {
hpos_err = math::max(hpos_err, Vector2f(_aid_src_gnss_pos.innovation).norm());
}
#endif // CONFIG_EKF2_GNSS
#if defined(CONFIG_EKF2_EXTERNAL_VISION)
if (_control_status.flags.ev_pos) {
hpos_err = math::max(hpos_err, Vector2f(_aid_src_ev_pos.innovation).norm());
}
#endif // CONFIG_EKF2_EXTERNAL_VISION
}
@@ -203,19 +209,24 @@ void Ekf::get_ekf_vel_accuracy(float *ekf_evh, float *ekf_evv) const
float vel_err_conservative = 0.0f;
#if defined(CONFIG_EKF2_OPTICAL_FLOW)
if (_control_status.flags.opt_flow) {
float gndclearance = math::max(_params.rng_gnd_clearance, 0.1f);
vel_err_conservative = math::max(getHagl(), gndclearance) * Vector2f(_aid_src_optical_flow.innovation).norm();
}
#endif // CONFIG_EKF2_OPTICAL_FLOW
#if defined(CONFIG_EKF2_GNSS)
if (_control_status.flags.gps) {
vel_err_conservative = math::max(vel_err_conservative, Vector2f(_aid_src_gnss_pos.innovation).norm());
}
#endif // CONFIG_EKF2_GNSS
#if defined(CONFIG_EKF2_EXTERNAL_VISION)
if (_control_status.flags.ev_pos) {
vel_err_conservative = math::max(vel_err_conservative, Vector2f(_aid_src_ev_pos.innovation).norm());
}
@@ -223,6 +234,7 @@ void Ekf::get_ekf_vel_accuracy(float *ekf_evh, float *ekf_evv) const
if (_control_status.flags.ev_vel) {
vel_err_conservative = math::max(vel_err_conservative, Vector2f(_aid_src_ev_vel.innovation).norm());
}
#endif // CONFIG_EKF2_EXTERNAL_VISION
hvel_err = math::max(hvel_err, vel_err_conservative);
@@ -244,8 +256,8 @@ void Ekf::get_ekf_ctrl_limits(float *vxy_max, float *vz_max, float *hagl_min, fl
// Calculate range finder limits
const float rangefinder_hagl_min = _range_sensor.getValidMinVal();
// Allow use of 75% of rangefinder maximum range to allow for angular motion
const float rangefinder_hagl_max = 0.75f * _range_sensor.getValidMaxVal();
// Allow use of 90% of rangefinder maximum range to allow for angular motion
const float rangefinder_hagl_max = 0.9f * _range_sensor.getValidMaxVal();
// TODO : calculate visual odometry limits
const bool relying_on_rangefinder = isOnlyActiveSourceOfVerticalPositionAiding(_control_status.flags.rng_hgt);
@@ -262,8 +274,16 @@ void Ekf::get_ekf_ctrl_limits(float *vxy_max, float *vz_max, float *hagl_min, fl
if (relying_on_optical_flow) {
// Calculate optical flow limits
const float flow_hagl_min = fmaxf(rangefinder_hagl_min, _flow_min_distance);
const float flow_hagl_max = fminf(rangefinder_hagl_max, _flow_max_distance);
float flow_hagl_min = _flow_min_distance;
float flow_hagl_max = _flow_max_distance;
// only limit optical flow height is dependent on range finder or terrain estimate invalid (precaution)
if ((!_control_status.flags.opt_flow_terrain && _control_status.flags.rng_terrain)
|| !isTerrainEstimateValid()
) {
flow_hagl_min = math::max(flow_hagl_min, rangefinder_hagl_min);
flow_hagl_max = math::min(flow_hagl_max, rangefinder_hagl_max);
}
const float flow_constrained_height = math::constrain(getHagl(), flow_hagl_min, flow_hagl_max);
@@ -274,6 +294,7 @@ void Ekf::get_ekf_ctrl_limits(float *vxy_max, float *vz_max, float *hagl_min, fl
*hagl_min = flow_hagl_min;
*hagl_max = flow_hagl_max;
}
# endif // CONFIG_EKF2_OPTICAL_FLOW
#endif // CONFIG_EKF2_RANGE_FINDER
@@ -301,23 +322,29 @@ float Ekf::getHeadingInnovationTestRatio() const
float test_ratio = 0.f;
#if defined(CONFIG_EKF2_MAGNETOMETER)
if (_control_status.flags.mag_hdg ||_control_status.flags.mag_3D) {
if (_control_status.flags.mag_hdg || _control_status.flags.mag_3D) {
for (auto &test_ratio_filtered : _aid_src_mag.test_ratio_filtered) {
test_ratio = math::max(test_ratio, fabsf(test_ratio_filtered));
}
}
#endif // CONFIG_EKF2_MAGNETOMETER
#if defined(CONFIG_EKF2_GNSS_YAW)
if (_control_status.flags.gps_yaw) {
test_ratio = math::max(test_ratio, fabsf(_aid_src_gnss_yaw.test_ratio_filtered));
}
#endif // CONFIG_EKF2_GNSS_YAW
#if defined(CONFIG_EKF2_EXTERNAL_VISION)
if (_control_status.flags.ev_yaw) {
test_ratio = math::max(test_ratio, fabsf(_aid_src_ev_yaw.test_ratio_filtered));
}
#endif // CONFIG_EKF2_EXTERNAL_VISION
return sqrtf(test_ratio);
@@ -329,27 +356,33 @@ float Ekf::getVelocityInnovationTestRatio() const
float test_ratio = -1.f;
#if defined(CONFIG_EKF2_GNSS)
if (_control_status.flags.gps) {
for (int i = 0; i < 3; i++) {
test_ratio = math::max(test_ratio, fabsf(_aid_src_gnss_vel.test_ratio_filtered[i]));
}
}
#endif // CONFIG_EKF2_GNSS
#if defined(CONFIG_EKF2_EXTERNAL_VISION)
if (_control_status.flags.ev_vel) {
for (int i = 0; i < 3; i++) {
test_ratio = math::max(test_ratio, fabsf(_aid_src_ev_vel.test_ratio_filtered[i]));
}
}
#endif // CONFIG_EKF2_EXTERNAL_VISION
#if defined(CONFIG_EKF2_OPTICAL_FLOW)
if (isOnlyActiveSourceOfHorizontalAiding(_control_status.flags.opt_flow)) {
for (auto &test_ratio_filtered : _aid_src_optical_flow.test_ratio_filtered) {
test_ratio = math::max(test_ratio, fabsf(test_ratio_filtered));
}
}
#endif // CONFIG_EKF2_OPTICAL_FLOW
if (PX4_ISFINITE(test_ratio) && (test_ratio >= 0.f)) {
@@ -365,25 +398,31 @@ float Ekf::getHorizontalPositionInnovationTestRatio() const
float test_ratio = -1.f;
#if defined(CONFIG_EKF2_GNSS)
if (_control_status.flags.gps) {
for (auto &test_ratio_filtered : _aid_src_gnss_pos.test_ratio_filtered) {
test_ratio = math::max(test_ratio, fabsf(test_ratio_filtered));
}
}
#endif // CONFIG_EKF2_GNSS
#if defined(CONFIG_EKF2_EXTERNAL_VISION)
if (_control_status.flags.ev_pos) {
for (auto &test_ratio_filtered : _aid_src_ev_pos.test_ratio_filtered) {
test_ratio = math::max(test_ratio, fabsf(test_ratio_filtered));
}
}
#endif // CONFIG_EKF2_EXTERNAL_VISION
#if defined(CONFIG_EKF2_AUX_GLOBAL_POSITION) && defined(MODULE_NAME)
if (_control_status.flags.aux_gpos) {
test_ratio = math::max(test_ratio, fabsf(_aux_global_position.test_ratio_filtered()));
}
#endif // CONFIG_EKF2_AUX_GLOBAL_POSITION
if (PX4_ISFINITE(test_ratio) && (test_ratio >= 0.f)) {
@@ -400,31 +439,39 @@ float Ekf::getVerticalPositionInnovationTestRatio() const
int n_hgt_sources = 0;
#if defined(CONFIG_EKF2_BAROMETER)
if (_control_status.flags.baro_hgt) {
hgt_sum += sqrtf(fabsf(_aid_src_baro_hgt.test_ratio_filtered));
n_hgt_sources++;
}
#endif // CONFIG_EKF2_BAROMETER
#if defined(CONFIG_EKF2_GNSS)
if (_control_status.flags.gps_hgt) {
hgt_sum += sqrtf(fabsf(_aid_src_gnss_hgt.test_ratio_filtered));
n_hgt_sources++;
}
#endif // CONFIG_EKF2_GNSS
#if defined(CONFIG_EKF2_RANGE_FINDER)
if (_control_status.flags.rng_hgt) {
hgt_sum += sqrtf(fabsf(_aid_src_rng_hgt.test_ratio_filtered));
n_hgt_sources++;
}
#endif // CONFIG_EKF2_RANGE_FINDER
#if defined(CONFIG_EKF2_EXTERNAL_VISION)
if (_control_status.flags.ev_hgt) {
hgt_sum += sqrtf(fabsf(_aid_src_ev_hgt.test_ratio_filtered));
n_hgt_sources++;
}
#endif // CONFIG_EKF2_EXTERNAL_VISION
if (n_hgt_sources > 0) {
@@ -437,10 +484,12 @@ float Ekf::getVerticalPositionInnovationTestRatio() const
float Ekf::getAirspeedInnovationTestRatio() const
{
#if defined(CONFIG_EKF2_AIRSPEED)
if (_control_status.flags.fuse_aspd) {
// return the airspeed fusion innovation test ratio
return sqrtf(fabsf(_aid_src_airspeed.test_ratio_filtered));
}
#endif // CONFIG_EKF2_AIRSPEED
return NAN;
@@ -449,10 +498,12 @@ float Ekf::getAirspeedInnovationTestRatio() const
float Ekf::getSyntheticSideslipInnovationTestRatio() const
{
#if defined(CONFIG_EKF2_SIDESLIP)
if (_control_status.flags.fuse_beta) {
// return the synthetic sideslip innovation test ratio
return sqrtf(fabsf(_aid_src_sideslip.test_ratio_filtered));
}
#endif // CONFIG_EKF2_SIDESLIP
return NAN;
@@ -464,10 +515,12 @@ float Ekf::getHeightAboveGroundInnovationTestRatio() const
#if defined(CONFIG_EKF2_TERRAIN)
# if defined(CONFIG_EKF2_RANGE_FINDER)
if (_hagl_sensor_status.flags.range_finder) {
if (_control_status.flags.rng_terrain) {
// return the terrain height innovation test ratio
test_ratio = math::max(test_ratio, fabsf(_aid_src_rng_hgt.test_ratio_filtered));
}
# endif // CONFIG_EKF2_RANGE_FINDER
#endif // CONFIG_EKF2_TERRAIN
@@ -483,10 +536,14 @@ void Ekf::get_ekf_soln_status(uint16_t *status) const
ekf_solution_status_u soln_status{};
// TODO: Is this accurate enough?
soln_status.flags.attitude = attitude_valid();
soln_status.flags.velocity_horiz = (isHorizontalAidingActive() || (_control_status.flags.fuse_beta && _control_status.flags.fuse_aspd)) && (_fault_status.value == 0);
soln_status.flags.velocity_vert = (_control_status.flags.baro_hgt || _control_status.flags.ev_hgt || _control_status.flags.gps_hgt || _control_status.flags.rng_hgt) && (_fault_status.value == 0);
soln_status.flags.pos_horiz_rel = (_control_status.flags.gps || _control_status.flags.ev_pos || _control_status.flags.opt_flow) && (_fault_status.value == 0);
soln_status.flags.pos_horiz_abs = (_control_status.flags.gps || _control_status.flags.ev_pos) && (_fault_status.value == 0);
soln_status.flags.velocity_horiz = (isHorizontalAidingActive() || (_control_status.flags.fuse_beta
&& _control_status.flags.fuse_aspd)) && (_fault_status.value == 0);
soln_status.flags.velocity_vert = (_control_status.flags.baro_hgt || _control_status.flags.ev_hgt
|| _control_status.flags.gps_hgt || _control_status.flags.rng_hgt) && (_fault_status.value == 0);
soln_status.flags.pos_horiz_rel = (_control_status.flags.gps || _control_status.flags.ev_pos
|| _control_status.flags.opt_flow) && (_fault_status.value == 0);
soln_status.flags.pos_horiz_abs = (_control_status.flags.gps || _control_status.flags.ev_pos)
&& (_fault_status.value == 0);
soln_status.flags.pos_vert_abs = soln_status.flags.velocity_vert;
#if defined(CONFIG_EKF2_TERRAIN)
soln_status.flags.pos_vert_agl = isTerrainEstimateValid();
@@ -498,11 +555,13 @@ void Ekf::get_ekf_soln_status(uint16_t *status) const
bool mag_innov_good = true;
#if defined(CONFIG_EKF2_MAGNETOMETER)
if (_control_status.flags.mag_hdg ||_control_status.flags.mag_3D) {
if (_control_status.flags.mag_hdg || _control_status.flags.mag_3D) {
if (Vector3f(_aid_src_mag.test_ratio).max() < 1.f) {
mag_innov_good = false;
}
}
#endif // CONFIG_EKF2_MAGNETOMETER
#if defined(CONFIG_EKF2_GNSS)
@@ -521,7 +580,8 @@ void Ekf::get_ekf_soln_status(uint16_t *status) const
void Ekf::fuse(const VectorState &K, float innovation)
{
// quat_nominal
Quatf delta_quat(matrix::AxisAnglef(K.slice<State::quat_nominal.dof, 1>(State::quat_nominal.idx, 0) * (-1.f * innovation)));
Quatf delta_quat(matrix::AxisAnglef(K.slice<State::quat_nominal.dof, 1>(State::quat_nominal.idx,
0) * (-1.f * innovation)));
_state.quat_nominal = delta_quat * _state.quat_nominal;
_state.quat_nominal.normalize();
_R_to_earth = Dcmf(_state.quat_nominal);
@@ -533,26 +593,35 @@ void Ekf::fuse(const VectorState &K, float innovation)
_state.pos = matrix::constrain(_state.pos - K.slice<State::pos.dof, 1>(State::pos.idx, 0) * innovation, -1.e6f, 1.e6f);
// gyro_bias
_state.gyro_bias = matrix::constrain(_state.gyro_bias - K.slice<State::gyro_bias.dof, 1>(State::gyro_bias.idx, 0) * innovation,
-getGyroBiasLimit(), getGyroBiasLimit());
_state.gyro_bias = matrix::constrain(_state.gyro_bias - K.slice<State::gyro_bias.dof, 1>(State::gyro_bias.idx,
0) * innovation,
-getGyroBiasLimit(), getGyroBiasLimit());
// accel_bias
_state.accel_bias = matrix::constrain(_state.accel_bias - K.slice<State::accel_bias.dof, 1>(State::accel_bias.idx, 0) * innovation,
-getAccelBiasLimit(), getAccelBiasLimit());
_state.accel_bias = matrix::constrain(_state.accel_bias - K.slice<State::accel_bias.dof, 1>(State::accel_bias.idx,
0) * innovation,
-getAccelBiasLimit(), getAccelBiasLimit());
#if defined(CONFIG_EKF2_MAGNETOMETER)
// mag_I, mag_B
if (_control_status.flags.mag) {
_state.mag_I = matrix::constrain(_state.mag_I - K.slice<State::mag_I.dof, 1>(State::mag_I.idx, 0) * innovation, -1.f, 1.f);
_state.mag_B = matrix::constrain(_state.mag_B - K.slice<State::mag_B.dof, 1>(State::mag_B.idx, 0) * innovation, -getMagBiasLimit(), getMagBiasLimit());
_state.mag_I = matrix::constrain(_state.mag_I - K.slice<State::mag_I.dof, 1>(State::mag_I.idx, 0) * innovation, -1.f,
1.f);
_state.mag_B = matrix::constrain(_state.mag_B - K.slice<State::mag_B.dof, 1>(State::mag_B.idx, 0) * innovation,
-getMagBiasLimit(), getMagBiasLimit());
}
#endif // CONFIG_EKF2_MAGNETOMETER
#if defined(CONFIG_EKF2_WIND)
// wind_vel
if (_control_status.flags.wind) {
_state.wind_vel = matrix::constrain(_state.wind_vel - K.slice<State::wind_vel.dof, 1>(State::wind_vel.idx, 0) * innovation, -1.e2f, 1.e2f);
_state.wind_vel = matrix::constrain(_state.wind_vel - K.slice<State::wind_vel.dof, 1>(State::wind_vel.idx,
0) * innovation, -1.e2f, 1.e2f);
}
#endif // CONFIG_EKF2_WIND
#if defined(CONFIG_EKF2_TERRAIN)
@@ -573,40 +642,43 @@ void Ekf::updateHorizontalDeadReckoningstatus()
// velocity aiding active
if ((_control_status.flags.gps || _control_status.flags.ev_vel)
&& isRecent(_time_last_hor_vel_fuse, _params.no_aid_timeout_max)
) {
&& isRecent(_time_last_hor_vel_fuse, _params.no_aid_timeout_max)
) {
inertial_dead_reckoning = false;
}
// position aiding active
if ((_control_status.flags.gps || _control_status.flags.ev_pos || _control_status.flags.aux_gpos)
&& isRecent(_time_last_hor_pos_fuse, _params.no_aid_timeout_max)
) {
&& isRecent(_time_last_hor_pos_fuse, _params.no_aid_timeout_max)
) {
inertial_dead_reckoning = false;
}
#if defined(CONFIG_EKF2_OPTICAL_FLOW)
// optical flow active
if (_control_status.flags.opt_flow
&& isRecent(_aid_src_optical_flow.time_last_fuse, _params.no_aid_timeout_max)
) {
&& isRecent(_aid_src_optical_flow.time_last_fuse, _params.no_aid_timeout_max)
) {
inertial_dead_reckoning = false;
} else {
if (!_control_status.flags.in_air && (_params.flow_ctrl == 1)
&& isRecent(_aid_src_optical_flow.timestamp_sample, _params.no_aid_timeout_max)
) {
&& isRecent(_aid_src_optical_flow.timestamp_sample, _params.no_aid_timeout_max)
) {
// currently landed, but optical flow aiding should be possible once in air
aiding_expected_in_air = true;
}
}
#endif // CONFIG_EKF2_OPTICAL_FLOW
#if defined(CONFIG_EKF2_AIRSPEED)
// air data aiding active
if ((_control_status.flags.fuse_aspd && isRecent(_aid_src_airspeed.time_last_fuse, _params.no_aid_timeout_max))
&& (_control_status.flags.fuse_beta && isRecent(_aid_src_sideslip.time_last_fuse, _params.no_aid_timeout_max))
) {
&& (_control_status.flags.fuse_beta && isRecent(_aid_src_sideslip.time_last_fuse, _params.no_aid_timeout_max))
) {
// wind_dead_reckoning: no other aiding but air data
_control_status.flags.wind_dead_reckoning = inertial_dead_reckoning;
@@ -617,13 +689,14 @@ void Ekf::updateHorizontalDeadReckoningstatus()
_control_status.flags.wind_dead_reckoning = false;
if (!_control_status.flags.in_air && _control_status.flags.fixed_wing
&& (_params.beta_fusion_enabled == 1)
&& (_params.arsp_thr > 0.f) && isRecent(_aid_src_airspeed.timestamp_sample, _params.no_aid_timeout_max)
) {
&& (_params.beta_fusion_enabled == 1)
&& (_params.arsp_thr > 0.f) && isRecent(_aid_src_airspeed.timestamp_sample, _params.no_aid_timeout_max)
) {
// currently landed, but air data aiding should be possible once in air
aiding_expected_in_air = true;
}
}
#endif // CONFIG_EKF2_AIRSPEED
// zero velocity update
@@ -704,6 +777,7 @@ void Ekf::updateGroundEffect()
{
if (_control_status.flags.in_air && !_control_status.flags.fixed_wing) {
#if defined(CONFIG_EKF2_TERRAIN)
if (isTerrainEstimateValid()) {
// automatically set ground effect if terrain is valid
float height = getHagl();
@@ -711,12 +785,12 @@ void Ekf::updateGroundEffect()
} else
#endif // CONFIG_EKF2_TERRAIN
if (_control_status.flags.gnd_effect) {
// Turn off ground effect compensation if it times out
if (isTimedOut(_time_last_gnd_effect_on, GNDEFFECT_TIMEOUT)) {
_control_status.flags.gnd_effect = false;
if (_control_status.flags.gnd_effect) {
// Turn off ground effect compensation if it times out
if (isTimedOut(_time_last_gnd_effect_on, GNDEFFECT_TIMEOUT)) {
_control_status.flags.gnd_effect = false;
}
}
}
} else {
_control_status.flags.gnd_effect = false;
@@ -728,10 +802,12 @@ void Ekf::updateGroundEffect()
void Ekf::resetWind()
{
#if defined(CONFIG_EKF2_AIRSPEED)
if (_control_status.flags.fuse_aspd && isRecent(_airspeed_sample_delayed.time_us, 1e6)) {
resetWindUsingAirspeed(_airspeed_sample_delayed);
return;
}
#endif // CONFIG_EKF2_AIRSPEED
resetWindToZero();
@@ -756,7 +832,8 @@ void Ekf::updateIMUBiasInhibit(const imuSample &imu_delayed)
{
const float alpha = math::constrain((imu_delayed.delta_ang_dt / _params.acc_bias_learn_tc), 0.f, 1.f);
const float beta = 1.f - alpha;
_ang_rate_magnitude_filt = fmaxf(imu_delayed.delta_ang.norm() / imu_delayed.delta_ang_dt, beta * _ang_rate_magnitude_filt);
_ang_rate_magnitude_filt = fmaxf(imu_delayed.delta_ang.norm() / imu_delayed.delta_ang_dt,
beta * _ang_rate_magnitude_filt);
}
{
@@ -781,8 +858,8 @@ void Ekf::updateIMUBiasInhibit(const imuSample &imu_delayed)
// accel bias inhibit
const bool do_inhibit_all_accel_axes = !(_params.imu_ctrl & static_cast<int32_t>(ImuCtrl::AccelBias))
|| is_manoeuvre_level_high
|| _fault_status.flags.bad_acc_vertical;
|| is_manoeuvre_level_high
|| _fault_status.flags.bad_acc_vertical;
for (unsigned index = 0; index < State::accel_bias.dof; index++) {
bool is_bias_observable = true;
@@ -853,6 +930,7 @@ bool Ekf::fuseDirectStateMeasurement(const float innov, const float innov_var, c
P(j, i) = P(i, j);
}
}
#endif
constrainStateVariances();
+33 -11
View File
@@ -86,14 +86,25 @@ void EstimatorInterface::setIMUData(const imuSample &imu_sample)
_time_latest_us = imu_sample.time_us;
// the output observer always runs
_output_predictor.calculateOutputStates(imu_sample.time_us, imu_sample.delta_ang, imu_sample.delta_ang_dt, imu_sample.delta_vel, imu_sample.delta_vel_dt);
_output_predictor.calculateOutputStates(imu_sample.time_us, imu_sample.delta_ang, imu_sample.delta_ang_dt,
imu_sample.delta_vel, imu_sample.delta_vel_dt);
// accumulate and down-sample imu data and push to the buffer when new downsampled data becomes available
if (_imu_down_sampler.update(imu_sample)) {
_imu_updated = true;
_imu_buffer.push(_imu_down_sampler.getDownSampledImuAndTriggerReset());
imuSample imu_downsampled = _imu_down_sampler.getDownSampledImuAndTriggerReset();
// as a precaution constrain the integration delta time to prevent numerical problems
const float filter_update_period_s = _params.filter_update_interval_us * 1e-6f;
const float imu_min_dt = 0.5f * filter_update_period_s;
const float imu_max_dt = 2.0f * filter_update_period_s;
imu_downsampled.delta_ang_dt = math::constrain(imu_downsampled.delta_ang_dt, imu_min_dt, imu_max_dt);
imu_downsampled.delta_vel_dt = math::constrain(imu_downsampled.delta_vel_dt, imu_min_dt, imu_max_dt);
_imu_buffer.push(imu_downsampled);
// get the oldest data from the buffer
_time_delayed_us = _imu_buffer.get_oldest().time_us;
@@ -141,7 +152,8 @@ void EstimatorInterface::setMagData(const magSample &mag_sample)
_time_last_mag_buffer_push = _time_latest_us;
} else {
ECL_WARN("mag data too fast %" PRIi64 " < %" PRIu64 " + %d", time_us, _mag_buffer->get_newest().time_us, _min_obs_interval_us);
ECL_WARN("mag data too fast %" PRIi64 " < %" PRIu64 " + %d", time_us, _mag_buffer->get_newest().time_us,
_min_obs_interval_us);
}
}
#endif // CONFIG_EKF2_MAGNETOMETER
@@ -179,13 +191,16 @@ void EstimatorInterface::setGpsData(const gnssSample &gnss_sample)
_time_last_gps_buffer_push = _time_latest_us;
#if defined(CONFIG_EKF2_GNSS_YAW)
if (PX4_ISFINITE(gnss_sample.yaw)) {
_time_last_gps_yaw_buffer_push = _time_latest_us;
}
#endif // CONFIG_EKF2_GNSS_YAW
} else {
ECL_WARN("GPS data too fast %" PRIi64 " < %" PRIu64 " + %d", time_us, _gps_buffer->get_newest().time_us, _min_obs_interval_us);
ECL_WARN("GPS data too fast %" PRIi64 " < %" PRIu64 " + %d", time_us, _gps_buffer->get_newest().time_us,
_min_obs_interval_us);
}
}
#endif // CONFIG_EKF2_GNSS
@@ -223,7 +238,8 @@ void EstimatorInterface::setBaroData(const baroSample &baro_sample)
_time_last_baro_buffer_push = _time_latest_us;
} else {
ECL_WARN("baro data too fast %" PRIi64 " < %" PRIu64 " + %d", time_us, _baro_buffer->get_newest().time_us, _min_obs_interval_us);
ECL_WARN("baro data too fast %" PRIi64 " < %" PRIu64 " + %d", time_us, _baro_buffer->get_newest().time_us,
_min_obs_interval_us);
}
}
#endif // CONFIG_EKF2_BAROMETER
@@ -260,7 +276,8 @@ void EstimatorInterface::setAirspeedData(const airspeedSample &airspeed_sample)
_airspeed_buffer->push(airspeed_sample_new);
} else {
ECL_WARN("airspeed data too fast %" PRIi64 " < %" PRIu64 " + %d", time_us, _airspeed_buffer->get_newest().time_us, _min_obs_interval_us);
ECL_WARN("airspeed data too fast %" PRIi64 " < %" PRIu64 " + %d", time_us, _airspeed_buffer->get_newest().time_us,
_min_obs_interval_us);
}
}
#endif // CONFIG_EKF2_AIRSPEED
@@ -298,7 +315,8 @@ void EstimatorInterface::setRangeData(const sensor::rangeSample &range_sample)
_time_last_range_buffer_push = _time_latest_us;
} else {
ECL_WARN("range data too fast %" PRIi64 " < %" PRIu64 " + %d", time_us, _range_buffer->get_newest().time_us, _min_obs_interval_us);
ECL_WARN("range data too fast %" PRIi64 " < %" PRIu64 " + %d", time_us, _range_buffer->get_newest().time_us,
_min_obs_interval_us);
}
}
#endif // CONFIG_EKF2_RANGE_FINDER
@@ -335,7 +353,8 @@ void EstimatorInterface::setOpticalFlowData(const flowSample &flow)
_flow_buffer->push(optflow_sample_new);
} else {
ECL_WARN("optical flow data too fast %" PRIi64 " < %" PRIu64 " + %d", time_us, _flow_buffer->get_newest().time_us, _min_obs_interval_us);
ECL_WARN("optical flow data too fast %" PRIi64 " < %" PRIu64 " + %d", time_us, _flow_buffer->get_newest().time_us,
_min_obs_interval_us);
}
}
#endif // CONFIG_EKF2_OPTICAL_FLOW
@@ -374,7 +393,8 @@ void EstimatorInterface::setExtVisionData(const extVisionSample &evdata)
_time_last_ext_vision_buffer_push = _time_latest_us;
} else {
ECL_WARN("EV data too fast %" PRIi64 " < %" PRIu64 " + %d", time_us, _ext_vision_buffer->get_newest().time_us, _min_obs_interval_us);
ECL_WARN("EV data too fast %" PRIi64 " < %" PRIu64 " + %d", time_us, _ext_vision_buffer->get_newest().time_us,
_min_obs_interval_us);
}
}
#endif // CONFIG_EKF2_EXTERNAL_VISION
@@ -411,7 +431,8 @@ void EstimatorInterface::setAuxVelData(const auxVelSample &auxvel_sample)
_auxvel_buffer->push(auxvel_sample_new);
} else {
ECL_WARN("aux velocity data too fast %" PRIi64 " < %" PRIu64 " + %d", time_us, _auxvel_buffer->get_newest().time_us, _min_obs_interval_us);
ECL_WARN("aux velocity data too fast %" PRIi64 " < %" PRIu64 " + %d", time_us, _auxvel_buffer->get_newest().time_us,
_min_obs_interval_us);
}
}
#endif // CONFIG_EKF2_AUXVEL
@@ -446,7 +467,8 @@ void EstimatorInterface::setSystemFlagData(const systemFlagUpdate &system_flags)
_system_flag_buffer->push(system_flags_new);
} else {
ECL_DEBUG("system flag update too fast %" PRIi64 " < %" PRIu64 " + %d", time_us, _system_flag_buffer->get_newest().time_us, _min_obs_interval_us);
ECL_DEBUG("system flag update too fast %" PRIi64 " < %" PRIu64 " + %d", time_us,
_system_flag_buffer->get_newest().time_us, _min_obs_interval_us);
}
}
+13 -18
View File
@@ -293,10 +293,6 @@ public:
const innovation_fault_status_u &innov_check_fail_status() const { return _innov_check_fail_status; }
const decltype(innovation_fault_status_u::flags) &innov_check_fail_status_flags() const { return _innov_check_fail_status.flags; }
const warning_event_status_u &warning_event_status() const { return _warning_events; }
const decltype(warning_event_status_u::flags) &warning_event_flags() const { return _warning_events.flags; }
void clear_warning_events() { _warning_events.value = 0; }
const information_event_status_u &information_event_status() const { return _information_events; }
const decltype(information_event_status_u::flags) &information_event_flags() const { return _information_events.flags; }
void clear_information_events() { _information_events.value = 0; }
@@ -348,15 +344,15 @@ protected:
OutputPredictor _output_predictor{};
#if defined(CONFIG_EKF2_AIRSPEED)
airspeedSample _airspeed_sample_delayed{};
airspeedSample _airspeed_sample_delayed {};
#endif // CONFIG_EKF2_AIRSPEED
#if defined(CONFIG_EKF2_EXTERNAL_VISION)
extVisionSample _ev_sample_prev{};
extVisionSample _ev_sample_prev {};
#endif // CONFIG_EKF2_EXTERNAL_VISION
#if defined(CONFIG_EKF2_RANGE_FINDER)
RingBuffer<sensor::rangeSample> *_range_buffer{nullptr};
RingBuffer<sensor::rangeSample> *_range_buffer {nullptr};
uint64_t _time_last_range_buffer_push{0};
sensor::SensorRangeFinder _range_sensor{};
@@ -364,7 +360,7 @@ protected:
#endif // CONFIG_EKF2_RANGE_FINDER
#if defined(CONFIG_EKF2_OPTICAL_FLOW)
RingBuffer<flowSample> *_flow_buffer{nullptr};
RingBuffer<flowSample> *_flow_buffer {nullptr};
flowSample _flow_sample_delayed{};
@@ -387,7 +383,7 @@ protected:
float _gpos_origin_epv{0.0f}; // vertical position uncertainty of the global origin
#if defined(CONFIG_EKF2_GNSS)
RingBuffer<gnssSample> *_gps_buffer{nullptr};
RingBuffer<gnssSample> *_gps_buffer {nullptr};
uint64_t _time_last_gps_buffer_push{0};
gnssSample _gps_sample_delayed{};
@@ -406,7 +402,7 @@ protected:
#endif // CONFIG_EKF2_GNSS
#if defined(CONFIG_EKF2_DRAG_FUSION)
RingBuffer<dragSample> *_drag_buffer{nullptr};
RingBuffer<dragSample> *_drag_buffer {nullptr};
dragSample _drag_down_sampled{}; // down sampled drag specific force data (filter prediction rate -> observation rate)
#endif // CONFIG_EKF2_DRAG_FUSION
@@ -424,25 +420,25 @@ protected:
RingBuffer<imuSample> _imu_buffer{kBufferLengthDefault};
#if defined(CONFIG_EKF2_MAGNETOMETER)
RingBuffer<magSample> *_mag_buffer{nullptr};
RingBuffer<magSample> *_mag_buffer {nullptr};
uint64_t _time_last_mag_buffer_push{0};
#endif // CONFIG_EKF2_MAGNETOMETER
#if defined(CONFIG_EKF2_AIRSPEED)
RingBuffer<airspeedSample> *_airspeed_buffer{nullptr};
RingBuffer<airspeedSample> *_airspeed_buffer {nullptr};
#endif // CONFIG_EKF2_AIRSPEED
#if defined(CONFIG_EKF2_EXTERNAL_VISION)
RingBuffer<extVisionSample> *_ext_vision_buffer{nullptr};
RingBuffer<extVisionSample> *_ext_vision_buffer {nullptr};
uint64_t _time_last_ext_vision_buffer_push{0};
#endif // CONFIG_EKF2_EXTERNAL_VISION
#if defined(CONFIG_EKF2_AUXVEL)
RingBuffer<auxVelSample> *_auxvel_buffer{nullptr};
RingBuffer<auxVelSample> *_auxvel_buffer {nullptr};
#endif // CONFIG_EKF2_AUXVEL
RingBuffer<systemFlagUpdate> *_system_flag_buffer{nullptr};
RingBuffer<systemFlagUpdate> *_system_flag_buffer {nullptr};
#if defined(CONFIG_EKF2_BAROMETER)
RingBuffer<baroSample> *_baro_buffer{nullptr};
RingBuffer<baroSample> *_baro_buffer {nullptr};
uint64_t _time_last_baro_buffer_push{0};
#endif // CONFIG_EKF2_BAROMETER
@@ -457,7 +453,7 @@ protected:
uint64_t _wmm_gps_time_last_set{0}; // time WMM last set
#if defined(CONFIG_EKF2_MAGNETOMETER)
float _mag_declination_gps{NAN}; // magnetic declination returned by the geo library using the last valid GPS position (rad)
float _mag_declination_gps {NAN}; // magnetic declination returned by the geo library using the last valid GPS position (rad)
float _mag_inclination_gps{NAN}; // magnetic inclination returned by the geo library using the last valid GPS position (rad)
float _mag_strength_gps{NAN}; // magnetic strength returned by the geo library using the last valid GPS position (T)
@@ -473,7 +469,6 @@ protected:
// these are used to record single frame events for external monitoring and should NOT be used for
// state logic becasue they will be cleared externally after being read.
warning_event_status_u _warning_events{};
information_event_status_u _information_events{};
unsigned _min_obs_interval_us{0}; // minimum time interval between observations that will guarantee data is not lost (usec)
+10 -3
View File
@@ -45,7 +45,7 @@ void Ekf::controlHeightFusion(const imuSample &imu_delayed)
#if defined(CONFIG_EKF2_BAROMETER)
updateGroundEffect();
controlBaroHeightFusion();
controlBaroHeightFusion(imu_delayed);
#endif // CONFIG_EKF2_BAROMETER
#if defined(CONFIG_EKF2_GNSS)
@@ -53,7 +53,7 @@ void Ekf::controlHeightFusion(const imuSample &imu_delayed)
#endif // CONFIG_EKF2_GNSS
#if defined(CONFIG_EKF2_RANGE_FINDER)
controlRangeHaglFusion();
controlRangeHaglFusion(imu_delayed);
#endif // CONFIG_EKF2_RANGE_FINDER
checkHeightSensorRefFallback();
@@ -216,7 +216,6 @@ void Ekf::checkVerticalAccelerationBias(const imuSample &imu_delayed)
_time_acc_bias_check = imu_delayed.time_us;
_fault_status.flags.bad_acc_bias = false;
_warning_events.flags.invalid_accel_bias_cov_reset = true;
ECL_WARN("invalid accel bias - covariance reset");
}
}
@@ -294,12 +293,15 @@ Likelihood Ekf::estimateInertialNavFallingLikelihood() const
} checks[6] {};
#if defined(CONFIG_EKF2_BAROMETER)
if (_control_status.flags.baro_hgt) {
checks[0] = {ReferenceType::PRESSURE, _aid_src_baro_hgt.innovation, _aid_src_baro_hgt.innovation_variance};
}
#endif // CONFIG_EKF2_BAROMETER
#if defined(CONFIG_EKF2_GNSS)
if (_control_status.flags.gps_hgt) {
checks[1] = {ReferenceType::GNSS, _aid_src_gnss_hgt.innovation, _aid_src_gnss_hgt.innovation_variance};
}
@@ -307,16 +309,20 @@ Likelihood Ekf::estimateInertialNavFallingLikelihood() const
if (_control_status.flags.gps) {
checks[2] = {ReferenceType::GNSS, _aid_src_gnss_vel.innovation[2], _aid_src_gnss_vel.innovation_variance[2]};
}
#endif // CONFIG_EKF2_GNSS
#if defined(CONFIG_EKF2_RANGE_FINDER)
if (_control_status.flags.rng_hgt) {
// Range is a distance to ground measurement, not a direct height observation and has an opposite sign
checks[3] = {ReferenceType::GROUND, -_aid_src_rng_hgt.innovation, _aid_src_rng_hgt.innovation_variance};
}
#endif // CONFIG_EKF2_RANGE_FINDER
#if defined(CONFIG_EKF2_EXTERNAL_VISION)
if (_control_status.flags.ev_hgt) {
checks[4] = {ReferenceType::GROUND, _aid_src_ev_hgt.innovation, _aid_src_ev_hgt.innovation_variance};
}
@@ -324,6 +330,7 @@ Likelihood Ekf::estimateInertialNavFallingLikelihood() const
if (_control_status.flags.ev_vel) {
checks[5] = {ReferenceType::GROUND, _aid_src_ev_vel.innovation[2], _aid_src_ev_vel.innovation_variance[2]};
}
#endif // CONFIG_EKF2_EXTERNAL_VISION
// Compute the check based on innovation ratio for all the sources
@@ -261,7 +261,8 @@ void OutputPredictor::calculateOutputStates(const uint64_t time_us, const Vector
}
void OutputPredictor::correctOutputStates(const uint64_t time_delayed_us,
const Quatf &quat_state, const Vector3f &vel_state, const Vector3f &pos_state, const matrix::Vector3f &gyro_bias, const matrix::Vector3f &accel_bias)
const Quatf &quat_state, const Vector3f &vel_state, const Vector3f &pos_state, const matrix::Vector3f &gyro_bias,
const matrix::Vector3f &accel_bias)
{
// calculate an average filter update time
if (_time_last_correct_states_us != 0) {
@@ -365,7 +366,8 @@ void OutputPredictor::applyCorrectionToVerticalOutputBuffer(float vert_vel_corre
next_state.vert_vel += vert_vel_correction;
// position is propagated forward using the corrected velocity and a trapezoidal integrator
next_state.vert_vel_integ = current_state.vert_vel_integ + (current_state.vert_vel + next_state.vert_vel) * 0.5f * next_state.dt;
next_state.vert_vel_integ = current_state.vert_vel_integ + (current_state.vert_vel + next_state.vert_vel) * 0.5f *
next_state.dt;
// advance the index
index = (index + 1) % size;
@@ -67,7 +67,8 @@ public:
const matrix::Vector3f &delta_velocity, const float delta_velocity_dt);
void correctOutputStates(const uint64_t time_delayed_us,
const matrix::Quatf &quat_state, const matrix::Vector3f &vel_state, const matrix::Vector3f &pos_state, const matrix::Vector3f &gyro_bias, const matrix::Vector3f &accel_bias);
const matrix::Quatf &quat_state, const matrix::Vector3f &vel_state, const matrix::Vector3f &pos_state,
const matrix::Vector3f &gyro_bias, const matrix::Vector3f &accel_bias);
void resetQuaternion(const matrix::Quatf &quat_change);
+9 -6
View File
@@ -40,9 +40,9 @@ void Ekf::updateVerticalPositionAidStatus(estimator_aid_source1d_s &aid_src, con
float innovation_variance = getStateVariance<State::pos>()(2) + observation_variance;
updateAidSourceStatus(aid_src, time_us,
observation, observation_variance,
innovation, innovation_variance,
innovation_gate);
observation, observation_variance,
innovation, innovation_variance,
innovation_gate);
// z special case if there is bad vertical acceleration data, then don't reject measurement,
// but limit innovation to prevent spikes that could destabilise the filter
@@ -57,8 +57,10 @@ bool Ekf::fuseHorizontalPosition(estimator_aid_source2d_s &aid_src)
{
// x & y
if (!aid_src.innovation_rejected
&& fuseDirectStateMeasurement(aid_src.innovation[0], aid_src.innovation_variance[0], aid_src.observation_variance[0], State::pos.idx + 0)
&& fuseDirectStateMeasurement(aid_src.innovation[1], aid_src.innovation_variance[1], aid_src.observation_variance[1], State::pos.idx + 1)
&& fuseDirectStateMeasurement(aid_src.innovation[0], aid_src.innovation_variance[0], aid_src.observation_variance[0],
State::pos.idx + 0)
&& fuseDirectStateMeasurement(aid_src.innovation[1], aid_src.innovation_variance[1], aid_src.observation_variance[1],
State::pos.idx + 1)
) {
aid_src.fused = true;
aid_src.time_last_fuse = _time_delayed_us;
@@ -76,7 +78,8 @@ bool Ekf::fuseVerticalPosition(estimator_aid_source1d_s &aid_src)
{
// z
if (!aid_src.innovation_rejected
&& fuseDirectStateMeasurement(aid_src.innovation, aid_src.innovation_variance, aid_src.observation_variance, State::pos.idx + 2)
&& fuseDirectStateMeasurement(aid_src.innovation, aid_src.innovation_variance, aid_src.observation_variance,
State::pos.idx + 2)
) {
aid_src.fused = true;
aid_src.time_last_fuse = _time_delayed_us;
+3 -3
View File
@@ -64,8 +64,8 @@ void Ekf::controlTerrainFakeFusion()
}
if (!_control_status.flags.in_air
&& !_hagl_sensor_status.flags.range_finder
&& !_hagl_sensor_status.flags.flow) {
&& !_control_status.flags.rng_terrain
&& !_control_status.flags.opt_flow_terrain) {
bool recent_terrain_aiding = false;
@@ -93,7 +93,7 @@ bool Ekf::isTerrainEstimateValid() const
#if defined(CONFIG_EKF2_RANGE_FINDER)
// Assume that the terrain estimate is always valid when direct observations are fused
if (_hagl_sensor_status.flags.range_finder && isRecent(_aid_src_rng_hgt.time_last_fuse, (uint64_t)5e6)) {
if (_control_status.flags.rng_terrain && isRecent(_aid_src_rng_hgt.time_last_fuse, (uint64_t)5e6)) {
valid = true;
}
+10 -5
View File
@@ -37,8 +37,10 @@ bool Ekf::fuseHorizontalVelocity(estimator_aid_source2d_s &aid_src)
{
// vx, vy
if (!aid_src.innovation_rejected
&& fuseDirectStateMeasurement(aid_src.innovation[0], aid_src.innovation_variance[0], aid_src.observation_variance[0], State::vel.idx + 0)
&& fuseDirectStateMeasurement(aid_src.innovation[1], aid_src.innovation_variance[1], aid_src.observation_variance[1], State::vel.idx + 1)
&& fuseDirectStateMeasurement(aid_src.innovation[0], aid_src.innovation_variance[0], aid_src.observation_variance[0],
State::vel.idx + 0)
&& fuseDirectStateMeasurement(aid_src.innovation[1], aid_src.innovation_variance[1], aid_src.observation_variance[1],
State::vel.idx + 1)
) {
aid_src.fused = true;
aid_src.time_last_fuse = _time_delayed_us;
@@ -56,9 +58,12 @@ bool Ekf::fuseVelocity(estimator_aid_source3d_s &aid_src)
{
// vx, vy, vz
if (!aid_src.innovation_rejected
&& fuseDirectStateMeasurement(aid_src.innovation[0], aid_src.innovation_variance[0], aid_src.observation_variance[0], State::vel.idx + 0)
&& fuseDirectStateMeasurement(aid_src.innovation[1], aid_src.innovation_variance[1], aid_src.observation_variance[1], State::vel.idx + 1)
&& fuseDirectStateMeasurement(aid_src.innovation[2], aid_src.innovation_variance[2], aid_src.observation_variance[2], State::vel.idx + 2)
&& fuseDirectStateMeasurement(aid_src.innovation[0], aid_src.innovation_variance[0], aid_src.observation_variance[0],
State::vel.idx + 0)
&& fuseDirectStateMeasurement(aid_src.innovation[1], aid_src.innovation_variance[1], aid_src.observation_variance[1],
State::vel.idx + 1)
&& fuseDirectStateMeasurement(aid_src.innovation[2], aid_src.innovation_variance[2], aid_src.observation_variance[2],
State::vel.idx + 2)
) {
aid_src.fused = true;
aid_src.time_last_fuse = _time_delayed_us;
@@ -301,7 +301,8 @@ void EKFGSF_yaw::predictEKF(const uint8_t model_index, const Vector3f &delta_ang
// Use fixed values for delta angle process noise variances
const float d_ang_var = sq(_gyro_noise * delta_ang_dt);
_ekf_gsf[model_index].P = sym::YawEstPredictCovariance(_ekf_gsf[model_index].X, _ekf_gsf[model_index].P, Vector2f(dvx, dvy), d_vel_var, daz, d_ang_var);
_ekf_gsf[model_index].P = sym::YawEstPredictCovariance(_ekf_gsf[model_index].X, _ekf_gsf[model_index].P, Vector2f(dvx,
dvy), d_vel_var, daz, d_ang_var);
// covariance matrix is symmetrical, so copy upper half to lower half
_ekf_gsf[model_index].P(1, 0) = _ekf_gsf[model_index].P(0, 1);
+2
View File
@@ -145,11 +145,13 @@ void Ekf::resetQuatStateYaw(float yaw, float yaw_variance)
_output_predictor.resetQuaternion(q_error);
#if defined(CONFIG_EKF2_EXTERNAL_VISION)
// update EV attitude error filter
if (_ev_q_error_initialized) {
const Quatf ev_q_error_updated = (q_error * _ev_q_error_filt.getState()).normalized();
_ev_q_error_filt.reset(ev_q_error_updated);
}
#endif // CONFIG_EKF2_EXTERNAL_VISION
// record the state change
+19 -29
View File
@@ -1107,16 +1107,7 @@ void EKF2::PublishEventFlags(const hrt_abstime &timestamp)
_filter_information_event_changes++;
}
// warning events
uint32_t warning_events = _ekf.warning_event_status().value;
bool warning_event_updated = false;
if (warning_events != 0) {
warning_event_updated = true;
_filter_warning_event_changes++;
}
if (information_event_updated || warning_event_updated) {
if (information_event_updated) {
estimator_event_flags_s event_flags{};
event_flags.timestamp_sample = _ekf.time_delayed_us();
@@ -1139,27 +1130,12 @@ void EKF2::PublishEventFlags(const hrt_abstime &timestamp)
event_flags.reset_hgt_to_rng = _ekf.information_event_flags().reset_hgt_to_rng;
event_flags.reset_hgt_to_ev = _ekf.information_event_flags().reset_hgt_to_ev;
event_flags.warning_event_changes = _filter_warning_event_changes;
event_flags.gps_quality_poor = _ekf.warning_event_flags().gps_quality_poor;
event_flags.gps_fusion_timout = _ekf.warning_event_flags().gps_fusion_timout;
event_flags.gps_data_stopped = _ekf.warning_event_flags().gps_data_stopped;
event_flags.gps_data_stopped_using_alternate = _ekf.warning_event_flags().gps_data_stopped_using_alternate;
event_flags.height_sensor_timeout = _ekf.warning_event_flags().height_sensor_timeout;
event_flags.stopping_navigation = _ekf.warning_event_flags().stopping_mag_use;
event_flags.invalid_accel_bias_cov_reset = _ekf.warning_event_flags().invalid_accel_bias_cov_reset;
event_flags.bad_yaw_using_gps_course = _ekf.warning_event_flags().bad_yaw_using_gps_course;
event_flags.stopping_mag_use = _ekf.warning_event_flags().stopping_mag_use;
event_flags.vision_data_stopped = _ekf.warning_event_flags().vision_data_stopped;
event_flags.emergency_yaw_reset_mag_stopped = _ekf.warning_event_flags().emergency_yaw_reset_mag_stopped;
event_flags.emergency_yaw_reset_gps_yaw_stopped = _ekf.warning_event_flags().emergency_yaw_reset_gps_yaw_stopped;
event_flags.timestamp = _replay_mode ? timestamp : hrt_absolute_time();
_estimator_event_flags_pub.update(event_flags);
_last_event_flags_publish = event_flags.timestamp;
_ekf.clear_information_events();
_ekf.clear_warning_events();
} else if ((_last_event_flags_publish != 0) && (timestamp >= _last_event_flags_publish + 1_s)) {
// continue publishing periodically
@@ -1253,6 +1229,7 @@ void EKF2::PublishGpsStatus(const hrt_abstime &timestamp)
estimator_gps_status.check_fail_max_vert_drift = _ekf.gps_check_fail_status_flags().vdrift;
estimator_gps_status.check_fail_max_horz_spd_err = _ekf.gps_check_fail_status_flags().hspeed;
estimator_gps_status.check_fail_max_vert_spd_err = _ekf.gps_check_fail_status_flags().vspeed;
estimator_gps_status.check_fail_spoofed_gps = _ekf.gps_check_fail_status_flags().spoofed;
estimator_gps_status.timestamp = _replay_mode ? timestamp : hrt_absolute_time();
_estimator_gps_status_pub.publish(estimator_gps_status);
@@ -1643,8 +1620,19 @@ void EKF2::PublishLocalPosition(const hrt_abstime &timestamp)
#if defined(CONFIG_EKF2_TERRAIN)
// Distance to bottom surface (ground) in meters, must be positive
lpos.dist_bottom = math::max(_ekf.getHagl(), 0.f);
lpos.dist_bottom_var = _ekf.getTerrainVariance();
lpos.dist_bottom_valid = _ekf.isTerrainEstimateValid();
lpos.dist_bottom_sensor_bitfield = _ekf.getTerrainEstimateSensorBitfield();
lpos.dist_bottom_sensor_bitfield = vehicle_local_position_s::DIST_BOTTOM_SENSOR_NONE;
if (_ekf.control_status_flags().rng_terrain) {
lpos.dist_bottom_sensor_bitfield |= vehicle_local_position_s::DIST_BOTTOM_SENSOR_RANGE;
}
if (_ekf.control_status_flags().opt_flow_terrain) {
lpos.dist_bottom_sensor_bitfield |= vehicle_local_position_s::DIST_BOTTOM_SENSOR_FLOW;
}
#endif // CONFIG_EKF2_TERRAIN
_ekf.get_ekf_lpos_accuracy(&lpos.eph, &lpos.epv);
@@ -1937,6 +1925,8 @@ void EKF2::PublishStatusFlags(const hrt_abstime &timestamp)
status_flags.cs_ev_yaw_fault = _ekf.control_status_flags().ev_yaw_fault;
status_flags.cs_mag_heading_consistent = _ekf.control_status_flags().mag_heading_consistent;
status_flags.cs_aux_gpos = _ekf.control_status_flags().aux_gpos;
status_flags.cs_rng_terrain = _ekf.control_status_flags().rng_terrain;
status_flags.cs_opt_flow_terrain = _ekf.control_status_flags().opt_flow_terrain;
status_flags.fault_status_changes = _filter_fault_status_changes;
status_flags.fs_bad_mag_x = _ekf.fault_status_flags().bad_mag_x;
@@ -2043,7 +2033,7 @@ void EKF2::PublishOpticalFlowVel(const hrt_abstime &timestamp)
_ekf.getFlowGyro().copyTo(flow_vel.gyro_rate);
_ekf.getFlowGyroBias().copyTo(flow_vel.gyro_bias);
_ekf.getRefBodyRate().copyTo(flow_vel.ref_gyro);
_ekf.getFlowRefBodyRate().copyTo(flow_vel.ref_gyro);
flow_vel.timestamp = _replay_mode ? timestamp : hrt_absolute_time();
@@ -2447,6 +2437,7 @@ void EKF2::UpdateGpsSample(ekf2_timestamps_s &ekf2_timestamps)
.yaw = vehicle_gps_position.heading, //TODO: move to different message
.yaw_acc = vehicle_gps_position.heading_accuracy,
.yaw_offset = vehicle_gps_position.heading_offset,
.spoofed = vehicle_gps_position.spoofing_state == sensor_gps_s::SPOOFING_STATE_MULTIPLE,
};
_ekf.setGpsData(gnss_sample);
@@ -2661,8 +2652,7 @@ void EKF2::UpdateAccelCalibration(const hrt_abstime &timestamp)
&& (_ekf.fault_status().value == 0)
&& !_ekf.fault_status_flags().bad_acc_bias
&& !_ekf.fault_status_flags().bad_acc_clipping
&& !_ekf.fault_status_flags().bad_acc_vertical
&& !_ekf.warning_event_flags().invalid_accel_bias_cov_reset;
&& !_ekf.fault_status_flags().bad_acc_vertical;
const bool learning_valid = bias_valid && !_ekf.accel_bias_inhibited();
-1
View File
@@ -418,7 +418,6 @@ private:
uint32_t _filter_control_status_changes{0};
uint32_t _filter_fault_status_changes{0};
uint32_t _innov_check_fail_status_changes{0};
uint32_t _filter_warning_event_changes{0};
uint32_t _filter_information_event_changes{0};
uORB::PublicationMulti<ekf2_timestamps_s> _ekf2_timestamps_pub{ORB_ID(ekf2_timestamps)};
+3 -2
View File
@@ -136,7 +136,7 @@ parameters:
run when the vehicle is on ground and stationary. 7 : Maximum allowed horizontal
speed set by EKF2_REQ_HDRIFT. This check will only run when the vehicle
is on ground and stationary. 8 : Maximum allowed vertical velocity discrepancy
set by EKF2_REQ_VDRIFT'
set by EKF2_REQ_VDRIFT. 9: Fails if GPS driver detects consistent spoofing'
type: bitmask
bit:
0: Min sat count (EKF2_REQ_NSATS)
@@ -148,9 +148,10 @@ parameters:
6: Max vertical position rate (EKF2_REQ_VDRIFT)
7: Max horizontal speed (EKF2_REQ_HDRIFT)
8: Max vertical velocity discrepancy (EKF2_REQ_VDRIFT)
9: Spoofing check
default: 245
min: 0
max: 511
max: 1023
EKF2_REQ_EPH:
description:
short: Required EPH to use GPS
@@ -75,14 +75,14 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
7290000,0.78,-0.025,0.0067,-0.62,-0.38,-0.098,-0.14,-0.3,-0.082,-3.7e+02,5.3e-05,-0.011,-0.00022,-0.0016,-0.00042,0.00015,-0.1,-0.024,0.5,-0.0019,-0.085,-0.068,0,0,-3.6e+02,0.0013,0.0013,0.056,0.33,0.33,0.2,0.3,0.3,0.14,7.3e-05,7.5e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00013,0.0013,0.00081,0.0013,0.0013,1,1,1.9
7390000,0.78,-0.024,0.0068,-0.62,-0.41,-0.11,-0.16,-0.34,-0.093,-3.7e+02,7.4e-05,-0.011,-0.00022,-0.0017,-0.00046,8.6e-07,-0.1,-0.024,0.5,-0.0018,-0.085,-0.068,0,0,-3.6e+02,0.0013,0.0014,0.056,0.37,0.37,0.18,0.36,0.36,0.13,7.3e-05,7.4e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00012,0.0013,0.00081,0.0013,0.0013,1,1,1.9
7490000,0.78,-0.024,0.0069,-0.62,-0.43,-0.12,-0.16,-0.38,-0.11,-3.7e+02,0.00021,-0.011,-0.00023,-0.0019,-0.00054,-0.00076,-0.1,-0.024,0.5,-0.002,-0.085,-0.069,0,0,-3.6e+02,0.0013,0.0014,0.055,0.42,0.42,0.15,0.43,0.43,0.12,7.2e-05,7.4e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00011,0.0013,0.0008,0.0013,0.0013,1,1,1.9
7590000,0.78,-0.024,0.007,-0.62,-0.45,-0.12,-0.16,-0.41,-0.12,-3.7e+02,0.0002,-0.011,-0.00022,-0.0018,-0.00051,-0.0016,-0.1,-0.024,0.5,-0.0019,-0.085,-0.068,0,0,-3.6e+02,0.0013,0.0014,0.055,0.46,0.46,0.14,0.52,0.51,0.12,7.2e-05,7.3e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00011,0.0013,0.0008,0.0013,0.0013,1,1,1.9
7590000,0.78,-0.024,0.007,-0.62,-0.45,-0.12,-0.16,-0.41,-0.12,-3.7e+02,0.0002,-0.011,-0.00022,-0.0018,-0.00052,-0.0016,-0.1,-0.024,0.5,-0.0019,-0.085,-0.068,0,0,-3.6e+02,0.0013,0.0014,0.055,0.46,0.46,0.14,0.52,0.51,0.12,7.2e-05,7.3e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00011,0.0013,0.0008,0.0013,0.0013,1,1,1.9
7690000,0.78,-0.024,0.007,-0.62,-0.011,-0.0016,-0.16,-0.44,-0.14,-3.7e+02,0.00029,-0.011,-0.00022,-0.0019,-0.00051,-0.0036,-0.1,-0.024,0.5,-0.002,-0.085,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,25,25,0.13,1e+02,1e+02,0.11,7.1e-05,7.3e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.0001,0.0013,0.0008,0.0013,0.0013,1,1,2
7790000,0.78,-0.024,0.0073,-0.62,-0.038,-0.0061,-0.16,-0.44,-0.14,-3.7e+02,0.00035,-0.011,-0.00023,-0.0019,-0.00051,-0.0056,-0.1,-0.024,0.5,-0.002,-0.085,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,25,25,0.12,1e+02,1e+02,0.11,7e-05,7.2e-05,2.4e-06,0.04,0.04,0.038,0.0013,0.0001,0.0013,0.00079,0.0013,0.0013,1,1,2
7890000,0.78,-0.024,0.0072,-0.62,-0.063,-0.011,-0.15,-0.44,-0.14,-3.7e+02,0.00039,-0.011,-0.00022,-0.0019,-0.00051,-0.0081,-0.1,-0.024,0.5,-0.0021,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,25,25,0.11,50,50,0.1,6.9e-05,7.1e-05,2.4e-06,0.04,0.04,0.038,0.0013,9.8e-05,0.0013,0.00079,0.0013,0.0013,1,1,2
7890000,0.78,-0.024,0.0072,-0.62,-0.063,-0.011,-0.15,-0.44,-0.14,-3.7e+02,0.00039,-0.011,-0.00022,-0.0019,-0.00051,-0.0081,-0.1,-0.024,0.5,-0.0021,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,25,25,0.11,50,50,0.1,6.9e-05,7e-05,2.4e-06,0.04,0.04,0.038,0.0013,9.8e-05,0.0013,0.00079,0.0013,0.0013,1,1,2
7990000,0.78,-0.024,0.0072,-0.62,-0.089,-0.016,-0.16,-0.45,-0.14,-3.7e+02,0.0004,-0.011,-0.00022,-0.0019,-0.00051,-0.0094,-0.1,-0.024,0.5,-0.0021,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,25,25,0.1,51,51,0.099,6.7e-05,6.9e-05,2.4e-06,0.04,0.04,0.038,0.0013,9.5e-05,0.0013,0.00079,0.0013,0.0013,1,1,2
8090000,0.78,-0.024,0.0071,-0.62,-0.11,-0.021,-0.17,-0.45,-0.14,-3.7e+02,0.00044,-0.01,-0.00021,-0.0019,-0.00051,-0.0096,-0.1,-0.024,0.5,-0.0022,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,24,24,0.1,35,35,0.097,6.6e-05,6.8e-05,2.4e-06,0.04,0.04,0.037,0.0013,9.4e-05,0.0013,0.00079,0.0013,0.0013,1,1,2.1
8190000,0.78,-0.024,0.0073,-0.62,-0.14,-0.025,-0.18,-0.47,-0.14,-3.7e+02,0.00043,-0.01,-0.00021,-0.0019,-0.00051,-0.012,-0.1,-0.024,0.5,-0.0022,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,25,25,0.099,36,36,0.094,6.4e-05,6.6e-05,2.4e-06,0.04,0.04,0.037,0.0013,9.2e-05,0.0013,0.00078,0.0013,0.0013,1,1,2.1
8290000,0.78,-0.024,0.0073,-0.62,-0.16,-0.03,-0.17,-0.47,-0.14,-3.7e+02,0.00053,-0.01,-0.00021,-0.0019,-0.00051,-0.016,-0.1,-0.024,0.5,-0.0023,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.054,24,24,0.097,28,28,0.091,6.3e-05,6.4e-05,2.4e-06,0.04,0.04,0.036,0.0013,9e-05,0.0013,0.00078,0.0013,0.0013,1,1,2.1
8290000,0.78,-0.024,0.0073,-0.62,-0.16,-0.03,-0.17,-0.47,-0.14,-3.7e+02,0.00053,-0.01,-0.00021,-0.0019,-0.00051,-0.016,-0.1,-0.024,0.5,-0.0023,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.054,24,24,0.097,28,28,0.091,6.2e-05,6.4e-05,2.4e-06,0.04,0.04,0.036,0.0013,9e-05,0.0013,0.00078,0.0013,0.0013,1,1,2.1
8390000,0.78,-0.024,0.007,-0.63,-0.18,-0.036,-0.17,-0.48,-0.15,-3.7e+02,0.00055,-0.01,-0.00021,-0.0019,-0.00051,-0.019,-0.1,-0.024,0.5,-0.0024,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.054,24,24,0.097,29,29,0.091,6.1e-05,6.3e-05,2.4e-06,0.04,0.04,0.035,0.0013,8.9e-05,0.0013,0.00078,0.0013,0.0013,1,1,2.1
8490000,0.78,-0.024,0.007,-0.63,-0.2,-0.04,-0.17,-0.49,-0.15,-3.7e+02,0.00056,-0.0099,-0.0002,-0.0019,-0.00051,-0.024,-0.1,-0.024,0.5,-0.0024,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.054,23,23,0.096,24,24,0.089,5.9e-05,6.1e-05,2.4e-06,0.04,0.04,0.034,0.0013,8.8e-05,0.0013,0.00077,0.0013,0.0013,1,1,2.2
8590000,0.78,-0.023,0.0072,-0.63,-0.22,-0.038,-0.17,-0.51,-0.15,-3.7e+02,0.00036,-0.0099,-0.0002,-0.0019,-0.00051,-0.028,-0.1,-0.024,0.5,-0.0022,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.054,23,23,0.095,26,26,0.088,5.6e-05,5.9e-05,2.4e-06,0.04,0.04,0.034,0.0013,8.7e-05,0.0013,0.00077,0.0013,0.0013,1,1,2.2
@@ -92,41 +92,41 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
8990000,0.78,-0.023,0.0068,-0.63,-0.27,-0.053,-0.14,-0.55,-0.16,-3.7e+02,0.00045,-0.0093,-0.00018,-0.0019,-0.00051,-0.049,-0.1,-0.024,0.5,-0.0026,-0.086,-0.069,0,0,-3.6e+02,0.0013,0.0014,0.054,19,19,0.096,24,24,0.087,4.8e-05,5e-05,2.4e-06,0.04,0.04,0.029,0.0012,8.3e-05,0.0013,0.00075,0.0013,0.0013,1,1,2.3
9090000,0.78,-0.022,0.0068,-0.63,-0.29,-0.054,-0.14,-0.58,-0.17,-3.7e+02,0.00037,-0.0092,-0.00018,-0.0019,-0.00051,-0.052,-0.1,-0.024,0.5,-0.0025,-0.086,-0.069,0,0,-3.6e+02,0.0013,0.0014,0.054,19,19,0.095,27,27,0.086,4.6e-05,4.8e-05,2.4e-06,0.04,0.04,0.028,0.0012,8.2e-05,0.0013,0.00075,0.0013,0.0013,1,1,2.3
9190000,0.78,-0.022,0.0061,-0.63,-0.3,-0.064,-0.14,-0.6,-0.17,-3.7e+02,0.00038,-0.0088,-0.00017,-0.0018,-0.0003,-0.055,-0.11,-0.025,0.5,-0.0027,-0.087,-0.069,0,0,-3.6e+02,0.0013,0.0013,0.054,19,19,0.094,30,30,0.085,4.3e-05,4.5e-05,2.4e-06,0.04,0.04,0.027,0.0012,8.2e-05,0.0013,0.00074,0.0013,0.0013,1,1,2.3
9290000,0.78,-0.022,0.0058,-0.63,-0.31,-0.073,-0.14,-0.62,-0.18,-3.7e+02,0.0004,-0.0086,-0.00016,-0.0018,-6.5e-05,-0.059,-0.11,-0.025,0.5,-0.0029,-0.087,-0.069,0,0,-3.6e+02,0.0013,0.0013,0.054,19,19,0.093,34,34,0.085,4.1e-05,4.3e-05,2.4e-06,0.04,0.04,0.025,0.0012,8.1e-05,0.0013,0.00074,0.0013,0.0013,1,1,2.4
9290000,0.78,-0.022,0.0058,-0.63,-0.31,-0.073,-0.14,-0.62,-0.18,-3.7e+02,0.0004,-0.0086,-0.00016,-0.0018,-6.6e-05,-0.059,-0.11,-0.025,0.5,-0.0029,-0.087,-0.069,0,0,-3.6e+02,0.0013,0.0013,0.054,19,19,0.093,34,34,0.085,4.1e-05,4.3e-05,2.4e-06,0.04,0.04,0.025,0.0012,8.1e-05,0.0013,0.00074,0.0013,0.0013,1,1,2.4
9390000,0.78,-0.022,0.0057,-0.63,-0.33,-0.082,-0.13,-0.65,-0.19,-3.7e+02,0.00043,-0.0085,-0.00016,-0.0019,0.00012,-0.063,-0.11,-0.025,0.5,-0.003,-0.087,-0.069,0,0,-3.6e+02,0.0013,0.0013,0.054,19,19,0.093,38,38,0.086,3.9e-05,4.1e-05,2.4e-06,0.04,0.04,0.024,0.0012,8e-05,0.0013,0.00074,0.0013,0.0013,1,1,2.4
9490000,0.78,-0.022,0.0052,-0.63,-0.33,-0.095,-0.13,-0.67,-0.21,-3.7e+02,0.00046,-0.0082,-0.00015,-0.0018,0.00038,-0.067,-0.11,-0.025,0.5,-0.0032,-0.087,-0.069,0,0,-3.6e+02,0.0013,0.0013,0.054,19,19,0.091,42,42,0.085,3.7e-05,3.9e-05,2.4e-06,0.04,0.04,0.023,0.0012,8e-05,0.0013,0.00073,0.0013,0.0013,1,1,2.4
9590000,0.78,-0.022,0.0049,-0.63,-0.34,-0.094,-0.13,-0.7,-0.22,-3.7e+02,0.00031,-0.008,-0.00014,-0.0018,0.00067,-0.07,-0.11,-0.025,0.5,-0.0031,-0.087,-0.069,0,0,-3.6e+02,0.0012,0.0013,0.054,20,20,0.09,47,47,0.085,3.5e-05,3.7e-05,2.4e-06,0.04,0.04,0.022,0.0012,7.9e-05,0.0013,0.00073,0.0013,0.0013,1,1,2.4
9590000,0.78,-0.022,0.0049,-0.63,-0.34,-0.094,-0.13,-0.7,-0.22,-3.7e+02,0.00031,-0.008,-0.00014,-0.0018,0.00066,-0.07,-0.11,-0.025,0.5,-0.0031,-0.087,-0.069,0,0,-3.6e+02,0.0012,0.0013,0.054,20,20,0.09,47,47,0.085,3.5e-05,3.7e-05,2.4e-06,0.04,0.04,0.022,0.0012,7.9e-05,0.0013,0.00073,0.0013,0.0013,1,1,2.4
9690000,0.78,-0.022,0.0051,-0.63,-0.36,-0.092,-0.12,-0.73,-0.22,-3.7e+02,0.00022,-0.008,-0.00014,-0.0021,0.0009,-0.075,-0.11,-0.025,0.5,-0.003,-0.087,-0.069,0,0,-3.6e+02,0.0012,0.0012,0.054,20,20,0.089,53,53,0.086,3.3e-05,3.5e-05,2.4e-06,0.04,0.04,0.02,0.0012,7.9e-05,0.0013,0.00072,0.0013,0.0013,1,1,2.5
9790000,0.78,-0.022,0.0047,-0.63,-0.37,-0.1,-0.11,-0.75,-0.24,-3.7e+02,0.00023,-0.0078,-0.00014,-0.0021,0.0012,-0.081,-0.11,-0.025,0.5,-0.0031,-0.087,-0.069,0,0,-3.6e+02,0.0012,0.0012,0.054,20,20,0.087,58,58,0.085,3.1e-05,3.3e-05,2.4e-06,0.04,0.04,0.019,0.0012,7.8e-05,0.0013,0.00072,0.0013,0.0013,1,1,2.5
9890000,0.78,-0.021,0.0045,-0.63,-0.37,-0.11,-0.11,-0.78,-0.24,-3.7e+02,0.00014,-0.0077,-0.00013,-0.0021,0.0014,-0.083,-0.11,-0.025,0.5,-0.0031,-0.087,-0.069,0,0,-3.6e+02,0.0012,0.0012,0.054,20,20,0.084,64,64,0.085,2.9e-05,3.2e-05,2.4e-06,0.04,0.04,0.018,0.0012,7.8e-05,0.0013,0.00072,0.0013,0.0013,1,1,2.5
9990000,0.78,-0.021,0.0045,-0.63,-0.39,-0.11,-0.1,-0.81,-0.25,-3.7e+02,9.8e-05,-0.0077,-0.00013,-0.0023,0.0016,-0.087,-0.11,-0.025,0.5,-0.0031,-0.088,-0.069,0,0,-3.6e+02,0.0012,0.0012,0.054,20,20,0.083,71,71,0.086,2.8e-05,3e-05,2.4e-06,0.04,0.04,0.017,0.0012,7.8e-05,0.0013,0.00071,0.0013,0.0013,1,1,2.5
10090000,0.78,-0.021,0.0043,-0.63,-0.39,-0.11,-0.096,-0.84,-0.26,-3.7e+02,-9.1e-06,-0.0075,-0.00012,-0.0023,0.0018,-0.09,-0.11,-0.025,0.5,-0.003,-0.088,-0.069,0,0,-3.6e+02,0.0012,0.0012,0.054,20,20,0.08,78,78,0.085,2.6e-05,2.9e-05,2.4e-06,0.04,0.04,0.016,0.0012,7.7e-05,0.0013,0.00071,0.0013,0.0013,1,1,2.6
10090000,0.78,-0.021,0.0043,-0.63,-0.39,-0.11,-0.096,-0.84,-0.26,-3.7e+02,-9.2e-06,-0.0075,-0.00012,-0.0023,0.0018,-0.09,-0.11,-0.025,0.5,-0.003,-0.088,-0.069,0,0,-3.6e+02,0.0012,0.0012,0.054,20,20,0.08,78,78,0.085,2.6e-05,2.9e-05,2.4e-06,0.04,0.04,0.016,0.0012,7.7e-05,0.0013,0.00071,0.0013,0.0013,1,1,2.6
10190000,0.78,-0.021,0.0045,-0.63,-0.42,-0.1,-0.096,-0.88,-0.26,-3.7e+02,-4.1e-05,-0.0076,-0.00012,-0.0024,0.0019,-0.091,-0.11,-0.025,0.5,-0.0029,-0.088,-0.069,0,0,-3.6e+02,0.0011,0.0011,0.054,20,20,0.078,85,85,0.084,2.5e-05,2.7e-05,2.4e-06,0.04,0.04,0.015,0.0012,7.7e-05,0.0013,0.00071,0.0013,0.0013,1,1,2.6
10290000,0.78,-0.021,0.0047,-0.63,-0.44,-0.1,-0.083,-0.92,-0.27,-3.7e+02,-6.8e-05,-0.0076,-0.00012,-0.0026,0.0022,-0.097,-0.11,-0.025,0.5,-0.0029,-0.088,-0.069,0,0,-3.6e+02,0.0011,0.0011,0.054,20,20,0.076,92,92,0.085,2.4e-05,2.6e-05,2.4e-06,0.04,0.04,0.014,0.0012,7.6e-05,0.0013,0.0007,0.0013,0.0013,1,1,2.6
10390000,0.78,-0.021,0.0045,-0.63,-0.0085,-0.022,0.0097,8e-05,-0.0019,-3.7e+02,-5.8e-05,-0.0075,-0.00012,-0.0026,0.0023,-0.1,-0.11,-0.025,0.5,-0.003,-0.088,-0.069,0,0,-3.6e+02,0.0011,0.0011,0.054,0.25,0.25,0.56,0.25,0.25,0.078,2.2e-05,2.4e-05,2.3e-06,0.04,0.04,0.013,0.0012,7.6e-05,0.0013,0.0007,0.0013,0.0013,1,1,2.6
10490000,0.78,-0.021,0.0046,-0.63,-0.028,-0.025,0.023,-0.0017,-0.0043,-3.7e+02,-8e-05,-0.0075,-0.00012,-0.0028,0.0025,-0.1,-0.11,-0.025,0.5,-0.0029,-0.088,-0.069,0,0,-3.6e+02,0.0011,0.0011,0.054,0.25,0.25,0.55,0.26,0.26,0.08,2.1e-05,2.3e-05,2.3e-06,0.04,0.04,0.012,0.0012,7.6e-05,0.0013,0.0007,0.0013,0.0013,1,1,2.7
10590000,0.78,-0.02,0.0043,-0.63,-0.026,-0.014,0.026,0.0015,-0.00091,-3.7e+02,-0.00026,-0.0074,-0.00011,-0.0019,0.0024,-0.1,-0.11,-0.025,0.5,-0.0028,-0.088,-0.069,0,0,-3.6e+02,0.0011,0.0011,0.054,0.13,0.13,0.27,0.13,0.13,0.073,2e-05,2.2e-05,2.3e-06,0.04,0.04,0.012,0.0012,7.6e-05,0.0013,0.0007,0.0013,0.0013,1,1,2.7
10690000,0.78,-0.02,0.0042,-0.63,-0.043,-0.015,0.03,-0.002,-0.0024,-3.7e+02,-0.00028,-0.0073,-0.00011,-0.0019,0.0025,-0.11,-0.11,-0.025,0.5,-0.0028,-0.088,-0.069,0,0,-3.6e+02,0.001,0.001,0.054,0.13,0.13,0.26,0.14,0.14,0.078,1.9e-05,2.1e-05,2.3e-06,0.04,0.04,0.011,0.0012,7.6e-05,0.0013,0.00069,0.0013,0.0013,1,1,2.7
10790000,0.78,-0.02,0.0038,-0.63,-0.04,-0.011,0.024,0.001,-0.0011,-3.7e+02,-0.00033,-0.0072,-0.0001,-0.00016,0.0013,-0.11,-0.11,-0.025,0.5,-0.0029,-0.088,-0.069,0,0,-3.6e+02,0.001,0.001,0.054,0.091,0.091,0.17,0.09,0.09,0.072,1.7e-05,1.9e-05,2.3e-06,0.039,0.039,0.011,0.0012,7.6e-05,0.0013,0.00069,0.0013,0.0013,1,1,2.7
10890000,0.78,-0.02,0.0037,-0.63,-0.057,-0.013,0.02,-0.0036,-0.0024,-3.7e+02,-0.00035,-0.0071,-0.0001,-0.0001,0.0014,-0.11,-0.11,-0.025,0.5,-0.0029,-0.088,-0.069,0,0,-3.6e+02,0.00099,0.00099,0.054,0.099,0.099,0.16,0.096,0.096,0.075,1.7e-05,1.8e-05,2.3e-06,0.039,0.039,0.011,0.0012,7.6e-05,0.0013,0.00069,0.0013,0.0013,1,1,2.8
10790000,0.78,-0.02,0.0038,-0.63,-0.04,-0.011,0.024,0.001,-0.0011,-3.7e+02,-0.00033,-0.0072,-0.0001,-0.00015,0.0013,-0.11,-0.11,-0.025,0.5,-0.0029,-0.088,-0.069,0,0,-3.6e+02,0.001,0.001,0.054,0.091,0.091,0.17,0.09,0.09,0.072,1.7e-05,1.9e-05,2.3e-06,0.039,0.039,0.011,0.0012,7.6e-05,0.0013,0.00069,0.0013,0.0013,1,1,2.7
10890000,0.78,-0.02,0.0037,-0.63,-0.057,-0.013,0.02,-0.0036,-0.0024,-3.7e+02,-0.00035,-0.0071,-0.0001,-9.7e-05,0.0014,-0.11,-0.11,-0.025,0.5,-0.0029,-0.088,-0.069,0,0,-3.6e+02,0.00099,0.00099,0.054,0.099,0.099,0.16,0.096,0.096,0.075,1.7e-05,1.8e-05,2.3e-06,0.039,0.039,0.011,0.0012,7.6e-05,0.0013,0.00069,0.0013,0.0013,1,1,2.8
10990000,0.78,-0.02,0.003,-0.63,-0.048,-0.011,0.015,0.00017,-0.0012,-3.7e+02,-0.00038,-0.0069,-9.7e-05,0.0036,-0.00085,-0.11,-0.11,-0.025,0.5,-0.0031,-0.089,-0.069,0,0,-3.6e+02,0.00093,0.00094,0.053,0.078,0.078,0.12,0.098,0.098,0.071,1.5e-05,1.7e-05,2.3e-06,0.038,0.038,0.011,0.0012,7.6e-05,0.0013,0.00069,0.0013,0.0013,1,1,2.8
11090000,0.78,-0.02,0.0026,-0.63,-0.06,-0.015,0.02,-0.0047,-0.0027,-3.7e+02,-0.00042,-0.0068,-9.2e-05,0.0037,-0.00042,-0.11,-0.11,-0.025,0.5,-0.0031,-0.089,-0.07,0,0,-3.6e+02,0.00092,0.00092,0.053,0.087,0.088,0.11,0.11,0.11,0.074,1.5e-05,1.6e-05,2.3e-06,0.038,0.038,0.011,0.0012,7.6e-05,0.0013,0.00068,0.0013,0.0013,1,1,2.8
11190000,0.78,-0.019,0.0021,-0.63,-0.053,-0.011,0.0082,0.00075,-0.00057,-3.7e+02,-0.00052,-0.0067,-8.9e-05,0.0082,-0.0036,-0.11,-0.11,-0.025,0.5,-0.0031,-0.089,-0.07,0,0,-3.6e+02,0.00085,0.00086,0.053,0.073,0.073,0.084,0.11,0.11,0.069,1.3e-05,1.5e-05,2.3e-06,0.037,0.037,0.011,0.0012,7.6e-05,0.0013,0.00068,0.0013,0.0013,1,1,2.8
11290000,0.78,-0.019,0.0022,-0.63,-0.069,-0.013,0.008,-0.0056,-0.0018,-3.7e+02,-0.00049,-0.0067,-9.1e-05,0.0083,-0.0038,-0.11,-0.11,-0.025,0.5,-0.0032,-0.089,-0.07,0,0,-3.6e+02,0.00084,0.00085,0.053,0.083,0.084,0.078,0.12,0.12,0.072,1.3e-05,1.4e-05,2.3e-06,0.037,0.037,0.01,0.0012,7.6e-05,0.0013,0.00068,0.0013,0.0012,1,1,2.9
11390000,0.78,-0.019,0.0018,-0.63,-0.064,-0.011,0.0024,0.00037,-0.00044,-3.7e+02,-0.00058,-0.0067,-8.9e-05,0.012,-0.0074,-0.11,-0.11,-0.025,0.5,-0.0032,-0.089,-0.07,0,0,-3.6e+02,0.00076,0.00077,0.052,0.067,0.068,0.063,0.081,0.081,0.068,1.2e-05,1.3e-05,2.3e-06,0.035,0.035,0.01,0.0012,7.5e-05,0.0013,0.00068,0.0013,0.0012,1,1,2.9
11490000,0.78,-0.019,0.002,-0.63,-0.078,-0.012,0.0032,-0.0071,-0.0015,-3.7e+02,-0.00056,-0.0068,-9.2e-05,0.012,-0.0079,-0.11,-0.11,-0.025,0.5,-0.0032,-0.089,-0.07,0,0,-3.6e+02,0.00076,0.00076,0.052,0.078,0.079,0.058,0.088,0.088,0.069,1.1e-05,1.2e-05,2.3e-06,0.035,0.035,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1,2.9
11490000,0.78,-0.019,0.002,-0.63,-0.078,-0.012,0.0032,-0.0071,-0.0014,-3.7e+02,-0.00056,-0.0068,-9.2e-05,0.012,-0.0079,-0.11,-0.11,-0.025,0.5,-0.0032,-0.089,-0.07,0,0,-3.6e+02,0.00076,0.00076,0.052,0.078,0.079,0.058,0.088,0.088,0.069,1.1e-05,1.2e-05,2.3e-06,0.035,0.035,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1,2.9
11590000,0.78,-0.019,0.0015,-0.63,-0.069,-0.012,-0.0027,-0.0021,-0.00084,-3.7e+02,-0.00061,-0.0067,-9.1e-05,0.017,-0.012,-0.11,-0.11,-0.025,0.5,-0.0033,-0.089,-0.07,0,0,-3.6e+02,0.00068,0.00069,0.052,0.066,0.066,0.049,0.068,0.068,0.066,1e-05,1.1e-05,2.3e-06,0.033,0.033,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1,2.9
11690000,0.78,-0.019,0.0016,-0.63,-0.08,-0.016,-0.0071,-0.0097,-0.0025,-3.7e+02,-0.00057,-0.0067,-9.2e-05,0.017,-0.012,-0.11,-0.11,-0.025,0.5,-0.0034,-0.089,-0.07,0,0,-3.6e+02,0.00067,0.00068,0.052,0.076,0.077,0.046,0.074,0.074,0.066,9.9e-06,1.1e-05,2.3e-06,0.033,0.033,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1,3
11790000,0.78,-0.019,0.001,-0.63,-0.072,-0.011,-0.0089,-0.0061,-0.00025,-3.7e+02,-0.00061,-0.0066,-9.1e-05,0.023,-0.015,-0.11,-0.11,-0.025,0.5,-0.0036,-0.09,-0.07,0,0,-3.6e+02,0.0006,0.00061,0.051,0.064,0.065,0.039,0.06,0.06,0.063,9.1e-06,9.9e-06,2.3e-06,0.03,0.03,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1,3
11890000,0.78,-0.019,0.0011,-0.63,-0.083,-0.012,-0.0098,-0.014,-0.0014,-3.7e+02,-0.00061,-0.0066,-9.1e-05,0.023,-0.016,-0.11,-0.11,-0.025,0.5,-0.0036,-0.09,-0.07,0,0,-3.6e+02,0.00059,0.00061,0.051,0.075,0.075,0.037,0.066,0.066,0.063,8.7e-06,9.5e-06,2.3e-06,0.03,0.03,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1,3
11990000,0.78,-0.019,0.00053,-0.63,-0.071,-0.0069,-0.015,-0.009,0.00086,-3.7e+02,-0.00076,-0.0065,-8.7e-05,0.027,-0.018,-0.11,-0.11,-0.025,0.5,-0.0035,-0.09,-0.07,0,0,-3.6e+02,0.00052,0.00054,0.051,0.063,0.064,0.033,0.055,0.055,0.061,8e-06,8.8e-06,2.3e-06,0.028,0.028,0.01,0.0012,7.5e-05,0.0013,0.00066,0.0013,0.0012,1,1,3
12090000,0.78,-0.018,0.00037,-0.63,-0.078,-0.0091,-0.021,-0.016,-3.3e-05,-3.7e+02,-0.00081,-0.0065,-8.3e-05,0.026,-0.017,-0.11,-0.11,-0.025,0.5,-0.0034,-0.09,-0.07,0,0,-3.6e+02,0.00052,0.00054,0.051,0.073,0.074,0.031,0.061,0.061,0.061,7.7e-06,8.4e-06,2.3e-06,0.028,0.028,0.01,0.0012,7.5e-05,0.0013,0.00066,0.0013,0.0012,1,1,3.1
11990000,0.78,-0.019,0.00053,-0.63,-0.071,-0.0068,-0.015,-0.009,0.00086,-3.7e+02,-0.00076,-0.0065,-8.7e-05,0.027,-0.018,-0.11,-0.11,-0.025,0.5,-0.0035,-0.09,-0.07,0,0,-3.6e+02,0.00052,0.00054,0.051,0.063,0.064,0.033,0.055,0.055,0.061,8e-06,8.8e-06,2.3e-06,0.028,0.028,0.01,0.0012,7.5e-05,0.0013,0.00066,0.0013,0.0012,1,1,3
12090000,0.78,-0.018,0.00037,-0.63,-0.078,-0.0091,-0.021,-0.016,-3.2e-05,-3.7e+02,-0.00081,-0.0065,-8.3e-05,0.026,-0.017,-0.11,-0.11,-0.025,0.5,-0.0034,-0.09,-0.07,0,0,-3.6e+02,0.00052,0.00054,0.051,0.073,0.074,0.031,0.061,0.061,0.061,7.7e-06,8.4e-06,2.3e-06,0.028,0.028,0.01,0.0012,7.5e-05,0.0013,0.00066,0.0013,0.0012,1,1,3.1
12190000,0.78,-0.018,-0.00031,-0.62,-0.064,-0.011,-0.016,-0.0085,-0.0004,-3.7e+02,-0.00082,-0.0064,-8.3e-05,0.032,-0.022,-0.11,-0.11,-0.025,0.5,-0.0037,-0.091,-0.07,0,0,-3.6e+02,0.00046,0.00048,0.051,0.062,0.062,0.028,0.052,0.052,0.059,7.2e-06,7.8e-06,2.3e-06,0.026,0.026,0.01,0.0012,7.5e-05,0.0012,0.00066,0.0013,0.0012,1,1,3.1
12290000,0.78,-0.019,-0.00032,-0.62,-0.07,-0.014,-0.015,-0.015,-0.0021,-3.7e+02,-0.00079,-0.0064,-8.3e-05,0.033,-0.021,-0.11,-0.11,-0.025,0.5,-0.0037,-0.091,-0.07,0,0,-3.6e+02,0.00046,0.00047,0.051,0.07,0.071,0.028,0.058,0.058,0.059,6.9e-06,7.5e-06,2.3e-06,0.026,0.026,0.01,0.0012,7.5e-05,0.0012,0.00066,0.0013,0.0012,1,1,3.1
12390000,0.78,-0.018,-0.00073,-0.62,-0.057,-0.012,-0.013,-0.0083,-0.001,-3.7e+02,-0.00086,-0.0063,-8.3e-05,0.037,-0.026,-0.11,-0.11,-0.025,0.5,-0.0038,-0.091,-0.07,0,0,-3.6e+02,0.0004,0.00042,0.05,0.059,0.06,0.026,0.05,0.05,0.057,6.4e-06,7e-06,2.3e-06,0.024,0.024,0.01,0.0012,7.5e-05,0.0012,0.00066,0.0013,0.0012,1,1,3.1
12490000,0.78,-0.018,-0.00059,-0.62,-0.064,-0.013,-0.016,-0.015,-0.0022,-3.7e+02,-0.00083,-0.0064,-8.5e-05,0.038,-0.026,-0.11,-0.11,-0.025,0.5,-0.0038,-0.091,-0.07,0,0,-3.6e+02,0.0004,0.00042,0.05,0.067,0.068,0.026,0.056,0.057,0.057,6.2e-06,6.8e-06,2.3e-06,0.024,0.024,0.01,0.0012,7.5e-05,0.0012,0.00066,0.0013,0.0012,1,1,3.2
12590000,0.78,-0.018,-0.00079,-0.62,-0.06,-0.011,-0.022,-0.013,-0.001,-3.7e+02,-0.00092,-0.0063,-8.3e-05,0.039,-0.027,-0.11,-0.11,-0.025,0.5,-0.0037,-0.091,-0.07,0,0,-3.6e+02,0.00036,0.00038,0.05,0.057,0.057,0.025,0.048,0.048,0.055,5.8e-06,6.4e-06,2.3e-06,0.022,0.023,0.0099,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1,3.2
12690000,0.78,-0.018,-0.00072,-0.62,-0.065,-0.011,-0.025,-0.019,-0.0014,-3.7e+02,-0.00099,-0.0064,-8.2e-05,0.036,-0.027,-0.11,-0.11,-0.025,0.5,-0.0035,-0.091,-0.07,0,0,-3.6e+02,0.00036,0.00037,0.05,0.064,0.064,0.025,0.055,0.055,0.055,5.6e-06,6.1e-06,2.3e-06,0.022,0.022,0.0099,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1,3.2
12690000,0.78,-0.018,-0.00072,-0.62,-0.065,-0.011,-0.025,-0.019,-0.0013,-3.7e+02,-0.00099,-0.0064,-8.2e-05,0.036,-0.027,-0.11,-0.11,-0.025,0.5,-0.0035,-0.091,-0.07,0,0,-3.6e+02,0.00036,0.00037,0.05,0.064,0.064,0.025,0.055,0.055,0.055,5.6e-06,6.1e-06,2.3e-06,0.022,0.023,0.0099,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1,3.2
12790000,0.78,-0.018,-0.001,-0.62,-0.061,-0.0098,-0.029,-0.017,-0.0012,-3.7e+02,-0.00097,-0.0063,-8.2e-05,0.04,-0.029,-0.11,-0.11,-0.025,0.5,-0.0036,-0.091,-0.07,0,0,-3.6e+02,0.00032,0.00034,0.05,0.054,0.054,0.024,0.048,0.048,0.053,5.3e-06,5.8e-06,2.3e-06,0.021,0.021,0.0097,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1,3.2
12890000,0.78,-0.018,-0.00099,-0.62,-0.068,-0.011,-0.028,-0.024,-0.0027,-3.7e+02,-0.00093,-0.0063,-8.2e-05,0.041,-0.029,-0.11,-0.11,-0.025,0.5,-0.0038,-0.091,-0.07,0,0,-3.6e+02,0.00032,0.00034,0.05,0.06,0.061,0.025,0.055,0.055,0.054,5.1e-06,5.6e-06,2.3e-06,0.02,0.021,0.0097,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1,3.3
12990000,0.78,-0.018,-0.0015,-0.62,-0.055,-0.01,-0.028,-0.018,-0.0026,-3.7e+02,-0.00097,-0.0062,-8e-05,0.045,-0.031,-0.11,-0.11,-0.025,0.5,-0.0038,-0.091,-0.07,0,0,-3.6e+02,0.00029,0.00031,0.05,0.054,0.054,0.025,0.057,0.057,0.052,4.9e-06,5.3e-06,2.3e-06,0.019,0.02,0.0094,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1,3.3
@@ -139,25 +139,25 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
13690000,0.78,-0.018,-0.0023,-0.62,-0.041,-0.015,-0.023,-0.018,-0.006,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.054,-0.035,-0.12,-0.11,-0.025,0.5,-0.0041,-0.091,-0.07,0,0,-3.6e+02,0.00023,0.00025,0.049,0.057,0.057,0.029,0.096,0.096,0.05,3.7e-06,4.1e-06,2.3e-06,0.016,0.017,0.0083,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.5
13790000,0.78,-0.018,-0.0024,-0.62,-0.029,-0.013,-0.024,-0.0067,-0.0046,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.054,-0.037,-0.12,-0.11,-0.025,0.5,-0.004,-0.092,-0.07,0,0,-3.6e+02,0.00021,0.00023,0.049,0.044,0.044,0.029,0.071,0.071,0.049,3.6e-06,4e-06,2.3e-06,0.015,0.016,0.0079,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.5
13890000,0.78,-0.018,-0.0025,-0.62,-0.033,-0.015,-0.029,-0.01,-0.0066,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.056,-0.037,-0.12,-0.11,-0.025,0.5,-0.0041,-0.092,-0.07,0,0,-3.6e+02,0.00021,0.00023,0.049,0.048,0.048,0.03,0.079,0.079,0.05,3.5e-06,3.9e-06,2.3e-06,0.015,0.016,0.0078,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.5
13990000,0.78,-0.018,-0.0026,-0.62,-0.025,-0.014,-0.028,-0.0036,-0.0056,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.057,-0.037,-0.12,-0.11,-0.025,0.5,-0.0041,-0.092,-0.07,0,0,-3.6e+02,0.0002,0.00021,0.049,0.039,0.039,0.03,0.062,0.062,0.05,3.3e-06,3.7e-06,2.3e-06,0.014,0.015,0.0074,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.5
13990000,0.78,-0.018,-0.0026,-0.62,-0.025,-0.014,-0.028,-0.0036,-0.0056,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.057,-0.038,-0.12,-0.11,-0.025,0.5,-0.0041,-0.092,-0.07,0,0,-3.6e+02,0.0002,0.00021,0.049,0.039,0.039,0.03,0.062,0.062,0.05,3.3e-06,3.7e-06,2.3e-06,0.014,0.015,0.0074,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.5
14090000,0.78,-0.018,-0.0027,-0.62,-0.026,-0.015,-0.029,-0.0058,-0.0071,-3.7e+02,-0.0011,-0.0061,-7.6e-05,0.056,-0.036,-0.12,-0.11,-0.025,0.5,-0.004,-0.092,-0.07,0,0,-3.6e+02,0.0002,0.00021,0.049,0.042,0.042,0.031,0.07,0.07,0.05,3.2e-06,3.6e-06,2.4e-06,0.014,0.015,0.0073,0.0012,7.4e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.6
14190000,0.78,-0.017,-0.0028,-0.62,-0.021,-0.013,-0.031,-0.00023,-0.005,-3.7e+02,-0.0011,-0.0061,-7.5e-05,0.058,-0.036,-0.12,-0.11,-0.026,0.5,-0.004,-0.092,-0.069,0,0,-3.6e+02,0.00019,0.0002,0.049,0.036,0.036,0.03,0.057,0.057,0.05,3.1e-06,3.5e-06,2.4e-06,0.014,0.015,0.0069,0.0012,7.4e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.6
14290000,0.78,-0.017,-0.0029,-0.62,-0.022,-0.015,-0.03,-0.0022,-0.0063,-3.7e+02,-0.0011,-0.006,-7.4e-05,0.057,-0.036,-0.12,-0.11,-0.026,0.5,-0.004,-0.092,-0.069,0,0,-3.6e+02,0.00019,0.0002,0.049,0.039,0.039,0.032,0.063,0.063,0.051,3e-06,3.4e-06,2.4e-06,0.013,0.014,0.0067,0.0012,7.4e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.6
14390000,0.78,-0.017,-0.003,-0.62,-0.017,-0.015,-0.032,0.0018,-0.005,-3.7e+02,-0.0011,-0.006,-7.3e-05,0.06,-0.035,-0.12,-0.11,-0.026,0.5,-0.004,-0.092,-0.069,0,0,-3.6e+02,0.00018,0.00019,0.049,0.033,0.033,0.031,0.053,0.053,0.05,2.9e-06,3.3e-06,2.4e-06,0.013,0.014,0.0063,0.0012,7.4e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.6
14390000,0.78,-0.017,-0.003,-0.62,-0.017,-0.015,-0.032,0.0018,-0.0049,-3.7e+02,-0.0011,-0.006,-7.3e-05,0.06,-0.035,-0.12,-0.11,-0.026,0.5,-0.004,-0.092,-0.069,0,0,-3.6e+02,0.00018,0.00019,0.049,0.033,0.033,0.031,0.053,0.053,0.05,2.9e-06,3.3e-06,2.4e-06,0.013,0.014,0.0063,0.0012,7.4e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.6
14490000,0.78,-0.017,-0.0031,-0.62,-0.019,-0.018,-0.035,-0.00044,-0.0069,-3.7e+02,-0.001,-0.006,-7.4e-05,0.062,-0.036,-0.12,-0.11,-0.026,0.5,-0.0041,-0.092,-0.069,0,0,-3.6e+02,0.00018,0.00019,0.049,0.036,0.036,0.032,0.059,0.059,0.051,2.8e-06,3.2e-06,2.4e-06,0.013,0.014,0.0062,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.7
14590000,0.78,-0.017,-0.003,-0.62,-0.02,-0.018,-0.035,-0.0013,-0.0065,-3.7e+02,-0.001,-0.006,-7.4e-05,0.063,-0.036,-0.12,-0.11,-0.026,0.5,-0.0042,-0.092,-0.069,0,0,-3.6e+02,0.00017,0.00019,0.049,0.031,0.031,0.031,0.05,0.05,0.051,2.8e-06,3.1e-06,2.4e-06,0.012,0.013,0.0058,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.7
14690000,0.78,-0.017,-0.0031,-0.62,-0.023,-0.017,-0.032,-0.0034,-0.0085,-3.7e+02,-0.00099,-0.006,-7.3e-05,0.064,-0.035,-0.12,-0.11,-0.026,0.5,-0.0042,-0.092,-0.069,0,0,-3.6e+02,0.00017,0.00019,0.049,0.034,0.034,0.032,0.056,0.056,0.051,2.7e-06,3e-06,2.4e-06,0.012,0.013,0.0056,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.7
14790000,0.78,-0.017,-0.0031,-0.62,-0.023,-0.016,-0.028,-0.0036,-0.0079,-3.7e+02,-0.00099,-0.006,-7.3e-05,0.065,-0.035,-0.12,-0.11,-0.026,0.5,-0.0042,-0.092,-0.069,0,0,-3.6e+02,0.00016,0.00018,0.049,0.03,0.03,0.031,0.048,0.048,0.051,2.6e-06,2.9e-06,2.4e-06,0.012,0.013,0.0053,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.7
14790000,0.78,-0.017,-0.0031,-0.62,-0.023,-0.016,-0.028,-0.0036,-0.0079,-3.7e+02,-0.00099,-0.006,-7.3e-05,0.065,-0.035,-0.12,-0.11,-0.026,0.5,-0.0042,-0.091,-0.069,0,0,-3.6e+02,0.00016,0.00018,0.049,0.03,0.03,0.031,0.048,0.048,0.051,2.6e-06,2.9e-06,2.4e-06,0.012,0.013,0.0053,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.7
14890000,0.78,-0.017,-0.0031,-0.62,-0.026,-0.019,-0.031,-0.006,-0.0098,-3.7e+02,-0.00098,-0.006,-7.3e-05,0.065,-0.035,-0.12,-0.11,-0.026,0.5,-0.0042,-0.092,-0.069,0,0,-3.6e+02,0.00016,0.00018,0.049,0.032,0.033,0.031,0.054,0.054,0.052,2.5e-06,2.9e-06,2.4e-06,0.012,0.013,0.0051,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.8
14990000,0.78,-0.017,-0.0031,-0.62,-0.024,-0.016,-0.027,-0.0046,-0.0077,-3.7e+02,-0.00098,-0.006,-7.3e-05,0.066,-0.036,-0.12,-0.11,-0.026,0.5,-0.0042,-0.092,-0.069,0,0,-3.6e+02,0.00016,0.00017,0.049,0.029,0.029,0.03,0.047,0.047,0.051,2.4e-06,2.8e-06,2.4e-06,0.012,0.012,0.0048,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.8
15090000,0.78,-0.017,-0.003,-0.62,-0.026,-0.017,-0.03,-0.0072,-0.0093,-3.7e+02,-0.00098,-0.006,-7.4e-05,0.066,-0.036,-0.12,-0.11,-0.026,0.5,-0.0042,-0.091,-0.069,0,0,-3.6e+02,0.00016,0.00017,0.049,0.031,0.031,0.031,0.052,0.052,0.052,2.4e-06,2.7e-06,2.4e-06,0.011,0.012,0.0046,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.8
15190000,0.78,-0.017,-0.003,-0.62,-0.024,-0.016,-0.027,-0.0058,-0.0075,-3.7e+02,-0.00097,-0.006,-7.4e-05,0.067,-0.037,-0.12,-0.11,-0.026,0.5,-0.0043,-0.091,-0.069,0,0,-3.6e+02,0.00015,0.00017,0.049,0.027,0.027,0.03,0.046,0.046,0.052,2.3e-06,2.6e-06,2.4e-06,0.011,0.012,0.0043,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.8
15290000,0.78,-0.017,-0.003,-0.62,-0.025,-0.018,-0.025,-0.0081,-0.0092,-3.7e+02,-0.00098,-0.006,-7.3e-05,0.067,-0.036,-0.12,-0.11,-0.026,0.5,-0.0042,-0.091,-0.069,0,0,-3.6e+02,0.00015,0.00017,0.049,0.03,0.03,0.03,0.051,0.051,0.052,2.2e-06,2.6e-06,2.4e-06,0.011,0.012,0.0041,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.9
15390000,0.78,-0.017,-0.0031,-0.62,-0.025,-0.018,-0.023,-0.0075,-0.0094,-3.7e+02,-0.001,-0.006,-7e-05,0.067,-0.035,-0.13,-0.11,-0.026,0.5,-0.0041,-0.091,-0.069,0,0,-3.6e+02,0.00015,0.00016,0.049,0.028,0.029,0.029,0.053,0.053,0.051,2.2e-06,2.5e-06,2.4e-06,0.011,0.012,0.0038,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,3.9
15490000,0.78,-0.017,-0.003,-0.62,-0.027,-0.018,-0.023,-0.01,-0.011,-3.7e+02,-0.001,-0.006,-7.1e-05,0.067,-0.036,-0.13,-0.11,-0.026,0.5,-0.0042,-0.091,-0.069,0,0,-3.6e+02,0.00015,0.00016,0.049,0.031,0.031,0.029,0.06,0.06,0.053,2.1e-06,2.4e-06,2.4e-06,0.011,0.012,0.0037,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,3.9
15490000,0.78,-0.017,-0.003,-0.62,-0.027,-0.018,-0.023,-0.01,-0.011,-3.7e+02,-0.001,-0.006,-7.2e-05,0.067,-0.036,-0.13,-0.11,-0.026,0.5,-0.0042,-0.091,-0.069,0,0,-3.6e+02,0.00015,0.00016,0.049,0.031,0.031,0.029,0.06,0.06,0.053,2.1e-06,2.4e-06,2.4e-06,0.011,0.012,0.0037,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,3.9
15590000,0.78,-0.017,-0.0029,-0.62,-0.026,-0.016,-0.022,-0.0097,-0.01,-3.7e+02,-0.001,-0.006,-7.2e-05,0.067,-0.037,-0.13,-0.11,-0.026,0.5,-0.0042,-0.091,-0.069,0,0,-3.6e+02,0.00015,0.00016,0.049,0.029,0.029,0.028,0.062,0.062,0.052,2.1e-06,2.4e-06,2.4e-06,0.011,0.011,0.0035,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,3.9
15690000,0.78,-0.017,-0.0029,-0.62,-0.027,-0.017,-0.022,-0.012,-0.012,-3.7e+02,-0.001,-0.006,-7.2e-05,0.066,-0.037,-0.13,-0.11,-0.026,0.5,-0.0042,-0.092,-0.069,0,0,-3.6e+02,0.00014,0.00016,0.049,0.031,0.032,0.028,0.069,0.069,0.052,2e-06,2.3e-06,2.4e-06,0.01,0.011,0.0033,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4
15790000,0.78,-0.017,-0.003,-0.62,-0.025,-0.016,-0.025,-0.0085,-0.0098,-3.7e+02,-0.001,-0.006,-7.2e-05,0.067,-0.037,-0.12,-0.11,-0.026,0.5,-0.0042,-0.092,-0.069,0,0,-3.6e+02,0.00014,0.00016,0.049,0.026,0.027,0.027,0.056,0.056,0.051,1.9e-06,2.2e-06,2.4e-06,0.01,0.011,0.0031,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4
15790000,0.78,-0.017,-0.003,-0.62,-0.025,-0.016,-0.025,-0.0085,-0.0098,-3.7e+02,-0.001,-0.006,-7.2e-05,0.067,-0.038,-0.12,-0.11,-0.026,0.5,-0.0042,-0.092,-0.069,0,0,-3.6e+02,0.00014,0.00016,0.049,0.026,0.027,0.027,0.056,0.056,0.051,1.9e-06,2.2e-06,2.4e-06,0.01,0.011,0.0031,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4
15890000,0.78,-0.017,-0.0029,-0.62,-0.026,-0.016,-0.023,-0.011,-0.011,-3.7e+02,-0.001,-0.006,-7.2e-05,0.066,-0.037,-0.13,-0.11,-0.026,0.5,-0.0041,-0.092,-0.069,0,0,-3.6e+02,0.00014,0.00015,0.049,0.028,0.028,0.027,0.062,0.062,0.052,1.9e-06,2.2e-06,2.4e-06,0.01,0.011,0.003,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4
15990000,0.78,-0.017,-0.003,-0.62,-0.024,-0.016,-0.018,-0.0078,-0.01,-3.7e+02,-0.0011,-0.006,-7e-05,0.066,-0.037,-0.13,-0.11,-0.026,0.5,-0.0041,-0.092,-0.069,0,0,-3.6e+02,0.00014,0.00015,0.049,0.024,0.024,0.026,0.052,0.052,0.051,1.8e-06,2.1e-06,2.4e-06,0.0099,0.011,0.0028,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4
16090000,0.78,-0.017,-0.0031,-0.62,-0.026,-0.018,-0.015,-0.0099,-0.012,-3.7e+02,-0.0011,-0.006,-6.7e-05,0.066,-0.035,-0.13,-0.11,-0.026,0.5,-0.004,-0.092,-0.069,0,0,-3.6e+02,0.00014,0.00015,0.049,0.026,0.026,0.025,0.058,0.058,0.052,1.8e-06,2.1e-06,2.4e-06,0.0097,0.011,0.0027,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.1
@@ -177,11 +177,11 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
17490000,0.78,-0.017,-0.003,-0.62,-0.025,-0.018,-0.0025,-0.016,-0.0094,-3.7e+02,-0.0012,-0.006,-5.9e-05,0.062,-0.035,-0.13,-0.11,-0.026,0.5,-0.0037,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.019,0.019,0.018,0.046,0.046,0.049,1.3e-06,1.5e-06,2.4e-06,0.0082,0.0091,0.0013,0.0012,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.4
17590000,0.78,-0.017,-0.003,-0.62,-0.024,-0.018,0.003,-0.013,-0.009,-3.7e+02,-0.0012,-0.006,-5.8e-05,0.062,-0.035,-0.13,-0.11,-0.026,0.5,-0.0037,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.017,0.018,0.017,0.041,0.041,0.048,1.2e-06,1.5e-06,2.4e-06,0.0081,0.009,0.0012,0.0012,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.4
17690000,0.78,-0.017,-0.0029,-0.62,-0.025,-0.02,0.0024,-0.016,-0.011,-3.7e+02,-0.0012,-0.006,-5.7e-05,0.062,-0.035,-0.13,-0.11,-0.026,0.5,-0.0037,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.019,0.019,0.017,0.045,0.045,0.048,1.2e-06,1.4e-06,2.4e-06,0.008,0.0089,0.0011,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.5
17790000,0.78,-0.017,-0.003,-0.62,-0.023,-0.021,0.0011,-0.014,-0.012,-3.7e+02,-0.0012,-0.006,-5.3e-05,0.062,-0.033,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.018,0.019,0.016,0.048,0.048,0.048,1.2e-06,1.4e-06,2.4e-06,0.008,0.0088,0.0011,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.5
17890000,0.78,-0.017,-0.0031,-0.62,-0.026,-0.022,0.0012,-0.017,-0.015,-3.7e+02,-0.0012,-0.006,-5.2e-05,0.062,-0.033,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.02,0.02,0.016,0.052,0.053,0.048,1.2e-06,1.4e-06,2.4e-06,0.0079,0.0087,0.001,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.5
17990000,0.78,-0.017,-0.003,-0.62,-0.025,-0.02,0.0024,-0.015,-0.014,-3.7e+02,-0.0012,-0.006,-5.1e-05,0.062,-0.033,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.019,0.02,0.016,0.055,0.055,0.047,1.1e-06,1.4e-06,2.4e-06,0.0078,0.0086,0.00099,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.5
17790000,0.78,-0.017,-0.003,-0.62,-0.023,-0.021,0.001,-0.014,-0.012,-3.7e+02,-0.0012,-0.006,-5.3e-05,0.062,-0.033,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.018,0.019,0.016,0.048,0.048,0.048,1.2e-06,1.4e-06,2.4e-06,0.008,0.0088,0.0011,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.5
17890000,0.78,-0.017,-0.0031,-0.62,-0.026,-0.022,0.0011,-0.017,-0.015,-3.7e+02,-0.0012,-0.006,-5.2e-05,0.062,-0.033,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.02,0.02,0.016,0.052,0.053,0.048,1.2e-06,1.4e-06,2.4e-06,0.0079,0.0087,0.001,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.5
17990000,0.78,-0.017,-0.003,-0.62,-0.025,-0.02,0.0023,-0.015,-0.014,-3.7e+02,-0.0012,-0.006,-5.1e-05,0.062,-0.033,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.019,0.02,0.016,0.055,0.055,0.047,1.1e-06,1.4e-06,2.4e-06,0.0078,0.0086,0.00099,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.5
18090000,0.78,-0.017,-0.003,-0.62,-0.027,-0.02,0.0047,-0.018,-0.016,-3.7e+02,-0.0012,-0.006,-5.4e-05,0.062,-0.034,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.021,0.021,0.016,0.06,0.061,0.047,1.1e-06,1.3e-06,2.4e-06,0.0078,0.0086,0.00096,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.6
18190000,0.78,-0.017,-0.003,-0.62,-0.023,-0.019,0.0061,-0.013,-0.013,-3.7e+02,-0.0012,-0.006,-5e-05,0.062,-0.034,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.018,0.018,0.015,0.051,0.051,0.047,1.1e-06,1.3e-06,2.4e-06,0.0077,0.0085,0.0009,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.6
18190000,0.78,-0.017,-0.003,-0.62,-0.023,-0.019,0.0061,-0.013,-0.013,-3.7e+02,-0.0012,-0.006,-5e-05,0.062,-0.034,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.018,0.018,0.015,0.051,0.051,0.047,1.1e-06,1.3e-06,2.3e-06,0.0077,0.0085,0.0009,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.6
18290000,0.78,-0.017,-0.0029,-0.62,-0.025,-0.02,0.0072,-0.016,-0.015,-3.7e+02,-0.0012,-0.006,-5.2e-05,0.062,-0.034,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.019,0.019,0.015,0.056,0.056,0.046,1.1e-06,1.3e-06,2.4e-06,0.0076,0.0084,0.00087,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.6
18390000,0.78,-0.017,-0.003,-0.62,-0.023,-0.021,0.0084,-0.012,-0.012,-3.7e+02,-0.0012,-0.006,-4.8e-05,0.063,-0.034,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.017,0.017,0.014,0.048,0.048,0.046,1e-06,1.2e-06,2.3e-06,0.0075,0.0083,0.00083,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.6
18490000,0.78,-0.017,-0.003,-0.62,-0.024,-0.022,0.0081,-0.014,-0.015,-3.7e+02,-0.0012,-0.006,-4.7e-05,0.062,-0.034,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.018,0.018,0.014,0.053,0.053,0.046,1e-06,1.2e-06,2.3e-06,0.0075,0.0083,0.0008,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.7
@@ -200,8 +200,8 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
19790000,0.78,-0.016,-0.0032,-0.62,-0.012,-0.018,0.01,-0.0075,-0.015,-3.7e+02,-0.0013,-0.006,-1.6e-05,0.06,-0.031,-0.13,-0.11,-0.026,0.5,-0.0033,-0.092,-0.068,0,0,-3.6e+02,0.0001,0.00011,0.049,0.014,0.014,0.011,0.039,0.039,0.042,7.7e-07,9.4e-07,2.3e-06,0.0068,0.0074,0.00049,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5
19890000,0.78,-0.016,-0.0032,-0.62,-0.011,-0.02,0.012,-0.0091,-0.018,-3.7e+02,-0.0013,-0.0059,-1.3e-05,0.061,-0.031,-0.13,-0.11,-0.026,0.5,-0.0032,-0.092,-0.068,0,0,-3.6e+02,0.0001,0.00011,0.049,0.015,0.015,0.011,0.043,0.043,0.042,7.6e-07,9.3e-07,2.3e-06,0.0067,0.0074,0.00048,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5
19990000,0.78,-0.016,-0.0032,-0.62,-0.0095,-0.02,0.014,-0.0079,-0.017,-3.7e+02,-0.0013,-0.0059,-3.8e-06,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0031,-0.092,-0.068,0,0,-3.6e+02,9.9e-05,0.00011,0.049,0.014,0.014,0.01,0.039,0.039,0.041,7.4e-07,9e-07,2.3e-06,0.0067,0.0073,0.00046,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5
20090000,0.78,-0.016,-0.0033,-0.62,-0.0095,-0.021,0.015,-0.0085,-0.02,-3.7e+02,-0.0013,-0.0059,1e-06,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.6e+02,9.9e-05,0.00011,0.049,0.014,0.015,0.01,0.042,0.042,0.042,7.3e-07,8.9e-07,2.3e-06,0.0066,0.0073,0.00045,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.1
20190000,0.78,-0.016,-0.0034,-0.62,-0.01,-0.019,0.017,-0.0087,-0.018,-3.7e+02,-0.0013,-0.0059,7e-06,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.6e+02,9.8e-05,0.00011,0.048,0.013,0.014,0.01,0.038,0.038,0.041,7.1e-07,8.7e-07,2.3e-06,0.0066,0.0072,0.00043,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.1
20090000,0.78,-0.016,-0.0033,-0.62,-0.0095,-0.021,0.015,-0.0085,-0.02,-3.7e+02,-0.0013,-0.0059,9.8e-07,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.6e+02,9.9e-05,0.00011,0.049,0.014,0.015,0.01,0.042,0.042,0.042,7.3e-07,8.9e-07,2.3e-06,0.0066,0.0073,0.00045,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.1
20190000,0.78,-0.016,-0.0034,-0.62,-0.01,-0.019,0.017,-0.0087,-0.018,-3.7e+02,-0.0013,-0.0059,6.9e-06,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.6e+02,9.8e-05,0.00011,0.048,0.013,0.014,0.01,0.038,0.038,0.041,7.1e-07,8.7e-07,2.3e-06,0.0066,0.0072,0.00043,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.1
20290000,0.78,-0.016,-0.0034,-0.62,-0.0088,-0.019,0.015,-0.0091,-0.02,-3.7e+02,-0.0013,-0.0059,8.7e-06,0.062,-0.028,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.6e+02,9.8e-05,0.00011,0.048,0.014,0.015,0.0099,0.042,0.042,0.041,7e-07,8.6e-07,2.3e-06,0.0065,0.0072,0.00042,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.1
20390000,0.78,-0.016,-0.0033,-0.62,-0.0084,-0.016,0.017,-0.009,-0.017,-3.7e+02,-0.0013,-0.0059,1.3e-05,0.062,-0.028,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.6e+02,9.7e-05,0.0001,0.048,0.013,0.014,0.0097,0.038,0.038,0.041,6.8e-07,8.4e-07,2.3e-06,0.0065,0.0071,0.00041,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.1
20490000,0.78,-0.016,-0.0034,-0.62,-0.0087,-0.017,0.017,-0.0099,-0.019,-3.7e+02,-0.0013,-0.0059,1.1e-05,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.6e+02,9.7e-05,0.0001,0.048,0.014,0.015,0.0096,0.041,0.042,0.041,6.8e-07,8.3e-07,2.3e-06,0.0065,0.0071,0.0004,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.2
@@ -222,12 +222,12 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
21990000,0.78,-0.016,-0.0034,-0.62,-0.0057,-0.0035,0.017,-0.008,-0.0069,-3.7e+02,-0.0013,-0.0059,5.6e-05,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.7e+02,8.8e-05,9.4e-05,0.048,0.013,0.013,0.0078,0.041,0.042,0.038,5.2e-07,6.4e-07,2.2e-06,0.0059,0.0065,0.00027,0.0011,7.1e-05,0.0012,0.0006,0.0012,0.0012,1,1,0.01
22090000,0.78,-0.016,-0.0034,-0.62,-0.0054,-0.0051,0.015,-0.0084,-0.0074,-3.7e+02,-0.0013,-0.0059,5.6e-05,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.9e-05,9.5e-05,0.048,0.013,0.014,0.0078,0.045,0.045,0.037,5.2e-07,6.3e-07,2.2e-06,0.0059,0.0065,0.00027,0.0011,7.1e-05,0.0012,0.0006,0.0012,0.0012,1,1,0.01
22190000,0.78,-0.016,-0.0034,-0.62,-0.0041,-0.0056,0.015,-0.007,-0.0066,-3.7e+02,-0.0013,-0.0059,5.9e-05,0.062,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.093,-0.068,0,0,-3.7e+02,8.7e-05,9.3e-05,0.048,0.012,0.013,0.0076,0.04,0.04,0.037,5.1e-07,6.2e-07,2.2e-06,0.0059,0.0064,0.00026,0.0011,7.1e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01
22290000,0.78,-0.016,-0.0034,-0.62,-0.0037,-0.0053,0.016,-0.0077,-0.007,-3.7e+02,-0.0013,-0.0059,5.8e-05,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.093,-0.068,0,0,-3.7e+02,8.8e-05,9.3e-05,0.048,0.013,0.014,0.0076,0.043,0.044,0.037,5e-07,6.1e-07,2.2e-06,0.0059,0.0064,0.00025,0.0011,7.1e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01
22290000,0.78,-0.016,-0.0034,-0.62,-0.0036,-0.0053,0.016,-0.0077,-0.007,-3.7e+02,-0.0013,-0.0059,5.8e-05,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.093,-0.068,0,0,-3.7e+02,8.8e-05,9.3e-05,0.048,0.013,0.014,0.0076,0.043,0.044,0.037,5e-07,6.1e-07,2.2e-06,0.0059,0.0064,0.00025,0.0011,7.1e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01
22390000,0.78,-0.016,-0.0034,-0.62,-0.0011,-0.0052,0.017,-0.0059,-0.0063,-3.7e+02,-0.0013,-0.0059,6.2e-05,0.061,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.093,-0.068,0,0,-3.7e+02,8.6e-05,9.2e-05,0.048,0.012,0.013,0.0075,0.039,0.04,0.037,4.9e-07,6e-07,2.2e-06,0.0058,0.0064,0.00025,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01
22490000,0.78,-0.016,-0.0034,-0.62,1.2e-05,-0.0059,0.018,-0.0053,-0.0068,-3.7e+02,-0.0014,-0.0059,6.2e-05,0.061,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.7e-05,9.2e-05,0.048,0.013,0.014,0.0074,0.042,0.043,0.037,4.9e-07,5.9e-07,2.2e-06,0.0058,0.0063,0.00024,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01
22490000,0.78,-0.016,-0.0034,-0.62,1.4e-05,-0.0059,0.018,-0.0053,-0.0067,-3.7e+02,-0.0014,-0.0059,6.2e-05,0.061,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.7e-05,9.2e-05,0.048,0.013,0.014,0.0074,0.042,0.043,0.037,4.9e-07,5.9e-07,2.2e-06,0.0058,0.0063,0.00024,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01
22590000,0.78,-0.016,-0.0034,-0.62,0.0019,-0.0048,0.017,-0.0036,-0.0061,-3.7e+02,-0.0014,-0.0059,6.6e-05,0.06,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.6e-05,9.2e-05,0.048,0.013,0.014,0.0073,0.045,0.045,0.036,4.8e-07,5.8e-07,2.2e-06,0.0058,0.0063,0.00024,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01
22690000,0.78,-0.016,-0.0035,-0.62,0.0034,-0.0061,0.019,-0.0029,-0.0072,-3.7e+02,-0.0014,-0.0059,7e-05,0.06,-0.027,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,-3.7e+02,8.7e-05,9.2e-05,0.048,0.014,0.015,0.0073,0.048,0.049,0.036,4.8e-07,5.8e-07,2.2e-06,0.0058,0.0063,0.00024,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01
22790000,0.78,-0.016,-0.0034,-0.62,0.0044,-0.0054,0.02,-0.0024,-0.0058,-3.7e+02,-0.0014,-0.0059,6.3e-05,0.06,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.6e-05,9.1e-05,0.048,0.014,0.015,0.0072,0.051,0.052,0.036,4.7e-07,5.7e-07,2.2e-06,0.0057,0.0062,0.00023,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01
22790000,0.78,-0.016,-0.0034,-0.62,0.0045,-0.0054,0.02,-0.0024,-0.0058,-3.7e+02,-0.0014,-0.0059,6.3e-05,0.06,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.6e-05,9.1e-05,0.048,0.014,0.015,0.0072,0.051,0.052,0.036,4.7e-07,5.7e-07,2.2e-06,0.0057,0.0062,0.00023,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01
22890000,0.78,-0.016,-0.0034,-0.62,0.0051,-0.0063,0.021,-0.0025,-0.0066,-3.7e+02,-0.0014,-0.0059,6.3e-05,0.06,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.6e-05,9.2e-05,0.048,0.015,0.016,0.0072,0.055,0.056,0.036,4.7e-07,5.7e-07,2.2e-06,0.0057,0.0062,0.00023,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01
22990000,0.78,-0.016,-0.0034,-0.62,0.0048,-0.0065,0.022,-0.0026,-0.0074,-3.7e+02,-0.0014,-0.0059,6.8e-05,0.06,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.5e-05,9.1e-05,0.048,0.015,0.016,0.0071,0.057,0.059,0.036,4.6e-07,5.6e-07,2.2e-06,0.0057,0.0062,0.00022,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01
23090000,0.78,-0.016,-0.0033,-0.62,0.0051,-0.0062,0.023,-0.0023,-0.0071,-3.7e+02,-0.0014,-0.0059,6.4e-05,0.06,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.093,-0.068,0,0,-3.7e+02,8.6e-05,9.1e-05,0.048,0.016,0.017,0.007,0.062,0.064,0.036,4.6e-07,5.6e-07,2.2e-06,0.0057,0.0062,0.00022,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01
@@ -238,7 +238,7 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
23590000,0.78,-0.0046,-0.0097,-0.62,0.015,-0.00011,-0.043,-0.0094,-0.0059,-3.7e+02,-0.0013,-0.0059,7.7e-05,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.3e-05,8.8e-05,0.047,0.014,0.015,0.0067,0.062,0.063,0.035,4.2e-07,5.1e-07,2.2e-06,0.0056,0.006,0.0002,0.0011,6.8e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01
23690000,0.78,0.0011,-0.0087,-0.62,0.043,0.014,-0.093,-0.007,-0.0057,-3.7e+02,-0.0013,-0.0059,7.9e-05,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.7e+02,8.3e-05,8.8e-05,0.047,0.015,0.016,0.0067,0.066,0.068,0.035,4.2e-07,5.1e-07,2.2e-06,0.0056,0.006,0.0002,0.0011,6.8e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01
23790000,0.78,-0.0026,-0.0062,-0.62,0.064,0.031,-0.15,-0.007,-0.0037,-3.7e+02,-0.0013,-0.0059,8.5e-05,0.063,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.067,0,0,-3.7e+02,8.2e-05,8.7e-05,0.047,0.013,0.014,0.0066,0.055,0.056,0.035,4.1e-07,4.9e-07,2.1e-06,0.0055,0.006,0.00019,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01
23890000,0.78,-0.0089,-0.0043,-0.62,0.077,0.043,-0.2,0.0005,6.2e-05,-3.7e+02,-0.0013,-0.0059,8.6e-05,0.063,-0.029,-0.13,-0.11,-0.026,0.5,-0.0031,-0.091,-0.067,0,0,-3.7e+02,8.2e-05,8.7e-05,0.047,0.014,0.015,0.0066,0.059,0.06,0.035,4.1e-07,4.9e-07,2.1e-06,0.0055,0.006,0.00019,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01
23890000,0.78,-0.0089,-0.0043,-0.62,0.077,0.043,-0.2,0.0005,6.3e-05,-3.7e+02,-0.0013,-0.0059,8.6e-05,0.063,-0.029,-0.13,-0.11,-0.026,0.5,-0.0031,-0.091,-0.067,0,0,-3.7e+02,8.2e-05,8.7e-05,0.047,0.014,0.015,0.0066,0.059,0.06,0.035,4.1e-07,4.9e-07,2.1e-06,0.0055,0.006,0.00019,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01
23990000,0.78,-0.014,-0.0035,-0.62,0.072,0.043,-0.25,-0.005,-0.0014,-3.7e+02,-0.0013,-0.0059,8.4e-05,0.064,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.091,-0.068,0,0,-3.7e+02,8.2e-05,8.7e-05,0.047,0.014,0.015,0.0066,0.061,0.063,0.035,4e-07,4.9e-07,2.1e-06,0.0055,0.006,0.00019,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01
24090000,0.78,-0.012,-0.0046,-0.62,0.073,0.042,-0.3,0.0014,0.002,-3.7e+02,-0.0013,-0.0059,8.8e-05,0.064,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.091,-0.067,0,0,-3.7e+02,8.2e-05,8.7e-05,0.047,0.015,0.016,0.0065,0.066,0.067,0.035,4e-07,4.9e-07,2.1e-06,0.0055,0.006,0.00019,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01
24190000,0.78,-0.01,-0.0055,-0.62,0.07,0.041,-0.35,-0.0058,-0.00021,-3.7e+02,-0.0013,-0.0059,8.6e-05,0.065,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.091,-0.068,0,0,-3.7e+02,8.2e-05,8.6e-05,0.047,0.015,0.016,0.0065,0.069,0.07,0.034,4e-07,4.8e-07,2.1e-06,0.0055,0.0059,0.00018,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01
@@ -259,7 +259,7 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
25690000,0.79,0.018,-0.014,-0.62,0.29,0.22,-1.2,-0.031,0.021,-3.7e+02,-0.00099,-0.0058,3e-05,0.08,-0.029,-0.13,-0.12,-0.027,0.5,-0.0031,-0.084,-0.068,0,0,-3.7e+02,8.3e-05,8.6e-05,0.046,0.025,0.026,0.0061,0.14,0.15,0.033,3.5e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00015,0.001,6e-05,0.0011,0.00056,0.0011,0.0011,1,1,0.01
25790000,0.78,0.025,-0.016,-0.62,0.35,0.25,-1.2,0.0015,0.042,-3.7e+02,-0.00099,-0.0058,4.2e-05,0.08,-0.029,-0.13,-0.12,-0.028,0.5,-0.0036,-0.083,-0.067,0,0,-3.7e+02,8.4e-05,8.6e-05,0.045,0.027,0.028,0.0061,0.15,0.16,0.033,3.5e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00015,0.00099,5.9e-05,0.0011,0.00056,0.001,0.0011,1,1,0.01
25890000,0.78,0.025,-0.016,-0.62,0.41,0.29,-1.3,0.041,0.065,-3.7e+02,-0.00099,-0.0058,5.7e-05,0.08,-0.029,-0.13,-0.12,-0.028,0.5,-0.0042,-0.081,-0.066,0,0,-3.7e+02,8.4e-05,8.7e-05,0.045,0.029,0.03,0.0061,0.16,0.17,0.033,3.5e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00015,0.00097,5.8e-05,0.0011,0.00056,0.001,0.0011,1,1,0.01
25990000,0.78,0.022,-0.016,-0.62,0.46,0.32,-1.3,0.084,0.093,-3.7e+02,-0.00099,-0.0058,6.6e-05,0.08,-0.029,-0.13,-0.12,-0.028,0.5,-0.0046,-0.08,-0.065,0,0,-3.7e+02,8.5e-05,8.8e-05,0.045,0.031,0.033,0.0061,0.18,0.18,0.033,3.5e-07,4.4e-07,2e-06,0.0053,0.0058,0.00015,0.00095,5.7e-05,0.0011,0.00055,0.001,0.0011,1,1,0.01
25990000,0.78,0.022,-0.016,-0.62,0.46,0.32,-1.3,0.084,0.093,-3.7e+02,-0.00099,-0.0058,6.6e-05,0.08,-0.03,-0.13,-0.12,-0.028,0.5,-0.0046,-0.08,-0.065,0,0,-3.7e+02,8.5e-05,8.8e-05,0.045,0.031,0.033,0.0061,0.18,0.18,0.033,3.5e-07,4.4e-07,2e-06,0.0053,0.0058,0.00015,0.00095,5.7e-05,0.0011,0.00055,0.001,0.0011,1,1,0.01
26090000,0.78,0.032,-0.019,-0.62,0.52,0.36,-1.3,0.13,0.13,-3.7e+02,-0.00099,-0.0058,6.4e-05,0.08,-0.03,-0.13,-0.12,-0.029,0.5,-0.0047,-0.079,-0.065,0,0,-3.7e+02,8.6e-05,8.8e-05,0.044,0.033,0.036,0.0061,0.19,0.19,0.033,3.5e-07,4.4e-07,2e-06,0.0053,0.0058,0.00015,0.00093,5.6e-05,0.0011,0.00055,0.00098,0.0011,1,1,0.01
26190000,0.78,0.042,-0.021,-0.62,0.59,0.41,-1.3,0.19,0.16,-3.7e+02,-0.00098,-0.0058,7.4e-05,0.08,-0.03,-0.13,-0.13,-0.03,0.5,-0.0055,-0.075,-0.063,0,0,-3.7e+02,8.7e-05,8.9e-05,0.043,0.036,0.039,0.0061,0.2,0.21,0.033,3.5e-07,4.4e-07,2e-06,0.0053,0.0058,0.00014,0.0009,5.4e-05,0.001,0.00054,0.00094,0.001,1,1,0.01
26290000,0.78,0.044,-0.022,-0.62,0.67,0.46,-1.3,0.25,0.2,-3.7e+02,-0.00097,-0.0058,7.8e-05,0.081,-0.03,-0.13,-0.13,-0.03,0.49,-0.0058,-0.073,-0.061,0,0,-3.7e+02,8.8e-05,8.9e-05,0.042,0.039,0.043,0.0061,0.21,0.22,0.033,3.5e-07,4.4e-07,2e-06,0.0053,0.0058,0.00014,0.00087,5.2e-05,0.001,0.00053,0.00091,0.00099,1,1,0.01
@@ -285,7 +285,7 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
28290000,0.78,0.054,-0.025,-0.63,2.4,1.7,-0.069,3.8,2.6,-3.7e+02,-0.00094,-0.0058,8.3e-05,0.084,-0.023,-0.13,-0.17,-0.04,0.46,-0.0049,-0.029,-0.029,0,0,-3.7e+02,0.0001,0.0001,0.0086,0.077,0.086,0.0061,0.71,0.75,0.033,3.7e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00036,2.4e-05,0.00045,0.00014,0.00038,0.00045,1,1,0.01
28390000,0.78,0.021,-0.013,-0.63,2.4,1.7,0.79,4,2.8,-3.7e+02,-0.00095,-0.0058,7.9e-05,0.084,-0.022,-0.13,-0.17,-0.041,0.46,-0.0046,-0.028,-0.029,0,0,-3.7e+02,0.0001,0.0001,0.0082,0.076,0.084,0.0061,0.75,0.79,0.033,3.7e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00036,2.3e-05,0.00045,0.00013,0.00037,0.00045,1,1,0.01
28490000,0.78,0.0015,-0.006,-0.63,2.4,1.7,1.1,4.3,3,-3.7e+02,-0.00096,-0.0058,7.4e-05,0.084,-0.021,-0.13,-0.17,-0.041,0.46,-0.0046,-0.028,-0.029,0,0,-3.7e+02,0.0001,0.0001,0.0079,0.077,0.083,0.0061,0.79,0.83,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00036,2.3e-05,0.00045,0.00013,0.00037,0.00045,1,1,0.01
28590000,0.78,-0.0022,-0.0046,-0.63,2.3,1.7,0.98,4.5,3.1,-3.7e+02,-0.00096,-0.0058,7.3e-05,0.084,-0.021,-0.13,-0.17,-0.041,0.46,-0.0046,-0.028,-0.029,0,0,-3.7e+02,0.0001,0.0001,0.0075,0.077,0.082,0.0061,0.83,0.87,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00035,2.3e-05,0.00045,0.00012,0.00037,0.00044,1,1,0.01
28590000,0.78,-0.0022,-0.0046,-0.63,2.3,1.7,0.98,4.5,3.1,-3.7e+02,-0.00096,-0.0058,7.2e-05,0.084,-0.021,-0.13,-0.17,-0.041,0.46,-0.0046,-0.028,-0.029,0,0,-3.7e+02,0.0001,0.0001,0.0075,0.077,0.082,0.0061,0.83,0.87,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00035,2.3e-05,0.00045,0.00012,0.00037,0.00044,1,1,0.01
28690000,0.78,-0.0031,-0.004,-0.63,2.3,1.6,0.99,4.7,3.3,-3.7e+02,-0.00097,-0.0058,6.8e-05,0.083,-0.021,-0.12,-0.17,-0.041,0.46,-0.0045,-0.028,-0.029,0,0,-3.7e+02,0.00011,0.0001,0.0072,0.077,0.082,0.0061,0.87,0.91,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00035,2.3e-05,0.00045,0.00012,0.00037,0.00044,1,1,0.01
28790000,0.78,-0.0035,-0.0038,-0.63,2.2,1.6,0.99,5,3.5,-3.7e+02,-0.00097,-0.0058,6.4e-05,0.083,-0.02,-0.12,-0.17,-0.041,0.46,-0.0043,-0.028,-0.029,0,0,-3.7e+02,0.00011,0.0001,0.0069,0.078,0.082,0.006,0.91,0.96,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00035,2.3e-05,0.00044,0.00012,0.00037,0.00044,1,1,0.01
28890000,0.78,-0.0032,-0.0038,-0.63,2.1,1.6,0.98,5.2,3.6,-3.7e+02,-0.00098,-0.0058,6e-05,0.082,-0.02,-0.12,-0.17,-0.041,0.46,-0.0042,-0.028,-0.029,0,0,-3.7e+02,0.00011,0.0001,0.0067,0.079,0.083,0.0061,0.96,1,0.033,3.5e-07,4.5e-07,2e-06,0.0051,0.0055,0.00011,0.00035,2.3e-05,0.00044,0.00011,0.00037,0.00044,1,1,0.01
@@ -302,90 +302,90 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
29990000,0.78,0.0036,-0.0058,-0.62,1.6,1.3,0.95,7.2,5.2,-3.7e+02,-0.001,-0.0057,1.4e-05,0.079,-0.013,-0.12,-0.17,-0.041,0.46,-0.003,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0052,0.096,0.11,0.006,1.5,1.7,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.3e-05,0.00043,9.6e-05,0.00036,0.00042,1,1,0.01
30090000,0.78,0.0035,-0.0058,-0.62,1.6,1.3,0.94,7.4,5.4,-3.7e+02,-0.001,-0.0057,1e-05,0.079,-0.012,-0.12,-0.17,-0.041,0.46,-0.0028,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0051,0.098,0.12,0.006,1.6,1.7,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00035,2.3e-05,0.00043,9.5e-05,0.00036,0.00042,1,1,0.01
30190000,0.78,0.0032,-0.0057,-0.62,1.6,1.3,0.93,7.6,5.5,-3.7e+02,-0.001,-0.0057,1.1e-05,0.078,-0.012,-0.12,-0.17,-0.041,0.46,-0.0029,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.005,0.1,0.12,0.006,1.7,1.8,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00035,2.2e-05,0.00043,9.4e-05,0.00036,0.00042,1,1,0.01
30290000,0.78,0.003,-0.0056,-0.62,1.5,1.3,0.92,7.7,5.6,-3.7e+02,-0.001,-0.0057,8.4e-06,0.078,-0.012,-0.12,-0.17,-0.041,0.46,-0.0028,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0049,0.1,0.13,0.006,1.7,1.9,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00035,2.2e-05,0.00043,9.3e-05,0.00036,0.00042,1,1,0.01
30290000,0.78,0.003,-0.0056,-0.62,1.5,1.3,0.92,7.7,5.6,-3.7e+02,-0.001,-0.0057,8.3e-06,0.078,-0.012,-0.12,-0.17,-0.041,0.46,-0.0028,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0049,0.1,0.13,0.006,1.7,1.9,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00035,2.2e-05,0.00043,9.3e-05,0.00036,0.00042,1,1,0.01
30390000,0.78,0.0028,-0.0056,-0.62,1.5,1.3,0.9,7.9,5.8,-3.7e+02,-0.0011,-0.0057,4.2e-06,0.077,-0.011,-0.12,-0.17,-0.041,0.46,-0.0028,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0049,0.1,0.13,0.006,1.8,2,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00035,2.2e-05,0.00042,9.2e-05,0.00036,0.00042,1,1,0.01
30490000,0.78,0.0026,-0.0055,-0.62,1.5,1.2,0.89,8,5.9,-3.7e+02,-0.0011,-0.0057,3.1e-06,0.077,-0.01,-0.12,-0.17,-0.041,0.46,-0.0028,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0048,0.11,0.14,0.006,1.9,2.1,0.033,3.2e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00034,2.2e-05,0.00042,9.2e-05,0.00036,0.00042,1,1,0.01
30590000,0.78,0.0021,-0.0054,-0.62,1.4,1.2,0.85,8.2,6,-3.7e+02,-0.0011,-0.0057,9.9e-07,0.077,-0.0095,-0.12,-0.17,-0.041,0.46,-0.0028,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0048,0.11,0.14,0.006,2,2.2,0.033,3.2e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00034,2.2e-05,0.00042,9.1e-05,0.00036,0.00042,1,1,0.01
30490000,0.78,0.0026,-0.0055,-0.62,1.5,1.2,0.89,8,5.9,-3.7e+02,-0.0011,-0.0057,3e-06,0.077,-0.01,-0.12,-0.17,-0.041,0.46,-0.0028,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0048,0.11,0.14,0.006,1.9,2.1,0.033,3.2e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00034,2.2e-05,0.00042,9.2e-05,0.00036,0.00042,1,1,0.01
30590000,0.78,0.0021,-0.0054,-0.62,1.4,1.2,0.85,8.2,6,-3.7e+02,-0.0011,-0.0057,9.7e-07,0.077,-0.0095,-0.12,-0.17,-0.041,0.46,-0.0028,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0048,0.11,0.14,0.006,2,2.2,0.033,3.2e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00034,2.2e-05,0.00042,9.1e-05,0.00036,0.00042,1,1,0.01
30690000,0.78,0.0018,-0.0053,-0.62,1.4,1.2,0.84,8.3,6.1,-3.7e+02,-0.0011,-0.0057,-2.3e-06,0.077,-0.0087,-0.12,-0.17,-0.041,0.46,-0.0027,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.00011,0.0047,0.11,0.15,0.006,2,2.3,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0054,0.0001,0.00034,2.2e-05,0.00042,9e-05,0.00036,0.00042,1,1,0.01
30790000,0.78,0.0014,-0.0052,-0.62,1.4,1.2,0.84,8.5,6.2,-3.7e+02,-0.0011,-0.0057,-5.4e-06,0.076,-0.0085,-0.12,-0.17,-0.041,0.46,-0.0026,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.00011,0.0047,0.11,0.15,0.006,2.1,2.4,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0054,0.0001,0.00034,2.2e-05,0.00042,9e-05,0.00036,0.00042,1,1,0.01
30890000,0.78,0.00095,-0.0051,-0.62,1.3,1.2,0.82,8.6,6.4,-3.7e+02,-0.0011,-0.0057,-8.3e-06,0.076,-0.0077,-0.12,-0.17,-0.041,0.46,-0.0026,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.00011,0.0046,0.12,0.16,0.0059,2.2,2.5,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0054,9.9e-05,0.00034,2.2e-05,0.00042,8.9e-05,0.00036,0.00042,1,1,0.01
30890000,0.78,0.00095,-0.0051,-0.62,1.3,1.2,0.82,8.6,6.4,-3.7e+02,-0.0011,-0.0057,-8.4e-06,0.076,-0.0077,-0.12,-0.17,-0.041,0.46,-0.0026,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.00011,0.0046,0.12,0.16,0.0059,2.2,2.5,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0054,9.9e-05,0.00034,2.2e-05,0.00042,8.9e-05,0.00036,0.00042,1,1,0.01
30990000,0.78,0.00035,-0.0051,-0.62,1.3,1.2,0.82,8.8,6.5,-3.7e+02,-0.0011,-0.0057,-1.2e-05,0.075,-0.0069,-0.12,-0.17,-0.041,0.46,-0.0025,-0.028,-0.027,0,0,-3.7e+02,0.00013,0.00011,0.0046,0.12,0.16,0.0059,2.3,2.6,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,9.9e-05,0.00034,2.2e-05,0.00042,8.9e-05,0.00036,0.00041,1,1,0.01
31090000,0.78,-0.00019,-0.0049,-0.62,1.3,1.1,0.81,8.9,6.6,-3.7e+02,-0.0011,-0.0057,-1.6e-05,0.075,-0.0062,-0.12,-0.17,-0.041,0.46,-0.0025,-0.028,-0.027,0,0,-3.7e+02,0.00013,0.00011,0.0045,0.12,0.17,0.0059,2.4,2.7,0.033,3.1e-07,4.6e-07,2e-06,0.0049,0.0053,9.8e-05,0.00034,2.2e-05,0.00042,8.8e-05,0.00036,0.00041,1,1,0.01
31190000,0.78,-0.00061,-0.0048,-0.62,1.2,1.1,0.8,9,6.7,-3.7e+02,-0.0011,-0.0057,-1.9e-05,0.075,-0.0054,-0.12,-0.17,-0.041,0.46,-0.0024,-0.028,-0.027,0,0,-3.7e+02,0.00013,0.00011,0.0045,0.12,0.18,0.0059,2.5,2.9,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.7e-05,0.00034,2.2e-05,0.00042,8.8e-05,0.00036,0.00041,1,1,0.01
31290000,0.78,-0.0012,-0.0046,-0.62,1.2,1.1,0.8,9.2,6.8,-3.7e+02,-0.0011,-0.0057,-2.1e-05,0.075,-0.0047,-0.12,-0.17,-0.041,0.46,-0.0024,-0.028,-0.027,0,0,-3.7e+02,0.00013,0.00011,0.0045,0.13,0.18,0.0059,2.6,3,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.7e-05,0.00034,2.2e-05,0.00042,8.8e-05,0.00036,0.00041,1,1,0.01
31390000,0.78,-0.0019,-0.0044,-0.62,1.2,1.1,0.8,9.3,6.9,-3.7e+02,-0.0011,-0.0057,-2.4e-05,0.075,-0.004,-0.12,-0.17,-0.041,0.46,-0.0024,-0.028,-0.027,0,0,-3.7e+02,0.00013,0.00011,0.0044,0.13,0.19,0.0059,2.6,3.1,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.6e-05,0.00034,2.2e-05,0.00042,8.7e-05,0.00036,0.00041,1,1,0.01
31390000,0.78,-0.0019,-0.0044,-0.62,1.2,1.1,0.8,9.3,6.9,-3.7e+02,-0.0011,-0.0057,-2.4e-05,0.075,-0.0041,-0.12,-0.17,-0.041,0.46,-0.0024,-0.028,-0.027,0,0,-3.7e+02,0.00013,0.00011,0.0044,0.13,0.19,0.0059,2.6,3.1,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.6e-05,0.00034,2.2e-05,0.00042,8.7e-05,0.00036,0.00041,1,1,0.01
31490000,0.78,-0.0025,-0.0043,-0.62,1.2,1.1,0.79,9.4,7,-3.7e+02,-0.0011,-0.0057,-3e-05,0.074,-0.0033,-0.12,-0.17,-0.041,0.46,-0.0023,-0.028,-0.026,0,0,-3.7e+02,0.00013,0.00011,0.0044,0.13,0.2,0.0059,2.7,3.3,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.6e-05,0.00034,2.2e-05,0.00042,8.7e-05,0.00036,0.00041,1,1,0.01
31590000,0.78,-0.0029,-0.0043,-0.62,1.1,1,0.79,9.5,7.1,-3.7e+02,-0.0011,-0.0057,-3.1e-05,0.073,-0.0026,-0.12,-0.17,-0.041,0.46,-0.0022,-0.028,-0.026,0,0,-3.7e+02,0.00013,0.00011,0.0044,0.13,0.21,0.0059,2.8,3.4,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.5e-05,0.00034,2.2e-05,0.00041,8.7e-05,0.00036,0.00041,1,1,0.01
31690000,0.78,-0.0037,-0.0041,-0.62,1.1,1,0.8,9.7,7.2,-3.7e+02,-0.0011,-0.0057,-3.3e-05,0.073,-0.0019,-0.12,-0.17,-0.041,0.46,-0.0022,-0.028,-0.026,0,0,-3.7e+02,0.00013,0.00011,0.0044,0.14,0.21,0.0059,2.9,3.5,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.4e-05,0.00034,2.2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1,0.01
31790000,0.78,-0.0044,-0.0039,-0.62,1.1,1,0.8,9.8,7.3,-3.7e+02,-0.0011,-0.0057,-3.6e-05,0.072,-0.001,-0.12,-0.17,-0.041,0.46,-0.0021,-0.029,-0.026,0,0,-3.7e+02,0.00013,0.00011,0.0043,0.14,0.22,0.0059,3.1,3.7,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0053,9.4e-05,0.00034,2.2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1,0.01
31890000,0.78,-0.0051,-0.0038,-0.62,1,0.99,0.79,9.9,7.4,-3.7e+02,-0.0011,-0.0057,-4e-05,0.072,-0.00016,-0.12,-0.17,-0.041,0.46,-0.0021,-0.029,-0.026,0,0,-3.7e+02,0.00013,0.00011,0.0043,0.14,0.23,0.0059,3.2,3.9,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0053,9.3e-05,0.00034,2.2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1,0.01
31990000,0.78,-0.0056,-0.0036,-0.62,1,0.97,0.79,10,7.5,-3.7e+02,-0.0012,-0.0057,-4.5e-05,0.071,0.00077,-0.12,-0.17,-0.041,0.46,-0.002,-0.029,-0.026,0,0,-3.7e+02,0.00014,0.00011,0.0043,0.15,0.24,0.0058,3.3,4,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0053,9.3e-05,0.00034,2.2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1,0.01
31890000,0.78,-0.0051,-0.0038,-0.62,1,0.99,0.79,9.9,7.4,-3.7e+02,-0.0011,-0.0057,-4e-05,0.072,-0.00017,-0.12,-0.17,-0.041,0.46,-0.0021,-0.029,-0.026,0,0,-3.7e+02,0.00013,0.00011,0.0043,0.14,0.23,0.0059,3.2,3.9,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0053,9.3e-05,0.00034,2.2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1,0.01
31990000,0.78,-0.0056,-0.0036,-0.62,1,0.97,0.79,10,7.5,-3.7e+02,-0.0012,-0.0057,-4.5e-05,0.071,0.00076,-0.12,-0.17,-0.041,0.46,-0.002,-0.029,-0.026,0,0,-3.7e+02,0.00014,0.00011,0.0043,0.15,0.24,0.0058,3.3,4,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0053,9.3e-05,0.00034,2.2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1,0.01
32090000,0.78,-0.0064,-0.0034,-0.62,0.99,0.96,0.8,10,7.7,-3.7e+02,-0.0012,-0.0057,-4.9e-05,0.071,0.0015,-0.11,-0.17,-0.041,0.46,-0.0019,-0.029,-0.026,0,0,-3.7e+02,0.00014,0.00011,0.0043,0.15,0.25,0.0059,3.4,4.2,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0052,9.2e-05,0.00034,2.2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1,0.01
32190000,0.78,-0.0073,-0.0032,-0.62,0.96,0.94,0.8,10,7.8,-3.7e+02,-0.0012,-0.0057,-5.8e-05,0.07,0.0024,-0.11,-0.17,-0.041,0.46,-0.0018,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0043,0.15,0.25,0.0058,3.5,4.4,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0052,9.1e-05,0.00034,2.2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1,0.01
32290000,0.78,-0.0081,-0.0031,-0.62,0.93,0.92,0.79,10,7.8,-3.7e+02,-0.0012,-0.0057,-6.2e-05,0.07,0.0034,-0.11,-0.17,-0.041,0.46,-0.0017,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.15,0.26,0.0058,3.6,4.6,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0052,9.1e-05,0.00034,2.2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1,0.01
32390000,0.78,-0.0087,-0.003,-0.62,0.9,0.9,0.79,10,7.9,-3.7e+02,-0.0012,-0.0057,-6.3e-05,0.069,0.0041,-0.11,-0.17,-0.041,0.46,-0.0017,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.16,0.27,0.0058,3.7,4.8,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0052,9e-05,0.00034,2.2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1,0.01
32490000,0.78,-0.0089,-0.003,-0.62,0.87,0.88,0.8,11,8,-3.7e+02,-0.0012,-0.0057,-6.5e-05,0.069,0.0048,-0.11,-0.17,-0.041,0.46,-0.0016,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.16,0.28,0.0058,3.9,5,0.033,2.9e-07,4.8e-07,2e-06,0.0049,0.0052,9e-05,0.00034,2.2e-05,0.0004,8.5e-05,0.00036,0.0004,1,1,0.01
32490000,0.78,-0.0089,-0.003,-0.62,0.87,0.88,0.8,11,8,-3.7e+02,-0.0012,-0.0057,-6.5e-05,0.069,0.0048,-0.11,-0.17,-0.041,0.46,-0.0016,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.16,0.28,0.0058,3.9,5,0.033,2.9e-07,4.7e-07,2e-06,0.0049,0.0052,9e-05,0.00034,2.2e-05,0.0004,8.5e-05,0.00036,0.0004,1,1,0.01
32590000,0.78,-0.0092,-0.0029,-0.62,-1.6,-0.84,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-6.9e-05,0.069,0.0052,-0.11,-0.17,-0.041,0.46,-0.0016,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.25,0.25,0.56,0.25,0.25,0.035,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.9e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.0004,1,1,0.01
32690000,0.79,-0.0093,-0.0029,-0.62,-1.6,-0.86,0.61,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.2e-05,0.068,0.0058,-0.11,-0.17,-0.041,0.46,-0.0015,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.25,0.25,0.55,0.26,0.26,0.047,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.9e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.0004,1,1,0.01
32790000,0.79,-0.0092,-0.0029,-0.62,-1.5,-0.84,0.61,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.4e-05,0.067,0.0062,-0.11,-0.17,-0.041,0.46,-0.0015,-0.029,-0.024,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.13,0.13,0.27,0.26,0.26,0.047,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.9e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.0004,1,1,0.01
32890000,0.79,-0.0091,-0.003,-0.62,-1.6,-0.86,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-8.3e-05,0.067,0.0067,-0.11,-0.17,-0.041,0.46,-0.0013,-0.029,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0042,0.13,0.13,0.26,0.27,0.27,0.058,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.00039,1,1,0.01
32990000,0.79,-0.0091,-0.0031,-0.62,-1.5,-0.85,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.7e-05,0.066,0.0072,-0.11,-0.17,-0.041,0.46,-0.0013,-0.029,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0041,0.084,0.085,0.17,0.27,0.27,0.056,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.00039,1,1,0.01
32990000,0.79,-0.0091,-0.0031,-0.62,-1.5,-0.85,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.8e-05,0.066,0.0072,-0.11,-0.17,-0.041,0.46,-0.0013,-0.029,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0041,0.084,0.085,0.17,0.27,0.27,0.056,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.00039,1,1,0.01
33090000,0.79,-0.0091,-0.0031,-0.62,-1.6,-0.87,0.57,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.5e-05,0.066,0.0074,-0.11,-0.17,-0.041,0.46,-0.0013,-0.029,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0041,0.084,0.085,0.16,0.28,0.28,0.065,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.00039,1,1,0.01
33190000,0.79,-0.0078,-0.0063,-0.61,-1.5,-0.85,0.52,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.2e-05,0.066,0.0075,-0.11,-0.17,-0.041,0.46,-0.0014,-0.029,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0041,0.063,0.065,0.11,0.28,0.28,0.062,2.8e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.3e-05,0.00036,0.00039,1,1,0.01
33290000,0.83,-0.0057,-0.018,-0.56,-1.5,-0.87,0.5,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.6e-05,0.066,0.0074,-0.11,-0.17,-0.041,0.46,-0.0014,-0.029,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0041,0.064,0.066,0.1,0.29,0.29,0.067,2.8e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.3e-05,0.00035,0.00039,1,1,0.01
33390000,0.9,-0.0064,-0.015,-0.44,-1.5,-0.86,0.7,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-6.3e-05,0.065,0.0071,-0.11,-0.18,-0.041,0.46,-0.00098,-0.027,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.004,0.051,0.053,0.082,0.29,0.29,0.065,2.8e-07,4.7e-07,2e-06,0.0048,0.0051,8.8e-05,0.00031,2e-05,0.0004,8.1e-05,0.00032,0.00039,1,1,0.01
33490000,0.96,-0.0051,-0.0069,-0.3,-1.5,-0.88,0.71,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-4.4e-05,0.065,0.0072,-0.11,-0.18,-0.043,0.46,-0.00048,-0.02,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0037,0.052,0.054,0.075,0.3,0.3,0.068,2.8e-07,4.7e-07,2e-06,0.0048,0.0051,8.8e-05,0.00023,1.6e-05,0.00039,7.3e-05,0.00024,0.00039,1,1,0.01
33590000,0.99,-0.0083,-0.00017,-0.13,-1.5,-0.86,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,1.7e-05,0.065,0.0072,-0.11,-0.19,-0.044,0.46,0.00029,-0.013,-0.024,0,0,-3.7e+02,0.00015,0.0001,0.0032,0.044,0.046,0.061,0.3,0.3,0.065,2.8e-07,4.6e-07,2e-06,0.0048,0.0051,8.8e-05,0.00015,1.2e-05,0.00039,6e-05,0.00015,0.00039,1,1,0.01
33690000,1,-0.012,0.004,0.038,-1.6,-0.88,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,2.3e-05,0.065,0.0072,-0.11,-0.19,-0.045,0.46,0.00013,-0.0091,-0.025,0,0,-3.7e+02,0.00015,0.0001,0.0028,0.044,0.048,0.056,0.31,0.31,0.067,2.8e-07,4.6e-07,2e-06,0.0048,0.0051,8.8e-05,0.0001,9e-06,0.00039,4.7e-05,9.7e-05,0.00038,1,1,0.01
33790000,0.98,-0.013,0.0065,0.21,-1.6,-0.9,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,6.8e-05,0.065,0.0072,-0.11,-0.2,-0.046,0.46,0.00049,-0.0066,-0.025,0,0,-3.7e+02,0.00015,0.0001,0.0023,0.039,0.043,0.047,0.31,0.31,0.064,2.7e-07,4.5e-07,1.9e-06,0.0048,0.0051,8.8e-05,6.9e-05,7.2e-06,0.00038,3.5e-05,6.2e-05,0.00038,1,1,0.01
33890000,0.93,-0.013,0.0085,0.37,-1.7,-0.95,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.2e-05,0.065,0.0072,-0.11,-0.2,-0.046,0.46,0.00071,-0.0053,-0.025,0,0,-3.7e+02,0.00015,0.0001,0.002,0.04,0.046,0.042,0.32,0.32,0.065,2.7e-07,4.5e-07,1.9e-06,0.0048,0.0051,8.8e-05,5e-05,6.2e-06,0.00038,2.7e-05,4.2e-05,0.00038,1,1,0.01
33490000,0.96,-0.0051,-0.0069,-0.3,-1.5,-0.88,0.71,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-4.4e-05,0.065,0.0071,-0.11,-0.18,-0.043,0.46,-0.00048,-0.02,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0037,0.052,0.054,0.075,0.3,0.3,0.068,2.8e-07,4.7e-07,2e-06,0.0048,0.0051,8.8e-05,0.00023,1.6e-05,0.00039,7.3e-05,0.00024,0.00039,1,1,0.01
33590000,0.99,-0.0083,-0.00017,-0.13,-1.5,-0.86,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,1.7e-05,0.065,0.0071,-0.11,-0.19,-0.044,0.46,0.00029,-0.013,-0.024,0,0,-3.7e+02,0.00015,0.0001,0.0032,0.044,0.046,0.061,0.3,0.3,0.065,2.8e-07,4.6e-07,2e-06,0.0048,0.0051,8.8e-05,0.00015,1.2e-05,0.00039,6e-05,0.00015,0.00039,1,1,0.01
33690000,1,-0.012,0.004,0.038,-1.6,-0.88,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,2.3e-05,0.065,0.0071,-0.11,-0.19,-0.045,0.46,0.00013,-0.0091,-0.025,0,0,-3.7e+02,0.00015,0.0001,0.0028,0.044,0.048,0.056,0.31,0.31,0.067,2.8e-07,4.6e-07,2e-06,0.0048,0.0051,8.8e-05,0.0001,9e-06,0.00039,4.7e-05,9.7e-05,0.00038,1,1,0.01
33790000,0.98,-0.013,0.0065,0.21,-1.6,-0.9,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,6.8e-05,0.065,0.0071,-0.11,-0.2,-0.046,0.46,0.00049,-0.0066,-0.025,0,0,-3.7e+02,0.00015,0.0001,0.0023,0.039,0.043,0.047,0.31,0.31,0.064,2.7e-07,4.5e-07,1.9e-06,0.0048,0.0051,8.8e-05,6.9e-05,7.2e-06,0.00038,3.5e-05,6.2e-05,0.00038,1,1,0.01
33890000,0.93,-0.013,0.0085,0.37,-1.7,-0.95,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.2e-05,0.065,0.0071,-0.11,-0.2,-0.046,0.46,0.00071,-0.0053,-0.025,0,0,-3.7e+02,0.00015,0.0001,0.002,0.04,0.046,0.042,0.32,0.32,0.065,2.7e-07,4.5e-07,1.9e-06,0.0048,0.0051,8.8e-05,5e-05,6.2e-06,0.00038,2.7e-05,4.2e-05,0.00038,1,1,0.01
33990000,0.86,-0.015,0.0071,0.51,-1.7,-0.98,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.065,0.0069,-0.11,-0.2,-0.046,0.46,0.0005,-0.0039,-0.025,0,0,-3.7e+02,0.00014,9.9e-05,0.0017,0.036,0.042,0.036,0.32,0.32,0.062,2.7e-07,4.4e-07,1.9e-06,0.0048,0.0051,8.8e-05,4e-05,5.6e-06,0.00038,2.1e-05,3e-05,0.00038,1,1,0.01
34090000,0.8,-0.016,0.0063,0.6,-1.7,-1.1,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.066,0.0063,-0.11,-0.2,-0.046,0.46,0.00017,-0.0033,-0.025,0,0,-3.7e+02,0.00014,9.9e-05,0.0016,0.038,0.046,0.033,0.33,0.33,0.063,2.7e-07,4.3e-07,1.9e-06,0.0048,0.0051,8.8e-05,3.4e-05,5.3e-06,0.00038,1.7e-05,2.4e-05,0.00038,1,1,0.01
34190000,0.75,-0.014,0.007,0.67,-1.8,-1.1,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0061,-0.11,-0.2,-0.047,0.46,0.00018,-0.0027,-0.025,0,0,-3.7e+02,0.00014,9.9e-05,0.0015,0.041,0.051,0.031,0.34,0.34,0.063,2.8e-07,4.3e-07,1.9e-06,0.0047,0.0051,8.8e-05,3e-05,5e-06,0.00038,1.4e-05,1.9e-05,0.00038,1,1,0.01
34290000,0.71,-0.011,0.0085,0.71,-1.8,-1.2,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0058,-0.11,-0.2,-0.047,0.46,0.00014,-0.0023,-0.025,0,0,-3.7e+02,0.00014,9.8e-05,0.0014,0.044,0.056,0.028,0.35,0.35,0.062,2.8e-07,4.3e-07,1.9e-06,0.0047,0.0051,8.8e-05,2.7e-05,4.9e-06,0.00038,1.2e-05,1.6e-05,0.00038,1,1,0.01
34390000,0.69,-0.0078,0.0099,0.73,-1.9,-1.3,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0054,-0.11,-0.2,-0.047,0.46,7.4e-05,-0.002,-0.025,0,0,-3.7e+02,0.00014,9.8e-05,0.0013,0.048,0.061,0.026,0.36,0.37,0.063,2.8e-07,4.3e-07,1.9e-06,0.0047,0.0051,8.8e-05,2.5e-05,4.8e-06,0.00038,1.1e-05,1.4e-05,0.00038,1,1,0.01
34490000,0.67,-0.0056,0.011,0.74,-1.9,-1.4,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0054,-0.11,-0.2,-0.047,0.46,3.2e-05,-0.002,-0.025,0,0,-3.7e+02,0.00014,9.7e-05,0.0013,0.052,0.068,0.024,0.38,0.38,0.062,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.8e-05,2.3e-05,4.7e-06,0.00038,9.9e-06,1.2e-05,0.00038,1,1,0.01
34590000,0.66,-0.0042,0.012,0.75,-2,-1.4,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.0053,-0.11,-0.2,-0.047,0.46,-6.3e-05,-0.0019,-0.025,0,0,-3.7e+02,0.00014,9.7e-05,0.0012,0.057,0.074,0.022,0.39,0.4,0.06,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.8e-05,2.2e-05,4.6e-06,0.00038,9e-06,1.1e-05,0.00038,1,1,0.01
34690000,0.65,-0.0034,0.013,0.76,-2,-1.5,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0052,-0.11,-0.2,-0.047,0.46,-4.8e-07,-0.0016,-0.025,0,0,-3.7e+02,0.00014,9.6e-05,0.0012,0.062,0.082,0.02,0.41,0.41,0.06,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.9e-05,2.1e-05,4.6e-06,0.00038,8.3e-06,9.9e-06,0.00038,1,1,0.01
34090000,0.8,-0.016,0.0063,0.6,-1.7,-1.1,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.066,0.0063,-0.11,-0.2,-0.046,0.46,0.00017,-0.0033,-0.025,0,0,-3.7e+02,0.00014,9.9e-05,0.0016,0.038,0.046,0.033,0.33,0.33,0.063,2.7e-07,4.3e-07,1.9e-06,0.0048,0.0051,8.9e-05,3.4e-05,5.3e-06,0.00038,1.7e-05,2.4e-05,0.00038,1,1,0.01
34190000,0.75,-0.014,0.007,0.67,-1.8,-1.1,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0061,-0.11,-0.2,-0.047,0.46,0.00018,-0.0027,-0.025,0,0,-3.7e+02,0.00014,9.9e-05,0.0015,0.041,0.051,0.031,0.34,0.34,0.063,2.8e-07,4.3e-07,1.9e-06,0.0047,0.0051,8.9e-05,3e-05,5e-06,0.00038,1.4e-05,1.9e-05,0.00038,1,1,0.01
34290000,0.71,-0.011,0.0085,0.71,-1.8,-1.2,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0058,-0.11,-0.2,-0.047,0.46,0.00014,-0.0023,-0.025,0,0,-3.7e+02,0.00014,9.8e-05,0.0014,0.044,0.056,0.028,0.35,0.35,0.062,2.8e-07,4.3e-07,1.9e-06,0.0047,0.0051,8.9e-05,2.7e-05,4.9e-06,0.00038,1.2e-05,1.6e-05,0.00038,1,1,0.01
34390000,0.69,-0.0078,0.0099,0.73,-1.9,-1.3,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0054,-0.11,-0.2,-0.047,0.46,7.3e-05,-0.002,-0.025,0,0,-3.7e+02,0.00014,9.8e-05,0.0013,0.048,0.061,0.026,0.36,0.37,0.063,2.8e-07,4.3e-07,1.9e-06,0.0047,0.0051,8.9e-05,2.5e-05,4.8e-06,0.00038,1.1e-05,1.4e-05,0.00038,1,1,0.01
34490000,0.67,-0.0056,0.011,0.74,-1.9,-1.4,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.0054,-0.11,-0.2,-0.047,0.46,3.2e-05,-0.002,-0.025,0,0,-3.7e+02,0.00014,9.7e-05,0.0013,0.052,0.068,0.024,0.38,0.38,0.062,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.9e-05,2.3e-05,4.7e-06,0.00038,9.9e-06,1.2e-05,0.00038,1,1,0.01
34590000,0.66,-0.0042,0.012,0.75,-2,-1.4,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.0053,-0.11,-0.2,-0.047,0.46,-6.4e-05,-0.0019,-0.025,0,0,-3.7e+02,0.00014,9.7e-05,0.0012,0.057,0.074,0.022,0.39,0.4,0.06,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.9e-05,2.2e-05,4.6e-06,0.00038,9e-06,1.1e-05,0.00038,1,1,0.01
34690000,0.65,-0.0034,0.013,0.76,-2,-1.5,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0052,-0.11,-0.2,-0.047,0.46,-5.8e-07,-0.0016,-0.025,0,0,-3.7e+02,0.00014,9.6e-05,0.0012,0.062,0.082,0.02,0.41,0.41,0.06,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.9e-05,2.1e-05,4.6e-06,0.00038,8.3e-06,9.9e-06,0.00038,1,1,0.01
34790000,0.65,-0.0028,0.013,0.76,-2.1,-1.6,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0051,-0.11,-0.2,-0.047,0.46,0.00012,-0.0016,-0.025,0,0,-3.7e+02,0.00014,9.6e-05,0.0012,0.068,0.09,0.018,0.42,0.43,0.059,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.9e-05,2.1e-05,4.5e-06,0.00038,7.8e-06,9.1e-06,0.00038,1,1,0.01
34890000,0.65,-0.0027,0.013,0.76,-2.1,-1.7,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,7.1e-05,-0.0016,-0.025,0,0,-3.7e+02,0.00014,9.6e-05,0.0012,0.075,0.099,0.017,0.44,0.46,0.058,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.9e-05,2e-05,4.5e-06,0.00038,7.3e-06,8.4e-06,0.00038,1,1,0.01
34890000,0.65,-0.0027,0.013,0.76,-2.1,-1.7,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0049,-0.11,-0.2,-0.047,0.46,7.1e-05,-0.0016,-0.025,0,0,-3.7e+02,0.00014,9.6e-05,0.0012,0.075,0.099,0.017,0.44,0.46,0.058,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.9e-05,2e-05,4.5e-06,0.00038,7.3e-06,8.4e-06,0.00038,1,1,0.01
34990000,0.64,-0.0062,0.02,0.76,-3,-2.6,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00018,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.5e-05,0.0012,0.092,0.13,0.016,0.46,0.48,0.057,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.9e-05,4.5e-06,0.00038,6.9e-06,7.9e-06,0.00038,1,1,0.01
35090000,0.64,-0.0063,0.02,0.76,-3.2,-2.7,-0.18,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.0002,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.5e-05,0.0012,0.1,0.14,0.015,0.49,0.51,0.056,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.9e-05,4.4e-06,0.00038,6.6e-06,7.4e-06,0.00038,1,1,0.01
35190000,0.64,-0.0064,0.02,0.76,-3.2,-2.8,-0.17,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00024,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.4e-05,0.0011,0.11,0.15,0.014,0.51,0.54,0.055,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.8e-05,4.4e-06,0.00038,6.3e-06,7e-06,0.00038,1,1,0.01
35290000,0.64,-0.0065,0.02,0.76,-3.2,-2.8,-0.16,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00029,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.4e-05,0.0011,0.12,0.17,0.013,0.54,0.58,0.053,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.8e-05,4.4e-06,0.00038,6e-06,6.6e-06,0.00038,1,1,0.01
35390000,0.64,-0.0065,0.02,0.76,-3.2,-2.9,-0.15,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00036,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.4e-05,0.0011,0.13,0.18,0.012,0.58,0.62,0.053,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.8e-05,4.3e-06,0.00038,5.8e-06,6.3e-06,0.00037,1,1,0.01
35490000,0.64,-0.0066,0.02,0.77,-3.3,-3,-0.14,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00043,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.3e-05,0.0011,0.14,0.19,0.012,0.61,0.67,0.052,2.9e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.8e-05,4.3e-06,0.00038,5.6e-06,6e-06,0.00037,1,1,0.01
35590000,0.64,-0.0066,0.02,0.77,-3.3,-3.1,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.0004,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.3e-05,0.0011,0.15,0.2,0.011,0.65,0.72,0.05,2.9e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.7e-05,4.3e-06,0.00038,5.4e-06,5.8e-06,0.00037,1,1,0.01
35690000,0.64,-0.0065,0.02,0.77,-3.3,-3.1,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0049,-0.11,-0.2,-0.047,0.46,0.00046,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.2e-05,0.0011,0.16,0.22,0.011,0.69,0.77,0.05,2.9e-07,4.4e-07,1.9e-06,0.0047,0.0051,8.9e-05,1.7e-05,4.3e-06,0.00038,5.3e-06,5.6e-06,0.00037,1,1,0.01
35790000,0.64,-0.0066,0.02,0.77,-3.4,-3.2,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0049,-0.11,-0.2,-0.047,0.46,0.00047,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.2e-05,0.0011,0.17,0.23,0.01,0.74,0.84,0.049,2.9e-07,4.4e-07,1.9e-06,0.0047,0.0051,8.9e-05,1.7e-05,4.3e-06,0.00038,5.1e-06,5.3e-06,0.00037,1,1,0.025
35890000,0.64,-0.0066,0.02,0.77,-3.4,-3.3,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00048,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.2e-05,0.0011,0.18,0.25,0.0096,0.79,0.9,0.048,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.7e-05,4.3e-06,0.00038,5e-06,5.2e-06,0.00037,1,1,0.056
35990000,0.64,-0.0066,0.02,0.77,-3.4,-3.3,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0049,-0.11,-0.2,-0.047,0.46,0.00045,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.1e-05,0.0011,0.2,0.26,0.0093,0.84,0.98,0.047,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.3e-06,0.00038,4.9e-06,5e-06,0.00037,1,1,0.086
36090000,0.64,-0.0067,0.02,0.77,-3.4,-3.4,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00048,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.1e-05,0.0011,0.21,0.28,0.0089,0.91,1.1,0.046,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.8e-06,4.8e-06,0.00037,1,1,0.12
36190000,0.64,-0.0067,0.02,0.77,-3.5,-3.5,-0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0053,-0.11,-0.2,-0.047,0.46,0.00056,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.1e-05,0.0011,0.22,0.3,0.0086,0.97,1.1,0.045,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.7e-06,4.7e-06,0.00037,1,1,0.15
36290000,0.64,-0.0067,0.02,0.77,-3.5,-3.6,-0.091,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00057,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9e-05,0.0011,0.24,0.31,0.0083,1,1.2,0.045,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.6e-06,4.6e-06,0.00037,1,1,0.18
36390000,0.64,-0.0067,0.02,0.77,-3.5,-3.6,-0.082,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.0051,-0.11,-0.2,-0.047,0.46,0.00056,-0.0015,-0.025,0,0,-3.7e+02,0.00012,9e-05,0.0011,0.25,0.33,0.0081,1.1,1.4,0.044,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.5e-06,4.4e-06,0.00037,1,1,0.21
36490000,0.64,-0.0068,0.02,0.77,-3.6,-3.7,-0.073,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.005,-0.11,-0.2,-0.047,0.46,0.00053,-0.0015,-0.025,0,0,-3.7e+02,0.00012,9e-05,0.0011,0.27,0.35,0.0078,1.2,1.5,0.043,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.6e-05,4.2e-06,0.00038,4.4e-06,4.3e-06,0.00037,1,1,0.24
36590000,0.64,-0.0068,0.02,0.77,-3.6,-3.8,-0.061,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.005,-0.11,-0.2,-0.047,0.46,0.00057,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.28,0.37,0.0076,1.3,1.6,0.042,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.6e-05,4.2e-06,0.00038,4.4e-06,4.2e-06,0.00037,1,1,0.27
36690000,0.64,-0.0068,0.02,0.77,-3.6,-3.9,-0.052,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.066,0.0052,-0.11,-0.2,-0.047,0.46,0.00059,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.3,0.39,0.0075,1.4,1.7,0.042,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.3e-06,4.1e-06,0.00037,1,1,0.31
36790000,0.64,-0.0069,0.02,0.77,-3.6,-3.9,-0.041,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.067,0.005,-0.11,-0.2,-0.047,0.46,0.00063,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.31,0.41,0.0073,1.5,1.9,0.041,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.3e-06,4e-06,0.00037,1,1,0.34
36890000,0.64,-0.0069,0.02,0.77,-3.7,-4,-0.033,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.067,0.0052,-0.11,-0.2,-0.047,0.46,0.00066,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.33,0.43,0.0072,1.6,2,0.04,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.2e-06,3.9e-06,0.00037,1,1,0.37
36990000,0.64,-0.0069,0.02,0.77,-3.7,-4.1,-0.024,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.067,0.0053,-0.11,-0.2,-0.047,0.46,0.00067,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.35,0.45,0.0071,1.8,2.2,0.04,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.2e-06,3.9e-06,0.00037,1,1,0.4
37090000,0.64,-0.0069,0.02,0.77,-3.7,-4.2,-0.015,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.068,0.0053,-0.11,-0.2,-0.047,0.46,0.00067,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.37,0.47,0.007,1.9,2.4,0.04,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.8e-06,0.00037,1,1,0.43
37190000,0.64,-0.0069,0.021,0.77,-3.7,-4.2,-0.0056,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.068,0.0053,-0.11,-0.2,-0.047,0.46,0.00067,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.38,0.49,0.0069,2,2.6,0.039,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.7e-06,0.00037,1,1,0.47
37290000,0.64,-0.007,0.021,0.77,-3.8,-4.3,0.0029,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.8e-05,0.068,0.0054,-0.11,-0.2,-0.047,0.46,0.00068,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.4,0.51,0.0068,2.2,2.8,0.039,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.7e-06,0.00037,1,1,0.5
37390000,0.64,-0.0069,0.021,0.77,-3.8,-4.4,0.011,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.4e-05,0.068,0.0053,-0.11,-0.2,-0.047,0.46,0.0007,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.0011,0.42,0.53,0.0068,2.4,3,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.6e-06,0.00037,1,1,0.53
37490000,0.64,-0.0069,0.021,0.77,-3.8,-4.5,0.019,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.8e-05,0.068,0.0053,-0.11,-0.2,-0.047,0.46,0.00072,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.44,0.56,0.0067,2.5,3.2,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.5e-06,0.00037,1,1,0.57
37590000,0.64,-0.007,0.021,0.77,-3.9,-4.5,0.029,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.4e-05,0.069,0.0053,-0.11,-0.2,-0.047,0.46,0.00073,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.46,0.58,0.0067,2.7,3.5,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.5e-06,0.00037,1,1,0.6
37690000,0.64,-0.007,0.021,0.77,-3.9,-4.6,0.039,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.8e-05,0.069,0.0054,-0.11,-0.2,-0.047,0.46,0.00074,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.48,0.6,0.0066,2.9,3.7,0.037,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.1e-05,1.5e-05,4.2e-06,0.00038,3.9e-06,3.4e-06,0.00037,1,1,0.64
37790000,0.64,-0.0071,0.021,0.77,-3.9,-4.7,0.048,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.6e-05,0.069,0.0052,-0.11,-0.2,-0.047,0.46,0.00075,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.5,0.63,0.0066,3.1,4,0.037,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.1e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.4e-06,0.00037,1,1,0.67
37890000,0.64,-0.0071,0.021,0.77,-3.9,-4.8,0.056,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.3e-05,0.069,0.0054,-0.11,-0.2,-0.047,0.46,0.00075,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.52,0.65,0.0065,3.4,4.3,0.036,3e-07,4.4e-07,1.8e-06,0.0047,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.3e-06,0.00037,1,1,0.7
37990000,0.64,-0.0072,0.021,0.77,-4,-4.8,0.066,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.3e-05,0.069,0.0052,-0.11,-0.2,-0.047,0.46,0.00075,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.54,0.67,0.0066,3.6,4.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.3e-06,0.00037,1,1,0.74
38090000,0.64,-0.0072,0.021,0.77,-4,-4.9,0.077,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.8e-05,0.07,0.0051,-0.11,-0.2,-0.047,0.46,0.00076,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.57,0.7,0.0065,3.9,4.9,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.2e-06,0.00037,1,1,0.77
38190000,0.64,-0.0072,0.021,0.77,-4,-5,0.085,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.6e-05,0.07,0.0051,-0.11,-0.2,-0.047,0.46,0.00077,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.59,0.72,0.0065,4.1,5.3,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.8e-06,3.2e-06,0.00037,1,1,0.81
38290000,0.64,-0.0072,0.021,0.77,-4,-5,0.093,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.5e-05,0.07,0.0051,-0.11,-0.2,-0.047,0.46,0.00077,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.61,0.75,0.0065,4.4,5.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.8e-06,3.1e-06,0.00037,1,1,0.84
38390000,0.64,-0.0071,0.021,0.77,-4.1,-5.1,0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.7e-05,0.07,0.0049,-0.11,-0.2,-0.047,0.46,0.00076,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.64,0.77,0.0065,4.7,6,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3.1e-06,0.00037,1,1,0.88
38490000,0.64,-0.0071,0.021,0.77,-4.1,-5.2,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.5e-05,0.07,0.005,-0.11,-0.2,-0.047,0.46,0.00077,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.66,0.8,0.0065,5.1,6.4,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1,0.92
38590000,0.64,-0.0071,0.021,0.77,-4.1,-5.3,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.6e-05,0.07,0.0052,-0.11,-0.2,-0.047,0.46,0.00077,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.68,0.82,0.0066,5.4,6.8,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1,0.95
38690000,0.64,-0.0071,0.021,0.77,-4.2,-5.3,0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.2e-05,0.069,0.0054,-0.11,-0.2,-0.047,0.46,0.00078,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.71,0.85,0.0066,5.8,7.3,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1,0.99
38790000,0.64,-0.0071,0.021,0.77,-4.2,-5.4,0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.1e-05,0.069,0.0052,-0.11,-0.2,-0.047,0.46,0.00078,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.73,0.87,0.0066,6.1,7.7,0.035,3.1e-07,4.3e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,2.9e-06,0.00037,1,1,1
38890000,0.64,-0.0072,0.021,0.77,-4.2,-5.4,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6e-05,0.069,0.0052,-0.11,-0.2,-0.047,0.46,0.00078,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.75,0.89,0.0066,6.5,8.2,0.035,3.1e-07,4.3e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,2.9e-06,0.00037,1,1,1.1
35190000,0.64,-0.0064,0.02,0.76,-3.2,-2.8,-0.17,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00024,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.4e-05,0.0011,0.11,0.15,0.014,0.51,0.54,0.055,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,9e-05,1.8e-05,4.4e-06,0.00038,6.3e-06,7e-06,0.00038,1,1,0.01
35290000,0.64,-0.0065,0.02,0.76,-3.2,-2.8,-0.16,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00029,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.4e-05,0.0011,0.12,0.17,0.013,0.54,0.58,0.053,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,9e-05,1.8e-05,4.4e-06,0.00038,6e-06,6.6e-06,0.00038,1,1,0.01
35390000,0.64,-0.0065,0.02,0.76,-3.2,-2.9,-0.15,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00036,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.4e-05,0.0011,0.13,0.18,0.012,0.58,0.62,0.053,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,9e-05,1.8e-05,4.3e-06,0.00038,5.8e-06,6.3e-06,0.00037,1,1,0.01
35490000,0.64,-0.0066,0.02,0.77,-3.3,-3,-0.14,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00043,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.3e-05,0.0011,0.14,0.19,0.012,0.61,0.67,0.052,2.9e-07,4.4e-07,1.8e-06,0.0047,0.0051,9e-05,1.8e-05,4.3e-06,0.00038,5.6e-06,6e-06,0.00037,1,1,0.01
35590000,0.64,-0.0066,0.02,0.77,-3.3,-3.1,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.0004,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.3e-05,0.0011,0.15,0.2,0.011,0.65,0.72,0.05,2.9e-07,4.4e-07,1.8e-06,0.0047,0.0051,9e-05,1.7e-05,4.3e-06,0.00038,5.4e-06,5.8e-06,0.00037,1,1,0.01
35690000,0.64,-0.0065,0.02,0.77,-3.3,-3.1,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0048,-0.11,-0.2,-0.047,0.46,0.00046,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.2e-05,0.0011,0.16,0.22,0.011,0.69,0.77,0.05,2.9e-07,4.4e-07,1.9e-06,0.0047,0.0051,9e-05,1.7e-05,4.3e-06,0.00038,5.3e-06,5.6e-06,0.00037,1,1,0.01
35790000,0.64,-0.0066,0.02,0.77,-3.4,-3.2,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0049,-0.11,-0.2,-0.047,0.46,0.00047,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.2e-05,0.0011,0.17,0.23,0.01,0.74,0.84,0.049,2.9e-07,4.4e-07,1.9e-06,0.0047,0.0051,9e-05,1.7e-05,4.3e-06,0.00038,5.1e-06,5.3e-06,0.00037,1,1,0.025
35890000,0.64,-0.0066,0.02,0.77,-3.4,-3.3,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00048,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.2e-05,0.0011,0.18,0.25,0.0096,0.79,0.9,0.048,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.7e-05,4.3e-06,0.00038,5e-06,5.2e-06,0.00037,1,1,0.056
35990000,0.64,-0.0066,0.02,0.77,-3.4,-3.3,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0049,-0.11,-0.2,-0.047,0.46,0.00045,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.1e-05,0.0011,0.2,0.26,0.0093,0.84,0.98,0.047,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.6e-05,4.3e-06,0.00038,4.9e-06,5e-06,0.00037,1,1,0.086
36090000,0.64,-0.0067,0.02,0.77,-3.4,-3.4,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00048,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.1e-05,0.0011,0.21,0.28,0.0089,0.91,1.1,0.046,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.6e-05,4.2e-06,0.00038,4.8e-06,4.8e-06,0.00037,1,1,0.12
36190000,0.64,-0.0067,0.02,0.77,-3.5,-3.5,-0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0053,-0.11,-0.2,-0.047,0.46,0.00056,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.1e-05,0.0011,0.22,0.3,0.0086,0.97,1.1,0.045,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.6e-05,4.2e-06,0.00038,4.7e-06,4.7e-06,0.00037,1,1,0.15
36290000,0.64,-0.0067,0.02,0.77,-3.5,-3.6,-0.091,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00057,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9e-05,0.0011,0.24,0.31,0.0083,1,1.2,0.045,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.6e-05,4.2e-06,0.00038,4.6e-06,4.6e-06,0.00037,1,1,0.18
36390000,0.64,-0.0067,0.02,0.77,-3.5,-3.6,-0.082,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.0051,-0.11,-0.2,-0.047,0.46,0.00056,-0.0015,-0.025,0,0,-3.7e+02,0.00012,9e-05,0.0011,0.25,0.33,0.0081,1.1,1.4,0.044,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.6e-05,4.2e-06,0.00038,4.5e-06,4.4e-06,0.00037,1,1,0.21
36490000,0.64,-0.0068,0.02,0.77,-3.6,-3.7,-0.073,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.005,-0.11,-0.2,-0.047,0.46,0.00053,-0.0015,-0.025,0,0,-3.7e+02,0.00012,9e-05,0.0011,0.27,0.35,0.0078,1.2,1.5,0.043,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.6e-05,4.2e-06,0.00038,4.4e-06,4.3e-06,0.00037,1,1,0.24
36590000,0.64,-0.0068,0.02,0.77,-3.6,-3.8,-0.061,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.005,-0.11,-0.2,-0.047,0.46,0.00057,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.28,0.37,0.0076,1.3,1.6,0.042,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.6e-05,4.2e-06,0.00038,4.4e-06,4.2e-06,0.00037,1,1,0.27
36690000,0.64,-0.0068,0.02,0.77,-3.6,-3.9,-0.052,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.066,0.0052,-0.11,-0.2,-0.047,0.46,0.00059,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.3,0.39,0.0075,1.4,1.7,0.042,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.5e-05,4.2e-06,0.00038,4.3e-06,4.1e-06,0.00037,1,1,0.31
36790000,0.64,-0.0069,0.02,0.77,-3.6,-3.9,-0.041,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.067,0.005,-0.11,-0.2,-0.047,0.46,0.00063,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.31,0.41,0.0073,1.5,1.9,0.041,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.5e-05,4.2e-06,0.00038,4.3e-06,4e-06,0.00037,1,1,0.34
36890000,0.64,-0.0069,0.02,0.77,-3.7,-4,-0.033,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.067,0.0051,-0.11,-0.2,-0.047,0.46,0.00066,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.33,0.43,0.0072,1.6,2,0.04,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.5e-05,4.2e-06,0.00038,4.2e-06,3.9e-06,0.00037,1,1,0.37
36990000,0.64,-0.0069,0.02,0.77,-3.7,-4.1,-0.024,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.067,0.0053,-0.11,-0.2,-0.047,0.46,0.00067,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.35,0.45,0.0071,1.8,2.2,0.04,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.5e-05,4.2e-06,0.00038,4.2e-06,3.9e-06,0.00037,1,1,0.4
37090000,0.64,-0.0069,0.02,0.77,-3.7,-4.2,-0.015,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.068,0.0053,-0.11,-0.2,-0.047,0.46,0.00067,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.37,0.47,0.007,1.9,2.4,0.04,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.1e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.8e-06,0.00037,1,1,0.43
37190000,0.64,-0.0069,0.021,0.77,-3.7,-4.2,-0.0056,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.068,0.0053,-0.11,-0.2,-0.047,0.46,0.00067,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.38,0.49,0.0069,2,2.6,0.039,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.1e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.7e-06,0.00037,1,1,0.47
37290000,0.64,-0.007,0.021,0.77,-3.8,-4.3,0.0029,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.8e-05,0.068,0.0054,-0.11,-0.2,-0.047,0.46,0.00068,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.4,0.51,0.0068,2.2,2.8,0.039,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.2e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.7e-06,0.00037,1,1,0.5
37390000,0.64,-0.0069,0.021,0.77,-3.8,-4.4,0.011,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.4e-05,0.068,0.0053,-0.11,-0.2,-0.047,0.46,0.0007,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.0011,0.42,0.53,0.0068,2.4,3,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.2e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.6e-06,0.00037,1,1,0.53
37490000,0.64,-0.0069,0.021,0.77,-3.8,-4.5,0.019,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.8e-05,0.068,0.0053,-0.11,-0.2,-0.047,0.46,0.00072,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.44,0.56,0.0067,2.5,3.2,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.2e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.5e-06,0.00037,1,1,0.57
37590000,0.64,-0.007,0.021,0.77,-3.9,-4.5,0.029,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.4e-05,0.069,0.0053,-0.11,-0.2,-0.047,0.46,0.00073,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.46,0.58,0.0067,2.7,3.5,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.2e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.5e-06,0.00037,1,1,0.6
37690000,0.64,-0.007,0.021,0.77,-3.9,-4.6,0.039,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.8e-05,0.069,0.0054,-0.11,-0.2,-0.047,0.46,0.00074,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.48,0.6,0.0066,2.9,3.7,0.037,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.2e-05,1.5e-05,4.2e-06,0.00038,3.9e-06,3.4e-06,0.00037,1,1,0.64
37790000,0.64,-0.0071,0.021,0.77,-3.9,-4.7,0.048,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.6e-05,0.069,0.0052,-0.11,-0.2,-0.047,0.46,0.00075,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.5,0.63,0.0066,3.1,4,0.037,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.2e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.4e-06,0.00037,1,1,0.67
37890000,0.64,-0.0071,0.021,0.77,-3.9,-4.8,0.056,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.3e-05,0.069,0.0054,-0.11,-0.2,-0.047,0.46,0.00075,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.52,0.65,0.0066,3.4,4.3,0.036,3e-07,4.4e-07,1.8e-06,0.0047,0.0049,9.2e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.3e-06,0.00037,1,1,0.7
37990000,0.64,-0.0072,0.021,0.77,-4,-4.8,0.066,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.3e-05,0.069,0.0052,-0.11,-0.2,-0.047,0.46,0.00075,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.54,0.67,0.0066,3.6,4.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.3e-06,0.00037,1,1,0.74
38090000,0.64,-0.0072,0.021,0.77,-4,-4.9,0.077,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.8e-05,0.07,0.0051,-0.11,-0.2,-0.047,0.46,0.00076,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.57,0.7,0.0065,3.9,4.9,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.2e-06,0.00037,1,1,0.77
38190000,0.64,-0.0072,0.021,0.77,-4,-5,0.085,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.6e-05,0.07,0.0051,-0.11,-0.2,-0.047,0.46,0.00077,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.59,0.72,0.0065,4.1,5.3,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.2e-06,0.00038,3.8e-06,3.2e-06,0.00037,1,1,0.81
38290000,0.64,-0.0072,0.021,0.77,-4,-5,0.093,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.5e-05,0.07,0.0051,-0.11,-0.2,-0.047,0.46,0.00077,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.61,0.75,0.0065,4.4,5.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.2e-06,0.00038,3.8e-06,3.1e-06,0.00037,1,1,0.84
38390000,0.64,-0.0071,0.021,0.77,-4.1,-5.1,0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.7e-05,0.07,0.0049,-0.11,-0.2,-0.047,0.46,0.00076,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.64,0.77,0.0065,4.7,6,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3.1e-06,0.00037,1,1,0.88
38490000,0.64,-0.0071,0.021,0.77,-4.1,-5.2,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.5e-05,0.07,0.005,-0.11,-0.2,-0.047,0.46,0.00077,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.66,0.8,0.0065,5.1,6.4,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1,0.92
38590000,0.64,-0.0071,0.021,0.77,-4.1,-5.3,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.6e-05,0.07,0.0052,-0.11,-0.2,-0.047,0.46,0.00077,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.68,0.82,0.0066,5.4,6.8,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1,0.95
38690000,0.64,-0.0071,0.021,0.77,-4.2,-5.3,0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.1e-05,0.069,0.0054,-0.11,-0.2,-0.047,0.46,0.00078,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.71,0.85,0.0066,5.8,7.3,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1,0.99
38790000,0.64,-0.0071,0.021,0.77,-4.2,-5.4,0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.1e-05,0.069,0.0052,-0.11,-0.2,-0.047,0.46,0.00078,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.73,0.88,0.0066,6.1,7.7,0.035,3.1e-07,4.3e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,2.9e-06,0.00037,1,1,1
38890000,0.64,-0.0072,0.021,0.77,-4.2,-5.4,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6e-05,0.069,0.0052,-0.11,-0.2,-0.047,0.46,0.00078,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.75,0.89,0.0066,6.5,8.2,0.035,3.1e-07,4.3e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,2.9e-06,0.00037,1,1,1.1
1 Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7],state[8],state[9],state[10],state[11],state[12],state[13],state[14],state[15],state[16],state[17],state[18],state[19],state[20],state[21],state[22],state[23],variance[0],variance[1],variance[2],variance[3],variance[4],variance[5],variance[6],variance[7],variance[8],variance[9],variance[10],variance[11],variance[12],variance[13],variance[14],variance[15],variance[16],variance[17],variance[18],variance[19],variance[20],variance[21],variance[22],variance[23]
75 7290000,0.78,-0.025,0.0067,-0.62,-0.38,-0.098,-0.14,-0.3,-0.082,-3.7e+02,5.3e-05,-0.011,-0.00022,-0.0016,-0.00042,0.00015,-0.1,-0.024,0.5,-0.0019,-0.085,-0.068,0,0,-3.6e+02,0.0013,0.0013,0.056,0.33,0.33,0.2,0.3,0.3,0.14,7.3e-05,7.5e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00013,0.0013,0.00081,0.0013,0.0013,1,1,1.9
76 7390000,0.78,-0.024,0.0068,-0.62,-0.41,-0.11,-0.16,-0.34,-0.093,-3.7e+02,7.4e-05,-0.011,-0.00022,-0.0017,-0.00046,8.6e-07,-0.1,-0.024,0.5,-0.0018,-0.085,-0.068,0,0,-3.6e+02,0.0013,0.0014,0.056,0.37,0.37,0.18,0.36,0.36,0.13,7.3e-05,7.4e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00012,0.0013,0.00081,0.0013,0.0013,1,1,1.9
77 7490000,0.78,-0.024,0.0069,-0.62,-0.43,-0.12,-0.16,-0.38,-0.11,-3.7e+02,0.00021,-0.011,-0.00023,-0.0019,-0.00054,-0.00076,-0.1,-0.024,0.5,-0.002,-0.085,-0.069,0,0,-3.6e+02,0.0013,0.0014,0.055,0.42,0.42,0.15,0.43,0.43,0.12,7.2e-05,7.4e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00011,0.0013,0.0008,0.0013,0.0013,1,1,1.9
78 7590000,0.78,-0.024,0.007,-0.62,-0.45,-0.12,-0.16,-0.41,-0.12,-3.7e+02,0.0002,-0.011,-0.00022,-0.0018,-0.00051,-0.0016,-0.1,-0.024,0.5,-0.0019,-0.085,-0.068,0,0,-3.6e+02,0.0013,0.0014,0.055,0.46,0.46,0.14,0.52,0.51,0.12,7.2e-05,7.3e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00011,0.0013,0.0008,0.0013,0.0013,1,1,1.9 7590000,0.78,-0.024,0.007,-0.62,-0.45,-0.12,-0.16,-0.41,-0.12,-3.7e+02,0.0002,-0.011,-0.00022,-0.0018,-0.00052,-0.0016,-0.1,-0.024,0.5,-0.0019,-0.085,-0.068,0,0,-3.6e+02,0.0013,0.0014,0.055,0.46,0.46,0.14,0.52,0.51,0.12,7.2e-05,7.3e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00011,0.0013,0.0008,0.0013,0.0013,1,1,1.9
79 7690000,0.78,-0.024,0.007,-0.62,-0.011,-0.0016,-0.16,-0.44,-0.14,-3.7e+02,0.00029,-0.011,-0.00022,-0.0019,-0.00051,-0.0036,-0.1,-0.024,0.5,-0.002,-0.085,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,25,25,0.13,1e+02,1e+02,0.11,7.1e-05,7.3e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.0001,0.0013,0.0008,0.0013,0.0013,1,1,2
80 7790000,0.78,-0.024,0.0073,-0.62,-0.038,-0.0061,-0.16,-0.44,-0.14,-3.7e+02,0.00035,-0.011,-0.00023,-0.0019,-0.00051,-0.0056,-0.1,-0.024,0.5,-0.002,-0.085,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,25,25,0.12,1e+02,1e+02,0.11,7e-05,7.2e-05,2.4e-06,0.04,0.04,0.038,0.0013,0.0001,0.0013,0.00079,0.0013,0.0013,1,1,2
81 7890000,0.78,-0.024,0.0072,-0.62,-0.063,-0.011,-0.15,-0.44,-0.14,-3.7e+02,0.00039,-0.011,-0.00022,-0.0019,-0.00051,-0.0081,-0.1,-0.024,0.5,-0.0021,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,25,25,0.11,50,50,0.1,6.9e-05,7.1e-05,2.4e-06,0.04,0.04,0.038,0.0013,9.8e-05,0.0013,0.00079,0.0013,0.0013,1,1,2 7890000,0.78,-0.024,0.0072,-0.62,-0.063,-0.011,-0.15,-0.44,-0.14,-3.7e+02,0.00039,-0.011,-0.00022,-0.0019,-0.00051,-0.0081,-0.1,-0.024,0.5,-0.0021,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,25,25,0.11,50,50,0.1,6.9e-05,7e-05,2.4e-06,0.04,0.04,0.038,0.0013,9.8e-05,0.0013,0.00079,0.0013,0.0013,1,1,2
82 7990000,0.78,-0.024,0.0072,-0.62,-0.089,-0.016,-0.16,-0.45,-0.14,-3.7e+02,0.0004,-0.011,-0.00022,-0.0019,-0.00051,-0.0094,-0.1,-0.024,0.5,-0.0021,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,25,25,0.1,51,51,0.099,6.7e-05,6.9e-05,2.4e-06,0.04,0.04,0.038,0.0013,9.5e-05,0.0013,0.00079,0.0013,0.0013,1,1,2
83 8090000,0.78,-0.024,0.0071,-0.62,-0.11,-0.021,-0.17,-0.45,-0.14,-3.7e+02,0.00044,-0.01,-0.00021,-0.0019,-0.00051,-0.0096,-0.1,-0.024,0.5,-0.0022,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,24,24,0.1,35,35,0.097,6.6e-05,6.8e-05,2.4e-06,0.04,0.04,0.037,0.0013,9.4e-05,0.0013,0.00079,0.0013,0.0013,1,1,2.1
84 8190000,0.78,-0.024,0.0073,-0.62,-0.14,-0.025,-0.18,-0.47,-0.14,-3.7e+02,0.00043,-0.01,-0.00021,-0.0019,-0.00051,-0.012,-0.1,-0.024,0.5,-0.0022,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,25,25,0.099,36,36,0.094,6.4e-05,6.6e-05,2.4e-06,0.04,0.04,0.037,0.0013,9.2e-05,0.0013,0.00078,0.0013,0.0013,1,1,2.1
85 8290000,0.78,-0.024,0.0073,-0.62,-0.16,-0.03,-0.17,-0.47,-0.14,-3.7e+02,0.00053,-0.01,-0.00021,-0.0019,-0.00051,-0.016,-0.1,-0.024,0.5,-0.0023,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.054,24,24,0.097,28,28,0.091,6.3e-05,6.4e-05,2.4e-06,0.04,0.04,0.036,0.0013,9e-05,0.0013,0.00078,0.0013,0.0013,1,1,2.1 8290000,0.78,-0.024,0.0073,-0.62,-0.16,-0.03,-0.17,-0.47,-0.14,-3.7e+02,0.00053,-0.01,-0.00021,-0.0019,-0.00051,-0.016,-0.1,-0.024,0.5,-0.0023,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.054,24,24,0.097,28,28,0.091,6.2e-05,6.4e-05,2.4e-06,0.04,0.04,0.036,0.0013,9e-05,0.0013,0.00078,0.0013,0.0013,1,1,2.1
86 8390000,0.78,-0.024,0.007,-0.63,-0.18,-0.036,-0.17,-0.48,-0.15,-3.7e+02,0.00055,-0.01,-0.00021,-0.0019,-0.00051,-0.019,-0.1,-0.024,0.5,-0.0024,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.054,24,24,0.097,29,29,0.091,6.1e-05,6.3e-05,2.4e-06,0.04,0.04,0.035,0.0013,8.9e-05,0.0013,0.00078,0.0013,0.0013,1,1,2.1
87 8490000,0.78,-0.024,0.007,-0.63,-0.2,-0.04,-0.17,-0.49,-0.15,-3.7e+02,0.00056,-0.0099,-0.0002,-0.0019,-0.00051,-0.024,-0.1,-0.024,0.5,-0.0024,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.054,23,23,0.096,24,24,0.089,5.9e-05,6.1e-05,2.4e-06,0.04,0.04,0.034,0.0013,8.8e-05,0.0013,0.00077,0.0013,0.0013,1,1,2.2
88 8590000,0.78,-0.023,0.0072,-0.63,-0.22,-0.038,-0.17,-0.51,-0.15,-3.7e+02,0.00036,-0.0099,-0.0002,-0.0019,-0.00051,-0.028,-0.1,-0.024,0.5,-0.0022,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.054,23,23,0.095,26,26,0.088,5.6e-05,5.9e-05,2.4e-06,0.04,0.04,0.034,0.0013,8.7e-05,0.0013,0.00077,0.0013,0.0013,1,1,2.2
92 8990000,0.78,-0.023,0.0068,-0.63,-0.27,-0.053,-0.14,-0.55,-0.16,-3.7e+02,0.00045,-0.0093,-0.00018,-0.0019,-0.00051,-0.049,-0.1,-0.024,0.5,-0.0026,-0.086,-0.069,0,0,-3.6e+02,0.0013,0.0014,0.054,19,19,0.096,24,24,0.087,4.8e-05,5e-05,2.4e-06,0.04,0.04,0.029,0.0012,8.3e-05,0.0013,0.00075,0.0013,0.0013,1,1,2.3
93 9090000,0.78,-0.022,0.0068,-0.63,-0.29,-0.054,-0.14,-0.58,-0.17,-3.7e+02,0.00037,-0.0092,-0.00018,-0.0019,-0.00051,-0.052,-0.1,-0.024,0.5,-0.0025,-0.086,-0.069,0,0,-3.6e+02,0.0013,0.0014,0.054,19,19,0.095,27,27,0.086,4.6e-05,4.8e-05,2.4e-06,0.04,0.04,0.028,0.0012,8.2e-05,0.0013,0.00075,0.0013,0.0013,1,1,2.3
94 9190000,0.78,-0.022,0.0061,-0.63,-0.3,-0.064,-0.14,-0.6,-0.17,-3.7e+02,0.00038,-0.0088,-0.00017,-0.0018,-0.0003,-0.055,-0.11,-0.025,0.5,-0.0027,-0.087,-0.069,0,0,-3.6e+02,0.0013,0.0013,0.054,19,19,0.094,30,30,0.085,4.3e-05,4.5e-05,2.4e-06,0.04,0.04,0.027,0.0012,8.2e-05,0.0013,0.00074,0.0013,0.0013,1,1,2.3
95 9290000,0.78,-0.022,0.0058,-0.63,-0.31,-0.073,-0.14,-0.62,-0.18,-3.7e+02,0.0004,-0.0086,-0.00016,-0.0018,-6.5e-05,-0.059,-0.11,-0.025,0.5,-0.0029,-0.087,-0.069,0,0,-3.6e+02,0.0013,0.0013,0.054,19,19,0.093,34,34,0.085,4.1e-05,4.3e-05,2.4e-06,0.04,0.04,0.025,0.0012,8.1e-05,0.0013,0.00074,0.0013,0.0013,1,1,2.4 9290000,0.78,-0.022,0.0058,-0.63,-0.31,-0.073,-0.14,-0.62,-0.18,-3.7e+02,0.0004,-0.0086,-0.00016,-0.0018,-6.6e-05,-0.059,-0.11,-0.025,0.5,-0.0029,-0.087,-0.069,0,0,-3.6e+02,0.0013,0.0013,0.054,19,19,0.093,34,34,0.085,4.1e-05,4.3e-05,2.4e-06,0.04,0.04,0.025,0.0012,8.1e-05,0.0013,0.00074,0.0013,0.0013,1,1,2.4
96 9390000,0.78,-0.022,0.0057,-0.63,-0.33,-0.082,-0.13,-0.65,-0.19,-3.7e+02,0.00043,-0.0085,-0.00016,-0.0019,0.00012,-0.063,-0.11,-0.025,0.5,-0.003,-0.087,-0.069,0,0,-3.6e+02,0.0013,0.0013,0.054,19,19,0.093,38,38,0.086,3.9e-05,4.1e-05,2.4e-06,0.04,0.04,0.024,0.0012,8e-05,0.0013,0.00074,0.0013,0.0013,1,1,2.4
97 9490000,0.78,-0.022,0.0052,-0.63,-0.33,-0.095,-0.13,-0.67,-0.21,-3.7e+02,0.00046,-0.0082,-0.00015,-0.0018,0.00038,-0.067,-0.11,-0.025,0.5,-0.0032,-0.087,-0.069,0,0,-3.6e+02,0.0013,0.0013,0.054,19,19,0.091,42,42,0.085,3.7e-05,3.9e-05,2.4e-06,0.04,0.04,0.023,0.0012,8e-05,0.0013,0.00073,0.0013,0.0013,1,1,2.4
98 9590000,0.78,-0.022,0.0049,-0.63,-0.34,-0.094,-0.13,-0.7,-0.22,-3.7e+02,0.00031,-0.008,-0.00014,-0.0018,0.00067,-0.07,-0.11,-0.025,0.5,-0.0031,-0.087,-0.069,0,0,-3.6e+02,0.0012,0.0013,0.054,20,20,0.09,47,47,0.085,3.5e-05,3.7e-05,2.4e-06,0.04,0.04,0.022,0.0012,7.9e-05,0.0013,0.00073,0.0013,0.0013,1,1,2.4 9590000,0.78,-0.022,0.0049,-0.63,-0.34,-0.094,-0.13,-0.7,-0.22,-3.7e+02,0.00031,-0.008,-0.00014,-0.0018,0.00066,-0.07,-0.11,-0.025,0.5,-0.0031,-0.087,-0.069,0,0,-3.6e+02,0.0012,0.0013,0.054,20,20,0.09,47,47,0.085,3.5e-05,3.7e-05,2.4e-06,0.04,0.04,0.022,0.0012,7.9e-05,0.0013,0.00073,0.0013,0.0013,1,1,2.4
99 9690000,0.78,-0.022,0.0051,-0.63,-0.36,-0.092,-0.12,-0.73,-0.22,-3.7e+02,0.00022,-0.008,-0.00014,-0.0021,0.0009,-0.075,-0.11,-0.025,0.5,-0.003,-0.087,-0.069,0,0,-3.6e+02,0.0012,0.0012,0.054,20,20,0.089,53,53,0.086,3.3e-05,3.5e-05,2.4e-06,0.04,0.04,0.02,0.0012,7.9e-05,0.0013,0.00072,0.0013,0.0013,1,1,2.5
100 9790000,0.78,-0.022,0.0047,-0.63,-0.37,-0.1,-0.11,-0.75,-0.24,-3.7e+02,0.00023,-0.0078,-0.00014,-0.0021,0.0012,-0.081,-0.11,-0.025,0.5,-0.0031,-0.087,-0.069,0,0,-3.6e+02,0.0012,0.0012,0.054,20,20,0.087,58,58,0.085,3.1e-05,3.3e-05,2.4e-06,0.04,0.04,0.019,0.0012,7.8e-05,0.0013,0.00072,0.0013,0.0013,1,1,2.5
101 9890000,0.78,-0.021,0.0045,-0.63,-0.37,-0.11,-0.11,-0.78,-0.24,-3.7e+02,0.00014,-0.0077,-0.00013,-0.0021,0.0014,-0.083,-0.11,-0.025,0.5,-0.0031,-0.087,-0.069,0,0,-3.6e+02,0.0012,0.0012,0.054,20,20,0.084,64,64,0.085,2.9e-05,3.2e-05,2.4e-06,0.04,0.04,0.018,0.0012,7.8e-05,0.0013,0.00072,0.0013,0.0013,1,1,2.5
102 9990000,0.78,-0.021,0.0045,-0.63,-0.39,-0.11,-0.1,-0.81,-0.25,-3.7e+02,9.8e-05,-0.0077,-0.00013,-0.0023,0.0016,-0.087,-0.11,-0.025,0.5,-0.0031,-0.088,-0.069,0,0,-3.6e+02,0.0012,0.0012,0.054,20,20,0.083,71,71,0.086,2.8e-05,3e-05,2.4e-06,0.04,0.04,0.017,0.0012,7.8e-05,0.0013,0.00071,0.0013,0.0013,1,1,2.5
103 10090000,0.78,-0.021,0.0043,-0.63,-0.39,-0.11,-0.096,-0.84,-0.26,-3.7e+02,-9.1e-06,-0.0075,-0.00012,-0.0023,0.0018,-0.09,-0.11,-0.025,0.5,-0.003,-0.088,-0.069,0,0,-3.6e+02,0.0012,0.0012,0.054,20,20,0.08,78,78,0.085,2.6e-05,2.9e-05,2.4e-06,0.04,0.04,0.016,0.0012,7.7e-05,0.0013,0.00071,0.0013,0.0013,1,1,2.6 10090000,0.78,-0.021,0.0043,-0.63,-0.39,-0.11,-0.096,-0.84,-0.26,-3.7e+02,-9.2e-06,-0.0075,-0.00012,-0.0023,0.0018,-0.09,-0.11,-0.025,0.5,-0.003,-0.088,-0.069,0,0,-3.6e+02,0.0012,0.0012,0.054,20,20,0.08,78,78,0.085,2.6e-05,2.9e-05,2.4e-06,0.04,0.04,0.016,0.0012,7.7e-05,0.0013,0.00071,0.0013,0.0013,1,1,2.6
104 10190000,0.78,-0.021,0.0045,-0.63,-0.42,-0.1,-0.096,-0.88,-0.26,-3.7e+02,-4.1e-05,-0.0076,-0.00012,-0.0024,0.0019,-0.091,-0.11,-0.025,0.5,-0.0029,-0.088,-0.069,0,0,-3.6e+02,0.0011,0.0011,0.054,20,20,0.078,85,85,0.084,2.5e-05,2.7e-05,2.4e-06,0.04,0.04,0.015,0.0012,7.7e-05,0.0013,0.00071,0.0013,0.0013,1,1,2.6
105 10290000,0.78,-0.021,0.0047,-0.63,-0.44,-0.1,-0.083,-0.92,-0.27,-3.7e+02,-6.8e-05,-0.0076,-0.00012,-0.0026,0.0022,-0.097,-0.11,-0.025,0.5,-0.0029,-0.088,-0.069,0,0,-3.6e+02,0.0011,0.0011,0.054,20,20,0.076,92,92,0.085,2.4e-05,2.6e-05,2.4e-06,0.04,0.04,0.014,0.0012,7.6e-05,0.0013,0.0007,0.0013,0.0013,1,1,2.6
106 10390000,0.78,-0.021,0.0045,-0.63,-0.0085,-0.022,0.0097,8e-05,-0.0019,-3.7e+02,-5.8e-05,-0.0075,-0.00012,-0.0026,0.0023,-0.1,-0.11,-0.025,0.5,-0.003,-0.088,-0.069,0,0,-3.6e+02,0.0011,0.0011,0.054,0.25,0.25,0.56,0.25,0.25,0.078,2.2e-05,2.4e-05,2.3e-06,0.04,0.04,0.013,0.0012,7.6e-05,0.0013,0.0007,0.0013,0.0013,1,1,2.6
107 10490000,0.78,-0.021,0.0046,-0.63,-0.028,-0.025,0.023,-0.0017,-0.0043,-3.7e+02,-8e-05,-0.0075,-0.00012,-0.0028,0.0025,-0.1,-0.11,-0.025,0.5,-0.0029,-0.088,-0.069,0,0,-3.6e+02,0.0011,0.0011,0.054,0.25,0.25,0.55,0.26,0.26,0.08,2.1e-05,2.3e-05,2.3e-06,0.04,0.04,0.012,0.0012,7.6e-05,0.0013,0.0007,0.0013,0.0013,1,1,2.7
108 10590000,0.78,-0.02,0.0043,-0.63,-0.026,-0.014,0.026,0.0015,-0.00091,-3.7e+02,-0.00026,-0.0074,-0.00011,-0.0019,0.0024,-0.1,-0.11,-0.025,0.5,-0.0028,-0.088,-0.069,0,0,-3.6e+02,0.0011,0.0011,0.054,0.13,0.13,0.27,0.13,0.13,0.073,2e-05,2.2e-05,2.3e-06,0.04,0.04,0.012,0.0012,7.6e-05,0.0013,0.0007,0.0013,0.0013,1,1,2.7
109 10690000,0.78,-0.02,0.0042,-0.63,-0.043,-0.015,0.03,-0.002,-0.0024,-3.7e+02,-0.00028,-0.0073,-0.00011,-0.0019,0.0025,-0.11,-0.11,-0.025,0.5,-0.0028,-0.088,-0.069,0,0,-3.6e+02,0.001,0.001,0.054,0.13,0.13,0.26,0.14,0.14,0.078,1.9e-05,2.1e-05,2.3e-06,0.04,0.04,0.011,0.0012,7.6e-05,0.0013,0.00069,0.0013,0.0013,1,1,2.7
110 10790000,0.78,-0.02,0.0038,-0.63,-0.04,-0.011,0.024,0.001,-0.0011,-3.7e+02,-0.00033,-0.0072,-0.0001,-0.00016,0.0013,-0.11,-0.11,-0.025,0.5,-0.0029,-0.088,-0.069,0,0,-3.6e+02,0.001,0.001,0.054,0.091,0.091,0.17,0.09,0.09,0.072,1.7e-05,1.9e-05,2.3e-06,0.039,0.039,0.011,0.0012,7.6e-05,0.0013,0.00069,0.0013,0.0013,1,1,2.7 10790000,0.78,-0.02,0.0038,-0.63,-0.04,-0.011,0.024,0.001,-0.0011,-3.7e+02,-0.00033,-0.0072,-0.0001,-0.00015,0.0013,-0.11,-0.11,-0.025,0.5,-0.0029,-0.088,-0.069,0,0,-3.6e+02,0.001,0.001,0.054,0.091,0.091,0.17,0.09,0.09,0.072,1.7e-05,1.9e-05,2.3e-06,0.039,0.039,0.011,0.0012,7.6e-05,0.0013,0.00069,0.0013,0.0013,1,1,2.7
111 10890000,0.78,-0.02,0.0037,-0.63,-0.057,-0.013,0.02,-0.0036,-0.0024,-3.7e+02,-0.00035,-0.0071,-0.0001,-0.0001,0.0014,-0.11,-0.11,-0.025,0.5,-0.0029,-0.088,-0.069,0,0,-3.6e+02,0.00099,0.00099,0.054,0.099,0.099,0.16,0.096,0.096,0.075,1.7e-05,1.8e-05,2.3e-06,0.039,0.039,0.011,0.0012,7.6e-05,0.0013,0.00069,0.0013,0.0013,1,1,2.8 10890000,0.78,-0.02,0.0037,-0.63,-0.057,-0.013,0.02,-0.0036,-0.0024,-3.7e+02,-0.00035,-0.0071,-0.0001,-9.7e-05,0.0014,-0.11,-0.11,-0.025,0.5,-0.0029,-0.088,-0.069,0,0,-3.6e+02,0.00099,0.00099,0.054,0.099,0.099,0.16,0.096,0.096,0.075,1.7e-05,1.8e-05,2.3e-06,0.039,0.039,0.011,0.0012,7.6e-05,0.0013,0.00069,0.0013,0.0013,1,1,2.8
112 10990000,0.78,-0.02,0.003,-0.63,-0.048,-0.011,0.015,0.00017,-0.0012,-3.7e+02,-0.00038,-0.0069,-9.7e-05,0.0036,-0.00085,-0.11,-0.11,-0.025,0.5,-0.0031,-0.089,-0.069,0,0,-3.6e+02,0.00093,0.00094,0.053,0.078,0.078,0.12,0.098,0.098,0.071,1.5e-05,1.7e-05,2.3e-06,0.038,0.038,0.011,0.0012,7.6e-05,0.0013,0.00069,0.0013,0.0013,1,1,2.8
113 11090000,0.78,-0.02,0.0026,-0.63,-0.06,-0.015,0.02,-0.0047,-0.0027,-3.7e+02,-0.00042,-0.0068,-9.2e-05,0.0037,-0.00042,-0.11,-0.11,-0.025,0.5,-0.0031,-0.089,-0.07,0,0,-3.6e+02,0.00092,0.00092,0.053,0.087,0.088,0.11,0.11,0.11,0.074,1.5e-05,1.6e-05,2.3e-06,0.038,0.038,0.011,0.0012,7.6e-05,0.0013,0.00068,0.0013,0.0013,1,1,2.8
114 11190000,0.78,-0.019,0.0021,-0.63,-0.053,-0.011,0.0082,0.00075,-0.00057,-3.7e+02,-0.00052,-0.0067,-8.9e-05,0.0082,-0.0036,-0.11,-0.11,-0.025,0.5,-0.0031,-0.089,-0.07,0,0,-3.6e+02,0.00085,0.00086,0.053,0.073,0.073,0.084,0.11,0.11,0.069,1.3e-05,1.5e-05,2.3e-06,0.037,0.037,0.011,0.0012,7.6e-05,0.0013,0.00068,0.0013,0.0013,1,1,2.8
115 11290000,0.78,-0.019,0.0022,-0.63,-0.069,-0.013,0.008,-0.0056,-0.0018,-3.7e+02,-0.00049,-0.0067,-9.1e-05,0.0083,-0.0038,-0.11,-0.11,-0.025,0.5,-0.0032,-0.089,-0.07,0,0,-3.6e+02,0.00084,0.00085,0.053,0.083,0.084,0.078,0.12,0.12,0.072,1.3e-05,1.4e-05,2.3e-06,0.037,0.037,0.01,0.0012,7.6e-05,0.0013,0.00068,0.0013,0.0012,1,1,2.9
116 11390000,0.78,-0.019,0.0018,-0.63,-0.064,-0.011,0.0024,0.00037,-0.00044,-3.7e+02,-0.00058,-0.0067,-8.9e-05,0.012,-0.0074,-0.11,-0.11,-0.025,0.5,-0.0032,-0.089,-0.07,0,0,-3.6e+02,0.00076,0.00077,0.052,0.067,0.068,0.063,0.081,0.081,0.068,1.2e-05,1.3e-05,2.3e-06,0.035,0.035,0.01,0.0012,7.5e-05,0.0013,0.00068,0.0013,0.0012,1,1,2.9
117 11490000,0.78,-0.019,0.002,-0.63,-0.078,-0.012,0.0032,-0.0071,-0.0015,-3.7e+02,-0.00056,-0.0068,-9.2e-05,0.012,-0.0079,-0.11,-0.11,-0.025,0.5,-0.0032,-0.089,-0.07,0,0,-3.6e+02,0.00076,0.00076,0.052,0.078,0.079,0.058,0.088,0.088,0.069,1.1e-05,1.2e-05,2.3e-06,0.035,0.035,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1,2.9 11490000,0.78,-0.019,0.002,-0.63,-0.078,-0.012,0.0032,-0.0071,-0.0014,-3.7e+02,-0.00056,-0.0068,-9.2e-05,0.012,-0.0079,-0.11,-0.11,-0.025,0.5,-0.0032,-0.089,-0.07,0,0,-3.6e+02,0.00076,0.00076,0.052,0.078,0.079,0.058,0.088,0.088,0.069,1.1e-05,1.2e-05,2.3e-06,0.035,0.035,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1,2.9
118 11590000,0.78,-0.019,0.0015,-0.63,-0.069,-0.012,-0.0027,-0.0021,-0.00084,-3.7e+02,-0.00061,-0.0067,-9.1e-05,0.017,-0.012,-0.11,-0.11,-0.025,0.5,-0.0033,-0.089,-0.07,0,0,-3.6e+02,0.00068,0.00069,0.052,0.066,0.066,0.049,0.068,0.068,0.066,1e-05,1.1e-05,2.3e-06,0.033,0.033,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1,2.9
119 11690000,0.78,-0.019,0.0016,-0.63,-0.08,-0.016,-0.0071,-0.0097,-0.0025,-3.7e+02,-0.00057,-0.0067,-9.2e-05,0.017,-0.012,-0.11,-0.11,-0.025,0.5,-0.0034,-0.089,-0.07,0,0,-3.6e+02,0.00067,0.00068,0.052,0.076,0.077,0.046,0.074,0.074,0.066,9.9e-06,1.1e-05,2.3e-06,0.033,0.033,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1,3
120 11790000,0.78,-0.019,0.001,-0.63,-0.072,-0.011,-0.0089,-0.0061,-0.00025,-3.7e+02,-0.00061,-0.0066,-9.1e-05,0.023,-0.015,-0.11,-0.11,-0.025,0.5,-0.0036,-0.09,-0.07,0,0,-3.6e+02,0.0006,0.00061,0.051,0.064,0.065,0.039,0.06,0.06,0.063,9.1e-06,9.9e-06,2.3e-06,0.03,0.03,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1,3
121 11890000,0.78,-0.019,0.0011,-0.63,-0.083,-0.012,-0.0098,-0.014,-0.0014,-3.7e+02,-0.00061,-0.0066,-9.1e-05,0.023,-0.016,-0.11,-0.11,-0.025,0.5,-0.0036,-0.09,-0.07,0,0,-3.6e+02,0.00059,0.00061,0.051,0.075,0.075,0.037,0.066,0.066,0.063,8.7e-06,9.5e-06,2.3e-06,0.03,0.03,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1,3
122 11990000,0.78,-0.019,0.00053,-0.63,-0.071,-0.0069,-0.015,-0.009,0.00086,-3.7e+02,-0.00076,-0.0065,-8.7e-05,0.027,-0.018,-0.11,-0.11,-0.025,0.5,-0.0035,-0.09,-0.07,0,0,-3.6e+02,0.00052,0.00054,0.051,0.063,0.064,0.033,0.055,0.055,0.061,8e-06,8.8e-06,2.3e-06,0.028,0.028,0.01,0.0012,7.5e-05,0.0013,0.00066,0.0013,0.0012,1,1,3 11990000,0.78,-0.019,0.00053,-0.63,-0.071,-0.0068,-0.015,-0.009,0.00086,-3.7e+02,-0.00076,-0.0065,-8.7e-05,0.027,-0.018,-0.11,-0.11,-0.025,0.5,-0.0035,-0.09,-0.07,0,0,-3.6e+02,0.00052,0.00054,0.051,0.063,0.064,0.033,0.055,0.055,0.061,8e-06,8.8e-06,2.3e-06,0.028,0.028,0.01,0.0012,7.5e-05,0.0013,0.00066,0.0013,0.0012,1,1,3
123 12090000,0.78,-0.018,0.00037,-0.63,-0.078,-0.0091,-0.021,-0.016,-3.3e-05,-3.7e+02,-0.00081,-0.0065,-8.3e-05,0.026,-0.017,-0.11,-0.11,-0.025,0.5,-0.0034,-0.09,-0.07,0,0,-3.6e+02,0.00052,0.00054,0.051,0.073,0.074,0.031,0.061,0.061,0.061,7.7e-06,8.4e-06,2.3e-06,0.028,0.028,0.01,0.0012,7.5e-05,0.0013,0.00066,0.0013,0.0012,1,1,3.1 12090000,0.78,-0.018,0.00037,-0.63,-0.078,-0.0091,-0.021,-0.016,-3.2e-05,-3.7e+02,-0.00081,-0.0065,-8.3e-05,0.026,-0.017,-0.11,-0.11,-0.025,0.5,-0.0034,-0.09,-0.07,0,0,-3.6e+02,0.00052,0.00054,0.051,0.073,0.074,0.031,0.061,0.061,0.061,7.7e-06,8.4e-06,2.3e-06,0.028,0.028,0.01,0.0012,7.5e-05,0.0013,0.00066,0.0013,0.0012,1,1,3.1
124 12190000,0.78,-0.018,-0.00031,-0.62,-0.064,-0.011,-0.016,-0.0085,-0.0004,-3.7e+02,-0.00082,-0.0064,-8.3e-05,0.032,-0.022,-0.11,-0.11,-0.025,0.5,-0.0037,-0.091,-0.07,0,0,-3.6e+02,0.00046,0.00048,0.051,0.062,0.062,0.028,0.052,0.052,0.059,7.2e-06,7.8e-06,2.3e-06,0.026,0.026,0.01,0.0012,7.5e-05,0.0012,0.00066,0.0013,0.0012,1,1,3.1
125 12290000,0.78,-0.019,-0.00032,-0.62,-0.07,-0.014,-0.015,-0.015,-0.0021,-3.7e+02,-0.00079,-0.0064,-8.3e-05,0.033,-0.021,-0.11,-0.11,-0.025,0.5,-0.0037,-0.091,-0.07,0,0,-3.6e+02,0.00046,0.00047,0.051,0.07,0.071,0.028,0.058,0.058,0.059,6.9e-06,7.5e-06,2.3e-06,0.026,0.026,0.01,0.0012,7.5e-05,0.0012,0.00066,0.0013,0.0012,1,1,3.1
126 12390000,0.78,-0.018,-0.00073,-0.62,-0.057,-0.012,-0.013,-0.0083,-0.001,-3.7e+02,-0.00086,-0.0063,-8.3e-05,0.037,-0.026,-0.11,-0.11,-0.025,0.5,-0.0038,-0.091,-0.07,0,0,-3.6e+02,0.0004,0.00042,0.05,0.059,0.06,0.026,0.05,0.05,0.057,6.4e-06,7e-06,2.3e-06,0.024,0.024,0.01,0.0012,7.5e-05,0.0012,0.00066,0.0013,0.0012,1,1,3.1
127 12490000,0.78,-0.018,-0.00059,-0.62,-0.064,-0.013,-0.016,-0.015,-0.0022,-3.7e+02,-0.00083,-0.0064,-8.5e-05,0.038,-0.026,-0.11,-0.11,-0.025,0.5,-0.0038,-0.091,-0.07,0,0,-3.6e+02,0.0004,0.00042,0.05,0.067,0.068,0.026,0.056,0.057,0.057,6.2e-06,6.8e-06,2.3e-06,0.024,0.024,0.01,0.0012,7.5e-05,0.0012,0.00066,0.0013,0.0012,1,1,3.2
128 12590000,0.78,-0.018,-0.00079,-0.62,-0.06,-0.011,-0.022,-0.013,-0.001,-3.7e+02,-0.00092,-0.0063,-8.3e-05,0.039,-0.027,-0.11,-0.11,-0.025,0.5,-0.0037,-0.091,-0.07,0,0,-3.6e+02,0.00036,0.00038,0.05,0.057,0.057,0.025,0.048,0.048,0.055,5.8e-06,6.4e-06,2.3e-06,0.022,0.023,0.0099,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1,3.2
129 12690000,0.78,-0.018,-0.00072,-0.62,-0.065,-0.011,-0.025,-0.019,-0.0014,-3.7e+02,-0.00099,-0.0064,-8.2e-05,0.036,-0.027,-0.11,-0.11,-0.025,0.5,-0.0035,-0.091,-0.07,0,0,-3.6e+02,0.00036,0.00037,0.05,0.064,0.064,0.025,0.055,0.055,0.055,5.6e-06,6.1e-06,2.3e-06,0.022,0.022,0.0099,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1,3.2 12690000,0.78,-0.018,-0.00072,-0.62,-0.065,-0.011,-0.025,-0.019,-0.0013,-3.7e+02,-0.00099,-0.0064,-8.2e-05,0.036,-0.027,-0.11,-0.11,-0.025,0.5,-0.0035,-0.091,-0.07,0,0,-3.6e+02,0.00036,0.00037,0.05,0.064,0.064,0.025,0.055,0.055,0.055,5.6e-06,6.1e-06,2.3e-06,0.022,0.023,0.0099,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1,3.2
130 12790000,0.78,-0.018,-0.001,-0.62,-0.061,-0.0098,-0.029,-0.017,-0.0012,-3.7e+02,-0.00097,-0.0063,-8.2e-05,0.04,-0.029,-0.11,-0.11,-0.025,0.5,-0.0036,-0.091,-0.07,0,0,-3.6e+02,0.00032,0.00034,0.05,0.054,0.054,0.024,0.048,0.048,0.053,5.3e-06,5.8e-06,2.3e-06,0.021,0.021,0.0097,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1,3.2
131 12890000,0.78,-0.018,-0.00099,-0.62,-0.068,-0.011,-0.028,-0.024,-0.0027,-3.7e+02,-0.00093,-0.0063,-8.2e-05,0.041,-0.029,-0.11,-0.11,-0.025,0.5,-0.0038,-0.091,-0.07,0,0,-3.6e+02,0.00032,0.00034,0.05,0.06,0.061,0.025,0.055,0.055,0.054,5.1e-06,5.6e-06,2.3e-06,0.02,0.021,0.0097,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1,3.3
132 12990000,0.78,-0.018,-0.0015,-0.62,-0.055,-0.01,-0.028,-0.018,-0.0026,-3.7e+02,-0.00097,-0.0062,-8e-05,0.045,-0.031,-0.11,-0.11,-0.025,0.5,-0.0038,-0.091,-0.07,0,0,-3.6e+02,0.00029,0.00031,0.05,0.054,0.054,0.025,0.057,0.057,0.052,4.9e-06,5.3e-06,2.3e-06,0.019,0.02,0.0094,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1,3.3
139 13690000,0.78,-0.018,-0.0023,-0.62,-0.041,-0.015,-0.023,-0.018,-0.006,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.054,-0.035,-0.12,-0.11,-0.025,0.5,-0.0041,-0.091,-0.07,0,0,-3.6e+02,0.00023,0.00025,0.049,0.057,0.057,0.029,0.096,0.096,0.05,3.7e-06,4.1e-06,2.3e-06,0.016,0.017,0.0083,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.5
140 13790000,0.78,-0.018,-0.0024,-0.62,-0.029,-0.013,-0.024,-0.0067,-0.0046,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.054,-0.037,-0.12,-0.11,-0.025,0.5,-0.004,-0.092,-0.07,0,0,-3.6e+02,0.00021,0.00023,0.049,0.044,0.044,0.029,0.071,0.071,0.049,3.6e-06,4e-06,2.3e-06,0.015,0.016,0.0079,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.5
141 13890000,0.78,-0.018,-0.0025,-0.62,-0.033,-0.015,-0.029,-0.01,-0.0066,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.056,-0.037,-0.12,-0.11,-0.025,0.5,-0.0041,-0.092,-0.07,0,0,-3.6e+02,0.00021,0.00023,0.049,0.048,0.048,0.03,0.079,0.079,0.05,3.5e-06,3.9e-06,2.3e-06,0.015,0.016,0.0078,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.5
142 13990000,0.78,-0.018,-0.0026,-0.62,-0.025,-0.014,-0.028,-0.0036,-0.0056,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.057,-0.037,-0.12,-0.11,-0.025,0.5,-0.0041,-0.092,-0.07,0,0,-3.6e+02,0.0002,0.00021,0.049,0.039,0.039,0.03,0.062,0.062,0.05,3.3e-06,3.7e-06,2.3e-06,0.014,0.015,0.0074,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.5 13990000,0.78,-0.018,-0.0026,-0.62,-0.025,-0.014,-0.028,-0.0036,-0.0056,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.057,-0.038,-0.12,-0.11,-0.025,0.5,-0.0041,-0.092,-0.07,0,0,-3.6e+02,0.0002,0.00021,0.049,0.039,0.039,0.03,0.062,0.062,0.05,3.3e-06,3.7e-06,2.3e-06,0.014,0.015,0.0074,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.5
143 14090000,0.78,-0.018,-0.0027,-0.62,-0.026,-0.015,-0.029,-0.0058,-0.0071,-3.7e+02,-0.0011,-0.0061,-7.6e-05,0.056,-0.036,-0.12,-0.11,-0.025,0.5,-0.004,-0.092,-0.07,0,0,-3.6e+02,0.0002,0.00021,0.049,0.042,0.042,0.031,0.07,0.07,0.05,3.2e-06,3.6e-06,2.4e-06,0.014,0.015,0.0073,0.0012,7.4e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.6
144 14190000,0.78,-0.017,-0.0028,-0.62,-0.021,-0.013,-0.031,-0.00023,-0.005,-3.7e+02,-0.0011,-0.0061,-7.5e-05,0.058,-0.036,-0.12,-0.11,-0.026,0.5,-0.004,-0.092,-0.069,0,0,-3.6e+02,0.00019,0.0002,0.049,0.036,0.036,0.03,0.057,0.057,0.05,3.1e-06,3.5e-06,2.4e-06,0.014,0.015,0.0069,0.0012,7.4e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.6
145 14290000,0.78,-0.017,-0.0029,-0.62,-0.022,-0.015,-0.03,-0.0022,-0.0063,-3.7e+02,-0.0011,-0.006,-7.4e-05,0.057,-0.036,-0.12,-0.11,-0.026,0.5,-0.004,-0.092,-0.069,0,0,-3.6e+02,0.00019,0.0002,0.049,0.039,0.039,0.032,0.063,0.063,0.051,3e-06,3.4e-06,2.4e-06,0.013,0.014,0.0067,0.0012,7.4e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.6
146 14390000,0.78,-0.017,-0.003,-0.62,-0.017,-0.015,-0.032,0.0018,-0.005,-3.7e+02,-0.0011,-0.006,-7.3e-05,0.06,-0.035,-0.12,-0.11,-0.026,0.5,-0.004,-0.092,-0.069,0,0,-3.6e+02,0.00018,0.00019,0.049,0.033,0.033,0.031,0.053,0.053,0.05,2.9e-06,3.3e-06,2.4e-06,0.013,0.014,0.0063,0.0012,7.4e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.6 14390000,0.78,-0.017,-0.003,-0.62,-0.017,-0.015,-0.032,0.0018,-0.0049,-3.7e+02,-0.0011,-0.006,-7.3e-05,0.06,-0.035,-0.12,-0.11,-0.026,0.5,-0.004,-0.092,-0.069,0,0,-3.6e+02,0.00018,0.00019,0.049,0.033,0.033,0.031,0.053,0.053,0.05,2.9e-06,3.3e-06,2.4e-06,0.013,0.014,0.0063,0.0012,7.4e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.6
147 14490000,0.78,-0.017,-0.0031,-0.62,-0.019,-0.018,-0.035,-0.00044,-0.0069,-3.7e+02,-0.001,-0.006,-7.4e-05,0.062,-0.036,-0.12,-0.11,-0.026,0.5,-0.0041,-0.092,-0.069,0,0,-3.6e+02,0.00018,0.00019,0.049,0.036,0.036,0.032,0.059,0.059,0.051,2.8e-06,3.2e-06,2.4e-06,0.013,0.014,0.0062,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.7
148 14590000,0.78,-0.017,-0.003,-0.62,-0.02,-0.018,-0.035,-0.0013,-0.0065,-3.7e+02,-0.001,-0.006,-7.4e-05,0.063,-0.036,-0.12,-0.11,-0.026,0.5,-0.0042,-0.092,-0.069,0,0,-3.6e+02,0.00017,0.00019,0.049,0.031,0.031,0.031,0.05,0.05,0.051,2.8e-06,3.1e-06,2.4e-06,0.012,0.013,0.0058,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.7
149 14690000,0.78,-0.017,-0.0031,-0.62,-0.023,-0.017,-0.032,-0.0034,-0.0085,-3.7e+02,-0.00099,-0.006,-7.3e-05,0.064,-0.035,-0.12,-0.11,-0.026,0.5,-0.0042,-0.092,-0.069,0,0,-3.6e+02,0.00017,0.00019,0.049,0.034,0.034,0.032,0.056,0.056,0.051,2.7e-06,3e-06,2.4e-06,0.012,0.013,0.0056,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.7
150 14790000,0.78,-0.017,-0.0031,-0.62,-0.023,-0.016,-0.028,-0.0036,-0.0079,-3.7e+02,-0.00099,-0.006,-7.3e-05,0.065,-0.035,-0.12,-0.11,-0.026,0.5,-0.0042,-0.092,-0.069,0,0,-3.6e+02,0.00016,0.00018,0.049,0.03,0.03,0.031,0.048,0.048,0.051,2.6e-06,2.9e-06,2.4e-06,0.012,0.013,0.0053,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.7 14790000,0.78,-0.017,-0.0031,-0.62,-0.023,-0.016,-0.028,-0.0036,-0.0079,-3.7e+02,-0.00099,-0.006,-7.3e-05,0.065,-0.035,-0.12,-0.11,-0.026,0.5,-0.0042,-0.091,-0.069,0,0,-3.6e+02,0.00016,0.00018,0.049,0.03,0.03,0.031,0.048,0.048,0.051,2.6e-06,2.9e-06,2.4e-06,0.012,0.013,0.0053,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.7
151 14890000,0.78,-0.017,-0.0031,-0.62,-0.026,-0.019,-0.031,-0.006,-0.0098,-3.7e+02,-0.00098,-0.006,-7.3e-05,0.065,-0.035,-0.12,-0.11,-0.026,0.5,-0.0042,-0.092,-0.069,0,0,-3.6e+02,0.00016,0.00018,0.049,0.032,0.033,0.031,0.054,0.054,0.052,2.5e-06,2.9e-06,2.4e-06,0.012,0.013,0.0051,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.8
152 14990000,0.78,-0.017,-0.0031,-0.62,-0.024,-0.016,-0.027,-0.0046,-0.0077,-3.7e+02,-0.00098,-0.006,-7.3e-05,0.066,-0.036,-0.12,-0.11,-0.026,0.5,-0.0042,-0.092,-0.069,0,0,-3.6e+02,0.00016,0.00017,0.049,0.029,0.029,0.03,0.047,0.047,0.051,2.4e-06,2.8e-06,2.4e-06,0.012,0.012,0.0048,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.8
153 15090000,0.78,-0.017,-0.003,-0.62,-0.026,-0.017,-0.03,-0.0072,-0.0093,-3.7e+02,-0.00098,-0.006,-7.4e-05,0.066,-0.036,-0.12,-0.11,-0.026,0.5,-0.0042,-0.091,-0.069,0,0,-3.6e+02,0.00016,0.00017,0.049,0.031,0.031,0.031,0.052,0.052,0.052,2.4e-06,2.7e-06,2.4e-06,0.011,0.012,0.0046,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.8
154 15190000,0.78,-0.017,-0.003,-0.62,-0.024,-0.016,-0.027,-0.0058,-0.0075,-3.7e+02,-0.00097,-0.006,-7.4e-05,0.067,-0.037,-0.12,-0.11,-0.026,0.5,-0.0043,-0.091,-0.069,0,0,-3.6e+02,0.00015,0.00017,0.049,0.027,0.027,0.03,0.046,0.046,0.052,2.3e-06,2.6e-06,2.4e-06,0.011,0.012,0.0043,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.8
155 15290000,0.78,-0.017,-0.003,-0.62,-0.025,-0.018,-0.025,-0.0081,-0.0092,-3.7e+02,-0.00098,-0.006,-7.3e-05,0.067,-0.036,-0.12,-0.11,-0.026,0.5,-0.0042,-0.091,-0.069,0,0,-3.6e+02,0.00015,0.00017,0.049,0.03,0.03,0.03,0.051,0.051,0.052,2.2e-06,2.6e-06,2.4e-06,0.011,0.012,0.0041,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.9
156 15390000,0.78,-0.017,-0.0031,-0.62,-0.025,-0.018,-0.023,-0.0075,-0.0094,-3.7e+02,-0.001,-0.006,-7e-05,0.067,-0.035,-0.13,-0.11,-0.026,0.5,-0.0041,-0.091,-0.069,0,0,-3.6e+02,0.00015,0.00016,0.049,0.028,0.029,0.029,0.053,0.053,0.051,2.2e-06,2.5e-06,2.4e-06,0.011,0.012,0.0038,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,3.9
157 15490000,0.78,-0.017,-0.003,-0.62,-0.027,-0.018,-0.023,-0.01,-0.011,-3.7e+02,-0.001,-0.006,-7.1e-05,0.067,-0.036,-0.13,-0.11,-0.026,0.5,-0.0042,-0.091,-0.069,0,0,-3.6e+02,0.00015,0.00016,0.049,0.031,0.031,0.029,0.06,0.06,0.053,2.1e-06,2.4e-06,2.4e-06,0.011,0.012,0.0037,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,3.9 15490000,0.78,-0.017,-0.003,-0.62,-0.027,-0.018,-0.023,-0.01,-0.011,-3.7e+02,-0.001,-0.006,-7.2e-05,0.067,-0.036,-0.13,-0.11,-0.026,0.5,-0.0042,-0.091,-0.069,0,0,-3.6e+02,0.00015,0.00016,0.049,0.031,0.031,0.029,0.06,0.06,0.053,2.1e-06,2.4e-06,2.4e-06,0.011,0.012,0.0037,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,3.9
158 15590000,0.78,-0.017,-0.0029,-0.62,-0.026,-0.016,-0.022,-0.0097,-0.01,-3.7e+02,-0.001,-0.006,-7.2e-05,0.067,-0.037,-0.13,-0.11,-0.026,0.5,-0.0042,-0.091,-0.069,0,0,-3.6e+02,0.00015,0.00016,0.049,0.029,0.029,0.028,0.062,0.062,0.052,2.1e-06,2.4e-06,2.4e-06,0.011,0.011,0.0035,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,3.9
159 15690000,0.78,-0.017,-0.0029,-0.62,-0.027,-0.017,-0.022,-0.012,-0.012,-3.7e+02,-0.001,-0.006,-7.2e-05,0.066,-0.037,-0.13,-0.11,-0.026,0.5,-0.0042,-0.092,-0.069,0,0,-3.6e+02,0.00014,0.00016,0.049,0.031,0.032,0.028,0.069,0.069,0.052,2e-06,2.3e-06,2.4e-06,0.01,0.011,0.0033,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4
160 15790000,0.78,-0.017,-0.003,-0.62,-0.025,-0.016,-0.025,-0.0085,-0.0098,-3.7e+02,-0.001,-0.006,-7.2e-05,0.067,-0.037,-0.12,-0.11,-0.026,0.5,-0.0042,-0.092,-0.069,0,0,-3.6e+02,0.00014,0.00016,0.049,0.026,0.027,0.027,0.056,0.056,0.051,1.9e-06,2.2e-06,2.4e-06,0.01,0.011,0.0031,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4 15790000,0.78,-0.017,-0.003,-0.62,-0.025,-0.016,-0.025,-0.0085,-0.0098,-3.7e+02,-0.001,-0.006,-7.2e-05,0.067,-0.038,-0.12,-0.11,-0.026,0.5,-0.0042,-0.092,-0.069,0,0,-3.6e+02,0.00014,0.00016,0.049,0.026,0.027,0.027,0.056,0.056,0.051,1.9e-06,2.2e-06,2.4e-06,0.01,0.011,0.0031,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4
161 15890000,0.78,-0.017,-0.0029,-0.62,-0.026,-0.016,-0.023,-0.011,-0.011,-3.7e+02,-0.001,-0.006,-7.2e-05,0.066,-0.037,-0.13,-0.11,-0.026,0.5,-0.0041,-0.092,-0.069,0,0,-3.6e+02,0.00014,0.00015,0.049,0.028,0.028,0.027,0.062,0.062,0.052,1.9e-06,2.2e-06,2.4e-06,0.01,0.011,0.003,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4
162 15990000,0.78,-0.017,-0.003,-0.62,-0.024,-0.016,-0.018,-0.0078,-0.01,-3.7e+02,-0.0011,-0.006,-7e-05,0.066,-0.037,-0.13,-0.11,-0.026,0.5,-0.0041,-0.092,-0.069,0,0,-3.6e+02,0.00014,0.00015,0.049,0.024,0.024,0.026,0.052,0.052,0.051,1.8e-06,2.1e-06,2.4e-06,0.0099,0.011,0.0028,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4
163 16090000,0.78,-0.017,-0.0031,-0.62,-0.026,-0.018,-0.015,-0.0099,-0.012,-3.7e+02,-0.0011,-0.006,-6.7e-05,0.066,-0.035,-0.13,-0.11,-0.026,0.5,-0.004,-0.092,-0.069,0,0,-3.6e+02,0.00014,0.00015,0.049,0.026,0.026,0.025,0.058,0.058,0.052,1.8e-06,2.1e-06,2.4e-06,0.0097,0.011,0.0027,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.1
177 17490000,0.78,-0.017,-0.003,-0.62,-0.025,-0.018,-0.0025,-0.016,-0.0094,-3.7e+02,-0.0012,-0.006,-5.9e-05,0.062,-0.035,-0.13,-0.11,-0.026,0.5,-0.0037,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.019,0.019,0.018,0.046,0.046,0.049,1.3e-06,1.5e-06,2.4e-06,0.0082,0.0091,0.0013,0.0012,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.4
178 17590000,0.78,-0.017,-0.003,-0.62,-0.024,-0.018,0.003,-0.013,-0.009,-3.7e+02,-0.0012,-0.006,-5.8e-05,0.062,-0.035,-0.13,-0.11,-0.026,0.5,-0.0037,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.017,0.018,0.017,0.041,0.041,0.048,1.2e-06,1.5e-06,2.4e-06,0.0081,0.009,0.0012,0.0012,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.4
179 17690000,0.78,-0.017,-0.0029,-0.62,-0.025,-0.02,0.0024,-0.016,-0.011,-3.7e+02,-0.0012,-0.006,-5.7e-05,0.062,-0.035,-0.13,-0.11,-0.026,0.5,-0.0037,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.019,0.019,0.017,0.045,0.045,0.048,1.2e-06,1.4e-06,2.4e-06,0.008,0.0089,0.0011,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.5
180 17790000,0.78,-0.017,-0.003,-0.62,-0.023,-0.021,0.0011,-0.014,-0.012,-3.7e+02,-0.0012,-0.006,-5.3e-05,0.062,-0.033,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.018,0.019,0.016,0.048,0.048,0.048,1.2e-06,1.4e-06,2.4e-06,0.008,0.0088,0.0011,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.5 17790000,0.78,-0.017,-0.003,-0.62,-0.023,-0.021,0.001,-0.014,-0.012,-3.7e+02,-0.0012,-0.006,-5.3e-05,0.062,-0.033,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.018,0.019,0.016,0.048,0.048,0.048,1.2e-06,1.4e-06,2.4e-06,0.008,0.0088,0.0011,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.5
181 17890000,0.78,-0.017,-0.0031,-0.62,-0.026,-0.022,0.0012,-0.017,-0.015,-3.7e+02,-0.0012,-0.006,-5.2e-05,0.062,-0.033,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.02,0.02,0.016,0.052,0.053,0.048,1.2e-06,1.4e-06,2.4e-06,0.0079,0.0087,0.001,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.5 17890000,0.78,-0.017,-0.0031,-0.62,-0.026,-0.022,0.0011,-0.017,-0.015,-3.7e+02,-0.0012,-0.006,-5.2e-05,0.062,-0.033,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.02,0.02,0.016,0.052,0.053,0.048,1.2e-06,1.4e-06,2.4e-06,0.0079,0.0087,0.001,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.5
182 17990000,0.78,-0.017,-0.003,-0.62,-0.025,-0.02,0.0024,-0.015,-0.014,-3.7e+02,-0.0012,-0.006,-5.1e-05,0.062,-0.033,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.019,0.02,0.016,0.055,0.055,0.047,1.1e-06,1.4e-06,2.4e-06,0.0078,0.0086,0.00099,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.5 17990000,0.78,-0.017,-0.003,-0.62,-0.025,-0.02,0.0023,-0.015,-0.014,-3.7e+02,-0.0012,-0.006,-5.1e-05,0.062,-0.033,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.019,0.02,0.016,0.055,0.055,0.047,1.1e-06,1.4e-06,2.4e-06,0.0078,0.0086,0.00099,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.5
183 18090000,0.78,-0.017,-0.003,-0.62,-0.027,-0.02,0.0047,-0.018,-0.016,-3.7e+02,-0.0012,-0.006,-5.4e-05,0.062,-0.034,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.021,0.021,0.016,0.06,0.061,0.047,1.1e-06,1.3e-06,2.4e-06,0.0078,0.0086,0.00096,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.6
184 18190000,0.78,-0.017,-0.003,-0.62,-0.023,-0.019,0.0061,-0.013,-0.013,-3.7e+02,-0.0012,-0.006,-5e-05,0.062,-0.034,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.018,0.018,0.015,0.051,0.051,0.047,1.1e-06,1.3e-06,2.4e-06,0.0077,0.0085,0.0009,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.6 18190000,0.78,-0.017,-0.003,-0.62,-0.023,-0.019,0.0061,-0.013,-0.013,-3.7e+02,-0.0012,-0.006,-5e-05,0.062,-0.034,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.018,0.018,0.015,0.051,0.051,0.047,1.1e-06,1.3e-06,2.3e-06,0.0077,0.0085,0.0009,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.6
185 18290000,0.78,-0.017,-0.0029,-0.62,-0.025,-0.02,0.0072,-0.016,-0.015,-3.7e+02,-0.0012,-0.006,-5.2e-05,0.062,-0.034,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.019,0.019,0.015,0.056,0.056,0.046,1.1e-06,1.3e-06,2.4e-06,0.0076,0.0084,0.00087,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.6
186 18390000,0.78,-0.017,-0.003,-0.62,-0.023,-0.021,0.0084,-0.012,-0.012,-3.7e+02,-0.0012,-0.006,-4.8e-05,0.063,-0.034,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.017,0.017,0.014,0.048,0.048,0.046,1e-06,1.2e-06,2.3e-06,0.0075,0.0083,0.00083,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.6
187 18490000,0.78,-0.017,-0.003,-0.62,-0.024,-0.022,0.0081,-0.014,-0.015,-3.7e+02,-0.0012,-0.006,-4.7e-05,0.062,-0.034,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.018,0.018,0.014,0.053,0.053,0.046,1e-06,1.2e-06,2.3e-06,0.0075,0.0083,0.0008,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.7
200 19790000,0.78,-0.016,-0.0032,-0.62,-0.012,-0.018,0.01,-0.0075,-0.015,-3.7e+02,-0.0013,-0.006,-1.6e-05,0.06,-0.031,-0.13,-0.11,-0.026,0.5,-0.0033,-0.092,-0.068,0,0,-3.6e+02,0.0001,0.00011,0.049,0.014,0.014,0.011,0.039,0.039,0.042,7.7e-07,9.4e-07,2.3e-06,0.0068,0.0074,0.00049,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5
201 19890000,0.78,-0.016,-0.0032,-0.62,-0.011,-0.02,0.012,-0.0091,-0.018,-3.7e+02,-0.0013,-0.0059,-1.3e-05,0.061,-0.031,-0.13,-0.11,-0.026,0.5,-0.0032,-0.092,-0.068,0,0,-3.6e+02,0.0001,0.00011,0.049,0.015,0.015,0.011,0.043,0.043,0.042,7.6e-07,9.3e-07,2.3e-06,0.0067,0.0074,0.00048,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5
202 19990000,0.78,-0.016,-0.0032,-0.62,-0.0095,-0.02,0.014,-0.0079,-0.017,-3.7e+02,-0.0013,-0.0059,-3.8e-06,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0031,-0.092,-0.068,0,0,-3.6e+02,9.9e-05,0.00011,0.049,0.014,0.014,0.01,0.039,0.039,0.041,7.4e-07,9e-07,2.3e-06,0.0067,0.0073,0.00046,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5
203 20090000,0.78,-0.016,-0.0033,-0.62,-0.0095,-0.021,0.015,-0.0085,-0.02,-3.7e+02,-0.0013,-0.0059,1e-06,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.6e+02,9.9e-05,0.00011,0.049,0.014,0.015,0.01,0.042,0.042,0.042,7.3e-07,8.9e-07,2.3e-06,0.0066,0.0073,0.00045,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.1 20090000,0.78,-0.016,-0.0033,-0.62,-0.0095,-0.021,0.015,-0.0085,-0.02,-3.7e+02,-0.0013,-0.0059,9.8e-07,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.6e+02,9.9e-05,0.00011,0.049,0.014,0.015,0.01,0.042,0.042,0.042,7.3e-07,8.9e-07,2.3e-06,0.0066,0.0073,0.00045,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.1
204 20190000,0.78,-0.016,-0.0034,-0.62,-0.01,-0.019,0.017,-0.0087,-0.018,-3.7e+02,-0.0013,-0.0059,7e-06,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.6e+02,9.8e-05,0.00011,0.048,0.013,0.014,0.01,0.038,0.038,0.041,7.1e-07,8.7e-07,2.3e-06,0.0066,0.0072,0.00043,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.1 20190000,0.78,-0.016,-0.0034,-0.62,-0.01,-0.019,0.017,-0.0087,-0.018,-3.7e+02,-0.0013,-0.0059,6.9e-06,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.6e+02,9.8e-05,0.00011,0.048,0.013,0.014,0.01,0.038,0.038,0.041,7.1e-07,8.7e-07,2.3e-06,0.0066,0.0072,0.00043,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.1
205 20290000,0.78,-0.016,-0.0034,-0.62,-0.0088,-0.019,0.015,-0.0091,-0.02,-3.7e+02,-0.0013,-0.0059,8.7e-06,0.062,-0.028,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.6e+02,9.8e-05,0.00011,0.048,0.014,0.015,0.0099,0.042,0.042,0.041,7e-07,8.6e-07,2.3e-06,0.0065,0.0072,0.00042,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.1
206 20390000,0.78,-0.016,-0.0033,-0.62,-0.0084,-0.016,0.017,-0.009,-0.017,-3.7e+02,-0.0013,-0.0059,1.3e-05,0.062,-0.028,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.6e+02,9.7e-05,0.0001,0.048,0.013,0.014,0.0097,0.038,0.038,0.041,6.8e-07,8.4e-07,2.3e-06,0.0065,0.0071,0.00041,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.1
207 20490000,0.78,-0.016,-0.0034,-0.62,-0.0087,-0.017,0.017,-0.0099,-0.019,-3.7e+02,-0.0013,-0.0059,1.1e-05,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.6e+02,9.7e-05,0.0001,0.048,0.014,0.015,0.0096,0.041,0.042,0.041,6.8e-07,8.3e-07,2.3e-06,0.0065,0.0071,0.0004,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.2
222 21990000,0.78,-0.016,-0.0034,-0.62,-0.0057,-0.0035,0.017,-0.008,-0.0069,-3.7e+02,-0.0013,-0.0059,5.6e-05,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.7e+02,8.8e-05,9.4e-05,0.048,0.013,0.013,0.0078,0.041,0.042,0.038,5.2e-07,6.4e-07,2.2e-06,0.0059,0.0065,0.00027,0.0011,7.1e-05,0.0012,0.0006,0.0012,0.0012,1,1,0.01
223 22090000,0.78,-0.016,-0.0034,-0.62,-0.0054,-0.0051,0.015,-0.0084,-0.0074,-3.7e+02,-0.0013,-0.0059,5.6e-05,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.9e-05,9.5e-05,0.048,0.013,0.014,0.0078,0.045,0.045,0.037,5.2e-07,6.3e-07,2.2e-06,0.0059,0.0065,0.00027,0.0011,7.1e-05,0.0012,0.0006,0.0012,0.0012,1,1,0.01
224 22190000,0.78,-0.016,-0.0034,-0.62,-0.0041,-0.0056,0.015,-0.007,-0.0066,-3.7e+02,-0.0013,-0.0059,5.9e-05,0.062,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.093,-0.068,0,0,-3.7e+02,8.7e-05,9.3e-05,0.048,0.012,0.013,0.0076,0.04,0.04,0.037,5.1e-07,6.2e-07,2.2e-06,0.0059,0.0064,0.00026,0.0011,7.1e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01
225 22290000,0.78,-0.016,-0.0034,-0.62,-0.0037,-0.0053,0.016,-0.0077,-0.007,-3.7e+02,-0.0013,-0.0059,5.8e-05,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.093,-0.068,0,0,-3.7e+02,8.8e-05,9.3e-05,0.048,0.013,0.014,0.0076,0.043,0.044,0.037,5e-07,6.1e-07,2.2e-06,0.0059,0.0064,0.00025,0.0011,7.1e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 22290000,0.78,-0.016,-0.0034,-0.62,-0.0036,-0.0053,0.016,-0.0077,-0.007,-3.7e+02,-0.0013,-0.0059,5.8e-05,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.093,-0.068,0,0,-3.7e+02,8.8e-05,9.3e-05,0.048,0.013,0.014,0.0076,0.043,0.044,0.037,5e-07,6.1e-07,2.2e-06,0.0059,0.0064,0.00025,0.0011,7.1e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01
226 22390000,0.78,-0.016,-0.0034,-0.62,-0.0011,-0.0052,0.017,-0.0059,-0.0063,-3.7e+02,-0.0013,-0.0059,6.2e-05,0.061,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.093,-0.068,0,0,-3.7e+02,8.6e-05,9.2e-05,0.048,0.012,0.013,0.0075,0.039,0.04,0.037,4.9e-07,6e-07,2.2e-06,0.0058,0.0064,0.00025,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01
227 22490000,0.78,-0.016,-0.0034,-0.62,1.2e-05,-0.0059,0.018,-0.0053,-0.0068,-3.7e+02,-0.0014,-0.0059,6.2e-05,0.061,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.7e-05,9.2e-05,0.048,0.013,0.014,0.0074,0.042,0.043,0.037,4.9e-07,5.9e-07,2.2e-06,0.0058,0.0063,0.00024,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 22490000,0.78,-0.016,-0.0034,-0.62,1.4e-05,-0.0059,0.018,-0.0053,-0.0067,-3.7e+02,-0.0014,-0.0059,6.2e-05,0.061,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.7e-05,9.2e-05,0.048,0.013,0.014,0.0074,0.042,0.043,0.037,4.9e-07,5.9e-07,2.2e-06,0.0058,0.0063,0.00024,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01
228 22590000,0.78,-0.016,-0.0034,-0.62,0.0019,-0.0048,0.017,-0.0036,-0.0061,-3.7e+02,-0.0014,-0.0059,6.6e-05,0.06,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.6e-05,9.2e-05,0.048,0.013,0.014,0.0073,0.045,0.045,0.036,4.8e-07,5.8e-07,2.2e-06,0.0058,0.0063,0.00024,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01
229 22690000,0.78,-0.016,-0.0035,-0.62,0.0034,-0.0061,0.019,-0.0029,-0.0072,-3.7e+02,-0.0014,-0.0059,7e-05,0.06,-0.027,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,-3.7e+02,8.7e-05,9.2e-05,0.048,0.014,0.015,0.0073,0.048,0.049,0.036,4.8e-07,5.8e-07,2.2e-06,0.0058,0.0063,0.00024,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01
230 22790000,0.78,-0.016,-0.0034,-0.62,0.0044,-0.0054,0.02,-0.0024,-0.0058,-3.7e+02,-0.0014,-0.0059,6.3e-05,0.06,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.6e-05,9.1e-05,0.048,0.014,0.015,0.0072,0.051,0.052,0.036,4.7e-07,5.7e-07,2.2e-06,0.0057,0.0062,0.00023,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 22790000,0.78,-0.016,-0.0034,-0.62,0.0045,-0.0054,0.02,-0.0024,-0.0058,-3.7e+02,-0.0014,-0.0059,6.3e-05,0.06,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.6e-05,9.1e-05,0.048,0.014,0.015,0.0072,0.051,0.052,0.036,4.7e-07,5.7e-07,2.2e-06,0.0057,0.0062,0.00023,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01
231 22890000,0.78,-0.016,-0.0034,-0.62,0.0051,-0.0063,0.021,-0.0025,-0.0066,-3.7e+02,-0.0014,-0.0059,6.3e-05,0.06,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.6e-05,9.2e-05,0.048,0.015,0.016,0.0072,0.055,0.056,0.036,4.7e-07,5.7e-07,2.2e-06,0.0057,0.0062,0.00023,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01
232 22990000,0.78,-0.016,-0.0034,-0.62,0.0048,-0.0065,0.022,-0.0026,-0.0074,-3.7e+02,-0.0014,-0.0059,6.8e-05,0.06,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.5e-05,9.1e-05,0.048,0.015,0.016,0.0071,0.057,0.059,0.036,4.6e-07,5.6e-07,2.2e-06,0.0057,0.0062,0.00022,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01
233 23090000,0.78,-0.016,-0.0033,-0.62,0.0051,-0.0062,0.023,-0.0023,-0.0071,-3.7e+02,-0.0014,-0.0059,6.4e-05,0.06,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.093,-0.068,0,0,-3.7e+02,8.6e-05,9.1e-05,0.048,0.016,0.017,0.007,0.062,0.064,0.036,4.6e-07,5.6e-07,2.2e-06,0.0057,0.0062,0.00022,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01
238 23590000,0.78,-0.0046,-0.0097,-0.62,0.015,-0.00011,-0.043,-0.0094,-0.0059,-3.7e+02,-0.0013,-0.0059,7.7e-05,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.3e-05,8.8e-05,0.047,0.014,0.015,0.0067,0.062,0.063,0.035,4.2e-07,5.1e-07,2.2e-06,0.0056,0.006,0.0002,0.0011,6.8e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01
239 23690000,0.78,0.0011,-0.0087,-0.62,0.043,0.014,-0.093,-0.007,-0.0057,-3.7e+02,-0.0013,-0.0059,7.9e-05,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.7e+02,8.3e-05,8.8e-05,0.047,0.015,0.016,0.0067,0.066,0.068,0.035,4.2e-07,5.1e-07,2.2e-06,0.0056,0.006,0.0002,0.0011,6.8e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01
240 23790000,0.78,-0.0026,-0.0062,-0.62,0.064,0.031,-0.15,-0.007,-0.0037,-3.7e+02,-0.0013,-0.0059,8.5e-05,0.063,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.067,0,0,-3.7e+02,8.2e-05,8.7e-05,0.047,0.013,0.014,0.0066,0.055,0.056,0.035,4.1e-07,4.9e-07,2.1e-06,0.0055,0.006,0.00019,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01
241 23890000,0.78,-0.0089,-0.0043,-0.62,0.077,0.043,-0.2,0.0005,6.2e-05,-3.7e+02,-0.0013,-0.0059,8.6e-05,0.063,-0.029,-0.13,-0.11,-0.026,0.5,-0.0031,-0.091,-0.067,0,0,-3.7e+02,8.2e-05,8.7e-05,0.047,0.014,0.015,0.0066,0.059,0.06,0.035,4.1e-07,4.9e-07,2.1e-06,0.0055,0.006,0.00019,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 23890000,0.78,-0.0089,-0.0043,-0.62,0.077,0.043,-0.2,0.0005,6.3e-05,-3.7e+02,-0.0013,-0.0059,8.6e-05,0.063,-0.029,-0.13,-0.11,-0.026,0.5,-0.0031,-0.091,-0.067,0,0,-3.7e+02,8.2e-05,8.7e-05,0.047,0.014,0.015,0.0066,0.059,0.06,0.035,4.1e-07,4.9e-07,2.1e-06,0.0055,0.006,0.00019,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01
242 23990000,0.78,-0.014,-0.0035,-0.62,0.072,0.043,-0.25,-0.005,-0.0014,-3.7e+02,-0.0013,-0.0059,8.4e-05,0.064,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.091,-0.068,0,0,-3.7e+02,8.2e-05,8.7e-05,0.047,0.014,0.015,0.0066,0.061,0.063,0.035,4e-07,4.9e-07,2.1e-06,0.0055,0.006,0.00019,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01
243 24090000,0.78,-0.012,-0.0046,-0.62,0.073,0.042,-0.3,0.0014,0.002,-3.7e+02,-0.0013,-0.0059,8.8e-05,0.064,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.091,-0.067,0,0,-3.7e+02,8.2e-05,8.7e-05,0.047,0.015,0.016,0.0065,0.066,0.067,0.035,4e-07,4.9e-07,2.1e-06,0.0055,0.006,0.00019,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01
244 24190000,0.78,-0.01,-0.0055,-0.62,0.07,0.041,-0.35,-0.0058,-0.00021,-3.7e+02,-0.0013,-0.0059,8.6e-05,0.065,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.091,-0.068,0,0,-3.7e+02,8.2e-05,8.6e-05,0.047,0.015,0.016,0.0065,0.069,0.07,0.034,4e-07,4.8e-07,2.1e-06,0.0055,0.0059,0.00018,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01
259 25690000,0.79,0.018,-0.014,-0.62,0.29,0.22,-1.2,-0.031,0.021,-3.7e+02,-0.00099,-0.0058,3e-05,0.08,-0.029,-0.13,-0.12,-0.027,0.5,-0.0031,-0.084,-0.068,0,0,-3.7e+02,8.3e-05,8.6e-05,0.046,0.025,0.026,0.0061,0.14,0.15,0.033,3.5e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00015,0.001,6e-05,0.0011,0.00056,0.0011,0.0011,1,1,0.01
260 25790000,0.78,0.025,-0.016,-0.62,0.35,0.25,-1.2,0.0015,0.042,-3.7e+02,-0.00099,-0.0058,4.2e-05,0.08,-0.029,-0.13,-0.12,-0.028,0.5,-0.0036,-0.083,-0.067,0,0,-3.7e+02,8.4e-05,8.6e-05,0.045,0.027,0.028,0.0061,0.15,0.16,0.033,3.5e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00015,0.00099,5.9e-05,0.0011,0.00056,0.001,0.0011,1,1,0.01
261 25890000,0.78,0.025,-0.016,-0.62,0.41,0.29,-1.3,0.041,0.065,-3.7e+02,-0.00099,-0.0058,5.7e-05,0.08,-0.029,-0.13,-0.12,-0.028,0.5,-0.0042,-0.081,-0.066,0,0,-3.7e+02,8.4e-05,8.7e-05,0.045,0.029,0.03,0.0061,0.16,0.17,0.033,3.5e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00015,0.00097,5.8e-05,0.0011,0.00056,0.001,0.0011,1,1,0.01
262 25990000,0.78,0.022,-0.016,-0.62,0.46,0.32,-1.3,0.084,0.093,-3.7e+02,-0.00099,-0.0058,6.6e-05,0.08,-0.029,-0.13,-0.12,-0.028,0.5,-0.0046,-0.08,-0.065,0,0,-3.7e+02,8.5e-05,8.8e-05,0.045,0.031,0.033,0.0061,0.18,0.18,0.033,3.5e-07,4.4e-07,2e-06,0.0053,0.0058,0.00015,0.00095,5.7e-05,0.0011,0.00055,0.001,0.0011,1,1,0.01 25990000,0.78,0.022,-0.016,-0.62,0.46,0.32,-1.3,0.084,0.093,-3.7e+02,-0.00099,-0.0058,6.6e-05,0.08,-0.03,-0.13,-0.12,-0.028,0.5,-0.0046,-0.08,-0.065,0,0,-3.7e+02,8.5e-05,8.8e-05,0.045,0.031,0.033,0.0061,0.18,0.18,0.033,3.5e-07,4.4e-07,2e-06,0.0053,0.0058,0.00015,0.00095,5.7e-05,0.0011,0.00055,0.001,0.0011,1,1,0.01
263 26090000,0.78,0.032,-0.019,-0.62,0.52,0.36,-1.3,0.13,0.13,-3.7e+02,-0.00099,-0.0058,6.4e-05,0.08,-0.03,-0.13,-0.12,-0.029,0.5,-0.0047,-0.079,-0.065,0,0,-3.7e+02,8.6e-05,8.8e-05,0.044,0.033,0.036,0.0061,0.19,0.19,0.033,3.5e-07,4.4e-07,2e-06,0.0053,0.0058,0.00015,0.00093,5.6e-05,0.0011,0.00055,0.00098,0.0011,1,1,0.01
264 26190000,0.78,0.042,-0.021,-0.62,0.59,0.41,-1.3,0.19,0.16,-3.7e+02,-0.00098,-0.0058,7.4e-05,0.08,-0.03,-0.13,-0.13,-0.03,0.5,-0.0055,-0.075,-0.063,0,0,-3.7e+02,8.7e-05,8.9e-05,0.043,0.036,0.039,0.0061,0.2,0.21,0.033,3.5e-07,4.4e-07,2e-06,0.0053,0.0058,0.00014,0.0009,5.4e-05,0.001,0.00054,0.00094,0.001,1,1,0.01
265 26290000,0.78,0.044,-0.022,-0.62,0.67,0.46,-1.3,0.25,0.2,-3.7e+02,-0.00097,-0.0058,7.8e-05,0.081,-0.03,-0.13,-0.13,-0.03,0.49,-0.0058,-0.073,-0.061,0,0,-3.7e+02,8.8e-05,8.9e-05,0.042,0.039,0.043,0.0061,0.21,0.22,0.033,3.5e-07,4.4e-07,2e-06,0.0053,0.0058,0.00014,0.00087,5.2e-05,0.001,0.00053,0.00091,0.00099,1,1,0.01
285 28290000,0.78,0.054,-0.025,-0.63,2.4,1.7,-0.069,3.8,2.6,-3.7e+02,-0.00094,-0.0058,8.3e-05,0.084,-0.023,-0.13,-0.17,-0.04,0.46,-0.0049,-0.029,-0.029,0,0,-3.7e+02,0.0001,0.0001,0.0086,0.077,0.086,0.0061,0.71,0.75,0.033,3.7e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00036,2.4e-05,0.00045,0.00014,0.00038,0.00045,1,1,0.01
286 28390000,0.78,0.021,-0.013,-0.63,2.4,1.7,0.79,4,2.8,-3.7e+02,-0.00095,-0.0058,7.9e-05,0.084,-0.022,-0.13,-0.17,-0.041,0.46,-0.0046,-0.028,-0.029,0,0,-3.7e+02,0.0001,0.0001,0.0082,0.076,0.084,0.0061,0.75,0.79,0.033,3.7e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00036,2.3e-05,0.00045,0.00013,0.00037,0.00045,1,1,0.01
287 28490000,0.78,0.0015,-0.006,-0.63,2.4,1.7,1.1,4.3,3,-3.7e+02,-0.00096,-0.0058,7.4e-05,0.084,-0.021,-0.13,-0.17,-0.041,0.46,-0.0046,-0.028,-0.029,0,0,-3.7e+02,0.0001,0.0001,0.0079,0.077,0.083,0.0061,0.79,0.83,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00036,2.3e-05,0.00045,0.00013,0.00037,0.00045,1,1,0.01
288 28590000,0.78,-0.0022,-0.0046,-0.63,2.3,1.7,0.98,4.5,3.1,-3.7e+02,-0.00096,-0.0058,7.3e-05,0.084,-0.021,-0.13,-0.17,-0.041,0.46,-0.0046,-0.028,-0.029,0,0,-3.7e+02,0.0001,0.0001,0.0075,0.077,0.082,0.0061,0.83,0.87,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00035,2.3e-05,0.00045,0.00012,0.00037,0.00044,1,1,0.01 28590000,0.78,-0.0022,-0.0046,-0.63,2.3,1.7,0.98,4.5,3.1,-3.7e+02,-0.00096,-0.0058,7.2e-05,0.084,-0.021,-0.13,-0.17,-0.041,0.46,-0.0046,-0.028,-0.029,0,0,-3.7e+02,0.0001,0.0001,0.0075,0.077,0.082,0.0061,0.83,0.87,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00035,2.3e-05,0.00045,0.00012,0.00037,0.00044,1,1,0.01
289 28690000,0.78,-0.0031,-0.004,-0.63,2.3,1.6,0.99,4.7,3.3,-3.7e+02,-0.00097,-0.0058,6.8e-05,0.083,-0.021,-0.12,-0.17,-0.041,0.46,-0.0045,-0.028,-0.029,0,0,-3.7e+02,0.00011,0.0001,0.0072,0.077,0.082,0.0061,0.87,0.91,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00035,2.3e-05,0.00045,0.00012,0.00037,0.00044,1,1,0.01
290 28790000,0.78,-0.0035,-0.0038,-0.63,2.2,1.6,0.99,5,3.5,-3.7e+02,-0.00097,-0.0058,6.4e-05,0.083,-0.02,-0.12,-0.17,-0.041,0.46,-0.0043,-0.028,-0.029,0,0,-3.7e+02,0.00011,0.0001,0.0069,0.078,0.082,0.006,0.91,0.96,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00035,2.3e-05,0.00044,0.00012,0.00037,0.00044,1,1,0.01
291 28890000,0.78,-0.0032,-0.0038,-0.63,2.1,1.6,0.98,5.2,3.6,-3.7e+02,-0.00098,-0.0058,6e-05,0.082,-0.02,-0.12,-0.17,-0.041,0.46,-0.0042,-0.028,-0.029,0,0,-3.7e+02,0.00011,0.0001,0.0067,0.079,0.083,0.0061,0.96,1,0.033,3.5e-07,4.5e-07,2e-06,0.0051,0.0055,0.00011,0.00035,2.3e-05,0.00044,0.00011,0.00037,0.00044,1,1,0.01
302 29990000,0.78,0.0036,-0.0058,-0.62,1.6,1.3,0.95,7.2,5.2,-3.7e+02,-0.001,-0.0057,1.4e-05,0.079,-0.013,-0.12,-0.17,-0.041,0.46,-0.003,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0052,0.096,0.11,0.006,1.5,1.7,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.3e-05,0.00043,9.6e-05,0.00036,0.00042,1,1,0.01
303 30090000,0.78,0.0035,-0.0058,-0.62,1.6,1.3,0.94,7.4,5.4,-3.7e+02,-0.001,-0.0057,1e-05,0.079,-0.012,-0.12,-0.17,-0.041,0.46,-0.0028,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0051,0.098,0.12,0.006,1.6,1.7,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00035,2.3e-05,0.00043,9.5e-05,0.00036,0.00042,1,1,0.01
304 30190000,0.78,0.0032,-0.0057,-0.62,1.6,1.3,0.93,7.6,5.5,-3.7e+02,-0.001,-0.0057,1.1e-05,0.078,-0.012,-0.12,-0.17,-0.041,0.46,-0.0029,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.005,0.1,0.12,0.006,1.7,1.8,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00035,2.2e-05,0.00043,9.4e-05,0.00036,0.00042,1,1,0.01
305 30290000,0.78,0.003,-0.0056,-0.62,1.5,1.3,0.92,7.7,5.6,-3.7e+02,-0.001,-0.0057,8.4e-06,0.078,-0.012,-0.12,-0.17,-0.041,0.46,-0.0028,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0049,0.1,0.13,0.006,1.7,1.9,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00035,2.2e-05,0.00043,9.3e-05,0.00036,0.00042,1,1,0.01 30290000,0.78,0.003,-0.0056,-0.62,1.5,1.3,0.92,7.7,5.6,-3.7e+02,-0.001,-0.0057,8.3e-06,0.078,-0.012,-0.12,-0.17,-0.041,0.46,-0.0028,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0049,0.1,0.13,0.006,1.7,1.9,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00035,2.2e-05,0.00043,9.3e-05,0.00036,0.00042,1,1,0.01
306 30390000,0.78,0.0028,-0.0056,-0.62,1.5,1.3,0.9,7.9,5.8,-3.7e+02,-0.0011,-0.0057,4.2e-06,0.077,-0.011,-0.12,-0.17,-0.041,0.46,-0.0028,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0049,0.1,0.13,0.006,1.8,2,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00035,2.2e-05,0.00042,9.2e-05,0.00036,0.00042,1,1,0.01
307 30490000,0.78,0.0026,-0.0055,-0.62,1.5,1.2,0.89,8,5.9,-3.7e+02,-0.0011,-0.0057,3.1e-06,0.077,-0.01,-0.12,-0.17,-0.041,0.46,-0.0028,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0048,0.11,0.14,0.006,1.9,2.1,0.033,3.2e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00034,2.2e-05,0.00042,9.2e-05,0.00036,0.00042,1,1,0.01 30490000,0.78,0.0026,-0.0055,-0.62,1.5,1.2,0.89,8,5.9,-3.7e+02,-0.0011,-0.0057,3e-06,0.077,-0.01,-0.12,-0.17,-0.041,0.46,-0.0028,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0048,0.11,0.14,0.006,1.9,2.1,0.033,3.2e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00034,2.2e-05,0.00042,9.2e-05,0.00036,0.00042,1,1,0.01
308 30590000,0.78,0.0021,-0.0054,-0.62,1.4,1.2,0.85,8.2,6,-3.7e+02,-0.0011,-0.0057,9.9e-07,0.077,-0.0095,-0.12,-0.17,-0.041,0.46,-0.0028,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0048,0.11,0.14,0.006,2,2.2,0.033,3.2e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00034,2.2e-05,0.00042,9.1e-05,0.00036,0.00042,1,1,0.01 30590000,0.78,0.0021,-0.0054,-0.62,1.4,1.2,0.85,8.2,6,-3.7e+02,-0.0011,-0.0057,9.7e-07,0.077,-0.0095,-0.12,-0.17,-0.041,0.46,-0.0028,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0048,0.11,0.14,0.006,2,2.2,0.033,3.2e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00034,2.2e-05,0.00042,9.1e-05,0.00036,0.00042,1,1,0.01
309 30690000,0.78,0.0018,-0.0053,-0.62,1.4,1.2,0.84,8.3,6.1,-3.7e+02,-0.0011,-0.0057,-2.3e-06,0.077,-0.0087,-0.12,-0.17,-0.041,0.46,-0.0027,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.00011,0.0047,0.11,0.15,0.006,2,2.3,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0054,0.0001,0.00034,2.2e-05,0.00042,9e-05,0.00036,0.00042,1,1,0.01
310 30790000,0.78,0.0014,-0.0052,-0.62,1.4,1.2,0.84,8.5,6.2,-3.7e+02,-0.0011,-0.0057,-5.4e-06,0.076,-0.0085,-0.12,-0.17,-0.041,0.46,-0.0026,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.00011,0.0047,0.11,0.15,0.006,2.1,2.4,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0054,0.0001,0.00034,2.2e-05,0.00042,9e-05,0.00036,0.00042,1,1,0.01
311 30890000,0.78,0.00095,-0.0051,-0.62,1.3,1.2,0.82,8.6,6.4,-3.7e+02,-0.0011,-0.0057,-8.3e-06,0.076,-0.0077,-0.12,-0.17,-0.041,0.46,-0.0026,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.00011,0.0046,0.12,0.16,0.0059,2.2,2.5,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0054,9.9e-05,0.00034,2.2e-05,0.00042,8.9e-05,0.00036,0.00042,1,1,0.01 30890000,0.78,0.00095,-0.0051,-0.62,1.3,1.2,0.82,8.6,6.4,-3.7e+02,-0.0011,-0.0057,-8.4e-06,0.076,-0.0077,-0.12,-0.17,-0.041,0.46,-0.0026,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.00011,0.0046,0.12,0.16,0.0059,2.2,2.5,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0054,9.9e-05,0.00034,2.2e-05,0.00042,8.9e-05,0.00036,0.00042,1,1,0.01
312 30990000,0.78,0.00035,-0.0051,-0.62,1.3,1.2,0.82,8.8,6.5,-3.7e+02,-0.0011,-0.0057,-1.2e-05,0.075,-0.0069,-0.12,-0.17,-0.041,0.46,-0.0025,-0.028,-0.027,0,0,-3.7e+02,0.00013,0.00011,0.0046,0.12,0.16,0.0059,2.3,2.6,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,9.9e-05,0.00034,2.2e-05,0.00042,8.9e-05,0.00036,0.00041,1,1,0.01
313 31090000,0.78,-0.00019,-0.0049,-0.62,1.3,1.1,0.81,8.9,6.6,-3.7e+02,-0.0011,-0.0057,-1.6e-05,0.075,-0.0062,-0.12,-0.17,-0.041,0.46,-0.0025,-0.028,-0.027,0,0,-3.7e+02,0.00013,0.00011,0.0045,0.12,0.17,0.0059,2.4,2.7,0.033,3.1e-07,4.6e-07,2e-06,0.0049,0.0053,9.8e-05,0.00034,2.2e-05,0.00042,8.8e-05,0.00036,0.00041,1,1,0.01
314 31190000,0.78,-0.00061,-0.0048,-0.62,1.2,1.1,0.8,9,6.7,-3.7e+02,-0.0011,-0.0057,-1.9e-05,0.075,-0.0054,-0.12,-0.17,-0.041,0.46,-0.0024,-0.028,-0.027,0,0,-3.7e+02,0.00013,0.00011,0.0045,0.12,0.18,0.0059,2.5,2.9,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.7e-05,0.00034,2.2e-05,0.00042,8.8e-05,0.00036,0.00041,1,1,0.01
315 31290000,0.78,-0.0012,-0.0046,-0.62,1.2,1.1,0.8,9.2,6.8,-3.7e+02,-0.0011,-0.0057,-2.1e-05,0.075,-0.0047,-0.12,-0.17,-0.041,0.46,-0.0024,-0.028,-0.027,0,0,-3.7e+02,0.00013,0.00011,0.0045,0.13,0.18,0.0059,2.6,3,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.7e-05,0.00034,2.2e-05,0.00042,8.8e-05,0.00036,0.00041,1,1,0.01
316 31390000,0.78,-0.0019,-0.0044,-0.62,1.2,1.1,0.8,9.3,6.9,-3.7e+02,-0.0011,-0.0057,-2.4e-05,0.075,-0.004,-0.12,-0.17,-0.041,0.46,-0.0024,-0.028,-0.027,0,0,-3.7e+02,0.00013,0.00011,0.0044,0.13,0.19,0.0059,2.6,3.1,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.6e-05,0.00034,2.2e-05,0.00042,8.7e-05,0.00036,0.00041,1,1,0.01 31390000,0.78,-0.0019,-0.0044,-0.62,1.2,1.1,0.8,9.3,6.9,-3.7e+02,-0.0011,-0.0057,-2.4e-05,0.075,-0.0041,-0.12,-0.17,-0.041,0.46,-0.0024,-0.028,-0.027,0,0,-3.7e+02,0.00013,0.00011,0.0044,0.13,0.19,0.0059,2.6,3.1,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.6e-05,0.00034,2.2e-05,0.00042,8.7e-05,0.00036,0.00041,1,1,0.01
317 31490000,0.78,-0.0025,-0.0043,-0.62,1.2,1.1,0.79,9.4,7,-3.7e+02,-0.0011,-0.0057,-3e-05,0.074,-0.0033,-0.12,-0.17,-0.041,0.46,-0.0023,-0.028,-0.026,0,0,-3.7e+02,0.00013,0.00011,0.0044,0.13,0.2,0.0059,2.7,3.3,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.6e-05,0.00034,2.2e-05,0.00042,8.7e-05,0.00036,0.00041,1,1,0.01
318 31590000,0.78,-0.0029,-0.0043,-0.62,1.1,1,0.79,9.5,7.1,-3.7e+02,-0.0011,-0.0057,-3.1e-05,0.073,-0.0026,-0.12,-0.17,-0.041,0.46,-0.0022,-0.028,-0.026,0,0,-3.7e+02,0.00013,0.00011,0.0044,0.13,0.21,0.0059,2.8,3.4,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.5e-05,0.00034,2.2e-05,0.00041,8.7e-05,0.00036,0.00041,1,1,0.01
319 31690000,0.78,-0.0037,-0.0041,-0.62,1.1,1,0.8,9.7,7.2,-3.7e+02,-0.0011,-0.0057,-3.3e-05,0.073,-0.0019,-0.12,-0.17,-0.041,0.46,-0.0022,-0.028,-0.026,0,0,-3.7e+02,0.00013,0.00011,0.0044,0.14,0.21,0.0059,2.9,3.5,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.4e-05,0.00034,2.2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1,0.01
320 31790000,0.78,-0.0044,-0.0039,-0.62,1.1,1,0.8,9.8,7.3,-3.7e+02,-0.0011,-0.0057,-3.6e-05,0.072,-0.001,-0.12,-0.17,-0.041,0.46,-0.0021,-0.029,-0.026,0,0,-3.7e+02,0.00013,0.00011,0.0043,0.14,0.22,0.0059,3.1,3.7,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0053,9.4e-05,0.00034,2.2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1,0.01
321 31890000,0.78,-0.0051,-0.0038,-0.62,1,0.99,0.79,9.9,7.4,-3.7e+02,-0.0011,-0.0057,-4e-05,0.072,-0.00016,-0.12,-0.17,-0.041,0.46,-0.0021,-0.029,-0.026,0,0,-3.7e+02,0.00013,0.00011,0.0043,0.14,0.23,0.0059,3.2,3.9,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0053,9.3e-05,0.00034,2.2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1,0.01 31890000,0.78,-0.0051,-0.0038,-0.62,1,0.99,0.79,9.9,7.4,-3.7e+02,-0.0011,-0.0057,-4e-05,0.072,-0.00017,-0.12,-0.17,-0.041,0.46,-0.0021,-0.029,-0.026,0,0,-3.7e+02,0.00013,0.00011,0.0043,0.14,0.23,0.0059,3.2,3.9,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0053,9.3e-05,0.00034,2.2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1,0.01
322 31990000,0.78,-0.0056,-0.0036,-0.62,1,0.97,0.79,10,7.5,-3.7e+02,-0.0012,-0.0057,-4.5e-05,0.071,0.00077,-0.12,-0.17,-0.041,0.46,-0.002,-0.029,-0.026,0,0,-3.7e+02,0.00014,0.00011,0.0043,0.15,0.24,0.0058,3.3,4,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0053,9.3e-05,0.00034,2.2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1,0.01 31990000,0.78,-0.0056,-0.0036,-0.62,1,0.97,0.79,10,7.5,-3.7e+02,-0.0012,-0.0057,-4.5e-05,0.071,0.00076,-0.12,-0.17,-0.041,0.46,-0.002,-0.029,-0.026,0,0,-3.7e+02,0.00014,0.00011,0.0043,0.15,0.24,0.0058,3.3,4,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0053,9.3e-05,0.00034,2.2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1,0.01
323 32090000,0.78,-0.0064,-0.0034,-0.62,0.99,0.96,0.8,10,7.7,-3.7e+02,-0.0012,-0.0057,-4.9e-05,0.071,0.0015,-0.11,-0.17,-0.041,0.46,-0.0019,-0.029,-0.026,0,0,-3.7e+02,0.00014,0.00011,0.0043,0.15,0.25,0.0059,3.4,4.2,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0052,9.2e-05,0.00034,2.2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1,0.01
324 32190000,0.78,-0.0073,-0.0032,-0.62,0.96,0.94,0.8,10,7.8,-3.7e+02,-0.0012,-0.0057,-5.8e-05,0.07,0.0024,-0.11,-0.17,-0.041,0.46,-0.0018,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0043,0.15,0.25,0.0058,3.5,4.4,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0052,9.1e-05,0.00034,2.2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1,0.01
325 32290000,0.78,-0.0081,-0.0031,-0.62,0.93,0.92,0.79,10,7.8,-3.7e+02,-0.0012,-0.0057,-6.2e-05,0.07,0.0034,-0.11,-0.17,-0.041,0.46,-0.0017,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.15,0.26,0.0058,3.6,4.6,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0052,9.1e-05,0.00034,2.2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1,0.01
326 32390000,0.78,-0.0087,-0.003,-0.62,0.9,0.9,0.79,10,7.9,-3.7e+02,-0.0012,-0.0057,-6.3e-05,0.069,0.0041,-0.11,-0.17,-0.041,0.46,-0.0017,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.16,0.27,0.0058,3.7,4.8,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0052,9e-05,0.00034,2.2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1,0.01
327 32490000,0.78,-0.0089,-0.003,-0.62,0.87,0.88,0.8,11,8,-3.7e+02,-0.0012,-0.0057,-6.5e-05,0.069,0.0048,-0.11,-0.17,-0.041,0.46,-0.0016,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.16,0.28,0.0058,3.9,5,0.033,2.9e-07,4.8e-07,2e-06,0.0049,0.0052,9e-05,0.00034,2.2e-05,0.0004,8.5e-05,0.00036,0.0004,1,1,0.01 32490000,0.78,-0.0089,-0.003,-0.62,0.87,0.88,0.8,11,8,-3.7e+02,-0.0012,-0.0057,-6.5e-05,0.069,0.0048,-0.11,-0.17,-0.041,0.46,-0.0016,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.16,0.28,0.0058,3.9,5,0.033,2.9e-07,4.7e-07,2e-06,0.0049,0.0052,9e-05,0.00034,2.2e-05,0.0004,8.5e-05,0.00036,0.0004,1,1,0.01
328 32590000,0.78,-0.0092,-0.0029,-0.62,-1.6,-0.84,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-6.9e-05,0.069,0.0052,-0.11,-0.17,-0.041,0.46,-0.0016,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.25,0.25,0.56,0.25,0.25,0.035,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.9e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.0004,1,1,0.01
329 32690000,0.79,-0.0093,-0.0029,-0.62,-1.6,-0.86,0.61,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.2e-05,0.068,0.0058,-0.11,-0.17,-0.041,0.46,-0.0015,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.25,0.25,0.55,0.26,0.26,0.047,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.9e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.0004,1,1,0.01
330 32790000,0.79,-0.0092,-0.0029,-0.62,-1.5,-0.84,0.61,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.4e-05,0.067,0.0062,-0.11,-0.17,-0.041,0.46,-0.0015,-0.029,-0.024,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.13,0.13,0.27,0.26,0.26,0.047,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.9e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.0004,1,1,0.01
331 32890000,0.79,-0.0091,-0.003,-0.62,-1.6,-0.86,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-8.3e-05,0.067,0.0067,-0.11,-0.17,-0.041,0.46,-0.0013,-0.029,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0042,0.13,0.13,0.26,0.27,0.27,0.058,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.00039,1,1,0.01
332 32990000,0.79,-0.0091,-0.0031,-0.62,-1.5,-0.85,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.7e-05,0.066,0.0072,-0.11,-0.17,-0.041,0.46,-0.0013,-0.029,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0041,0.084,0.085,0.17,0.27,0.27,0.056,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.00039,1,1,0.01 32990000,0.79,-0.0091,-0.0031,-0.62,-1.5,-0.85,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.8e-05,0.066,0.0072,-0.11,-0.17,-0.041,0.46,-0.0013,-0.029,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0041,0.084,0.085,0.17,0.27,0.27,0.056,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.00039,1,1,0.01
333 33090000,0.79,-0.0091,-0.0031,-0.62,-1.6,-0.87,0.57,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.5e-05,0.066,0.0074,-0.11,-0.17,-0.041,0.46,-0.0013,-0.029,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0041,0.084,0.085,0.16,0.28,0.28,0.065,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.00039,1,1,0.01
334 33190000,0.79,-0.0078,-0.0063,-0.61,-1.5,-0.85,0.52,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.2e-05,0.066,0.0075,-0.11,-0.17,-0.041,0.46,-0.0014,-0.029,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0041,0.063,0.065,0.11,0.28,0.28,0.062,2.8e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.3e-05,0.00036,0.00039,1,1,0.01
335 33290000,0.83,-0.0057,-0.018,-0.56,-1.5,-0.87,0.5,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.6e-05,0.066,0.0074,-0.11,-0.17,-0.041,0.46,-0.0014,-0.029,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0041,0.064,0.066,0.1,0.29,0.29,0.067,2.8e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.3e-05,0.00035,0.00039,1,1,0.01
336 33390000,0.9,-0.0064,-0.015,-0.44,-1.5,-0.86,0.7,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-6.3e-05,0.065,0.0071,-0.11,-0.18,-0.041,0.46,-0.00098,-0.027,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.004,0.051,0.053,0.082,0.29,0.29,0.065,2.8e-07,4.7e-07,2e-06,0.0048,0.0051,8.8e-05,0.00031,2e-05,0.0004,8.1e-05,0.00032,0.00039,1,1,0.01
337 33490000,0.96,-0.0051,-0.0069,-0.3,-1.5,-0.88,0.71,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-4.4e-05,0.065,0.0072,-0.11,-0.18,-0.043,0.46,-0.00048,-0.02,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0037,0.052,0.054,0.075,0.3,0.3,0.068,2.8e-07,4.7e-07,2e-06,0.0048,0.0051,8.8e-05,0.00023,1.6e-05,0.00039,7.3e-05,0.00024,0.00039,1,1,0.01 33490000,0.96,-0.0051,-0.0069,-0.3,-1.5,-0.88,0.71,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-4.4e-05,0.065,0.0071,-0.11,-0.18,-0.043,0.46,-0.00048,-0.02,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0037,0.052,0.054,0.075,0.3,0.3,0.068,2.8e-07,4.7e-07,2e-06,0.0048,0.0051,8.8e-05,0.00023,1.6e-05,0.00039,7.3e-05,0.00024,0.00039,1,1,0.01
338 33590000,0.99,-0.0083,-0.00017,-0.13,-1.5,-0.86,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,1.7e-05,0.065,0.0072,-0.11,-0.19,-0.044,0.46,0.00029,-0.013,-0.024,0,0,-3.7e+02,0.00015,0.0001,0.0032,0.044,0.046,0.061,0.3,0.3,0.065,2.8e-07,4.6e-07,2e-06,0.0048,0.0051,8.8e-05,0.00015,1.2e-05,0.00039,6e-05,0.00015,0.00039,1,1,0.01 33590000,0.99,-0.0083,-0.00017,-0.13,-1.5,-0.86,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,1.7e-05,0.065,0.0071,-0.11,-0.19,-0.044,0.46,0.00029,-0.013,-0.024,0,0,-3.7e+02,0.00015,0.0001,0.0032,0.044,0.046,0.061,0.3,0.3,0.065,2.8e-07,4.6e-07,2e-06,0.0048,0.0051,8.8e-05,0.00015,1.2e-05,0.00039,6e-05,0.00015,0.00039,1,1,0.01
339 33690000,1,-0.012,0.004,0.038,-1.6,-0.88,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,2.3e-05,0.065,0.0072,-0.11,-0.19,-0.045,0.46,0.00013,-0.0091,-0.025,0,0,-3.7e+02,0.00015,0.0001,0.0028,0.044,0.048,0.056,0.31,0.31,0.067,2.8e-07,4.6e-07,2e-06,0.0048,0.0051,8.8e-05,0.0001,9e-06,0.00039,4.7e-05,9.7e-05,0.00038,1,1,0.01 33690000,1,-0.012,0.004,0.038,-1.6,-0.88,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,2.3e-05,0.065,0.0071,-0.11,-0.19,-0.045,0.46,0.00013,-0.0091,-0.025,0,0,-3.7e+02,0.00015,0.0001,0.0028,0.044,0.048,0.056,0.31,0.31,0.067,2.8e-07,4.6e-07,2e-06,0.0048,0.0051,8.8e-05,0.0001,9e-06,0.00039,4.7e-05,9.7e-05,0.00038,1,1,0.01
340 33790000,0.98,-0.013,0.0065,0.21,-1.6,-0.9,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,6.8e-05,0.065,0.0072,-0.11,-0.2,-0.046,0.46,0.00049,-0.0066,-0.025,0,0,-3.7e+02,0.00015,0.0001,0.0023,0.039,0.043,0.047,0.31,0.31,0.064,2.7e-07,4.5e-07,1.9e-06,0.0048,0.0051,8.8e-05,6.9e-05,7.2e-06,0.00038,3.5e-05,6.2e-05,0.00038,1,1,0.01 33790000,0.98,-0.013,0.0065,0.21,-1.6,-0.9,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,6.8e-05,0.065,0.0071,-0.11,-0.2,-0.046,0.46,0.00049,-0.0066,-0.025,0,0,-3.7e+02,0.00015,0.0001,0.0023,0.039,0.043,0.047,0.31,0.31,0.064,2.7e-07,4.5e-07,1.9e-06,0.0048,0.0051,8.8e-05,6.9e-05,7.2e-06,0.00038,3.5e-05,6.2e-05,0.00038,1,1,0.01
341 33890000,0.93,-0.013,0.0085,0.37,-1.7,-0.95,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.2e-05,0.065,0.0072,-0.11,-0.2,-0.046,0.46,0.00071,-0.0053,-0.025,0,0,-3.7e+02,0.00015,0.0001,0.002,0.04,0.046,0.042,0.32,0.32,0.065,2.7e-07,4.5e-07,1.9e-06,0.0048,0.0051,8.8e-05,5e-05,6.2e-06,0.00038,2.7e-05,4.2e-05,0.00038,1,1,0.01 33890000,0.93,-0.013,0.0085,0.37,-1.7,-0.95,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.2e-05,0.065,0.0071,-0.11,-0.2,-0.046,0.46,0.00071,-0.0053,-0.025,0,0,-3.7e+02,0.00015,0.0001,0.002,0.04,0.046,0.042,0.32,0.32,0.065,2.7e-07,4.5e-07,1.9e-06,0.0048,0.0051,8.8e-05,5e-05,6.2e-06,0.00038,2.7e-05,4.2e-05,0.00038,1,1,0.01
342 33990000,0.86,-0.015,0.0071,0.51,-1.7,-0.98,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.065,0.0069,-0.11,-0.2,-0.046,0.46,0.0005,-0.0039,-0.025,0,0,-3.7e+02,0.00014,9.9e-05,0.0017,0.036,0.042,0.036,0.32,0.32,0.062,2.7e-07,4.4e-07,1.9e-06,0.0048,0.0051,8.8e-05,4e-05,5.6e-06,0.00038,2.1e-05,3e-05,0.00038,1,1,0.01
343 34090000,0.8,-0.016,0.0063,0.6,-1.7,-1.1,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.066,0.0063,-0.11,-0.2,-0.046,0.46,0.00017,-0.0033,-0.025,0,0,-3.7e+02,0.00014,9.9e-05,0.0016,0.038,0.046,0.033,0.33,0.33,0.063,2.7e-07,4.3e-07,1.9e-06,0.0048,0.0051,8.8e-05,3.4e-05,5.3e-06,0.00038,1.7e-05,2.4e-05,0.00038,1,1,0.01 34090000,0.8,-0.016,0.0063,0.6,-1.7,-1.1,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.066,0.0063,-0.11,-0.2,-0.046,0.46,0.00017,-0.0033,-0.025,0,0,-3.7e+02,0.00014,9.9e-05,0.0016,0.038,0.046,0.033,0.33,0.33,0.063,2.7e-07,4.3e-07,1.9e-06,0.0048,0.0051,8.9e-05,3.4e-05,5.3e-06,0.00038,1.7e-05,2.4e-05,0.00038,1,1,0.01
344 34190000,0.75,-0.014,0.007,0.67,-1.8,-1.1,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0061,-0.11,-0.2,-0.047,0.46,0.00018,-0.0027,-0.025,0,0,-3.7e+02,0.00014,9.9e-05,0.0015,0.041,0.051,0.031,0.34,0.34,0.063,2.8e-07,4.3e-07,1.9e-06,0.0047,0.0051,8.8e-05,3e-05,5e-06,0.00038,1.4e-05,1.9e-05,0.00038,1,1,0.01 34190000,0.75,-0.014,0.007,0.67,-1.8,-1.1,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0061,-0.11,-0.2,-0.047,0.46,0.00018,-0.0027,-0.025,0,0,-3.7e+02,0.00014,9.9e-05,0.0015,0.041,0.051,0.031,0.34,0.34,0.063,2.8e-07,4.3e-07,1.9e-06,0.0047,0.0051,8.9e-05,3e-05,5e-06,0.00038,1.4e-05,1.9e-05,0.00038,1,1,0.01
345 34290000,0.71,-0.011,0.0085,0.71,-1.8,-1.2,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0058,-0.11,-0.2,-0.047,0.46,0.00014,-0.0023,-0.025,0,0,-3.7e+02,0.00014,9.8e-05,0.0014,0.044,0.056,0.028,0.35,0.35,0.062,2.8e-07,4.3e-07,1.9e-06,0.0047,0.0051,8.8e-05,2.7e-05,4.9e-06,0.00038,1.2e-05,1.6e-05,0.00038,1,1,0.01 34290000,0.71,-0.011,0.0085,0.71,-1.8,-1.2,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0058,-0.11,-0.2,-0.047,0.46,0.00014,-0.0023,-0.025,0,0,-3.7e+02,0.00014,9.8e-05,0.0014,0.044,0.056,0.028,0.35,0.35,0.062,2.8e-07,4.3e-07,1.9e-06,0.0047,0.0051,8.9e-05,2.7e-05,4.9e-06,0.00038,1.2e-05,1.6e-05,0.00038,1,1,0.01
346 34390000,0.69,-0.0078,0.0099,0.73,-1.9,-1.3,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0054,-0.11,-0.2,-0.047,0.46,7.4e-05,-0.002,-0.025,0,0,-3.7e+02,0.00014,9.8e-05,0.0013,0.048,0.061,0.026,0.36,0.37,0.063,2.8e-07,4.3e-07,1.9e-06,0.0047,0.0051,8.8e-05,2.5e-05,4.8e-06,0.00038,1.1e-05,1.4e-05,0.00038,1,1,0.01 34390000,0.69,-0.0078,0.0099,0.73,-1.9,-1.3,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0054,-0.11,-0.2,-0.047,0.46,7.3e-05,-0.002,-0.025,0,0,-3.7e+02,0.00014,9.8e-05,0.0013,0.048,0.061,0.026,0.36,0.37,0.063,2.8e-07,4.3e-07,1.9e-06,0.0047,0.0051,8.9e-05,2.5e-05,4.8e-06,0.00038,1.1e-05,1.4e-05,0.00038,1,1,0.01
347 34490000,0.67,-0.0056,0.011,0.74,-1.9,-1.4,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0054,-0.11,-0.2,-0.047,0.46,3.2e-05,-0.002,-0.025,0,0,-3.7e+02,0.00014,9.7e-05,0.0013,0.052,0.068,0.024,0.38,0.38,0.062,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.8e-05,2.3e-05,4.7e-06,0.00038,9.9e-06,1.2e-05,0.00038,1,1,0.01 34490000,0.67,-0.0056,0.011,0.74,-1.9,-1.4,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.0054,-0.11,-0.2,-0.047,0.46,3.2e-05,-0.002,-0.025,0,0,-3.7e+02,0.00014,9.7e-05,0.0013,0.052,0.068,0.024,0.38,0.38,0.062,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.9e-05,2.3e-05,4.7e-06,0.00038,9.9e-06,1.2e-05,0.00038,1,1,0.01
348 34590000,0.66,-0.0042,0.012,0.75,-2,-1.4,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.0053,-0.11,-0.2,-0.047,0.46,-6.3e-05,-0.0019,-0.025,0,0,-3.7e+02,0.00014,9.7e-05,0.0012,0.057,0.074,0.022,0.39,0.4,0.06,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.8e-05,2.2e-05,4.6e-06,0.00038,9e-06,1.1e-05,0.00038,1,1,0.01 34590000,0.66,-0.0042,0.012,0.75,-2,-1.4,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.0053,-0.11,-0.2,-0.047,0.46,-6.4e-05,-0.0019,-0.025,0,0,-3.7e+02,0.00014,9.7e-05,0.0012,0.057,0.074,0.022,0.39,0.4,0.06,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.9e-05,2.2e-05,4.6e-06,0.00038,9e-06,1.1e-05,0.00038,1,1,0.01
349 34690000,0.65,-0.0034,0.013,0.76,-2,-1.5,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0052,-0.11,-0.2,-0.047,0.46,-4.8e-07,-0.0016,-0.025,0,0,-3.7e+02,0.00014,9.6e-05,0.0012,0.062,0.082,0.02,0.41,0.41,0.06,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.9e-05,2.1e-05,4.6e-06,0.00038,8.3e-06,9.9e-06,0.00038,1,1,0.01 34690000,0.65,-0.0034,0.013,0.76,-2,-1.5,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0052,-0.11,-0.2,-0.047,0.46,-5.8e-07,-0.0016,-0.025,0,0,-3.7e+02,0.00014,9.6e-05,0.0012,0.062,0.082,0.02,0.41,0.41,0.06,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.9e-05,2.1e-05,4.6e-06,0.00038,8.3e-06,9.9e-06,0.00038,1,1,0.01
350 34790000,0.65,-0.0028,0.013,0.76,-2.1,-1.6,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0051,-0.11,-0.2,-0.047,0.46,0.00012,-0.0016,-0.025,0,0,-3.7e+02,0.00014,9.6e-05,0.0012,0.068,0.09,0.018,0.42,0.43,0.059,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.9e-05,2.1e-05,4.5e-06,0.00038,7.8e-06,9.1e-06,0.00038,1,1,0.01
351 34890000,0.65,-0.0027,0.013,0.76,-2.1,-1.7,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,7.1e-05,-0.0016,-0.025,0,0,-3.7e+02,0.00014,9.6e-05,0.0012,0.075,0.099,0.017,0.44,0.46,0.058,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.9e-05,2e-05,4.5e-06,0.00038,7.3e-06,8.4e-06,0.00038,1,1,0.01 34890000,0.65,-0.0027,0.013,0.76,-2.1,-1.7,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0049,-0.11,-0.2,-0.047,0.46,7.1e-05,-0.0016,-0.025,0,0,-3.7e+02,0.00014,9.6e-05,0.0012,0.075,0.099,0.017,0.44,0.46,0.058,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.9e-05,2e-05,4.5e-06,0.00038,7.3e-06,8.4e-06,0.00038,1,1,0.01
352 34990000,0.64,-0.0062,0.02,0.76,-3,-2.6,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00018,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.5e-05,0.0012,0.092,0.13,0.016,0.46,0.48,0.057,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.9e-05,4.5e-06,0.00038,6.9e-06,7.9e-06,0.00038,1,1,0.01
353 35090000,0.64,-0.0063,0.02,0.76,-3.2,-2.7,-0.18,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.0002,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.5e-05,0.0012,0.1,0.14,0.015,0.49,0.51,0.056,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.9e-05,4.4e-06,0.00038,6.6e-06,7.4e-06,0.00038,1,1,0.01
354 35190000,0.64,-0.0064,0.02,0.76,-3.2,-2.8,-0.17,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00024,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.4e-05,0.0011,0.11,0.15,0.014,0.51,0.54,0.055,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.8e-05,4.4e-06,0.00038,6.3e-06,7e-06,0.00038,1,1,0.01 35190000,0.64,-0.0064,0.02,0.76,-3.2,-2.8,-0.17,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00024,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.4e-05,0.0011,0.11,0.15,0.014,0.51,0.54,0.055,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,9e-05,1.8e-05,4.4e-06,0.00038,6.3e-06,7e-06,0.00038,1,1,0.01
355 35290000,0.64,-0.0065,0.02,0.76,-3.2,-2.8,-0.16,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00029,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.4e-05,0.0011,0.12,0.17,0.013,0.54,0.58,0.053,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.8e-05,4.4e-06,0.00038,6e-06,6.6e-06,0.00038,1,1,0.01 35290000,0.64,-0.0065,0.02,0.76,-3.2,-2.8,-0.16,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00029,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.4e-05,0.0011,0.12,0.17,0.013,0.54,0.58,0.053,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,9e-05,1.8e-05,4.4e-06,0.00038,6e-06,6.6e-06,0.00038,1,1,0.01
356 35390000,0.64,-0.0065,0.02,0.76,-3.2,-2.9,-0.15,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00036,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.4e-05,0.0011,0.13,0.18,0.012,0.58,0.62,0.053,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.8e-05,4.3e-06,0.00038,5.8e-06,6.3e-06,0.00037,1,1,0.01 35390000,0.64,-0.0065,0.02,0.76,-3.2,-2.9,-0.15,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00036,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.4e-05,0.0011,0.13,0.18,0.012,0.58,0.62,0.053,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,9e-05,1.8e-05,4.3e-06,0.00038,5.8e-06,6.3e-06,0.00037,1,1,0.01
357 35490000,0.64,-0.0066,0.02,0.77,-3.3,-3,-0.14,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00043,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.3e-05,0.0011,0.14,0.19,0.012,0.61,0.67,0.052,2.9e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.8e-05,4.3e-06,0.00038,5.6e-06,6e-06,0.00037,1,1,0.01 35490000,0.64,-0.0066,0.02,0.77,-3.3,-3,-0.14,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00043,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.3e-05,0.0011,0.14,0.19,0.012,0.61,0.67,0.052,2.9e-07,4.4e-07,1.8e-06,0.0047,0.0051,9e-05,1.8e-05,4.3e-06,0.00038,5.6e-06,6e-06,0.00037,1,1,0.01
358 35590000,0.64,-0.0066,0.02,0.77,-3.3,-3.1,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.0004,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.3e-05,0.0011,0.15,0.2,0.011,0.65,0.72,0.05,2.9e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.7e-05,4.3e-06,0.00038,5.4e-06,5.8e-06,0.00037,1,1,0.01 35590000,0.64,-0.0066,0.02,0.77,-3.3,-3.1,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.0004,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.3e-05,0.0011,0.15,0.2,0.011,0.65,0.72,0.05,2.9e-07,4.4e-07,1.8e-06,0.0047,0.0051,9e-05,1.7e-05,4.3e-06,0.00038,5.4e-06,5.8e-06,0.00037,1,1,0.01
359 35690000,0.64,-0.0065,0.02,0.77,-3.3,-3.1,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0049,-0.11,-0.2,-0.047,0.46,0.00046,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.2e-05,0.0011,0.16,0.22,0.011,0.69,0.77,0.05,2.9e-07,4.4e-07,1.9e-06,0.0047,0.0051,8.9e-05,1.7e-05,4.3e-06,0.00038,5.3e-06,5.6e-06,0.00037,1,1,0.01 35690000,0.64,-0.0065,0.02,0.77,-3.3,-3.1,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0048,-0.11,-0.2,-0.047,0.46,0.00046,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.2e-05,0.0011,0.16,0.22,0.011,0.69,0.77,0.05,2.9e-07,4.4e-07,1.9e-06,0.0047,0.0051,9e-05,1.7e-05,4.3e-06,0.00038,5.3e-06,5.6e-06,0.00037,1,1,0.01
360 35790000,0.64,-0.0066,0.02,0.77,-3.4,-3.2,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0049,-0.11,-0.2,-0.047,0.46,0.00047,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.2e-05,0.0011,0.17,0.23,0.01,0.74,0.84,0.049,2.9e-07,4.4e-07,1.9e-06,0.0047,0.0051,8.9e-05,1.7e-05,4.3e-06,0.00038,5.1e-06,5.3e-06,0.00037,1,1,0.025 35790000,0.64,-0.0066,0.02,0.77,-3.4,-3.2,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0049,-0.11,-0.2,-0.047,0.46,0.00047,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.2e-05,0.0011,0.17,0.23,0.01,0.74,0.84,0.049,2.9e-07,4.4e-07,1.9e-06,0.0047,0.0051,9e-05,1.7e-05,4.3e-06,0.00038,5.1e-06,5.3e-06,0.00037,1,1,0.025
361 35890000,0.64,-0.0066,0.02,0.77,-3.4,-3.3,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00048,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.2e-05,0.0011,0.18,0.25,0.0096,0.79,0.9,0.048,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.7e-05,4.3e-06,0.00038,5e-06,5.2e-06,0.00037,1,1,0.056 35890000,0.64,-0.0066,0.02,0.77,-3.4,-3.3,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00048,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.2e-05,0.0011,0.18,0.25,0.0096,0.79,0.9,0.048,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.7e-05,4.3e-06,0.00038,5e-06,5.2e-06,0.00037,1,1,0.056
362 35990000,0.64,-0.0066,0.02,0.77,-3.4,-3.3,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0049,-0.11,-0.2,-0.047,0.46,0.00045,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.1e-05,0.0011,0.2,0.26,0.0093,0.84,0.98,0.047,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.3e-06,0.00038,4.9e-06,5e-06,0.00037,1,1,0.086 35990000,0.64,-0.0066,0.02,0.77,-3.4,-3.3,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0049,-0.11,-0.2,-0.047,0.46,0.00045,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.1e-05,0.0011,0.2,0.26,0.0093,0.84,0.98,0.047,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.6e-05,4.3e-06,0.00038,4.9e-06,5e-06,0.00037,1,1,0.086
363 36090000,0.64,-0.0067,0.02,0.77,-3.4,-3.4,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00048,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.1e-05,0.0011,0.21,0.28,0.0089,0.91,1.1,0.046,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.8e-06,4.8e-06,0.00037,1,1,0.12 36090000,0.64,-0.0067,0.02,0.77,-3.4,-3.4,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00048,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.1e-05,0.0011,0.21,0.28,0.0089,0.91,1.1,0.046,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.6e-05,4.2e-06,0.00038,4.8e-06,4.8e-06,0.00037,1,1,0.12
364 36190000,0.64,-0.0067,0.02,0.77,-3.5,-3.5,-0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0053,-0.11,-0.2,-0.047,0.46,0.00056,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.1e-05,0.0011,0.22,0.3,0.0086,0.97,1.1,0.045,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.7e-06,4.7e-06,0.00037,1,1,0.15 36190000,0.64,-0.0067,0.02,0.77,-3.5,-3.5,-0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0053,-0.11,-0.2,-0.047,0.46,0.00056,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.1e-05,0.0011,0.22,0.3,0.0086,0.97,1.1,0.045,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.6e-05,4.2e-06,0.00038,4.7e-06,4.7e-06,0.00037,1,1,0.15
365 36290000,0.64,-0.0067,0.02,0.77,-3.5,-3.6,-0.091,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00057,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9e-05,0.0011,0.24,0.31,0.0083,1,1.2,0.045,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.6e-06,4.6e-06,0.00037,1,1,0.18 36290000,0.64,-0.0067,0.02,0.77,-3.5,-3.6,-0.091,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00057,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9e-05,0.0011,0.24,0.31,0.0083,1,1.2,0.045,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.6e-05,4.2e-06,0.00038,4.6e-06,4.6e-06,0.00037,1,1,0.18
366 36390000,0.64,-0.0067,0.02,0.77,-3.5,-3.6,-0.082,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.0051,-0.11,-0.2,-0.047,0.46,0.00056,-0.0015,-0.025,0,0,-3.7e+02,0.00012,9e-05,0.0011,0.25,0.33,0.0081,1.1,1.4,0.044,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.5e-06,4.4e-06,0.00037,1,1,0.21 36390000,0.64,-0.0067,0.02,0.77,-3.5,-3.6,-0.082,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.0051,-0.11,-0.2,-0.047,0.46,0.00056,-0.0015,-0.025,0,0,-3.7e+02,0.00012,9e-05,0.0011,0.25,0.33,0.0081,1.1,1.4,0.044,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.6e-05,4.2e-06,0.00038,4.5e-06,4.4e-06,0.00037,1,1,0.21
367 36490000,0.64,-0.0068,0.02,0.77,-3.6,-3.7,-0.073,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.005,-0.11,-0.2,-0.047,0.46,0.00053,-0.0015,-0.025,0,0,-3.7e+02,0.00012,9e-05,0.0011,0.27,0.35,0.0078,1.2,1.5,0.043,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.6e-05,4.2e-06,0.00038,4.4e-06,4.3e-06,0.00037,1,1,0.24 36490000,0.64,-0.0068,0.02,0.77,-3.6,-3.7,-0.073,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.005,-0.11,-0.2,-0.047,0.46,0.00053,-0.0015,-0.025,0,0,-3.7e+02,0.00012,9e-05,0.0011,0.27,0.35,0.0078,1.2,1.5,0.043,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.6e-05,4.2e-06,0.00038,4.4e-06,4.3e-06,0.00037,1,1,0.24
368 36590000,0.64,-0.0068,0.02,0.77,-3.6,-3.8,-0.061,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.005,-0.11,-0.2,-0.047,0.46,0.00057,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.28,0.37,0.0076,1.3,1.6,0.042,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.6e-05,4.2e-06,0.00038,4.4e-06,4.2e-06,0.00037,1,1,0.27 36590000,0.64,-0.0068,0.02,0.77,-3.6,-3.8,-0.061,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.005,-0.11,-0.2,-0.047,0.46,0.00057,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.28,0.37,0.0076,1.3,1.6,0.042,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.6e-05,4.2e-06,0.00038,4.4e-06,4.2e-06,0.00037,1,1,0.27
369 36690000,0.64,-0.0068,0.02,0.77,-3.6,-3.9,-0.052,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.066,0.0052,-0.11,-0.2,-0.047,0.46,0.00059,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.3,0.39,0.0075,1.4,1.7,0.042,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.3e-06,4.1e-06,0.00037,1,1,0.31 36690000,0.64,-0.0068,0.02,0.77,-3.6,-3.9,-0.052,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.066,0.0052,-0.11,-0.2,-0.047,0.46,0.00059,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.3,0.39,0.0075,1.4,1.7,0.042,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.5e-05,4.2e-06,0.00038,4.3e-06,4.1e-06,0.00037,1,1,0.31
370 36790000,0.64,-0.0069,0.02,0.77,-3.6,-3.9,-0.041,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.067,0.005,-0.11,-0.2,-0.047,0.46,0.00063,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.31,0.41,0.0073,1.5,1.9,0.041,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.3e-06,4e-06,0.00037,1,1,0.34 36790000,0.64,-0.0069,0.02,0.77,-3.6,-3.9,-0.041,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.067,0.005,-0.11,-0.2,-0.047,0.46,0.00063,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.31,0.41,0.0073,1.5,1.9,0.041,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.5e-05,4.2e-06,0.00038,4.3e-06,4e-06,0.00037,1,1,0.34
371 36890000,0.64,-0.0069,0.02,0.77,-3.7,-4,-0.033,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.067,0.0052,-0.11,-0.2,-0.047,0.46,0.00066,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.33,0.43,0.0072,1.6,2,0.04,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.2e-06,3.9e-06,0.00037,1,1,0.37 36890000,0.64,-0.0069,0.02,0.77,-3.7,-4,-0.033,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.067,0.0051,-0.11,-0.2,-0.047,0.46,0.00066,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.33,0.43,0.0072,1.6,2,0.04,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.5e-05,4.2e-06,0.00038,4.2e-06,3.9e-06,0.00037,1,1,0.37
372 36990000,0.64,-0.0069,0.02,0.77,-3.7,-4.1,-0.024,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.067,0.0053,-0.11,-0.2,-0.047,0.46,0.00067,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.35,0.45,0.0071,1.8,2.2,0.04,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.2e-06,3.9e-06,0.00037,1,1,0.4 36990000,0.64,-0.0069,0.02,0.77,-3.7,-4.1,-0.024,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.067,0.0053,-0.11,-0.2,-0.047,0.46,0.00067,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.35,0.45,0.0071,1.8,2.2,0.04,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.5e-05,4.2e-06,0.00038,4.2e-06,3.9e-06,0.00037,1,1,0.4
373 37090000,0.64,-0.0069,0.02,0.77,-3.7,-4.2,-0.015,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.068,0.0053,-0.11,-0.2,-0.047,0.46,0.00067,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.37,0.47,0.007,1.9,2.4,0.04,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.8e-06,0.00037,1,1,0.43 37090000,0.64,-0.0069,0.02,0.77,-3.7,-4.2,-0.015,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.068,0.0053,-0.11,-0.2,-0.047,0.46,0.00067,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.37,0.47,0.007,1.9,2.4,0.04,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.1e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.8e-06,0.00037,1,1,0.43
374 37190000,0.64,-0.0069,0.021,0.77,-3.7,-4.2,-0.0056,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.068,0.0053,-0.11,-0.2,-0.047,0.46,0.00067,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.38,0.49,0.0069,2,2.6,0.039,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.7e-06,0.00037,1,1,0.47 37190000,0.64,-0.0069,0.021,0.77,-3.7,-4.2,-0.0056,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.068,0.0053,-0.11,-0.2,-0.047,0.46,0.00067,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.38,0.49,0.0069,2,2.6,0.039,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.1e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.7e-06,0.00037,1,1,0.47
375 37290000,0.64,-0.007,0.021,0.77,-3.8,-4.3,0.0029,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.8e-05,0.068,0.0054,-0.11,-0.2,-0.047,0.46,0.00068,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.4,0.51,0.0068,2.2,2.8,0.039,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.7e-06,0.00037,1,1,0.5 37290000,0.64,-0.007,0.021,0.77,-3.8,-4.3,0.0029,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.8e-05,0.068,0.0054,-0.11,-0.2,-0.047,0.46,0.00068,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.4,0.51,0.0068,2.2,2.8,0.039,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.2e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.7e-06,0.00037,1,1,0.5
376 37390000,0.64,-0.0069,0.021,0.77,-3.8,-4.4,0.011,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.4e-05,0.068,0.0053,-0.11,-0.2,-0.047,0.46,0.0007,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.0011,0.42,0.53,0.0068,2.4,3,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.6e-06,0.00037,1,1,0.53 37390000,0.64,-0.0069,0.021,0.77,-3.8,-4.4,0.011,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.4e-05,0.068,0.0053,-0.11,-0.2,-0.047,0.46,0.0007,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.0011,0.42,0.53,0.0068,2.4,3,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.2e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.6e-06,0.00037,1,1,0.53
377 37490000,0.64,-0.0069,0.021,0.77,-3.8,-4.5,0.019,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.8e-05,0.068,0.0053,-0.11,-0.2,-0.047,0.46,0.00072,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.44,0.56,0.0067,2.5,3.2,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.5e-06,0.00037,1,1,0.57 37490000,0.64,-0.0069,0.021,0.77,-3.8,-4.5,0.019,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.8e-05,0.068,0.0053,-0.11,-0.2,-0.047,0.46,0.00072,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.44,0.56,0.0067,2.5,3.2,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.2e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.5e-06,0.00037,1,1,0.57
378 37590000,0.64,-0.007,0.021,0.77,-3.9,-4.5,0.029,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.4e-05,0.069,0.0053,-0.11,-0.2,-0.047,0.46,0.00073,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.46,0.58,0.0067,2.7,3.5,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.5e-06,0.00037,1,1,0.6 37590000,0.64,-0.007,0.021,0.77,-3.9,-4.5,0.029,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.4e-05,0.069,0.0053,-0.11,-0.2,-0.047,0.46,0.00073,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.46,0.58,0.0067,2.7,3.5,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.2e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.5e-06,0.00037,1,1,0.6
379 37690000,0.64,-0.007,0.021,0.77,-3.9,-4.6,0.039,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.8e-05,0.069,0.0054,-0.11,-0.2,-0.047,0.46,0.00074,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.48,0.6,0.0066,2.9,3.7,0.037,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.1e-05,1.5e-05,4.2e-06,0.00038,3.9e-06,3.4e-06,0.00037,1,1,0.64 37690000,0.64,-0.007,0.021,0.77,-3.9,-4.6,0.039,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.8e-05,0.069,0.0054,-0.11,-0.2,-0.047,0.46,0.00074,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.48,0.6,0.0066,2.9,3.7,0.037,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.2e-05,1.5e-05,4.2e-06,0.00038,3.9e-06,3.4e-06,0.00037,1,1,0.64
380 37790000,0.64,-0.0071,0.021,0.77,-3.9,-4.7,0.048,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.6e-05,0.069,0.0052,-0.11,-0.2,-0.047,0.46,0.00075,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.5,0.63,0.0066,3.1,4,0.037,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.1e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.4e-06,0.00037,1,1,0.67 37790000,0.64,-0.0071,0.021,0.77,-3.9,-4.7,0.048,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.6e-05,0.069,0.0052,-0.11,-0.2,-0.047,0.46,0.00075,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.5,0.63,0.0066,3.1,4,0.037,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.2e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.4e-06,0.00037,1,1,0.67
381 37890000,0.64,-0.0071,0.021,0.77,-3.9,-4.8,0.056,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.3e-05,0.069,0.0054,-0.11,-0.2,-0.047,0.46,0.00075,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.52,0.65,0.0065,3.4,4.3,0.036,3e-07,4.4e-07,1.8e-06,0.0047,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.3e-06,0.00037,1,1,0.7 37890000,0.64,-0.0071,0.021,0.77,-3.9,-4.8,0.056,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.3e-05,0.069,0.0054,-0.11,-0.2,-0.047,0.46,0.00075,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.52,0.65,0.0066,3.4,4.3,0.036,3e-07,4.4e-07,1.8e-06,0.0047,0.0049,9.2e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.3e-06,0.00037,1,1,0.7
382 37990000,0.64,-0.0072,0.021,0.77,-4,-4.8,0.066,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.3e-05,0.069,0.0052,-0.11,-0.2,-0.047,0.46,0.00075,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.54,0.67,0.0066,3.6,4.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.3e-06,0.00037,1,1,0.74 37990000,0.64,-0.0072,0.021,0.77,-4,-4.8,0.066,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.3e-05,0.069,0.0052,-0.11,-0.2,-0.047,0.46,0.00075,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.54,0.67,0.0066,3.6,4.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.3e-06,0.00037,1,1,0.74
383 38090000,0.64,-0.0072,0.021,0.77,-4,-4.9,0.077,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.8e-05,0.07,0.0051,-0.11,-0.2,-0.047,0.46,0.00076,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.57,0.7,0.0065,3.9,4.9,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.2e-06,0.00037,1,1,0.77 38090000,0.64,-0.0072,0.021,0.77,-4,-4.9,0.077,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.8e-05,0.07,0.0051,-0.11,-0.2,-0.047,0.46,0.00076,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.57,0.7,0.0065,3.9,4.9,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.2e-06,0.00037,1,1,0.77
384 38190000,0.64,-0.0072,0.021,0.77,-4,-5,0.085,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.6e-05,0.07,0.0051,-0.11,-0.2,-0.047,0.46,0.00077,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.59,0.72,0.0065,4.1,5.3,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.8e-06,3.2e-06,0.00037,1,1,0.81 38190000,0.64,-0.0072,0.021,0.77,-4,-5,0.085,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.6e-05,0.07,0.0051,-0.11,-0.2,-0.047,0.46,0.00077,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.59,0.72,0.0065,4.1,5.3,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.2e-06,0.00038,3.8e-06,3.2e-06,0.00037,1,1,0.81
385 38290000,0.64,-0.0072,0.021,0.77,-4,-5,0.093,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.5e-05,0.07,0.0051,-0.11,-0.2,-0.047,0.46,0.00077,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.61,0.75,0.0065,4.4,5.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.2e-06,0.00038,3.8e-06,3.1e-06,0.00037,1,1,0.84 38290000,0.64,-0.0072,0.021,0.77,-4,-5,0.093,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.5e-05,0.07,0.0051,-0.11,-0.2,-0.047,0.46,0.00077,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.61,0.75,0.0065,4.4,5.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.2e-06,0.00038,3.8e-06,3.1e-06,0.00037,1,1,0.84
386 38390000,0.64,-0.0071,0.021,0.77,-4.1,-5.1,0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.7e-05,0.07,0.0049,-0.11,-0.2,-0.047,0.46,0.00076,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.64,0.77,0.0065,4.7,6,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3.1e-06,0.00037,1,1,0.88 38390000,0.64,-0.0071,0.021,0.77,-4.1,-5.1,0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.7e-05,0.07,0.0049,-0.11,-0.2,-0.047,0.46,0.00076,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.64,0.77,0.0065,4.7,6,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3.1e-06,0.00037,1,1,0.88
387 38490000,0.64,-0.0071,0.021,0.77,-4.1,-5.2,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.5e-05,0.07,0.005,-0.11,-0.2,-0.047,0.46,0.00077,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.66,0.8,0.0065,5.1,6.4,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1,0.92 38490000,0.64,-0.0071,0.021,0.77,-4.1,-5.2,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.5e-05,0.07,0.005,-0.11,-0.2,-0.047,0.46,0.00077,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.66,0.8,0.0065,5.1,6.4,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1,0.92
388 38590000,0.64,-0.0071,0.021,0.77,-4.1,-5.3,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.6e-05,0.07,0.0052,-0.11,-0.2,-0.047,0.46,0.00077,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.68,0.82,0.0066,5.4,6.8,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1,0.95 38590000,0.64,-0.0071,0.021,0.77,-4.1,-5.3,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.6e-05,0.07,0.0052,-0.11,-0.2,-0.047,0.46,0.00077,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.68,0.82,0.0066,5.4,6.8,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1,0.95
389 38690000,0.64,-0.0071,0.021,0.77,-4.2,-5.3,0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.2e-05,0.069,0.0054,-0.11,-0.2,-0.047,0.46,0.00078,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.71,0.85,0.0066,5.8,7.3,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1,0.99 38690000,0.64,-0.0071,0.021,0.77,-4.2,-5.3,0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.1e-05,0.069,0.0054,-0.11,-0.2,-0.047,0.46,0.00078,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.71,0.85,0.0066,5.8,7.3,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1,0.99
390 38790000,0.64,-0.0071,0.021,0.77,-4.2,-5.4,0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.1e-05,0.069,0.0052,-0.11,-0.2,-0.047,0.46,0.00078,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.73,0.87,0.0066,6.1,7.7,0.035,3.1e-07,4.3e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,2.9e-06,0.00037,1,1,1 38790000,0.64,-0.0071,0.021,0.77,-4.2,-5.4,0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.1e-05,0.069,0.0052,-0.11,-0.2,-0.047,0.46,0.00078,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.73,0.88,0.0066,6.1,7.7,0.035,3.1e-07,4.3e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,2.9e-06,0.00037,1,1,1
391 38890000,0.64,-0.0072,0.021,0.77,-4.2,-5.4,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6e-05,0.069,0.0052,-0.11,-0.2,-0.047,0.46,0.00078,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.75,0.89,0.0066,6.5,8.2,0.035,3.1e-07,4.3e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,2.9e-06,0.00037,1,1,1.1 38890000,0.64,-0.0072,0.021,0.77,-4.2,-5.4,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6e-05,0.069,0.0052,-0.11,-0.2,-0.047,0.46,0.00078,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.75,0.89,0.0066,6.5,8.2,0.035,3.1e-07,4.3e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,2.9e-06,0.00037,1,1,1.1
@@ -67,8 +67,8 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
6490000,1,-0.0089,-0.011,0.00062,0.0057,0.016,-0.039,0.0041,0.0076,-0.053,-0.0018,-0.0056,-8.7e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.095,0.0018,0.0018,0.0001,0.25,0.25,0.038,0.15,0.15,0.07,0.00012,0.00012,2.9e-06,0.04,0.04,0.0036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7
6590000,1,-0.0089,-0.011,0.00055,0.0039,0.015,-0.042,0.0029,0.0058,-0.056,-0.0017,-0.0056,-8.9e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.095,0.0016,0.0016,9.6e-05,0.2,0.2,0.036,0.12,0.12,0.069,9.8e-05,9.8e-05,2.6e-06,0.04,0.04,0.0034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7
6690000,1,-0.0088,-0.011,0.0005,0.0022,0.018,-0.044,0.0032,0.0075,-0.057,-0.0017,-0.0056,-8.9e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.095,0.0016,0.0016,9.9e-05,0.23,0.23,0.035,0.14,0.14,0.068,9.8e-05,9.8e-05,2.6e-06,0.04,0.04,0.0031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7
6790000,1,-0.0089,-0.011,0.00047,0.003,0.015,-0.042,0.0021,0.006,-0.058,-0.0017,-0.0056,-9.1e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.095,0.0014,0.0014,9.3e-05,0.18,0.18,0.034,0.11,0.11,0.068,8.1e-05,8.1e-05,2.4e-06,0.04,0.04,0.003,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7
6890000,1,-0.0087,-0.011,0.00039,0.0023,0.015,-0.039,0.0024,0.0075,-0.055,-0.0017,-0.0056,-9.1e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.095,0.0015,0.0015,9.6e-05,0.21,0.21,0.032,0.14,0.14,0.067,8.1e-05,8.1e-05,2.4e-06,0.04,0.04,0.0028,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.8
6790000,1,-0.0089,-0.011,0.00047,0.003,0.015,-0.042,0.0021,0.006,-0.058,-0.0017,-0.0056,-9.1e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.095,0.0014,0.0014,9.3e-05,0.18,0.18,0.034,0.11,0.11,0.068,8e-05,8.1e-05,2.4e-06,0.04,0.04,0.003,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7
6890000,1,-0.0087,-0.011,0.00039,0.0023,0.015,-0.039,0.0024,0.0075,-0.055,-0.0017,-0.0056,-9.1e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.095,0.0015,0.0015,9.6e-05,0.21,0.21,0.032,0.14,0.14,0.067,8e-05,8.1e-05,2.4e-06,0.04,0.04,0.0028,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.8
6990000,-0.29,0.024,-0.0061,0.96,-0.2,-0.032,-0.037,-0.11,-0.019,-0.055,-0.00077,-0.0097,-0.0002,0,0,-0.13,-0.091,-0.021,0.51,0.069,-0.028,-0.058,0,0,0.095,0.0011,0.0012,0.076,0.16,0.16,0.031,0.1,0.1,0.066,6.3e-05,6.4e-05,2.2e-06,0.04,0.04,0.0026,0.0014,0.00049,0.0014,0.0014,0.0012,0.0014,1,1,1.8
7090000,-0.29,0.025,-0.0062,0.96,-0.24,-0.048,-0.038,-0.15,-0.027,-0.056,-0.00064,-0.01,-0.00021,0,0,-0.13,-0.099,-0.023,0.51,0.075,-0.029,-0.065,0,0,0.095,0.0011,0.0011,0.063,0.19,0.18,0.03,0.13,0.13,0.066,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0024,0.0013,0.00025,0.0013,0.0013,0.00095,0.0013,1,1,1.8
7190000,-0.29,0.025,-0.0062,0.96,-0.26,-0.057,-0.037,-0.17,-0.034,-0.059,-0.0006,-0.01,-0.00021,-0.00035,-7.7e-05,-0.13,-0.1,-0.023,0.51,0.077,-0.03,-0.067,0,0,0.095,0.0011,0.0011,0.06,0.21,0.21,0.029,0.16,0.15,0.065,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0023,0.0013,0.00018,0.0013,0.0013,0.0009,0.0013,1,1,1.8
@@ -93,20 +93,20 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
9090000,-0.29,0.02,-0.0063,0.96,-0.46,-0.16,-0.0099,-0.72,-0.24,-0.032,-0.00071,-0.0082,-0.00016,-0.0012,0.00029,-0.13,-0.1,-0.024,0.5,0.08,-0.031,-0.069,0,0,0.095,0.0006,0.00062,0.053,1.2,1.2,0.016,2.7,2.7,0.053,4.5e-05,4.5e-05,2.2e-06,0.04,0.04,0.00087,0.0012,8.2e-05,0.0013,0.0012,0.0008,0.0013,1,1,2.3
9190000,-0.29,0.02,-0.0063,0.96,-0.46,-0.16,-0.0095,-0.73,-0.24,-0.033,-0.00081,-0.008,-0.00016,-0.0011,0.00042,-0.13,-0.1,-0.024,0.5,0.081,-0.031,-0.069,0,0,0.095,0.00059,0.0006,0.053,1.2,1.2,0.016,3,3,0.052,4.3e-05,4.3e-05,2.2e-06,0.04,0.04,0.00084,0.0012,8.2e-05,0.0013,0.0012,0.00079,0.0013,1,1,2.3
9290000,-0.29,0.02,-0.006,0.96,-0.45,-0.16,-0.0081,-0.73,-0.25,-0.03,-0.00081,-0.0078,-0.00015,-0.001,0.00048,-0.13,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00058,0.00059,0.053,1.3,1.3,0.015,3.3,3.3,0.052,4.1e-05,4.1e-05,2.2e-06,0.04,0.04,0.0008,0.0012,8.1e-05,0.0013,0.0012,0.00079,0.0013,1,1,2.4
9390000,-0.29,0.02,-0.0058,0.96,-0.45,-0.18,-0.0071,-0.75,-0.29,-0.031,-0.00073,-0.0076,-0.00015,-0.00084,0.00046,-0.13,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00057,0.00058,0.053,1.4,1.4,0.015,3.7,3.6,0.052,4e-05,4e-05,2.2e-06,0.04,0.04,0.00077,0.0012,8e-05,0.0013,0.0012,0.00079,0.0013,1,1,2.4
9390000,-0.29,0.02,-0.0058,0.96,-0.45,-0.18,-0.0071,-0.75,-0.29,-0.031,-0.00073,-0.0077,-0.00015,-0.00084,0.00046,-0.13,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00057,0.00058,0.053,1.4,1.4,0.015,3.7,3.6,0.052,4e-05,4e-05,2.2e-06,0.04,0.04,0.00077,0.0012,8e-05,0.0013,0.0012,0.00079,0.0013,1,1,2.4
9490000,-0.29,0.019,-0.0059,0.96,-0.46,-0.17,-0.0055,-0.78,-0.29,-0.028,-0.0008,-0.0076,-0.00015,-0.00092,0.00055,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00056,0.00057,0.053,1.4,1.4,0.015,4,4,0.051,3.8e-05,3.8e-05,2.2e-06,0.04,0.04,0.00074,0.0012,8e-05,0.0013,0.0012,0.00079,0.0013,1,1,2.4
9590000,-0.29,0.019,-0.0059,0.96,-0.46,-0.19,-0.0054,-0.81,-0.34,-0.029,-0.00068,-0.0075,-0.00015,-0.00086,0.00042,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00055,0.00056,0.053,1.5,1.5,0.014,4.4,4.3,0.05,3.6e-05,3.6e-05,2.2e-06,0.04,0.04,0.00072,0.0012,7.9e-05,0.0013,0.0012,0.00078,0.0013,1,1,2.4
9590000,-0.29,0.019,-0.0059,0.96,-0.46,-0.19,-0.0054,-0.81,-0.34,-0.029,-0.00068,-0.0075,-0.00015,-0.00085,0.00042,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00055,0.00056,0.053,1.5,1.5,0.014,4.4,4.3,0.05,3.6e-05,3.6e-05,2.2e-06,0.04,0.04,0.00072,0.0012,7.9e-05,0.0013,0.0012,0.00078,0.0013,1,1,2.4
9690000,-0.29,0.019,-0.0058,0.96,-0.46,-0.2,-0.0026,-0.83,-0.37,-0.028,-0.00064,-0.0074,-0.00015,-0.00077,0.00041,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00054,0.00056,0.053,1.6,1.6,0.014,4.8,4.8,0.05,3.5e-05,3.4e-05,2.2e-06,0.04,0.04,0.00069,0.0012,7.9e-05,0.0013,0.0012,0.00078,0.0013,1,1,2.5
9790000,-0.29,0.019,-0.0058,0.96,-0.48,-0.22,-0.0039,-0.88,-0.41,-0.029,-0.00055,-0.0074,-0.00015,-0.00076,0.00033,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00054,0.00055,0.053,1.6,1.6,0.014,5.2,5.2,0.05,3.3e-05,3.3e-05,2.2e-06,0.04,0.04,0.00067,0.0012,7.8e-05,0.0013,0.0012,0.00078,0.0013,1,1,2.5
9890000,-0.29,0.019,-0.0057,0.96,-0.47,-0.22,-0.0027,-0.87,-0.43,-0.03,-0.00058,-0.0072,-0.00014,-0.00052,0.00039,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00053,0.00054,0.053,1.7,1.7,0.013,5.7,5.6,0.049,3.1e-05,3.1e-05,2.2e-06,0.04,0.04,0.00064,0.0012,7.8e-05,0.0013,0.0012,0.00078,0.0013,1,1,2.5
9790000,-0.29,0.019,-0.0058,0.96,-0.48,-0.22,-0.0039,-0.88,-0.41,-0.029,-0.00055,-0.0074,-0.00015,-0.00075,0.00033,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00054,0.00055,0.053,1.6,1.6,0.014,5.2,5.2,0.05,3.3e-05,3.3e-05,2.2e-06,0.04,0.04,0.00067,0.0012,7.8e-05,0.0013,0.0012,0.00078,0.0013,1,1,2.5
9890000,-0.29,0.019,-0.0057,0.96,-0.47,-0.22,-0.0027,-0.87,-0.43,-0.03,-0.00058,-0.0072,-0.00014,-0.00051,0.00039,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00053,0.00054,0.053,1.7,1.7,0.013,5.7,5.6,0.049,3.1e-05,3.1e-05,2.2e-06,0.04,0.04,0.00064,0.0012,7.8e-05,0.0013,0.0012,0.00078,0.0013,1,1,2.5
9990000,-0.29,0.019,-0.0057,0.96,-0.48,-0.23,-0.002,-0.92,-0.47,-0.032,-0.00052,-0.0072,-0.00015,-0.00043,0.00033,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00053,0.00054,0.053,1.8,1.8,0.013,6.2,6.2,0.049,3e-05,2.9e-05,2.2e-06,0.04,0.04,0.00062,0.0012,7.7e-05,0.0013,0.0012,0.00077,0.0013,1,1,2.5
10090000,-0.29,0.019,-0.0056,0.96,-0.49,-0.25,-0.00079,-0.95,-0.53,-0.03,-0.00041,-0.0071,-0.00015,-0.00044,0.00025,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00052,0.00053,0.053,1.9,1.9,0.013,6.8,6.7,0.049,2.8e-05,2.8e-05,2.2e-06,0.04,0.04,0.0006,0.0012,7.7e-05,0.0013,0.0012,0.00077,0.0013,1,1,2.6
10090000,-0.29,0.019,-0.0056,0.96,-0.49,-0.25,-0.00079,-0.95,-0.53,-0.03,-0.00041,-0.0071,-0.00015,-0.00043,0.00025,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00052,0.00053,0.053,1.9,1.9,0.013,6.8,6.7,0.049,2.8e-05,2.8e-05,2.2e-06,0.04,0.04,0.0006,0.0012,7.7e-05,0.0013,0.0012,0.00077,0.0013,1,1,2.6
10190000,-0.29,0.019,-0.0055,0.96,-0.49,-0.27,5.1e-05,-0.97,-0.6,-0.031,-0.00028,-0.007,-0.00015,-0.00027,0.00012,-0.14,-0.1,-0.024,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00052,0.00053,0.053,2,1.9,0.013,7.3,7.3,0.048,2.7e-05,2.6e-05,2.2e-06,0.04,0.04,0.00058,0.0012,7.7e-05,0.0013,0.0012,0.00077,0.0013,1,1,2.6
10290000,-0.29,0.019,-0.0055,0.96,-0.48,-0.27,-0.0011,-0.97,-0.61,-0.03,-0.00034,-0.0069,-0.00014,-0.00015,0.00018,-0.14,-0.1,-0.024,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00052,0.00052,0.053,2,2,0.012,8,7.9,0.048,2.6e-05,2.5e-05,2.2e-06,0.04,0.04,0.00057,0.0012,7.6e-05,0.0013,0.0012,0.00077,0.0013,1,1,2.6
10390000,-0.29,0.019,-0.0054,0.96,0.0032,-0.0054,-0.0025,0.00059,-0.00016,-0.029,-0.00039,-0.0067,-0.00014,3.7e-06,0.00025,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00051,0.00052,0.053,0.25,0.25,0.56,0.25,0.25,0.048,2.4e-05,2.4e-05,2.2e-06,0.04,0.04,0.00055,0.0012,7.6e-05,0.0013,0.0012,0.00077,0.0013,1,1,2.6
10490000,-0.29,0.019,-0.0053,0.96,-0.0099,-0.0093,0.0071,0.00026,-0.00086,-0.024,-0.00032,-0.0067,-0.00014,-0.00014,0.00019,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00051,0.00052,0.053,0.26,0.26,0.55,0.26,0.26,0.057,2.3e-05,2.2e-05,2.2e-06,0.04,0.04,0.00054,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.7
10590000,-0.29,0.019,-0.0052,0.96,-0.02,-0.0079,0.013,-0.0011,-0.00061,-0.022,-0.00041,-0.0066,-0.00013,0.00011,0.00055,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.0005,0.00051,0.053,0.13,0.13,0.27,0.26,0.26,0.055,2.2e-05,2.1e-05,2.2e-06,0.039,0.039,0.00052,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.7
10690000,-0.29,0.019,-0.0051,0.96,-0.033,-0.011,0.016,-0.0038,-0.0016,-0.018,-0.00039,-0.0065,-0.00013,0.00014,0.00054,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.0005,0.00051,0.053,0.14,0.14,0.26,0.27,0.27,0.065,2.1e-05,2e-05,2.2e-06,0.039,0.039,0.00052,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.7
10390000,-0.29,0.019,-0.0054,0.96,0.0032,-0.0054,-0.0025,0.00059,-0.00016,-0.029,-0.00039,-0.0067,-0.00014,9.3e-06,0.00025,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00051,0.00052,0.053,0.25,0.25,0.56,0.25,0.25,0.048,2.4e-05,2.4e-05,2.2e-06,0.04,0.04,0.00055,0.0012,7.6e-05,0.0013,0.0012,0.00077,0.0013,1,1,2.6
10490000,-0.29,0.019,-0.0053,0.96,-0.0099,-0.0093,0.0071,0.00026,-0.00086,-0.024,-0.00032,-0.0067,-0.00014,-0.00013,0.00019,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00051,0.00052,0.053,0.26,0.26,0.55,0.26,0.26,0.057,2.3e-05,2.2e-05,2.2e-06,0.04,0.04,0.00054,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.7
10590000,-0.29,0.019,-0.0052,0.96,-0.02,-0.0079,0.013,-0.0011,-0.00061,-0.022,-0.00041,-0.0066,-0.00013,0.00012,0.00055,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.0005,0.00051,0.053,0.13,0.13,0.27,0.26,0.26,0.055,2.2e-05,2.1e-05,2.2e-06,0.039,0.039,0.00052,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.7
10690000,-0.29,0.019,-0.0051,0.96,-0.033,-0.011,0.016,-0.0038,-0.0016,-0.018,-0.00039,-0.0065,-0.00013,0.00015,0.00054,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.0005,0.00051,0.053,0.14,0.14,0.26,0.27,0.27,0.065,2.1e-05,2e-05,2.2e-06,0.039,0.039,0.00052,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.7
10790000,-0.29,0.019,-0.005,0.96,-0.033,-0.015,0.014,0.00012,-0.0018,-0.016,-0.00042,-0.0064,-0.00013,0.002,5.9e-05,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00048,0.00049,0.052,0.094,0.094,0.17,0.13,0.13,0.062,2e-05,1.9e-05,2.2e-06,0.038,0.038,0.00051,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.7
10890000,-0.29,0.019,-0.0049,0.96,-0.043,-0.02,0.01,-0.0036,-0.0035,-0.019,-0.00054,-0.0063,-0.00012,0.0021,0.0002,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00048,0.00049,0.052,0.1,0.1,0.16,0.14,0.14,0.068,1.9e-05,1.8e-05,2.2e-06,0.038,0.038,0.0005,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.8
10990000,-0.29,0.019,-0.005,0.96,-0.039,-0.022,0.016,-0.0014,-0.0019,-0.012,-0.00058,-0.0064,-0.00012,0.0058,0.00072,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.095,0.00045,0.00046,0.052,0.081,0.081,0.12,0.091,0.091,0.065,1.8e-05,1.7e-05,2.2e-06,0.036,0.036,0.00049,0.0012,7.6e-05,0.0013,0.0012,0.00075,0.0013,1,1,2.8
@@ -149,18 +149,18 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
14690000,-0.29,0.015,-0.0049,0.96,-0.016,-0.0041,0.018,-0.00088,-0.0058,0.01,-0.0007,-0.0059,-0.00011,0.064,0.01,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,7.6e-05,7.4e-05,0.051,0.035,0.035,0.0065,0.052,0.052,0.037,3.7e-06,3.4e-06,2.2e-06,0.0037,0.004,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.7
14790000,-0.29,0.015,-0.005,0.96,-0.019,-0.0015,0.018,-0.00058,-0.0013,0.013,-0.00073,-0.0058,-0.00011,0.065,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7.3e-05,7.1e-05,0.051,0.03,0.03,0.0064,0.046,0.046,0.036,3.5e-06,3.2e-06,2.2e-06,0.0036,0.0038,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.7
14890000,-0.29,0.015,-0.0049,0.96,-0.02,0.00041,0.022,-0.0027,-0.0017,0.014,-0.00074,-0.0058,-0.00011,0.065,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7.4e-05,7.2e-05,0.051,0.033,0.033,0.0064,0.052,0.052,0.036,3.4e-06,3.1e-06,2.2e-06,0.0035,0.0038,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.8
14990000,-0.29,0.015,-0.0049,0.96,-0.02,-0.0015,0.025,-0.0022,-0.0029,0.016,-0.00075,-0.0057,-0.00011,0.066,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7.1e-05,7e-05,0.051,0.029,0.029,0.0064,0.045,0.045,0.036,3.3e-06,3e-06,2.2e-06,0.0034,0.0036,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.8
14990000,-0.29,0.015,-0.0049,0.96,-0.02,-0.0016,0.025,-0.0022,-0.0029,0.016,-0.00075,-0.0057,-0.00011,0.066,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7.1e-05,7e-05,0.051,0.029,0.029,0.0064,0.045,0.045,0.036,3.3e-06,3e-06,2.2e-06,0.0034,0.0036,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.8
15090000,-0.29,0.015,-0.0048,0.96,-0.021,-0.0027,0.029,-0.0043,-0.0031,0.018,-0.00075,-0.0057,-0.00011,0.066,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7.2e-05,7e-05,0.051,0.031,0.031,0.0064,0.051,0.051,0.035,3.2e-06,2.9e-06,2.2e-06,0.0033,0.0036,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.8
15190000,-0.29,0.016,-0.005,0.96,-0.021,-0.00079,0.029,-0.0034,-0.0024,0.02,-0.00073,-0.0057,-0.00011,0.067,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7e-05,6.8e-05,0.051,0.027,0.028,0.0064,0.045,0.045,0.035,3.1e-06,2.8e-06,2.2e-06,0.0032,0.0035,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.8
15290000,-0.29,0.016,-0.005,0.96,-0.024,-0.00091,0.029,-0.0058,-0.0029,0.017,-0.00075,-0.0057,-0.00011,0.067,0.014,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7e-05,6.9e-05,0.051,0.03,0.03,0.0065,0.05,0.05,0.035,3e-06,2.7e-06,2.2e-06,0.0032,0.0035,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,3.9
15390000,-0.29,0.016,-0.0051,0.96,-0.023,-0.0028,0.028,-0.0046,-0.0024,0.017,-0.00075,-0.0057,-0.00011,0.068,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.8e-05,6.7e-05,0.051,0.026,0.026,0.0064,0.044,0.044,0.034,2.9e-06,2.7e-06,2.2e-06,0.0031,0.0033,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,3.9
15390000,-0.29,0.016,-0.0051,0.96,-0.023,-0.0028,0.028,-0.0046,-0.0024,0.017,-0.00075,-0.0057,-0.00011,0.068,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.8e-05,6.7e-05,0.051,0.026,0.026,0.0064,0.044,0.044,0.034,2.9e-06,2.6e-06,2.2e-06,0.0031,0.0033,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,3.9
15490000,-0.29,0.016,-0.0051,0.96,-0.025,-0.00034,0.028,-0.007,-0.0026,0.018,-0.00075,-0.0057,-0.00011,0.068,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.9e-05,6.7e-05,0.051,0.028,0.028,0.0065,0.05,0.05,0.034,2.8e-06,2.6e-06,2.2e-06,0.0031,0.0033,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,3.9
15590000,-0.29,0.016,-0.0051,0.96,-0.022,-0.0047,0.028,-0.0032,-0.0058,0.017,-0.00079,-0.0057,-0.00011,0.068,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.7e-05,6.6e-05,0.051,0.025,0.025,0.0065,0.044,0.044,0.034,2.7e-06,2.5e-06,2.2e-06,0.003,0.0032,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,3.9
15690000,-0.29,0.016,-0.005,0.96,-0.024,-0.0026,0.028,-0.0048,-0.0062,0.018,-0.00083,-0.0057,-0.00011,0.067,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.8e-05,6.6e-05,0.051,0.027,0.027,0.0066,0.049,0.049,0.034,2.7e-06,2.4e-06,2.2e-06,0.0029,0.0032,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4
15790000,-0.29,0.015,-0.005,0.96,-0.021,-0.0013,0.028,-0.0035,-0.0053,0.019,-0.00087,-0.0058,-0.00011,0.066,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.6e-05,6.4e-05,0.051,0.024,0.024,0.0066,0.043,0.043,0.033,2.6e-06,2.3e-06,2.2e-06,0.0029,0.0031,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4
15890000,-0.29,0.016,-0.0051,0.96,-0.021,-0.0026,0.029,-0.0059,-0.0053,0.019,-0.00084,-0.0057,-0.00011,0.067,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.7e-05,6.5e-05,0.051,0.026,0.026,0.0067,0.049,0.049,0.034,2.5e-06,2.3e-06,2.2e-06,0.0028,0.0031,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4
15990000,-0.29,0.016,-0.005,0.96,-0.02,-0.0021,0.026,-0.0049,-0.0045,0.018,-0.00083,-0.0057,-0.00011,0.067,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.6e-05,6.3e-05,0.051,0.023,0.023,0.0068,0.043,0.043,0.033,2.4e-06,2.2e-06,2.2e-06,0.0028,0.003,0.00042,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4
16090000,-0.29,0.016,-0.005,0.96,-0.022,-0.00082,0.024,-0.0072,-0.0045,0.018,-0.00082,-0.0057,-0.00011,0.068,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.6e-05,6.4e-05,0.051,0.024,0.025,0.0069,0.048,0.048,0.033,2.4e-06,2.1e-06,2.2e-06,0.0027,0.003,0.00042,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.1
16090000,-0.29,0.016,-0.005,0.96,-0.022,-0.00083,0.024,-0.0072,-0.0045,0.018,-0.00082,-0.0057,-0.00011,0.068,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.6e-05,6.4e-05,0.051,0.024,0.025,0.0069,0.048,0.048,0.033,2.4e-06,2.1e-06,2.2e-06,0.0027,0.003,0.00042,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.1
16190000,-0.29,0.016,-0.005,0.96,-0.02,-0.00061,0.023,-0.0071,-0.0037,0.015,-0.0008,-0.0057,-0.00011,0.068,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.5e-05,6.3e-05,0.051,0.022,0.022,0.0069,0.043,0.043,0.033,2.3e-06,2.1e-06,2.2e-06,0.0027,0.0029,0.00042,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.1
16290000,-0.29,0.015,-0.005,0.96,-0.022,0.00033,0.022,-0.009,-0.0038,0.017,-0.00081,-0.0057,-0.00011,0.068,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.6e-05,6.3e-05,0.051,0.023,0.024,0.007,0.048,0.048,0.033,2.2e-06,2e-06,2.2e-06,0.0027,0.0029,0.00042,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.1
16390000,-0.29,0.016,-0.0049,0.96,-0.023,-0.00021,0.023,-0.007,-0.0037,0.017,-0.00083,-0.0057,-0.00011,0.069,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.4e-05,6.2e-05,0.051,0.021,0.021,0.007,0.042,0.042,0.033,2.2e-06,2e-06,2.2e-06,0.0026,0.0029,0.00041,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.1
@@ -192,7 +192,7 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
18990000,-0.29,0.015,-0.0048,0.96,-0.029,0.012,0.023,-0.013,0.0056,0.028,-0.0011,-0.0058,-0.00012,0.069,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.7e-05,5.4e-05,0.051,0.015,0.015,0.0079,0.042,0.042,0.034,1.1e-06,1e-06,2.2e-06,0.0021,0.0024,0.00031,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.8
19090000,-0.29,0.015,-0.0048,0.96,-0.028,0.013,0.024,-0.016,0.0063,0.024,-0.0011,-0.0058,-0.00012,0.069,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.8e-05,5.4e-05,0.051,0.016,0.016,0.0079,0.045,0.046,0.035,1.1e-06,9.9e-07,2.2e-06,0.0021,0.0024,0.0003,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.8
19190000,-0.29,0.015,-0.0048,0.96,-0.026,0.014,0.023,-0.014,0.0062,0.023,-0.0011,-0.0058,-0.00012,0.068,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.7e-05,5.3e-05,0.05,0.014,0.015,0.0079,0.041,0.041,0.034,1.1e-06,9.6e-07,2.2e-06,0.0021,0.0024,0.0003,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.8
19290000,-0.29,0.015,-0.0048,0.96,-0.027,0.014,0.024,-0.017,0.0075,0.022,-0.0011,-0.0058,-0.00012,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.7e-05,5.3e-05,0.05,0.015,0.016,0.0079,0.044,0.044,0.034,1.1e-06,9.5e-07,2.2e-06,0.0021,0.0024,0.00029,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.9
19290000,-0.29,0.015,-0.0048,0.96,-0.027,0.014,0.024,-0.017,0.0074,0.022,-0.0011,-0.0058,-0.00012,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.7e-05,5.3e-05,0.05,0.015,0.016,0.0079,0.044,0.044,0.034,1.1e-06,9.5e-07,2.2e-06,0.0021,0.0024,0.00029,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.9
19390000,-0.29,0.015,-0.0049,0.96,-0.026,0.012,0.025,-0.015,0.0073,0.021,-0.0011,-0.0058,-0.00012,0.068,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.6e-05,5.3e-05,0.05,0.014,0.015,0.0078,0.04,0.04,0.035,1e-06,9.2e-07,2.2e-06,0.0021,0.0023,0.00029,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.9
19490000,-0.29,0.015,-0.005,0.96,-0.028,0.013,0.024,-0.018,0.0088,0.021,-0.0011,-0.0058,-0.00012,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.7e-05,5.3e-05,0.05,0.015,0.016,0.0078,0.043,0.044,0.035,1e-06,9.1e-07,2.2e-06,0.0021,0.0023,0.00029,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.9
19590000,-0.29,0.015,-0.0049,0.96,-0.025,0.014,0.026,-0.015,0.007,0.021,-0.0011,-0.0058,-0.00013,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.6e-05,5.2e-05,0.05,0.014,0.014,0.0077,0.039,0.039,0.035,9.9e-07,8.8e-07,2.2e-06,0.0021,0.0023,0.00028,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.9
@@ -219,7 +219,7 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
21690000,-0.29,0.012,-0.0018,0.96,-0.0024,-0.019,-1.1,-0.014,0.0039,-0.49,-0.0011,-0.0058,-0.00011,0.07,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-0.39,5.2e-05,4.7e-05,0.05,0.017,0.018,0.0069,0.066,0.067,0.035,6.8e-07,6e-07,2.1e-06,0.0019,0.0022,0.0002,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01
21790000,-0.29,0.012,-0.0021,0.96,-0.0082,-0.011,-1.3,-0.015,0.01,-0.61,-0.0011,-0.0058,-0.0001,0.07,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-0.51,5.1e-05,4.7e-05,0.05,0.017,0.018,0.0069,0.069,0.069,0.034,6.6e-07,5.8e-07,2.1e-06,0.0019,0.0022,0.0002,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01
21890000,-0.29,0.012,-0.0025,0.96,-0.014,-0.0073,-1.4,-0.016,0.0096,-0.75,-0.0011,-0.0058,-0.0001,0.07,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-0.65,5.1e-05,4.7e-05,0.05,0.018,0.019,0.0068,0.074,0.075,0.034,6.6e-07,5.8e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01
21990000,-0.29,0.012,-0.0032,0.96,-0.02,0.00089,-1.4,-0.022,0.017,-0.89,-0.001,-0.0058,-8.7e-05,0.07,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-0.79,5.1e-05,4.6e-05,0.05,0.018,0.019,0.0068,0.076,0.077,0.034,6.4e-07,5.7e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01
21990000,-0.29,0.012,-0.0032,0.96,-0.02,0.00088,-1.4,-0.022,0.017,-0.89,-0.001,-0.0058,-8.7e-05,0.07,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-0.79,5.1e-05,4.6e-05,0.05,0.018,0.019,0.0068,0.076,0.077,0.034,6.4e-07,5.7e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01
22090000,-0.29,0.013,-0.0038,0.96,-0.023,0.0041,-1.4,-0.023,0.016,-1,-0.0011,-0.0058,-8.4e-05,0.07,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-0.93,5.1e-05,4.7e-05,0.05,0.019,0.02,0.0068,0.082,0.084,0.034,6.4e-07,5.6e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01
22190000,-0.29,0.013,-0.0042,0.96,-0.03,0.011,-1.4,-0.027,0.024,-1.2,-0.0011,-0.0058,-7.1e-05,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-1.1,5e-05,4.6e-05,0.05,0.018,0.02,0.0067,0.085,0.086,0.034,6.2e-07,5.5e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01
22290000,-0.29,0.014,-0.0049,0.96,-0.038,0.015,-1.4,-0.031,0.025,-1.3,-0.0011,-0.0058,-7.1e-05,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-1.2,5.1e-05,4.6e-05,0.05,0.019,0.021,0.0067,0.091,0.093,0.034,6.2e-07,5.4e-07,2.1e-06,0.0019,0.0022,0.00018,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01
@@ -247,7 +247,7 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
24490000,-0.29,0.018,-0.0065,0.96,-0.059,0.047,0.08,-0.061,0.038,-3.6,-0.0012,-0.0058,-0.00011,0.067,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.5,4.6e-05,4.2e-05,0.049,0.021,0.023,0.006,0.2,0.2,0.033,4.6e-07,4.1e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01
24590000,-0.29,0.018,-0.0071,0.96,-0.047,0.045,0.076,-0.042,0.033,-3.6,-0.0013,-0.0058,-0.00012,0.067,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.5,4.6e-05,4.2e-05,0.049,0.02,0.022,0.0059,0.2,0.2,0.033,4.5e-07,4e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01
24690000,-0.29,0.018,-0.0076,0.96,-0.045,0.044,0.075,-0.046,0.036,-3.5,-0.0013,-0.0058,-0.00012,0.067,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.4,4.6e-05,4.2e-05,0.049,0.021,0.023,0.0059,0.21,0.21,0.033,4.5e-07,4e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01
24790000,-0.29,0.017,-0.0077,0.96,-0.039,0.043,0.067,-0.034,0.028,-3.5,-0.0013,-0.0058,-0.00013,0.067,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.4,4.6e-05,4.2e-05,0.049,0.02,0.022,0.0059,0.21,0.21,0.032,4.4e-07,3.9e-07,2e-06,0.0019,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01
24790000,-0.29,0.017,-0.0077,0.96,-0.039,0.043,0.067,-0.034,0.028,-3.5,-0.0013,-0.0058,-0.00013,0.067,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.4,4.6e-05,4.2e-05,0.049,0.02,0.022,0.0059,0.21,0.21,0.032,4.4e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01
24890000,-0.29,0.017,-0.0076,0.96,-0.038,0.045,0.056,-0.037,0.032,-3.5,-0.0013,-0.0058,-0.00013,0.067,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.4,4.6e-05,4.2e-05,0.049,0.021,0.023,0.0059,0.22,0.22,0.032,4.4e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01
24990000,-0.29,0.016,-0.0074,0.96,-0.025,0.046,0.049,-0.022,0.026,-3.5,-0.0013,-0.0058,-0.00013,0.067,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.4,4.6e-05,4.2e-05,0.048,0.021,0.022,0.0058,0.22,0.22,0.032,4.3e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01
25090000,-0.29,0.016,-0.0077,0.96,-0.021,0.046,0.047,-0.023,0.031,-3.5,-0.0013,-0.0058,-0.00013,0.067,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.6e-05,4.2e-05,0.048,0.021,0.023,0.0058,0.23,0.23,0.032,4.3e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01
@@ -265,11 +265,11 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
26290000,-0.3,0.015,-0.0073,0.96,0.042,0.02,0.015,0.027,-0.015,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.29,0.29,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01
26390000,-0.3,0.015,-0.0067,0.96,0.04,0.011,0.019,0.019,-0.03,-3.5,-0.0014,-0.0058,-0.00021,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0056,0.28,0.29,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01
26490000,-0.3,0.015,-0.0065,0.96,0.043,0.0088,0.028,0.024,-0.029,-3.5,-0.0014,-0.0058,-0.00022,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.3,0.3,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01
26590000,-0.3,0.015,-0.0059,0.95,0.042,-0.0012,0.028,0.023,-0.041,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.021,0.022,0.0056,0.29,0.3,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01
26590000,-0.3,0.015,-0.0059,0.95,0.042,-0.0012,0.028,0.023,-0.042,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.021,0.022,0.0056,0.29,0.3,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01
26690000,-0.3,0.015,-0.0058,0.95,0.044,-0.0048,0.027,0.027,-0.041,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.31,0.31,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01
26790000,-0.3,0.014,-0.0056,0.95,0.047,-0.011,0.026,0.025,-0.054,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.3,0.31,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01
26890000,-0.3,0.014,-0.005,0.96,0.053,-0.013,0.022,0.03,-0.056,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0055,0.31,0.32,0.032,3.7e-07,3.3e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01
26990000,-0.3,0.015,-0.0044,0.95,0.054,-0.02,0.021,0.023,-0.063,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.016,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.31,0.31,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01
26990000,-0.3,0.015,-0.0044,0.95,0.054,-0.02,0.021,0.023,-0.064,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.016,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.31,0.31,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01
27090000,-0.3,0.015,-0.0042,0.95,0.056,-0.026,0.025,0.028,-0.066,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.022,0.023,0.0055,0.32,0.33,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01
27190000,-0.3,0.015,-0.0043,0.96,0.057,-0.03,0.027,0.019,-0.069,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.32,0.32,0.031,3.6e-07,3.2e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01
27290000,-0.3,0.016,-0.0043,0.96,0.064,-0.034,0.14,0.025,-0.072,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.022,0.023,0.0055,0.33,0.34,0.031,3.6e-07,3.2e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01
@@ -314,38 +314,38 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
31190000,-0.29,0.016,-0.0028,0.96,0.043,-0.0042,0.8,0.094,-0.039,-0.74,-0.0012,-0.0058,-2.7e-05,0.067,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.64,4.4e-05,3.8e-05,0.048,0.02,0.021,0.0052,0.21,0.22,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01
31290000,-0.29,0.016,-0.003,0.96,0.04,-0.0027,0.8,0.097,-0.041,-0.67,-0.0012,-0.0058,-2.3e-05,0.067,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.57,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.22,0.23,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01
31390000,-0.29,0.015,-0.0028,0.96,0.035,0.0022,0.8,0.091,-0.037,-0.59,-0.0012,-0.0058,-2.5e-05,0.067,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.49,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.22,0.23,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.4e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01
31490000,-0.29,0.016,-0.0025,0.96,0.037,0.0056,0.8,0.096,-0.036,-0.52,-0.0012,-0.0058,-2.8e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.42,4.4e-05,3.8e-05,0.048,0.021,0.022,0.0052,0.23,0.24,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.4e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01
31490000,-0.29,0.016,-0.0025,0.96,0.036,0.0056,0.8,0.096,-0.036,-0.52,-0.0012,-0.0058,-2.8e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.42,4.4e-05,3.8e-05,0.048,0.021,0.022,0.0052,0.23,0.24,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.4e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01
31590000,-0.29,0.016,-0.0023,0.96,0.037,0.0074,0.8,0.093,-0.032,-0.45,-0.0012,-0.0058,-2e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.35,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.23,0.24,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.3e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01
31690000,-0.29,0.016,-0.0023,0.96,0.041,0.0084,0.8,0.098,-0.032,-0.38,-0.0012,-0.0058,-1.3e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.28,4.4e-05,3.8e-05,0.048,0.021,0.022,0.0051,0.24,0.25,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.3e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01
31790000,-0.29,0.017,-0.0025,0.96,0.035,0.014,0.8,0.094,-0.023,-0.3,-0.0012,-0.0058,-9.9e-07,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.2,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.24,0.25,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.2e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01
31790000,-0.29,0.017,-0.0025,0.96,0.035,0.014,0.8,0.094,-0.023,-0.3,-0.0012,-0.0058,-1e-06,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.2,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.24,0.25,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.2e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01
31890000,-0.29,0.017,-0.0022,0.96,0.033,0.015,0.8,0.099,-0.021,-0.24,-0.0012,-0.0058,1.4e-06,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.14,4.3e-05,3.7e-05,0.048,0.021,0.022,0.0051,0.25,0.26,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.2e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01
31990000,-0.29,0.016,-0.0025,0.96,0.03,0.017,0.79,0.096,-0.016,-0.17,-0.0012,-0.0058,5.2e-07,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.068,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.25,0.26,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.2e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01
32090000,-0.29,0.016,-0.0029,0.96,0.031,0.021,0.8,0.099,-0.014,-0.096,-0.0012,-0.0058,9.3e-08,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.0038,4.3e-05,3.7e-05,0.048,0.021,0.023,0.0051,0.26,0.27,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01
32090000,-0.29,0.016,-0.0029,0.96,0.031,0.021,0.8,0.099,-0.014,-0.096,-0.0012,-0.0058,8.8e-08,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.0038,4.3e-05,3.7e-05,0.048,0.021,0.023,0.0051,0.26,0.27,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01
32190000,-0.29,0.016,-0.0032,0.96,0.028,0.028,0.8,0.094,-0.0046,-0.028,-0.0012,-0.0058,3.2e-06,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.072,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.26,0.27,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01
32290000,-0.29,0.016,-0.003,0.96,0.027,0.03,0.79,0.098,-0.0019,0.042,-0.0012,-0.0058,7e-06,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.14,4.3e-05,3.7e-05,0.048,0.021,0.023,0.0051,0.27,0.28,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01
32390000,-0.29,0.016,-0.0032,0.96,0.024,0.032,0.79,0.094,0.0018,0.12,-0.0012,-0.0058,5.2e-06,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.22,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.27,0.28,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01
32490000,-0.29,0.015,-0.0063,0.96,-0.016,0.085,-0.078,0.092,0.0094,0.12,-0.0012,-0.0058,2.9e-06,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.22,4.3e-05,3.7e-05,0.048,0.022,0.024,0.0051,0.28,0.29,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01
32590000,-0.29,0.015,-0.0063,0.96,-0.014,0.084,-0.081,0.093,0.0025,0.1,-0.0012,-0.0058,-2e-06,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.2,4.2e-05,3.7e-05,0.047,0.021,0.023,0.0051,0.28,0.29,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01
32690000,-0.29,0.015,-0.0063,0.96,-0.0097,0.091,-0.082,0.091,0.011,0.087,-0.0012,-0.0058,-2e-06,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.19,4.3e-05,3.7e-05,0.047,0.022,0.024,0.0051,0.29,0.3,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01
32790000,-0.29,0.015,-0.0061,0.96,-0.0057,0.09,-0.083,0.093,0.0037,0.072,-0.0012,-0.0058,-7.5e-06,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.17,4.2e-05,3.7e-05,0.047,0.021,0.023,0.0051,0.29,0.3,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01
32890000,-0.29,0.015,-0.0061,0.96,-0.0062,0.096,-0.085,0.092,0.012,0.057,-0.0012,-0.0058,-3e-06,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.16,4.2e-05,3.7e-05,0.047,0.022,0.023,0.0051,0.3,0.31,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01
32990000,-0.29,0.015,-0.006,0.96,-0.0023,0.091,-0.084,0.092,-0.00052,0.043,-0.0013,-0.0058,-1.1e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.14,4.2e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.3,0.31,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01
33090000,-0.29,0.015,-0.0059,0.96,0.0014,0.097,-0.081,0.092,0.0087,0.036,-0.0013,-0.0058,-1e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.14,4.2e-05,3.7e-05,0.047,0.022,0.023,0.0051,0.31,0.32,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01
32790000,-0.29,0.015,-0.0061,0.96,-0.0057,0.09,-0.083,0.093,0.0037,0.072,-0.0012,-0.0058,-7.5e-06,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.17,4.2e-05,3.7e-05,0.047,0.021,0.023,0.0051,0.29,0.3,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01
32890000,-0.29,0.015,-0.0061,0.96,-0.0062,0.096,-0.085,0.092,0.012,0.057,-0.0012,-0.0058,-3e-06,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.16,4.2e-05,3.7e-05,0.047,0.022,0.023,0.0051,0.3,0.31,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01
32990000,-0.29,0.015,-0.006,0.96,-0.0023,0.091,-0.084,0.092,-0.00052,0.043,-0.0013,-0.0058,-1.1e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.14,4.2e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.3,0.31,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01
33090000,-0.29,0.015,-0.0059,0.96,0.0014,0.097,-0.081,0.092,0.0087,0.036,-0.0013,-0.0058,-1e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.14,4.2e-05,3.7e-05,0.047,0.022,0.023,0.0051,0.31,0.32,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01
33190000,-0.29,0.015,-0.0059,0.96,0.0056,0.093,-0.08,0.093,-0.0059,0.028,-0.0013,-0.0058,-2.9e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.13,4.1e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.31,0.31,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01
33290000,-0.29,0.015,-0.0059,0.96,0.0098,0.096,-0.08,0.094,0.0029,0.02,-0.0013,-0.0058,-1.8e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.2e-05,3.7e-05,0.047,0.021,0.023,0.0051,0.32,0.33,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01
33390000,-0.3,0.015,-0.0058,0.96,0.014,0.093,-0.078,0.094,-0.0054,0.01,-0.0013,-0.0058,-2.6e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.32,0.32,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.033
33290000,-0.29,0.015,-0.0059,0.96,0.0098,0.096,-0.08,0.094,0.0029,0.02,-0.0013,-0.0058,-1.8e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.2e-05,3.7e-05,0.047,0.021,0.023,0.0051,0.32,0.33,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01
33390000,-0.3,0.015,-0.0058,0.96,0.014,0.093,-0.078,0.094,-0.0054,0.01,-0.0013,-0.0058,-2.6e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.32,0.32,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.033
33490000,-0.3,0.015,-0.0058,0.96,0.02,0.097,-0.078,0.097,0.004,-0.00072,-0.0013,-0.0058,-2.1e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.33,0.34,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.058
33590000,-0.3,0.015,-0.0056,0.95,0.023,0.094,-0.075,0.096,-0.0089,-0.01,-0.0013,-0.0058,-2.7e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.33,0.33,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.083
33690000,-0.3,0.015,-0.0056,0.95,0.026,0.098,-0.076,0.097,8.9e-05,-0.019,-0.0013,-0.0058,-2.2e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.34,0.35,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.11
33590000,-0.3,0.015,-0.0056,0.95,0.023,0.094,-0.075,0.096,-0.0089,-0.01,-0.0013,-0.0058,-2.7e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.33,0.33,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.083
33690000,-0.3,0.015,-0.0056,0.95,0.026,0.098,-0.076,0.097,8.7e-05,-0.019,-0.0013,-0.0058,-2.2e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.34,0.35,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.11
33790000,-0.3,0.015,-0.0056,0.95,0.028,0.096,-0.071,0.094,-0.013,-0.028,-0.0013,-0.0058,-3.5e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.34,0.34,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.13
33890000,-0.3,0.015,-0.0055,0.95,0.033,0.097,-0.071,0.097,-0.004,-0.037,-0.0013,-0.0058,-2.5e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.35,0.36,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.16
33990000,-0.3,0.015,-0.0054,0.95,0.035,0.096,-0.068,0.096,-0.012,-0.042,-0.0013,-0.0058,-3.6e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.35,0.35,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.18
34090000,-0.3,0.015,-0.0054,0.95,0.038,0.1,-0.067,0.099,-0.0027,-0.046,-0.0013,-0.0057,-3.2e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.36,0.37,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.21
34190000,-0.3,0.015,-0.0054,0.95,0.039,0.097,-0.064,0.094,-0.014,-0.05,-0.0013,-0.0057,-3.8e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.36,0.36,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.23
34290000,-0.3,0.015,-0.0052,0.95,0.041,0.1,-0.062,0.098,-0.0047,-0.055,-0.0013,-0.0057,-3e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.005,0.37,0.37,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.26
34390000,-0.3,0.015,-0.0051,0.95,0.042,0.097,-0.057,0.093,-0.016,-0.059,-0.0013,-0.0057,-3.9e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.37,0.37,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.28
33890000,-0.3,0.015,-0.0055,0.95,0.033,0.097,-0.071,0.097,-0.004,-0.037,-0.0013,-0.0058,-2.5e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.35,0.36,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.16
33990000,-0.3,0.015,-0.0054,0.95,0.035,0.096,-0.068,0.096,-0.012,-0.042,-0.0013,-0.0058,-3.6e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.35,0.35,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.18
34090000,-0.3,0.015,-0.0054,0.95,0.038,0.1,-0.067,0.099,-0.0027,-0.046,-0.0013,-0.0057,-3.2e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.36,0.37,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.21
34190000,-0.3,0.015,-0.0054,0.95,0.039,0.097,-0.064,0.094,-0.014,-0.05,-0.0013,-0.0057,-3.7e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.36,0.36,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.23
34290000,-0.3,0.015,-0.0052,0.95,0.041,0.1,-0.062,0.098,-0.0047,-0.055,-0.0013,-0.0057,-3e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.005,0.37,0.37,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.26
34390000,-0.3,0.015,-0.0051,0.95,0.042,0.097,-0.057,0.093,-0.016,-0.059,-0.0013,-0.0057,-3.9e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.37,0.37,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.28
34490000,-0.3,0.015,-0.0051,0.95,0.045,0.1,-0.055,0.097,-0.0068,-0.061,-0.0013,-0.0057,-3e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.085,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.31
34590000,-0.3,0.014,-0.005,0.95,0.045,0.098,0.74,0.092,-0.021,-0.033,-0.0013,-0.0057,-4.1e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.33
34690000,-0.3,0.014,-0.0051,0.95,0.05,0.1,1.7,0.097,-0.011,0.087,-0.0013,-0.0057,-3.7e-05,0.066,0.016,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.39,0.39,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.36
34590000,-0.3,0.014,-0.005,0.95,0.045,0.098,0.74,0.092,-0.021,-0.033,-0.0013,-0.0057,-4e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.33
34690000,-0.3,0.014,-0.0051,0.95,0.05,0.1,1.7,0.097,-0.011,0.087,-0.0013,-0.0057,-3.7e-05,0.066,0.016,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.39,0.39,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.36
34790000,-0.3,0.014,-0.005,0.95,0.051,0.099,2.7,0.091,-0.025,0.27,-0.0013,-0.0057,-4.7e-05,0.066,0.016,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.019,0.019,0.005,0.39,0.39,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.38
34890000,-0.3,0.014,-0.005,0.95,0.056,0.1,3.7,0.096,-0.015,0.56,-0.0013,-0.0057,-4.3e-05,0.066,0.016,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.019,0.019,0.005,0.4,0.4,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.3e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.41
1 Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7],state[8],state[9],state[10],state[11],state[12],state[13],state[14],state[15],state[16],state[17],state[18],state[19],state[20],state[21],state[22],state[23],variance[0],variance[1],variance[2],variance[3],variance[4],variance[5],variance[6],variance[7],variance[8],variance[9],variance[10],variance[11],variance[12],variance[13],variance[14],variance[15],variance[16],variance[17],variance[18],variance[19],variance[20],variance[21],variance[22],variance[23]
67 6490000,1,-0.0089,-0.011,0.00062,0.0057,0.016,-0.039,0.0041,0.0076,-0.053,-0.0018,-0.0056,-8.7e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.095,0.0018,0.0018,0.0001,0.25,0.25,0.038,0.15,0.15,0.07,0.00012,0.00012,2.9e-06,0.04,0.04,0.0036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7
68 6590000,1,-0.0089,-0.011,0.00055,0.0039,0.015,-0.042,0.0029,0.0058,-0.056,-0.0017,-0.0056,-8.9e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.095,0.0016,0.0016,9.6e-05,0.2,0.2,0.036,0.12,0.12,0.069,9.8e-05,9.8e-05,2.6e-06,0.04,0.04,0.0034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7
69 6690000,1,-0.0088,-0.011,0.0005,0.0022,0.018,-0.044,0.0032,0.0075,-0.057,-0.0017,-0.0056,-8.9e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.095,0.0016,0.0016,9.9e-05,0.23,0.23,0.035,0.14,0.14,0.068,9.8e-05,9.8e-05,2.6e-06,0.04,0.04,0.0031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7
70 6790000,1,-0.0089,-0.011,0.00047,0.003,0.015,-0.042,0.0021,0.006,-0.058,-0.0017,-0.0056,-9.1e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.095,0.0014,0.0014,9.3e-05,0.18,0.18,0.034,0.11,0.11,0.068,8.1e-05,8.1e-05,2.4e-06,0.04,0.04,0.003,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 6790000,1,-0.0089,-0.011,0.00047,0.003,0.015,-0.042,0.0021,0.006,-0.058,-0.0017,-0.0056,-9.1e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.095,0.0014,0.0014,9.3e-05,0.18,0.18,0.034,0.11,0.11,0.068,8e-05,8.1e-05,2.4e-06,0.04,0.04,0.003,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7
71 6890000,1,-0.0087,-0.011,0.00039,0.0023,0.015,-0.039,0.0024,0.0075,-0.055,-0.0017,-0.0056,-9.1e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.095,0.0015,0.0015,9.6e-05,0.21,0.21,0.032,0.14,0.14,0.067,8.1e-05,8.1e-05,2.4e-06,0.04,0.04,0.0028,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.8 6890000,1,-0.0087,-0.011,0.00039,0.0023,0.015,-0.039,0.0024,0.0075,-0.055,-0.0017,-0.0056,-9.1e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.095,0.0015,0.0015,9.6e-05,0.21,0.21,0.032,0.14,0.14,0.067,8e-05,8.1e-05,2.4e-06,0.04,0.04,0.0028,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.8
72 6990000,-0.29,0.024,-0.0061,0.96,-0.2,-0.032,-0.037,-0.11,-0.019,-0.055,-0.00077,-0.0097,-0.0002,0,0,-0.13,-0.091,-0.021,0.51,0.069,-0.028,-0.058,0,0,0.095,0.0011,0.0012,0.076,0.16,0.16,0.031,0.1,0.1,0.066,6.3e-05,6.4e-05,2.2e-06,0.04,0.04,0.0026,0.0014,0.00049,0.0014,0.0014,0.0012,0.0014,1,1,1.8
73 7090000,-0.29,0.025,-0.0062,0.96,-0.24,-0.048,-0.038,-0.15,-0.027,-0.056,-0.00064,-0.01,-0.00021,0,0,-0.13,-0.099,-0.023,0.51,0.075,-0.029,-0.065,0,0,0.095,0.0011,0.0011,0.063,0.19,0.18,0.03,0.13,0.13,0.066,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0024,0.0013,0.00025,0.0013,0.0013,0.00095,0.0013,1,1,1.8
74 7190000,-0.29,0.025,-0.0062,0.96,-0.26,-0.057,-0.037,-0.17,-0.034,-0.059,-0.0006,-0.01,-0.00021,-0.00035,-7.7e-05,-0.13,-0.1,-0.023,0.51,0.077,-0.03,-0.067,0,0,0.095,0.0011,0.0011,0.06,0.21,0.21,0.029,0.16,0.15,0.065,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0023,0.0013,0.00018,0.0013,0.0013,0.0009,0.0013,1,1,1.8
93 9090000,-0.29,0.02,-0.0063,0.96,-0.46,-0.16,-0.0099,-0.72,-0.24,-0.032,-0.00071,-0.0082,-0.00016,-0.0012,0.00029,-0.13,-0.1,-0.024,0.5,0.08,-0.031,-0.069,0,0,0.095,0.0006,0.00062,0.053,1.2,1.2,0.016,2.7,2.7,0.053,4.5e-05,4.5e-05,2.2e-06,0.04,0.04,0.00087,0.0012,8.2e-05,0.0013,0.0012,0.0008,0.0013,1,1,2.3
94 9190000,-0.29,0.02,-0.0063,0.96,-0.46,-0.16,-0.0095,-0.73,-0.24,-0.033,-0.00081,-0.008,-0.00016,-0.0011,0.00042,-0.13,-0.1,-0.024,0.5,0.081,-0.031,-0.069,0,0,0.095,0.00059,0.0006,0.053,1.2,1.2,0.016,3,3,0.052,4.3e-05,4.3e-05,2.2e-06,0.04,0.04,0.00084,0.0012,8.2e-05,0.0013,0.0012,0.00079,0.0013,1,1,2.3
95 9290000,-0.29,0.02,-0.006,0.96,-0.45,-0.16,-0.0081,-0.73,-0.25,-0.03,-0.00081,-0.0078,-0.00015,-0.001,0.00048,-0.13,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00058,0.00059,0.053,1.3,1.3,0.015,3.3,3.3,0.052,4.1e-05,4.1e-05,2.2e-06,0.04,0.04,0.0008,0.0012,8.1e-05,0.0013,0.0012,0.00079,0.0013,1,1,2.4
96 9390000,-0.29,0.02,-0.0058,0.96,-0.45,-0.18,-0.0071,-0.75,-0.29,-0.031,-0.00073,-0.0076,-0.00015,-0.00084,0.00046,-0.13,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00057,0.00058,0.053,1.4,1.4,0.015,3.7,3.6,0.052,4e-05,4e-05,2.2e-06,0.04,0.04,0.00077,0.0012,8e-05,0.0013,0.0012,0.00079,0.0013,1,1,2.4 9390000,-0.29,0.02,-0.0058,0.96,-0.45,-0.18,-0.0071,-0.75,-0.29,-0.031,-0.00073,-0.0077,-0.00015,-0.00084,0.00046,-0.13,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00057,0.00058,0.053,1.4,1.4,0.015,3.7,3.6,0.052,4e-05,4e-05,2.2e-06,0.04,0.04,0.00077,0.0012,8e-05,0.0013,0.0012,0.00079,0.0013,1,1,2.4
97 9490000,-0.29,0.019,-0.0059,0.96,-0.46,-0.17,-0.0055,-0.78,-0.29,-0.028,-0.0008,-0.0076,-0.00015,-0.00092,0.00055,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00056,0.00057,0.053,1.4,1.4,0.015,4,4,0.051,3.8e-05,3.8e-05,2.2e-06,0.04,0.04,0.00074,0.0012,8e-05,0.0013,0.0012,0.00079,0.0013,1,1,2.4
98 9590000,-0.29,0.019,-0.0059,0.96,-0.46,-0.19,-0.0054,-0.81,-0.34,-0.029,-0.00068,-0.0075,-0.00015,-0.00086,0.00042,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00055,0.00056,0.053,1.5,1.5,0.014,4.4,4.3,0.05,3.6e-05,3.6e-05,2.2e-06,0.04,0.04,0.00072,0.0012,7.9e-05,0.0013,0.0012,0.00078,0.0013,1,1,2.4 9590000,-0.29,0.019,-0.0059,0.96,-0.46,-0.19,-0.0054,-0.81,-0.34,-0.029,-0.00068,-0.0075,-0.00015,-0.00085,0.00042,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00055,0.00056,0.053,1.5,1.5,0.014,4.4,4.3,0.05,3.6e-05,3.6e-05,2.2e-06,0.04,0.04,0.00072,0.0012,7.9e-05,0.0013,0.0012,0.00078,0.0013,1,1,2.4
99 9690000,-0.29,0.019,-0.0058,0.96,-0.46,-0.2,-0.0026,-0.83,-0.37,-0.028,-0.00064,-0.0074,-0.00015,-0.00077,0.00041,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00054,0.00056,0.053,1.6,1.6,0.014,4.8,4.8,0.05,3.5e-05,3.4e-05,2.2e-06,0.04,0.04,0.00069,0.0012,7.9e-05,0.0013,0.0012,0.00078,0.0013,1,1,2.5
100 9790000,-0.29,0.019,-0.0058,0.96,-0.48,-0.22,-0.0039,-0.88,-0.41,-0.029,-0.00055,-0.0074,-0.00015,-0.00076,0.00033,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00054,0.00055,0.053,1.6,1.6,0.014,5.2,5.2,0.05,3.3e-05,3.3e-05,2.2e-06,0.04,0.04,0.00067,0.0012,7.8e-05,0.0013,0.0012,0.00078,0.0013,1,1,2.5 9790000,-0.29,0.019,-0.0058,0.96,-0.48,-0.22,-0.0039,-0.88,-0.41,-0.029,-0.00055,-0.0074,-0.00015,-0.00075,0.00033,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00054,0.00055,0.053,1.6,1.6,0.014,5.2,5.2,0.05,3.3e-05,3.3e-05,2.2e-06,0.04,0.04,0.00067,0.0012,7.8e-05,0.0013,0.0012,0.00078,0.0013,1,1,2.5
101 9890000,-0.29,0.019,-0.0057,0.96,-0.47,-0.22,-0.0027,-0.87,-0.43,-0.03,-0.00058,-0.0072,-0.00014,-0.00052,0.00039,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00053,0.00054,0.053,1.7,1.7,0.013,5.7,5.6,0.049,3.1e-05,3.1e-05,2.2e-06,0.04,0.04,0.00064,0.0012,7.8e-05,0.0013,0.0012,0.00078,0.0013,1,1,2.5 9890000,-0.29,0.019,-0.0057,0.96,-0.47,-0.22,-0.0027,-0.87,-0.43,-0.03,-0.00058,-0.0072,-0.00014,-0.00051,0.00039,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00053,0.00054,0.053,1.7,1.7,0.013,5.7,5.6,0.049,3.1e-05,3.1e-05,2.2e-06,0.04,0.04,0.00064,0.0012,7.8e-05,0.0013,0.0012,0.00078,0.0013,1,1,2.5
102 9990000,-0.29,0.019,-0.0057,0.96,-0.48,-0.23,-0.002,-0.92,-0.47,-0.032,-0.00052,-0.0072,-0.00015,-0.00043,0.00033,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00053,0.00054,0.053,1.8,1.8,0.013,6.2,6.2,0.049,3e-05,2.9e-05,2.2e-06,0.04,0.04,0.00062,0.0012,7.7e-05,0.0013,0.0012,0.00077,0.0013,1,1,2.5
103 10090000,-0.29,0.019,-0.0056,0.96,-0.49,-0.25,-0.00079,-0.95,-0.53,-0.03,-0.00041,-0.0071,-0.00015,-0.00044,0.00025,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00052,0.00053,0.053,1.9,1.9,0.013,6.8,6.7,0.049,2.8e-05,2.8e-05,2.2e-06,0.04,0.04,0.0006,0.0012,7.7e-05,0.0013,0.0012,0.00077,0.0013,1,1,2.6 10090000,-0.29,0.019,-0.0056,0.96,-0.49,-0.25,-0.00079,-0.95,-0.53,-0.03,-0.00041,-0.0071,-0.00015,-0.00043,0.00025,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00052,0.00053,0.053,1.9,1.9,0.013,6.8,6.7,0.049,2.8e-05,2.8e-05,2.2e-06,0.04,0.04,0.0006,0.0012,7.7e-05,0.0013,0.0012,0.00077,0.0013,1,1,2.6
104 10190000,-0.29,0.019,-0.0055,0.96,-0.49,-0.27,5.1e-05,-0.97,-0.6,-0.031,-0.00028,-0.007,-0.00015,-0.00027,0.00012,-0.14,-0.1,-0.024,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00052,0.00053,0.053,2,1.9,0.013,7.3,7.3,0.048,2.7e-05,2.6e-05,2.2e-06,0.04,0.04,0.00058,0.0012,7.7e-05,0.0013,0.0012,0.00077,0.0013,1,1,2.6
105 10290000,-0.29,0.019,-0.0055,0.96,-0.48,-0.27,-0.0011,-0.97,-0.61,-0.03,-0.00034,-0.0069,-0.00014,-0.00015,0.00018,-0.14,-0.1,-0.024,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00052,0.00052,0.053,2,2,0.012,8,7.9,0.048,2.6e-05,2.5e-05,2.2e-06,0.04,0.04,0.00057,0.0012,7.6e-05,0.0013,0.0012,0.00077,0.0013,1,1,2.6
106 10390000,-0.29,0.019,-0.0054,0.96,0.0032,-0.0054,-0.0025,0.00059,-0.00016,-0.029,-0.00039,-0.0067,-0.00014,3.7e-06,0.00025,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00051,0.00052,0.053,0.25,0.25,0.56,0.25,0.25,0.048,2.4e-05,2.4e-05,2.2e-06,0.04,0.04,0.00055,0.0012,7.6e-05,0.0013,0.0012,0.00077,0.0013,1,1,2.6 10390000,-0.29,0.019,-0.0054,0.96,0.0032,-0.0054,-0.0025,0.00059,-0.00016,-0.029,-0.00039,-0.0067,-0.00014,9.3e-06,0.00025,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00051,0.00052,0.053,0.25,0.25,0.56,0.25,0.25,0.048,2.4e-05,2.4e-05,2.2e-06,0.04,0.04,0.00055,0.0012,7.6e-05,0.0013,0.0012,0.00077,0.0013,1,1,2.6
107 10490000,-0.29,0.019,-0.0053,0.96,-0.0099,-0.0093,0.0071,0.00026,-0.00086,-0.024,-0.00032,-0.0067,-0.00014,-0.00014,0.00019,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00051,0.00052,0.053,0.26,0.26,0.55,0.26,0.26,0.057,2.3e-05,2.2e-05,2.2e-06,0.04,0.04,0.00054,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.7 10490000,-0.29,0.019,-0.0053,0.96,-0.0099,-0.0093,0.0071,0.00026,-0.00086,-0.024,-0.00032,-0.0067,-0.00014,-0.00013,0.00019,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00051,0.00052,0.053,0.26,0.26,0.55,0.26,0.26,0.057,2.3e-05,2.2e-05,2.2e-06,0.04,0.04,0.00054,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.7
108 10590000,-0.29,0.019,-0.0052,0.96,-0.02,-0.0079,0.013,-0.0011,-0.00061,-0.022,-0.00041,-0.0066,-0.00013,0.00011,0.00055,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.0005,0.00051,0.053,0.13,0.13,0.27,0.26,0.26,0.055,2.2e-05,2.1e-05,2.2e-06,0.039,0.039,0.00052,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.7 10590000,-0.29,0.019,-0.0052,0.96,-0.02,-0.0079,0.013,-0.0011,-0.00061,-0.022,-0.00041,-0.0066,-0.00013,0.00012,0.00055,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.0005,0.00051,0.053,0.13,0.13,0.27,0.26,0.26,0.055,2.2e-05,2.1e-05,2.2e-06,0.039,0.039,0.00052,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.7
109 10690000,-0.29,0.019,-0.0051,0.96,-0.033,-0.011,0.016,-0.0038,-0.0016,-0.018,-0.00039,-0.0065,-0.00013,0.00014,0.00054,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.0005,0.00051,0.053,0.14,0.14,0.26,0.27,0.27,0.065,2.1e-05,2e-05,2.2e-06,0.039,0.039,0.00052,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.7 10690000,-0.29,0.019,-0.0051,0.96,-0.033,-0.011,0.016,-0.0038,-0.0016,-0.018,-0.00039,-0.0065,-0.00013,0.00015,0.00054,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.0005,0.00051,0.053,0.14,0.14,0.26,0.27,0.27,0.065,2.1e-05,2e-05,2.2e-06,0.039,0.039,0.00052,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.7
110 10790000,-0.29,0.019,-0.005,0.96,-0.033,-0.015,0.014,0.00012,-0.0018,-0.016,-0.00042,-0.0064,-0.00013,0.002,5.9e-05,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00048,0.00049,0.052,0.094,0.094,0.17,0.13,0.13,0.062,2e-05,1.9e-05,2.2e-06,0.038,0.038,0.00051,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.7
111 10890000,-0.29,0.019,-0.0049,0.96,-0.043,-0.02,0.01,-0.0036,-0.0035,-0.019,-0.00054,-0.0063,-0.00012,0.0021,0.0002,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00048,0.00049,0.052,0.1,0.1,0.16,0.14,0.14,0.068,1.9e-05,1.8e-05,2.2e-06,0.038,0.038,0.0005,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.8
112 10990000,-0.29,0.019,-0.005,0.96,-0.039,-0.022,0.016,-0.0014,-0.0019,-0.012,-0.00058,-0.0064,-0.00012,0.0058,0.00072,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.095,0.00045,0.00046,0.052,0.081,0.081,0.12,0.091,0.091,0.065,1.8e-05,1.7e-05,2.2e-06,0.036,0.036,0.00049,0.0012,7.6e-05,0.0013,0.0012,0.00075,0.0013,1,1,2.8
149 14690000,-0.29,0.015,-0.0049,0.96,-0.016,-0.0041,0.018,-0.00088,-0.0058,0.01,-0.0007,-0.0059,-0.00011,0.064,0.01,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,7.6e-05,7.4e-05,0.051,0.035,0.035,0.0065,0.052,0.052,0.037,3.7e-06,3.4e-06,2.2e-06,0.0037,0.004,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.7
150 14790000,-0.29,0.015,-0.005,0.96,-0.019,-0.0015,0.018,-0.00058,-0.0013,0.013,-0.00073,-0.0058,-0.00011,0.065,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7.3e-05,7.1e-05,0.051,0.03,0.03,0.0064,0.046,0.046,0.036,3.5e-06,3.2e-06,2.2e-06,0.0036,0.0038,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.7
151 14890000,-0.29,0.015,-0.0049,0.96,-0.02,0.00041,0.022,-0.0027,-0.0017,0.014,-0.00074,-0.0058,-0.00011,0.065,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7.4e-05,7.2e-05,0.051,0.033,0.033,0.0064,0.052,0.052,0.036,3.4e-06,3.1e-06,2.2e-06,0.0035,0.0038,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.8
152 14990000,-0.29,0.015,-0.0049,0.96,-0.02,-0.0015,0.025,-0.0022,-0.0029,0.016,-0.00075,-0.0057,-0.00011,0.066,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7.1e-05,7e-05,0.051,0.029,0.029,0.0064,0.045,0.045,0.036,3.3e-06,3e-06,2.2e-06,0.0034,0.0036,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.8 14990000,-0.29,0.015,-0.0049,0.96,-0.02,-0.0016,0.025,-0.0022,-0.0029,0.016,-0.00075,-0.0057,-0.00011,0.066,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7.1e-05,7e-05,0.051,0.029,0.029,0.0064,0.045,0.045,0.036,3.3e-06,3e-06,2.2e-06,0.0034,0.0036,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.8
153 15090000,-0.29,0.015,-0.0048,0.96,-0.021,-0.0027,0.029,-0.0043,-0.0031,0.018,-0.00075,-0.0057,-0.00011,0.066,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7.2e-05,7e-05,0.051,0.031,0.031,0.0064,0.051,0.051,0.035,3.2e-06,2.9e-06,2.2e-06,0.0033,0.0036,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.8
154 15190000,-0.29,0.016,-0.005,0.96,-0.021,-0.00079,0.029,-0.0034,-0.0024,0.02,-0.00073,-0.0057,-0.00011,0.067,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7e-05,6.8e-05,0.051,0.027,0.028,0.0064,0.045,0.045,0.035,3.1e-06,2.8e-06,2.2e-06,0.0032,0.0035,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.8
155 15290000,-0.29,0.016,-0.005,0.96,-0.024,-0.00091,0.029,-0.0058,-0.0029,0.017,-0.00075,-0.0057,-0.00011,0.067,0.014,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7e-05,6.9e-05,0.051,0.03,0.03,0.0065,0.05,0.05,0.035,3e-06,2.7e-06,2.2e-06,0.0032,0.0035,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,3.9
156 15390000,-0.29,0.016,-0.0051,0.96,-0.023,-0.0028,0.028,-0.0046,-0.0024,0.017,-0.00075,-0.0057,-0.00011,0.068,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.8e-05,6.7e-05,0.051,0.026,0.026,0.0064,0.044,0.044,0.034,2.9e-06,2.7e-06,2.2e-06,0.0031,0.0033,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,3.9 15390000,-0.29,0.016,-0.0051,0.96,-0.023,-0.0028,0.028,-0.0046,-0.0024,0.017,-0.00075,-0.0057,-0.00011,0.068,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.8e-05,6.7e-05,0.051,0.026,0.026,0.0064,0.044,0.044,0.034,2.9e-06,2.6e-06,2.2e-06,0.0031,0.0033,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,3.9
157 15490000,-0.29,0.016,-0.0051,0.96,-0.025,-0.00034,0.028,-0.007,-0.0026,0.018,-0.00075,-0.0057,-0.00011,0.068,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.9e-05,6.7e-05,0.051,0.028,0.028,0.0065,0.05,0.05,0.034,2.8e-06,2.6e-06,2.2e-06,0.0031,0.0033,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,3.9
158 15590000,-0.29,0.016,-0.0051,0.96,-0.022,-0.0047,0.028,-0.0032,-0.0058,0.017,-0.00079,-0.0057,-0.00011,0.068,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.7e-05,6.6e-05,0.051,0.025,0.025,0.0065,0.044,0.044,0.034,2.7e-06,2.5e-06,2.2e-06,0.003,0.0032,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,3.9
159 15690000,-0.29,0.016,-0.005,0.96,-0.024,-0.0026,0.028,-0.0048,-0.0062,0.018,-0.00083,-0.0057,-0.00011,0.067,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.8e-05,6.6e-05,0.051,0.027,0.027,0.0066,0.049,0.049,0.034,2.7e-06,2.4e-06,2.2e-06,0.0029,0.0032,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4
160 15790000,-0.29,0.015,-0.005,0.96,-0.021,-0.0013,0.028,-0.0035,-0.0053,0.019,-0.00087,-0.0058,-0.00011,0.066,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.6e-05,6.4e-05,0.051,0.024,0.024,0.0066,0.043,0.043,0.033,2.6e-06,2.3e-06,2.2e-06,0.0029,0.0031,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4
161 15890000,-0.29,0.016,-0.0051,0.96,-0.021,-0.0026,0.029,-0.0059,-0.0053,0.019,-0.00084,-0.0057,-0.00011,0.067,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.7e-05,6.5e-05,0.051,0.026,0.026,0.0067,0.049,0.049,0.034,2.5e-06,2.3e-06,2.2e-06,0.0028,0.0031,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4
162 15990000,-0.29,0.016,-0.005,0.96,-0.02,-0.0021,0.026,-0.0049,-0.0045,0.018,-0.00083,-0.0057,-0.00011,0.067,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.6e-05,6.3e-05,0.051,0.023,0.023,0.0068,0.043,0.043,0.033,2.4e-06,2.2e-06,2.2e-06,0.0028,0.003,0.00042,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4
163 16090000,-0.29,0.016,-0.005,0.96,-0.022,-0.00082,0.024,-0.0072,-0.0045,0.018,-0.00082,-0.0057,-0.00011,0.068,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.6e-05,6.4e-05,0.051,0.024,0.025,0.0069,0.048,0.048,0.033,2.4e-06,2.1e-06,2.2e-06,0.0027,0.003,0.00042,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.1 16090000,-0.29,0.016,-0.005,0.96,-0.022,-0.00083,0.024,-0.0072,-0.0045,0.018,-0.00082,-0.0057,-0.00011,0.068,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.6e-05,6.4e-05,0.051,0.024,0.025,0.0069,0.048,0.048,0.033,2.4e-06,2.1e-06,2.2e-06,0.0027,0.003,0.00042,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.1
164 16190000,-0.29,0.016,-0.005,0.96,-0.02,-0.00061,0.023,-0.0071,-0.0037,0.015,-0.0008,-0.0057,-0.00011,0.068,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.5e-05,6.3e-05,0.051,0.022,0.022,0.0069,0.043,0.043,0.033,2.3e-06,2.1e-06,2.2e-06,0.0027,0.0029,0.00042,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.1
165 16290000,-0.29,0.015,-0.005,0.96,-0.022,0.00033,0.022,-0.009,-0.0038,0.017,-0.00081,-0.0057,-0.00011,0.068,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.6e-05,6.3e-05,0.051,0.023,0.024,0.007,0.048,0.048,0.033,2.2e-06,2e-06,2.2e-06,0.0027,0.0029,0.00042,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.1
166 16390000,-0.29,0.016,-0.0049,0.96,-0.023,-0.00021,0.023,-0.007,-0.0037,0.017,-0.00083,-0.0057,-0.00011,0.069,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.4e-05,6.2e-05,0.051,0.021,0.021,0.007,0.042,0.042,0.033,2.2e-06,2e-06,2.2e-06,0.0026,0.0029,0.00041,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.1
192 18990000,-0.29,0.015,-0.0048,0.96,-0.029,0.012,0.023,-0.013,0.0056,0.028,-0.0011,-0.0058,-0.00012,0.069,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.7e-05,5.4e-05,0.051,0.015,0.015,0.0079,0.042,0.042,0.034,1.1e-06,1e-06,2.2e-06,0.0021,0.0024,0.00031,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.8
193 19090000,-0.29,0.015,-0.0048,0.96,-0.028,0.013,0.024,-0.016,0.0063,0.024,-0.0011,-0.0058,-0.00012,0.069,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.8e-05,5.4e-05,0.051,0.016,0.016,0.0079,0.045,0.046,0.035,1.1e-06,9.9e-07,2.2e-06,0.0021,0.0024,0.0003,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.8
194 19190000,-0.29,0.015,-0.0048,0.96,-0.026,0.014,0.023,-0.014,0.0062,0.023,-0.0011,-0.0058,-0.00012,0.068,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.7e-05,5.3e-05,0.05,0.014,0.015,0.0079,0.041,0.041,0.034,1.1e-06,9.6e-07,2.2e-06,0.0021,0.0024,0.0003,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.8
195 19290000,-0.29,0.015,-0.0048,0.96,-0.027,0.014,0.024,-0.017,0.0075,0.022,-0.0011,-0.0058,-0.00012,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.7e-05,5.3e-05,0.05,0.015,0.016,0.0079,0.044,0.044,0.034,1.1e-06,9.5e-07,2.2e-06,0.0021,0.0024,0.00029,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.9 19290000,-0.29,0.015,-0.0048,0.96,-0.027,0.014,0.024,-0.017,0.0074,0.022,-0.0011,-0.0058,-0.00012,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.7e-05,5.3e-05,0.05,0.015,0.016,0.0079,0.044,0.044,0.034,1.1e-06,9.5e-07,2.2e-06,0.0021,0.0024,0.00029,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.9
196 19390000,-0.29,0.015,-0.0049,0.96,-0.026,0.012,0.025,-0.015,0.0073,0.021,-0.0011,-0.0058,-0.00012,0.068,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.6e-05,5.3e-05,0.05,0.014,0.015,0.0078,0.04,0.04,0.035,1e-06,9.2e-07,2.2e-06,0.0021,0.0023,0.00029,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.9
197 19490000,-0.29,0.015,-0.005,0.96,-0.028,0.013,0.024,-0.018,0.0088,0.021,-0.0011,-0.0058,-0.00012,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.7e-05,5.3e-05,0.05,0.015,0.016,0.0078,0.043,0.044,0.035,1e-06,9.1e-07,2.2e-06,0.0021,0.0023,0.00029,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.9
198 19590000,-0.29,0.015,-0.0049,0.96,-0.025,0.014,0.026,-0.015,0.007,0.021,-0.0011,-0.0058,-0.00013,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.6e-05,5.2e-05,0.05,0.014,0.014,0.0077,0.039,0.039,0.035,9.9e-07,8.8e-07,2.2e-06,0.0021,0.0023,0.00028,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.9
219 21690000,-0.29,0.012,-0.0018,0.96,-0.0024,-0.019,-1.1,-0.014,0.0039,-0.49,-0.0011,-0.0058,-0.00011,0.07,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-0.39,5.2e-05,4.7e-05,0.05,0.017,0.018,0.0069,0.066,0.067,0.035,6.8e-07,6e-07,2.1e-06,0.0019,0.0022,0.0002,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01
220 21790000,-0.29,0.012,-0.0021,0.96,-0.0082,-0.011,-1.3,-0.015,0.01,-0.61,-0.0011,-0.0058,-0.0001,0.07,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-0.51,5.1e-05,4.7e-05,0.05,0.017,0.018,0.0069,0.069,0.069,0.034,6.6e-07,5.8e-07,2.1e-06,0.0019,0.0022,0.0002,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01
221 21890000,-0.29,0.012,-0.0025,0.96,-0.014,-0.0073,-1.4,-0.016,0.0096,-0.75,-0.0011,-0.0058,-0.0001,0.07,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-0.65,5.1e-05,4.7e-05,0.05,0.018,0.019,0.0068,0.074,0.075,0.034,6.6e-07,5.8e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01
222 21990000,-0.29,0.012,-0.0032,0.96,-0.02,0.00089,-1.4,-0.022,0.017,-0.89,-0.001,-0.0058,-8.7e-05,0.07,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-0.79,5.1e-05,4.6e-05,0.05,0.018,0.019,0.0068,0.076,0.077,0.034,6.4e-07,5.7e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 21990000,-0.29,0.012,-0.0032,0.96,-0.02,0.00088,-1.4,-0.022,0.017,-0.89,-0.001,-0.0058,-8.7e-05,0.07,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-0.79,5.1e-05,4.6e-05,0.05,0.018,0.019,0.0068,0.076,0.077,0.034,6.4e-07,5.7e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01
223 22090000,-0.29,0.013,-0.0038,0.96,-0.023,0.0041,-1.4,-0.023,0.016,-1,-0.0011,-0.0058,-8.4e-05,0.07,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-0.93,5.1e-05,4.7e-05,0.05,0.019,0.02,0.0068,0.082,0.084,0.034,6.4e-07,5.6e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01
224 22190000,-0.29,0.013,-0.0042,0.96,-0.03,0.011,-1.4,-0.027,0.024,-1.2,-0.0011,-0.0058,-7.1e-05,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-1.1,5e-05,4.6e-05,0.05,0.018,0.02,0.0067,0.085,0.086,0.034,6.2e-07,5.5e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01
225 22290000,-0.29,0.014,-0.0049,0.96,-0.038,0.015,-1.4,-0.031,0.025,-1.3,-0.0011,-0.0058,-7.1e-05,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-1.2,5.1e-05,4.6e-05,0.05,0.019,0.021,0.0067,0.091,0.093,0.034,6.2e-07,5.4e-07,2.1e-06,0.0019,0.0022,0.00018,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01
247 24490000,-0.29,0.018,-0.0065,0.96,-0.059,0.047,0.08,-0.061,0.038,-3.6,-0.0012,-0.0058,-0.00011,0.067,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.5,4.6e-05,4.2e-05,0.049,0.021,0.023,0.006,0.2,0.2,0.033,4.6e-07,4.1e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01
248 24590000,-0.29,0.018,-0.0071,0.96,-0.047,0.045,0.076,-0.042,0.033,-3.6,-0.0013,-0.0058,-0.00012,0.067,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.5,4.6e-05,4.2e-05,0.049,0.02,0.022,0.0059,0.2,0.2,0.033,4.5e-07,4e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01
249 24690000,-0.29,0.018,-0.0076,0.96,-0.045,0.044,0.075,-0.046,0.036,-3.5,-0.0013,-0.0058,-0.00012,0.067,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.4,4.6e-05,4.2e-05,0.049,0.021,0.023,0.0059,0.21,0.21,0.033,4.5e-07,4e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01
250 24790000,-0.29,0.017,-0.0077,0.96,-0.039,0.043,0.067,-0.034,0.028,-3.5,-0.0013,-0.0058,-0.00013,0.067,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.4,4.6e-05,4.2e-05,0.049,0.02,0.022,0.0059,0.21,0.21,0.032,4.4e-07,3.9e-07,2e-06,0.0019,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 24790000,-0.29,0.017,-0.0077,0.96,-0.039,0.043,0.067,-0.034,0.028,-3.5,-0.0013,-0.0058,-0.00013,0.067,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.4,4.6e-05,4.2e-05,0.049,0.02,0.022,0.0059,0.21,0.21,0.032,4.4e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01
251 24890000,-0.29,0.017,-0.0076,0.96,-0.038,0.045,0.056,-0.037,0.032,-3.5,-0.0013,-0.0058,-0.00013,0.067,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.4,4.6e-05,4.2e-05,0.049,0.021,0.023,0.0059,0.22,0.22,0.032,4.4e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01
252 24990000,-0.29,0.016,-0.0074,0.96,-0.025,0.046,0.049,-0.022,0.026,-3.5,-0.0013,-0.0058,-0.00013,0.067,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.4,4.6e-05,4.2e-05,0.048,0.021,0.022,0.0058,0.22,0.22,0.032,4.3e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01
253 25090000,-0.29,0.016,-0.0077,0.96,-0.021,0.046,0.047,-0.023,0.031,-3.5,-0.0013,-0.0058,-0.00013,0.067,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.6e-05,4.2e-05,0.048,0.021,0.023,0.0058,0.23,0.23,0.032,4.3e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01
265 26290000,-0.3,0.015,-0.0073,0.96,0.042,0.02,0.015,0.027,-0.015,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.29,0.29,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01
266 26390000,-0.3,0.015,-0.0067,0.96,0.04,0.011,0.019,0.019,-0.03,-3.5,-0.0014,-0.0058,-0.00021,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0056,0.28,0.29,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01
267 26490000,-0.3,0.015,-0.0065,0.96,0.043,0.0088,0.028,0.024,-0.029,-3.5,-0.0014,-0.0058,-0.00022,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.3,0.3,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01
268 26590000,-0.3,0.015,-0.0059,0.95,0.042,-0.0012,0.028,0.023,-0.041,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.021,0.022,0.0056,0.29,0.3,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 26590000,-0.3,0.015,-0.0059,0.95,0.042,-0.0012,0.028,0.023,-0.042,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.021,0.022,0.0056,0.29,0.3,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01
269 26690000,-0.3,0.015,-0.0058,0.95,0.044,-0.0048,0.027,0.027,-0.041,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.31,0.31,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01
270 26790000,-0.3,0.014,-0.0056,0.95,0.047,-0.011,0.026,0.025,-0.054,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.3,0.31,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01
271 26890000,-0.3,0.014,-0.005,0.96,0.053,-0.013,0.022,0.03,-0.056,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0055,0.31,0.32,0.032,3.7e-07,3.3e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01
272 26990000,-0.3,0.015,-0.0044,0.95,0.054,-0.02,0.021,0.023,-0.063,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.016,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.31,0.31,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 26990000,-0.3,0.015,-0.0044,0.95,0.054,-0.02,0.021,0.023,-0.064,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.016,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.31,0.31,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01
273 27090000,-0.3,0.015,-0.0042,0.95,0.056,-0.026,0.025,0.028,-0.066,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.022,0.023,0.0055,0.32,0.33,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01
274 27190000,-0.3,0.015,-0.0043,0.96,0.057,-0.03,0.027,0.019,-0.069,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.32,0.32,0.031,3.6e-07,3.2e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01
275 27290000,-0.3,0.016,-0.0043,0.96,0.064,-0.034,0.14,0.025,-0.072,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.022,0.023,0.0055,0.33,0.34,0.031,3.6e-07,3.2e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01
314 31190000,-0.29,0.016,-0.0028,0.96,0.043,-0.0042,0.8,0.094,-0.039,-0.74,-0.0012,-0.0058,-2.7e-05,0.067,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.64,4.4e-05,3.8e-05,0.048,0.02,0.021,0.0052,0.21,0.22,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01
315 31290000,-0.29,0.016,-0.003,0.96,0.04,-0.0027,0.8,0.097,-0.041,-0.67,-0.0012,-0.0058,-2.3e-05,0.067,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.57,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.22,0.23,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01
316 31390000,-0.29,0.015,-0.0028,0.96,0.035,0.0022,0.8,0.091,-0.037,-0.59,-0.0012,-0.0058,-2.5e-05,0.067,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.49,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.22,0.23,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.4e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01
317 31490000,-0.29,0.016,-0.0025,0.96,0.037,0.0056,0.8,0.096,-0.036,-0.52,-0.0012,-0.0058,-2.8e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.42,4.4e-05,3.8e-05,0.048,0.021,0.022,0.0052,0.23,0.24,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.4e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 31490000,-0.29,0.016,-0.0025,0.96,0.036,0.0056,0.8,0.096,-0.036,-0.52,-0.0012,-0.0058,-2.8e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.42,4.4e-05,3.8e-05,0.048,0.021,0.022,0.0052,0.23,0.24,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.4e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01
318 31590000,-0.29,0.016,-0.0023,0.96,0.037,0.0074,0.8,0.093,-0.032,-0.45,-0.0012,-0.0058,-2e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.35,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.23,0.24,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.3e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01
319 31690000,-0.29,0.016,-0.0023,0.96,0.041,0.0084,0.8,0.098,-0.032,-0.38,-0.0012,-0.0058,-1.3e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.28,4.4e-05,3.8e-05,0.048,0.021,0.022,0.0051,0.24,0.25,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.3e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01
320 31790000,-0.29,0.017,-0.0025,0.96,0.035,0.014,0.8,0.094,-0.023,-0.3,-0.0012,-0.0058,-9.9e-07,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.2,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.24,0.25,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.2e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 31790000,-0.29,0.017,-0.0025,0.96,0.035,0.014,0.8,0.094,-0.023,-0.3,-0.0012,-0.0058,-1e-06,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.2,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.24,0.25,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.2e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01
321 31890000,-0.29,0.017,-0.0022,0.96,0.033,0.015,0.8,0.099,-0.021,-0.24,-0.0012,-0.0058,1.4e-06,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.14,4.3e-05,3.7e-05,0.048,0.021,0.022,0.0051,0.25,0.26,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.2e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01
322 31990000,-0.29,0.016,-0.0025,0.96,0.03,0.017,0.79,0.096,-0.016,-0.17,-0.0012,-0.0058,5.2e-07,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.068,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.25,0.26,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.2e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01
323 32090000,-0.29,0.016,-0.0029,0.96,0.031,0.021,0.8,0.099,-0.014,-0.096,-0.0012,-0.0058,9.3e-08,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.0038,4.3e-05,3.7e-05,0.048,0.021,0.023,0.0051,0.26,0.27,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 32090000,-0.29,0.016,-0.0029,0.96,0.031,0.021,0.8,0.099,-0.014,-0.096,-0.0012,-0.0058,8.8e-08,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.0038,4.3e-05,3.7e-05,0.048,0.021,0.023,0.0051,0.26,0.27,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01
324 32190000,-0.29,0.016,-0.0032,0.96,0.028,0.028,0.8,0.094,-0.0046,-0.028,-0.0012,-0.0058,3.2e-06,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.072,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.26,0.27,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01
325 32290000,-0.29,0.016,-0.003,0.96,0.027,0.03,0.79,0.098,-0.0019,0.042,-0.0012,-0.0058,7e-06,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.14,4.3e-05,3.7e-05,0.048,0.021,0.023,0.0051,0.27,0.28,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01
326 32390000,-0.29,0.016,-0.0032,0.96,0.024,0.032,0.79,0.094,0.0018,0.12,-0.0012,-0.0058,5.2e-06,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.22,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.27,0.28,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01
327 32490000,-0.29,0.015,-0.0063,0.96,-0.016,0.085,-0.078,0.092,0.0094,0.12,-0.0012,-0.0058,2.9e-06,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.22,4.3e-05,3.7e-05,0.048,0.022,0.024,0.0051,0.28,0.29,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01
328 32590000,-0.29,0.015,-0.0063,0.96,-0.014,0.084,-0.081,0.093,0.0025,0.1,-0.0012,-0.0058,-2e-06,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.2,4.2e-05,3.7e-05,0.047,0.021,0.023,0.0051,0.28,0.29,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01
329 32690000,-0.29,0.015,-0.0063,0.96,-0.0097,0.091,-0.082,0.091,0.011,0.087,-0.0012,-0.0058,-2e-06,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.19,4.3e-05,3.7e-05,0.047,0.022,0.024,0.0051,0.29,0.3,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01
330 32790000,-0.29,0.015,-0.0061,0.96,-0.0057,0.09,-0.083,0.093,0.0037,0.072,-0.0012,-0.0058,-7.5e-06,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.17,4.2e-05,3.7e-05,0.047,0.021,0.023,0.0051,0.29,0.3,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 32790000,-0.29,0.015,-0.0061,0.96,-0.0057,0.09,-0.083,0.093,0.0037,0.072,-0.0012,-0.0058,-7.5e-06,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.17,4.2e-05,3.7e-05,0.047,0.021,0.023,0.0051,0.29,0.3,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01
331 32890000,-0.29,0.015,-0.0061,0.96,-0.0062,0.096,-0.085,0.092,0.012,0.057,-0.0012,-0.0058,-3e-06,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.16,4.2e-05,3.7e-05,0.047,0.022,0.023,0.0051,0.3,0.31,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 32890000,-0.29,0.015,-0.0061,0.96,-0.0062,0.096,-0.085,0.092,0.012,0.057,-0.0012,-0.0058,-3e-06,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.16,4.2e-05,3.7e-05,0.047,0.022,0.023,0.0051,0.3,0.31,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01
332 32990000,-0.29,0.015,-0.006,0.96,-0.0023,0.091,-0.084,0.092,-0.00052,0.043,-0.0013,-0.0058,-1.1e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.14,4.2e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.3,0.31,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 32990000,-0.29,0.015,-0.006,0.96,-0.0023,0.091,-0.084,0.092,-0.00052,0.043,-0.0013,-0.0058,-1.1e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.14,4.2e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.3,0.31,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01
333 33090000,-0.29,0.015,-0.0059,0.96,0.0014,0.097,-0.081,0.092,0.0087,0.036,-0.0013,-0.0058,-1e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.14,4.2e-05,3.7e-05,0.047,0.022,0.023,0.0051,0.31,0.32,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 33090000,-0.29,0.015,-0.0059,0.96,0.0014,0.097,-0.081,0.092,0.0087,0.036,-0.0013,-0.0058,-1e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.14,4.2e-05,3.7e-05,0.047,0.022,0.023,0.0051,0.31,0.32,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01
334 33190000,-0.29,0.015,-0.0059,0.96,0.0056,0.093,-0.08,0.093,-0.0059,0.028,-0.0013,-0.0058,-2.9e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.13,4.1e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.31,0.31,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01
335 33290000,-0.29,0.015,-0.0059,0.96,0.0098,0.096,-0.08,0.094,0.0029,0.02,-0.0013,-0.0058,-1.8e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.2e-05,3.7e-05,0.047,0.021,0.023,0.0051,0.32,0.33,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 33290000,-0.29,0.015,-0.0059,0.96,0.0098,0.096,-0.08,0.094,0.0029,0.02,-0.0013,-0.0058,-1.8e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.2e-05,3.7e-05,0.047,0.021,0.023,0.0051,0.32,0.33,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01
336 33390000,-0.3,0.015,-0.0058,0.96,0.014,0.093,-0.078,0.094,-0.0054,0.01,-0.0013,-0.0058,-2.6e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.32,0.32,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.033 33390000,-0.3,0.015,-0.0058,0.96,0.014,0.093,-0.078,0.094,-0.0054,0.01,-0.0013,-0.0058,-2.6e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.32,0.32,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.033
337 33490000,-0.3,0.015,-0.0058,0.96,0.02,0.097,-0.078,0.097,0.004,-0.00072,-0.0013,-0.0058,-2.1e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.33,0.34,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.058
338 33590000,-0.3,0.015,-0.0056,0.95,0.023,0.094,-0.075,0.096,-0.0089,-0.01,-0.0013,-0.0058,-2.7e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.33,0.33,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.083 33590000,-0.3,0.015,-0.0056,0.95,0.023,0.094,-0.075,0.096,-0.0089,-0.01,-0.0013,-0.0058,-2.7e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.33,0.33,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.083
339 33690000,-0.3,0.015,-0.0056,0.95,0.026,0.098,-0.076,0.097,8.9e-05,-0.019,-0.0013,-0.0058,-2.2e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.34,0.35,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.11 33690000,-0.3,0.015,-0.0056,0.95,0.026,0.098,-0.076,0.097,8.7e-05,-0.019,-0.0013,-0.0058,-2.2e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.34,0.35,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.11
340 33790000,-0.3,0.015,-0.0056,0.95,0.028,0.096,-0.071,0.094,-0.013,-0.028,-0.0013,-0.0058,-3.5e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.34,0.34,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.13
341 33890000,-0.3,0.015,-0.0055,0.95,0.033,0.097,-0.071,0.097,-0.004,-0.037,-0.0013,-0.0058,-2.5e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.35,0.36,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.16 33890000,-0.3,0.015,-0.0055,0.95,0.033,0.097,-0.071,0.097,-0.004,-0.037,-0.0013,-0.0058,-2.5e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.35,0.36,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.16
342 33990000,-0.3,0.015,-0.0054,0.95,0.035,0.096,-0.068,0.096,-0.012,-0.042,-0.0013,-0.0058,-3.6e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.35,0.35,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.18 33990000,-0.3,0.015,-0.0054,0.95,0.035,0.096,-0.068,0.096,-0.012,-0.042,-0.0013,-0.0058,-3.6e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.35,0.35,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.18
343 34090000,-0.3,0.015,-0.0054,0.95,0.038,0.1,-0.067,0.099,-0.0027,-0.046,-0.0013,-0.0057,-3.2e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.36,0.37,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.21 34090000,-0.3,0.015,-0.0054,0.95,0.038,0.1,-0.067,0.099,-0.0027,-0.046,-0.0013,-0.0057,-3.2e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.36,0.37,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.21
344 34190000,-0.3,0.015,-0.0054,0.95,0.039,0.097,-0.064,0.094,-0.014,-0.05,-0.0013,-0.0057,-3.8e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.36,0.36,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.23 34190000,-0.3,0.015,-0.0054,0.95,0.039,0.097,-0.064,0.094,-0.014,-0.05,-0.0013,-0.0057,-3.7e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.36,0.36,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.23
345 34290000,-0.3,0.015,-0.0052,0.95,0.041,0.1,-0.062,0.098,-0.0047,-0.055,-0.0013,-0.0057,-3e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.005,0.37,0.37,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.26 34290000,-0.3,0.015,-0.0052,0.95,0.041,0.1,-0.062,0.098,-0.0047,-0.055,-0.0013,-0.0057,-3e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.005,0.37,0.37,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.26
346 34390000,-0.3,0.015,-0.0051,0.95,0.042,0.097,-0.057,0.093,-0.016,-0.059,-0.0013,-0.0057,-3.9e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.37,0.37,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.28 34390000,-0.3,0.015,-0.0051,0.95,0.042,0.097,-0.057,0.093,-0.016,-0.059,-0.0013,-0.0057,-3.9e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.37,0.37,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.28
347 34490000,-0.3,0.015,-0.0051,0.95,0.045,0.1,-0.055,0.097,-0.0068,-0.061,-0.0013,-0.0057,-3e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.085,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.31
348 34590000,-0.3,0.014,-0.005,0.95,0.045,0.098,0.74,0.092,-0.021,-0.033,-0.0013,-0.0057,-4.1e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.33 34590000,-0.3,0.014,-0.005,0.95,0.045,0.098,0.74,0.092,-0.021,-0.033,-0.0013,-0.0057,-4e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.33
349 34690000,-0.3,0.014,-0.0051,0.95,0.05,0.1,1.7,0.097,-0.011,0.087,-0.0013,-0.0057,-3.7e-05,0.066,0.016,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.39,0.39,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.36 34690000,-0.3,0.014,-0.0051,0.95,0.05,0.1,1.7,0.097,-0.011,0.087,-0.0013,-0.0057,-3.7e-05,0.066,0.016,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.39,0.39,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.36
350 34790000,-0.3,0.014,-0.005,0.95,0.051,0.099,2.7,0.091,-0.025,0.27,-0.0013,-0.0057,-4.7e-05,0.066,0.016,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.019,0.019,0.005,0.39,0.39,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.38
351 34890000,-0.3,0.014,-0.005,0.95,0.056,0.1,3.7,0.096,-0.015,0.56,-0.0013,-0.0057,-4.3e-05,0.066,0.016,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.019,0.019,0.005,0.4,0.4,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.3e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.41
@@ -242,16 +242,12 @@ bool EkfWrapper::isWindVelocityEstimated() const
bool EkfWrapper::isIntendingTerrainRngFusion() const
{
terrain_fusion_status_u terrain_status;
terrain_status.value = _ekf->getTerrainEstimateSensorBitfield();
return terrain_status.flags.range_finder;
return _ekf->control_status_flags().rng_terrain;
}
bool EkfWrapper::isIntendingTerrainFlowFusion() const
{
terrain_fusion_status_u terrain_status;
terrain_status.value = _ekf->getTerrainEstimateSensorBitfield();
return terrain_status.flags.flow;
return _ekf->control_status_flags().opt_flow_terrain;
}
Eulerf EkfWrapper::getEulerAngles() const
@@ -632,29 +632,27 @@ bool FlightTaskAuto::_evaluateGlobalReference()
State FlightTaskAuto::_getCurrentState()
{
// Calculate the vehicle current state based on the Navigator triplets and the current position.
const Vector2f u_prev_to_target_xy = Vector2f(_triplet_target - _triplet_prev_wp).unit_or_zero();
const Vector2f pos_to_target_xy = Vector2f(_triplet_target - _position);
const Vector2f prev_to_pos_xy = Vector2f(_position - _triplet_prev_wp);
const Vector3f u_prev_to_target = (_triplet_target - _triplet_prev_wp).unit_or_zero();
const Vector3f prev_to_pos = _position - _triplet_prev_wp;
const Vector3f pos_to_target = _triplet_target - _position;
// Calculate the closest point to the vehicle position on the line prev_wp - target
const Vector2f closest_pt_xy = Vector2f(_triplet_prev_wp) + u_prev_to_target_xy * (prev_to_pos_xy *
u_prev_to_target_xy);
_closest_pt = Vector3f(closest_pt_xy(0), closest_pt_xy(1), _triplet_target(2));
_closest_pt = _triplet_prev_wp + u_prev_to_target * (prev_to_pos * u_prev_to_target);
State return_state = State::none;
if (u_prev_to_target_xy.length() < FLT_EPSILON) {
if (!u_prev_to_target.longerThan(FLT_EPSILON)) {
// Previous and target are the same point, so we better don't try to do any special line following
return_state = State::none;
} else if (u_prev_to_target_xy * pos_to_target_xy < 0.0f) {
} else if (u_prev_to_target * pos_to_target < 0.0f) {
// Target is behind
return_state = State::target_behind;
} else if (u_prev_to_target_xy * prev_to_pos_xy < 0.0f && prev_to_pos_xy.longerThan(_target_acceptance_radius)) {
} else if (u_prev_to_target * prev_to_pos < 0.0f && prev_to_pos.longerThan(_target_acceptance_radius)) {
// Previous is in front
return_state = State::previous_infront;
} else if (Vector2f(_position - _closest_pt).longerThan(_target_acceptance_radius)) {
} else if ((_position - _closest_pt).longerThan(_target_acceptance_radius)) {
// Vehicle too far from the track
return_state = State::offtrack;
@@ -990,7 +990,6 @@ private:
(ParamFloat<px4::params::FW_FLAPS_LND_SCL>) _param_fw_flaps_lnd_scl,
(ParamFloat<px4::params::FW_FLAPS_TO_SCL>) _param_fw_flaps_to_scl,
(ParamFloat<px4::params::FW_SPOILERS_LND>) _param_fw_spoilers_lnd,
(ParamFloat<px4::params::FW_SPOILERS_DESC>) _param_fw_spoilers_desc,
(ParamInt<px4::params::FW_POS_STK_CONF>) _param_fw_pos_stk_conf,
@@ -193,9 +193,9 @@ PARAM_DEFINE_FLOAT(NPFG_PERIOD_SF, 1.5f);
PARAM_DEFINE_FLOAT(FW_THR_SLEW_MAX, 0.0f);
/**
* Minimum pitch angle
* Minimum pitch angle setpoint
*
* The minimum pitch angle setpoint for a height-rate or altitude controlled mode.
* Applies in any altitude controlled flight mode.
*
* @unit deg
* @min -60.0
@@ -207,9 +207,9 @@ PARAM_DEFINE_FLOAT(FW_THR_SLEW_MAX, 0.0f);
PARAM_DEFINE_FLOAT(FW_P_LIM_MIN, -30.0f);
/**
* Maximum pitch angle
* Maximum pitch angle setpoint
*
* The maximum pitch angle setpoint setpoint for a height-rate or altitude controlled mode.
* Applies in any altitude controlled flight mode.
*
* @unit deg
* @min 0.0
@@ -221,9 +221,9 @@ PARAM_DEFINE_FLOAT(FW_P_LIM_MIN, -30.0f);
PARAM_DEFINE_FLOAT(FW_P_LIM_MAX, 30.0f);
/**
* Maximum roll angle
* Maximum roll angle setpoint
*
* The maximum roll angle setpoint for setpoint for a height-rate or altitude controlled mode.
* Applies in any altitude controlled flight mode.
*
* @unit deg
* @min 35.0
@@ -237,7 +237,7 @@ PARAM_DEFINE_FLOAT(FW_R_LIM, 50.0f);
/**
* Throttle limit max
*
* Maximum throttle limit in altitude controlled modes.
* Applies in any altitude controlled flight mode.
* Should be set accordingly to achieve FW_T_CLMB_MAX.
*
* @unit norm
@@ -252,13 +252,10 @@ PARAM_DEFINE_FLOAT(FW_THR_MAX, 1.0f);
/**
* Throttle limit min
*
* Minimum throttle limit in altitude controlled modes.
* Applies in any altitude controlled flight mode.
* Usually set to 0 but can be increased to prevent the motor from stopping when
* descending, which can increase achievable descent rates.
*
* For aircraft with internal combustion engine this parameter should be set
* for desired idle rpm.
*
* @unit norm
* @min 0.0
* @max 1.0
@@ -271,13 +268,7 @@ PARAM_DEFINE_FLOAT(FW_THR_MIN, 0.0f);
/**
* Idle throttle
*
* This is the minimum throttle while on the ground
*
* For aircraft with internal combustion engines, this parameter should be set
* above the desired idle rpm. For electric motors, idle should typically be set
* to zero.
*
* Note that in automatic modes, "landed" conditions will engage idle throttle.
* This is the minimum throttle while on the ground ("landed") in auto modes.
*
* @unit norm
* @min 0.0
@@ -318,9 +309,9 @@ PARAM_DEFINE_FLOAT(FW_TKO_PITCH_MIN, 10.0f);
/**
* Takeoff Airspeed
*
* The calibrated airspeed setpoint TECS will stabilize to during the takeoff climbout.
* The calibrated airspeed setpoint during the takeoff climbout.
*
* If set <= 0.0, FW_AIRSPD_MIN will be set by default.
* If set <= 0, FW_AIRSPD_MIN will be set by default.
*
* @unit m/s
* @min -1.0
@@ -344,7 +335,9 @@ PARAM_DEFINE_FLOAT(FW_TKO_AIRSPD, -1.0f);
PARAM_DEFINE_FLOAT(FW_LND_FLALT, 0.5f);
/**
* Use terrain estimation during landing. This is critical for detecting when to flare, and should be enabled if possible.
* Use terrain estimation during landing.
*
* This is critical for detecting when to flare, and should be enabled if possible.
*
* NOTE: terrain estimate is currently solely derived from a distance sensor.
*
@@ -365,9 +358,9 @@ PARAM_DEFINE_INT32(FW_LND_USETER, 1);
/**
* Early landing configuration deployment
*
* When disabled, the landing configuration (flaps, landing airspeed, etc.) is only activated
* on the final approach to landing. When enabled, it is already activated when entering the
* final loiter-down (loiter-to-alt) waypoint before the landing approach.
* Allows to deploy the landing configuration (flaps, landing airspeed, etc.) already in
* the loiter-down waypoint before the final approach.
* Otherwise is enabled only in the final approach.
*
* @boolean
*
@@ -378,8 +371,7 @@ PARAM_DEFINE_INT32(FW_LND_EARLYCFG, 0);
/**
* Flare, minimum pitch
*
* Minimum pitch during flare, a positive sign means nose up
* Applied once flaring is triggered
* Minimum pitch during landing flare.
*
* @unit deg
* @min -5
@@ -393,8 +385,7 @@ PARAM_DEFINE_FLOAT(FW_LND_FL_PMIN, 2.5f);
/**
* Flare, maximum pitch
*
* Maximum pitch during flare, a positive sign means nose up
* Applied once flaring is triggered
* Maximum pitch during landing flare.
*
* @unit deg
* @min 0
@@ -410,7 +401,7 @@ PARAM_DEFINE_FLOAT(FW_LND_FL_PMAX, 15.0f);
*
* The calibrated airspeed setpoint during landing.
*
* If set <= 0.0, landing airspeed = FW_AIRSPD_MIN by default.
* If set <= 0, landing airspeed = FW_AIRSPD_MIN by default.
*
* @unit m/s
* @min -1.0
@@ -423,9 +414,8 @@ PARAM_DEFINE_FLOAT(FW_LND_AIRSPD, -1.f);
/**
* Altitude time constant factor for landing
*
* Set this parameter to less than 1.0 to make TECS react faster to altitude errors during
* landing than during normal flight. During landing, the TECS
* altitude time constant (FW_T_ALT_TC) is multiplied by this value.
* During landing, the TECS altitude time constant (FW_T_ALT_TC)
* is multiplied by this value.
*
* @unit
* @min 0.2
@@ -445,10 +435,6 @@ PARAM_DEFINE_FLOAT(FW_LND_THRTC_SC, 1.0f);
* Maximum descent rate
*
* This sets the maximum descent rate that the controller will use.
* If this value is too large, the aircraft can over-speed on descent.
* This should be set to a value that can be achieved without
* exceeding the lower pitch angle limit and without over-speeding
* the aircraft.
*
* @unit m/s
* @min 1.0
@@ -463,7 +449,6 @@ PARAM_DEFINE_FLOAT(FW_T_SINK_MAX, 5.0f);
* Throttle damping factor
*
* This is the damping gain for the throttle demand loop.
* Increase to add damping to correct for oscillations in speed and height.
*
* @min 0.0
* @max 1.0
@@ -476,7 +461,6 @@ PARAM_DEFINE_FLOAT(FW_T_THR_DAMPING, 0.05f);
/**
* Integrator gain throttle
*
* Integrator gain on the throttle part of the control loop.
* Increase it to trim out speed and height offsets faster,
* with the downside of possible overshoots and oscillations.
*
@@ -491,7 +475,6 @@ PARAM_DEFINE_FLOAT(FW_T_THR_INTEG, 0.02f);
/**
* Integrator gain pitch
*
* Integrator gain on the pitch part of the control loop.
* Increase it to trim out speed and height offsets faster,
* with the downside of possible overshoots and oscillations.
*
@@ -506,11 +489,9 @@ PARAM_DEFINE_FLOAT(FW_T_I_GAIN_PIT, 0.1f);
/**
* Maximum vertical acceleration
*
* This is the maximum vertical acceleration (in m/s/s)
* This is the maximum vertical acceleration
* either up or down that the controller will use to correct speed
* or height errors. The default value of 7 m/s/s (equivalent to +- 0.7 g)
* allows for reasonably aggressive pitch changes if required to recover
* from under-speed conditions.
* or height errors.
*
* @unit m/s^2
* @min 1.0
@@ -522,9 +503,9 @@ PARAM_DEFINE_FLOAT(FW_T_I_GAIN_PIT, 0.1f);
PARAM_DEFINE_FLOAT(FW_T_VERT_ACC, 7.0f);
/**
* Airspeed measurement standard deviation for airspeed filter.
* Airspeed measurement standard deviation
*
* This is the measurement standard deviation for the airspeed used in the airspeed filter in TECS.
* For the airspeed filter in TECS.
*
* @unit m/s
* @min 0.01
@@ -536,9 +517,9 @@ PARAM_DEFINE_FLOAT(FW_T_VERT_ACC, 7.0f);
PARAM_DEFINE_FLOAT(FW_T_SPD_STD, 0.2f);
/**
* Airspeed rate measurement standard deviation for airspeed filter.
* Airspeed rate measurement standard deviation
*
* This is the measurement standard deviation for the airspeed rate used in the airspeed filter in TECS.
* For the airspeed filter in TECS.
*
* @unit m/s^2
* @min 0.01
@@ -550,12 +531,10 @@ PARAM_DEFINE_FLOAT(FW_T_SPD_STD, 0.2f);
PARAM_DEFINE_FLOAT(FW_T_SPD_DEV_STD, 0.2f);
/**
* Process noise standard deviation for the airspeed rate in the airspeed filter.
* Process noise standard deviation for the airspeed rate
*
* This is the process noise standard deviation in the airspeed filter filter defining the noise in the
* airspeed rate for the constant airspeed rate model. This is used to define how much the airspeed and
* the airspeed rate are filtered. The smaller the value the more the measurements are smoothed with the
* drawback for delays.
* This is defining the noise in the airspeed rate for the constant airspeed rate model
* of the TECS airspeed filter.
*
* @unit m/s^2
* @min 0.01
@@ -570,14 +549,9 @@ PARAM_DEFINE_FLOAT(FW_T_SPD_PRC_STD, 0.2f);
/**
* Roll -> Throttle feedforward
*
* Increasing this gain turn increases the amount of throttle that will
* be used to compensate for the additional drag created by turning.
* Ideally this should be set to approximately 10 x the extra sink rate
* in m/s created by a 45 degree bank turn. Increase this gain if
* the aircraft initially loses energy in turns and reduce if the
* aircraft initially gains energy in turns. Efficient high aspect-ratio
* aircraft (eg powered sailplanes) can use a lower value, whereas
* inefficient low aspect-ratio models (eg delta wings) can use a higher value.
* Is used to compensate for the additional drag created by turning.
* Increase this gain if the aircraft initially loses energy in turns
* and reduce if the aircraft initially gains energy in turns.
*
* @min 0.0
* @max 20.0
@@ -590,13 +564,11 @@ PARAM_DEFINE_FLOAT(FW_T_RLL2THR, 15.0f);
/**
* Speed <--> Altitude priority
*
* This parameter adjusts the amount of weighting that the pitch control
* Adjusts the amount of weighting that the pitch control
* applies to speed vs height errors. Setting it to 0.0 will cause the
* pitch control to control height and ignore speed errors. This will
* normally improve height accuracy but give larger airspeed errors.
* pitch control to control height and ignore speed errors.
* Setting it to 2.0 will cause the pitch control loop to control speed
* and ignore height errors. This will normally reduce airspeed errors,
* but give larger height errors. The default value of 1.0 allows the pitch
* and ignore height errors. The default value of 1.0 allows the pitch
* control to simultaneously control height and speed.
* Set to 2 for gliders.
*
@@ -609,12 +581,7 @@ PARAM_DEFINE_FLOAT(FW_T_RLL2THR, 15.0f);
PARAM_DEFINE_FLOAT(FW_T_SPDWEIGHT, 1.0f);
/**
* Pitch damping factor
*
* This is the damping gain for the pitch demand loop. Increase to add
* damping to correct for oscillations in height. The default value of 0.0
* will work well provided the pitch to servo controller has been tuned
* properly.
* Pitch damping gain
*
* @min 0.0
* @max 2.0
@@ -635,7 +602,10 @@ PARAM_DEFINE_FLOAT(FW_T_PTCH_DAMP, 0.1f);
PARAM_DEFINE_FLOAT(FW_T_ALT_TC, 5.0f);
/**
* Minimum altitude error needed to descend with max airspeed. A negative value disables fast descend.
* Fast descend: minimum altitude error
*
* Minimum altitude error needed to descend with max airspeed and minimal throttle.
* A negative value disables fast descend.
*
* @min -1.0
* @decimal 0
@@ -680,9 +650,9 @@ PARAM_DEFINE_FLOAT(FW_T_TAS_TC, 5.0f);
PARAM_DEFINE_FLOAT(FW_GND_SPD_MIN, 5.0f);
/**
* RC stick configuration fixed-wing.
* Custom stick configuration
*
* Set RC/joystick configuration for fixed-wing manual position and altitude controlled flight.
* Applies in manual Position and Altitude flight modes.
*
* @min 0
* @max 3
@@ -720,9 +690,8 @@ PARAM_DEFINE_FLOAT(FW_T_SEB_R_FF, 1.0f);
/**
* Default target climbrate.
*
* The default rate at which the vehicle will climb in autonomous modes to achieve altitude setpoints.
* In manual modes this defines the maximum rate at which the altitude setpoint can be increased.
*
* In auto modes: default climb rate output by controller to achieve altitude setpoints.
* In manual modes: maximum climb rate setpoint.
*
* @unit m/s
* @min 0.5
@@ -736,9 +705,8 @@ PARAM_DEFINE_FLOAT(FW_T_CLMB_R_SP, 3.0f);
/**
* Default target sinkrate.
*
*
* The default rate at which the vehicle will sink in autonomous modes to achieve altitude setpoints.
* In manual modes this defines the maximum rate at which the altitude setpoint can be decreased.
* In auto modes: default sink rate output by controller to achieve altitude setpoints.
* In manual modes: maximum sink rate setpoint.
*
* @unit m/s
* @min 0.5
@@ -752,7 +720,7 @@ PARAM_DEFINE_FLOAT(FW_T_SINK_R_SP, 2.0f);
/**
* GPS failure loiter time
*
* The time in seconds the system should do open loop loiter and wait for GPS recovery
* The time the system should do open loop loiter and wait for GPS recovery
* before it starts descending. Set to 0 to disable. Roll angle is set to FW_GPSF_R.
* Does only apply for fixed-wing vehicles or VTOLs with NAV_FORCE_VT set to 0.
*
@@ -766,7 +734,7 @@ PARAM_DEFINE_INT32(FW_GPSF_LT, 30);
/**
* GPS failure fixed roll angle
*
* Roll in degrees during the loiter after the vehicle has lost GPS in an auto mode (e.g. mission or loiter).
* Roll angle in GPS failure loiter mode.
*
* @unit deg
* @min 0.0
@@ -875,7 +843,7 @@ PARAM_DEFINE_FLOAT(FW_LND_TD_OFF, 3.0);
* Approach path nudging: shifts the touchdown point laterally along with the entire approach path
*
* This is useful for manually adjusting the landing point in real time when map or GNSS errors cause an offset from the
* desired landing vector. Nuding is done with yaw stick, constrained to FW_LND_TD_OFF (in meters) and the direction is
* desired landing vector. Nudging is done with yaw stick, constrained to FW_LND_TD_OFF (in meters) and the direction is
* relative to the vehicle heading (stick deflection to the right = land point moves to the right as seen by the vehicle).
*
* @min 0
@@ -914,7 +882,6 @@ PARAM_DEFINE_INT32(FW_LND_ABORT, 3);
* Multiplying this factor with the current absolute wind estimate gives the airspeed offset
* added to the minimum airspeed setpoint limit. This helps to make the
* system more robust against disturbances (turbulence) in high wind.
* Only applies to AUTO flight mode.
*
* @min 0
* @decimal 2
@@ -975,15 +942,3 @@ PARAM_DEFINE_FLOAT(FW_FLAPS_LND_SCL, 1.0f);
* @group FW Attitude Control
*/
PARAM_DEFINE_FLOAT(FW_SPOILERS_LND, 0.f);
/**
* Spoiler descend setting
*
* @unit norm
* @min 0.0
* @max 1.0
* @decimal 2
* @increment 0.01
* @group FW Attitude Control
*/
PARAM_DEFINE_FLOAT(FW_SPOILERS_DESC, 0.f);
+2 -1
View File
@@ -103,7 +103,8 @@ void LoggedTopics::add_default_topics()
add_topic("position_setpoint_triplet", 200);
add_optional_topic("px4io_status");
add_topic("radio_status");
add_topic("rover_ackermann_guidance_status", 100);
add_optional_topic("rover_ackermann_guidance_status", 100);
add_optional_topic("rover_ackermann_status", 100);
add_topic("rtl_time_estimate", 1000);
add_topic("rtl_status", 2000);
add_optional_topic("sensor_airflow", 100);
@@ -42,6 +42,7 @@ px4_add_module(
DEPENDS
RoverAckermannGuidance
px4_work_queue
SlewRate
MODULE_CONFIG
module.yaml
)
+96 -30
View File
@@ -40,6 +40,7 @@ RoverAckermann::RoverAckermann() :
ModuleParams(nullptr),
ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::rate_ctrl)
{
_rover_ackermann_status_pub.advertise();
updateParams();
}
@@ -52,6 +53,16 @@ bool RoverAckermann::init()
void RoverAckermann::updateParams()
{
ModuleParams::updateParams();
// Update slew rates
if (_param_ra_max_accel.get() > FLT_EPSILON && _param_ra_max_speed.get() > FLT_EPSILON) {
_throttle_with_accel_limit.setSlewRate(_param_ra_max_accel.get() / _param_ra_max_speed.get());
}
if (_param_ra_max_steering_rate.get() > FLT_EPSILON && _param_ra_max_steer_angle.get() > FLT_EPSILON) {
_steering_with_rate_limit.setSlewRate((M_DEG_TO_RAD_F * _param_ra_max_steering_rate.get()) /
_param_ra_max_steer_angle.get());
}
}
void RoverAckermann::Run()
@@ -59,6 +70,7 @@ void RoverAckermann::Run()
if (should_exit()) {
ScheduleClear();
exit_and_cleanup();
return;
}
// uORB subscriber updates
@@ -70,44 +82,98 @@ void RoverAckermann::Run()
vehicle_status_s vehicle_status;
_vehicle_status_sub.copy(&vehicle_status);
_nav_state = vehicle_status.nav_state;
_armed = vehicle_status.arming_state == 2;
}
// Navigation modes
switch (_nav_state) {
case vehicle_status_s::NAVIGATION_STATE_MANUAL: {
manual_control_setpoint_s manual_control_setpoint{};
if (_local_position_sub.updated()) {
vehicle_local_position_s local_position{};
_local_position_sub.copy(&local_position);
const Vector3f rover_velocity = {local_position.vx, local_position.vy, local_position.vz};
_actual_speed = rover_velocity.norm();
}
if (_manual_control_setpoint_sub.update(&manual_control_setpoint)) {
_motor_setpoint.steering = manual_control_setpoint.roll;
_motor_setpoint.throttle = manual_control_setpoint.throttle;
}
// Timestamps
hrt_abstime timestamp_prev = _timestamp;
_timestamp = hrt_absolute_time();
const float dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 5000_ms) * 1e-6f;
} break;
if (_armed) {
// Navigation modes
switch (_nav_state) {
case vehicle_status_s::NAVIGATION_STATE_MANUAL: {
manual_control_setpoint_s manual_control_setpoint{};
case vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION:
_motor_setpoint = _ackermann_guidance.purePursuit();
break;
if (_manual_control_setpoint_sub.update(&manual_control_setpoint)) {
_motor_setpoint.steering = manual_control_setpoint.roll;
_motor_setpoint.throttle = manual_control_setpoint.throttle;
}
default: // Unimplemented nav states will stop the rover
} break;
case vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION:
case vehicle_status_s::NAVIGATION_STATE_AUTO_RTL:
_motor_setpoint = _ackermann_guidance.purePursuit(_nav_state);
break;
default: // Unimplemented nav states will stop the rover
_motor_setpoint.steering = 0.f;
_motor_setpoint.throttle = 0.f;
break;
}
// Sanitize actuator commands
if (!PX4_ISFINITE(_motor_setpoint.steering)) {
_motor_setpoint.steering = 0.f;
}
if (!PX4_ISFINITE(_motor_setpoint.throttle)) {
_motor_setpoint.throttle = 0.f;
}
// Acceleration slew rate
if (_param_ra_max_accel.get() > FLT_EPSILON && _param_ra_max_speed.get() > FLT_EPSILON
&& fabsf(_motor_setpoint.throttle) > fabsf(_throttle_with_accel_limit.getState())) {
_throttle_with_accel_limit.update(_motor_setpoint.throttle, dt);
} else {
_throttle_with_accel_limit.setForcedValue(_motor_setpoint.throttle);
}
// Steering slew rate
if (_param_ra_max_steering_rate.get() > FLT_EPSILON && _param_ra_max_steer_angle.get() > FLT_EPSILON) {
_steering_with_rate_limit.update(_motor_setpoint.steering, dt);
} else {
_steering_with_rate_limit.setForcedValue(_motor_setpoint.steering);
}
// Publish rover ackermann status (logging)
rover_ackermann_status_s rover_ackermann_status{};
rover_ackermann_status.timestamp = _timestamp;
rover_ackermann_status.throttle_setpoint = _motor_setpoint.throttle;
rover_ackermann_status.steering_setpoint = _motor_setpoint.steering;
rover_ackermann_status.actual_speed = _actual_speed;
_rover_ackermann_status_pub.publish(rover_ackermann_status);
// Publish to motor
actuator_motors_s actuator_motors{};
actuator_motors.reversible_flags = _param_r_rev.get();
actuator_motors.control[0] = math::constrain(_throttle_with_accel_limit.getState(), -1.f, 1.f);
actuator_motors.timestamp = _timestamp;
_actuator_motors_pub.publish(actuator_motors);
// Publish to servo
actuator_servos_s actuator_servos{};
actuator_servos.control[0] = math::constrain(_steering_with_rate_limit.getState(), -1.f, 1.f);
actuator_servos.timestamp = _timestamp;
_actuator_servos_pub.publish(actuator_servos);
} else { // Reset on disarm
_motor_setpoint.steering = 0.f;
_motor_setpoint.throttle = 0.f;
break;
_throttle_with_accel_limit.setForcedValue(0.f);
_steering_with_rate_limit.setForcedValue(0.f);
}
hrt_abstime now = hrt_absolute_time();
// Publish to wheel motors
actuator_motors_s actuator_motors{};
actuator_motors.reversible_flags = _param_r_rev.get();
actuator_motors.control[0] = _motor_setpoint.throttle;
actuator_motors.timestamp = now;
_actuator_motors_pub.publish(actuator_motors);
// Publish to servo
actuator_servos_s actuator_servos{};
actuator_servos.control[0] = _motor_setpoint.steering;
actuator_servos.timestamp = now;
_actuator_servos_pub.publish(actuator_servos);
}
int RoverAckermann::task_spawn(int argc, char *argv[])
@@ -147,7 +213,7 @@ int RoverAckermann::print_usage(const char *reason)
PRINT_MODULE_DESCRIPTION(
R"DESCR_STR(
### Description
Rover state machine.
Rover ackermann module.
)DESCR_STR");
PRINT_MODULE_USAGE_NAME("rover_ackermann", "controller");
+16 -1
View File
@@ -39,6 +39,7 @@
#include <px4_platform_common/module.h>
#include <px4_platform_common/module_params.h>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <lib/slew_rate/SlewRate.hpp>
// uORB includes
#include <uORB/Publication.hpp>
@@ -49,6 +50,9 @@
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/actuator_motors.h>
#include <uORB/topics/actuator_servos.h>
#include <uORB/topics/rover_ackermann_status.h>
#include <uORB/topics/vehicle_local_position.h>
// Standard library includes
#include <math.h>
@@ -89,10 +93,12 @@ private:
uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)};
uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)};
uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)};
uORB::Subscription _local_position_sub{ORB_ID(vehicle_local_position)};
// uORB publications
uORB::PublicationMulti<actuator_motors_s> _actuator_motors_pub{ORB_ID(actuator_motors)};
uORB::Publication<actuator_servos_s> _actuator_servos_pub{ORB_ID(actuator_servos)};
uORB::Publication<rover_ackermann_status_s> _rover_ackermann_status_pub{ORB_ID(rover_ackermann_status)};
// Instances
RoverAckermannGuidance _ackermann_guidance{this};
@@ -100,9 +106,18 @@ private:
// Variables
int _nav_state{0};
RoverAckermannGuidance::motor_setpoint _motor_setpoint;
hrt_abstime _timestamp{0};
float _actual_speed{0.f};
SlewRate<float> _steering_with_rate_limit{0.f};
SlewRate<float> _throttle_with_accel_limit{0.f};
bool _armed{false};
// Parameters
DEFINE_PARAMETERS(
(ParamInt<px4::params::CA_R_REV>) _param_r_rev
(ParamInt<px4::params::CA_R_REV>) _param_r_rev,
(ParamFloat<px4::params::RA_MAX_STR_ANG>) _param_ra_max_steer_angle,
(ParamFloat<px4::params::RA_MAX_SPEED>) _param_ra_max_speed,
(ParamFloat<px4::params::RA_MAX_ACCEL>) _param_ra_max_accel,
(ParamFloat<px4::params::RA_MAX_STR_RATE>) _param_ra_max_steering_rate
)
};
@@ -40,6 +40,7 @@ using namespace time_literals;
RoverAckermannGuidance::RoverAckermannGuidance(ModuleParams *parent) : ModuleParams(parent)
{
_rover_ackermann_guidance_status_pub.advertise();
updateParams();
pid_init(&_pid_throttle, PID_MODE_DERIVATIV_NONE, 0.001f);
}
@@ -55,13 +56,14 @@ void RoverAckermannGuidance::updateParams()
1); // Output limit
}
RoverAckermannGuidance::motor_setpoint RoverAckermannGuidance::purePursuit()
RoverAckermannGuidance::motor_setpoint RoverAckermannGuidance::purePursuit(const int nav_state)
{
// Initializations
float desired_speed{0.f};
float desired_steering{0.f};
float vehicle_yaw{0.f};
float actual_speed{0.f};
bool mission_finished{false};
// uORB subscriber updates
if (_vehicle_global_position_sub.updated()) {
@@ -84,6 +86,12 @@ RoverAckermannGuidance::motor_setpoint RoverAckermannGuidance::purePursuit()
actual_speed = rover_velocity.norm();
}
if (_home_position_sub.updated()) {
home_position_s home_position{};
_home_position_sub.copy(&home_position);
_home_position = Vector2d(home_position.lat, home_position.lon);
}
if (_position_setpoint_triplet_sub.updated()) {
updateWaypoints();
}
@@ -98,21 +106,58 @@ RoverAckermannGuidance::motor_setpoint RoverAckermannGuidance::purePursuit()
if (_mission_result_sub.updated()) {
mission_result_s mission_result{};
_mission_result_sub.copy(&mission_result);
_mission_finished = mission_result.finished;
mission_finished = mission_result.finished;
}
if (nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_RTL
&& get_distance_to_next_waypoint(_curr_pos(0), _curr_pos(1), _next_wp(0),
_next_wp(1)) < _acceptance_radius) { // Return to launch
mission_finished = true;
}
// Guidance logic
if (!_mission_finished) {
if (!mission_finished) {
// Calculate desired speed
const float distance_to_prev_wp = get_distance_to_next_waypoint(_curr_pos(0), _curr_pos(1),
_prev_wp(0),
_prev_wp(1));
const float distance_to_curr_wp = get_distance_to_next_waypoint(_curr_pos(0), _curr_pos(1),
_curr_wp(0),
_curr_wp(1));
if (distance_to_prev_wp <= _prev_acc_rad) { // Cornering speed
const float cornering_speed = _param_ra_miss_vel_gain.get() / _prev_acc_rad;
desired_speed = math::constrain(cornering_speed, _param_ra_miss_vel_min.get(), _param_ra_miss_vel_def.get());
if (_param_ra_miss_vel_min.get() > 0.f && _param_ra_miss_vel_min.get() < _param_ra_miss_vel_def.get()
&& _param_ra_miss_vel_gain.get() > FLT_EPSILON) { // Cornering slow down effect
if (distance_to_prev_wp <= _prev_acceptance_radius && _prev_acceptance_radius > FLT_EPSILON) {
const float cornering_speed = _param_ra_miss_vel_gain.get() / _prev_acceptance_radius;
desired_speed = math::constrain(cornering_speed, _param_ra_miss_vel_min.get(), _param_ra_miss_vel_def.get());
} else { // Default mission speed
} else if (distance_to_curr_wp <= _acceptance_radius && _acceptance_radius > FLT_EPSILON) {
const float cornering_speed = _param_ra_miss_vel_gain.get() / _acceptance_radius;
desired_speed = math::constrain(cornering_speed, _param_ra_miss_vel_min.get(), _param_ra_miss_vel_def.get());
} else { // Straight line speed
if (_param_ra_max_accel.get() > FLT_EPSILON && _param_ra_max_jerk.get() > FLT_EPSILON
&& _acceptance_radius > FLT_EPSILON) {
float max_velocity{0.f};
if (nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_RTL) {
max_velocity = math::trajectory::computeMaxSpeedFromDistance(_param_ra_max_jerk.get(),
_param_ra_max_accel.get(), distance_to_curr_wp, 0.f);
} else {
const float cornering_speed = _param_ra_miss_vel_gain.get() / _acceptance_radius;
max_velocity = math::trajectory::computeMaxSpeedFromDistance(_param_ra_max_jerk.get(),
_param_ra_max_accel.get(), distance_to_curr_wp - _acceptance_radius, cornering_speed);
}
desired_speed = math::constrain(max_velocity, _param_ra_miss_vel_min.get(), _param_ra_miss_vel_def.get());
} else {
desired_speed = _param_ra_miss_vel_def.get();
}
}
} else {
desired_speed = _param_ra_miss_vel_def.get();
}
@@ -124,9 +169,9 @@ RoverAckermannGuidance::motor_setpoint RoverAckermannGuidance::purePursuit()
}
// Throttle PID
hrt_abstime now = hrt_absolute_time();
const float dt = math::min((now - _time_stamp_last), 5000_ms) / 1e6f;
_time_stamp_last = now;
hrt_abstime timestamp_prev = _timestamp;
_timestamp = hrt_absolute_time();
const float dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 5000_ms) * 1e-6f;
float throttle = 0.f;
if (desired_speed < FLT_EPSILON) {
@@ -144,8 +189,7 @@ RoverAckermannGuidance::motor_setpoint RoverAckermannGuidance::purePursuit()
}
// Publish ackermann controller status (logging)
_rover_ackermann_guidance_status.timestamp = now;
_rover_ackermann_guidance_status.actual_speed = actual_speed;
_rover_ackermann_guidance_status.timestamp = _timestamp;
_rover_ackermann_guidance_status.desired_speed = desired_speed;
_rover_ackermann_guidance_status.pid_throttle_integral = _pid_throttle.integral;
_rover_ackermann_guidance_status_pub.publish(_rover_ackermann_guidance_status);
@@ -165,7 +209,12 @@ void RoverAckermannGuidance::updateWaypoints()
_position_setpoint_triplet_sub.copy(&position_setpoint_triplet);
// Global waypoint coordinates
_curr_wp = Vector2d(position_setpoint_triplet.current.lat, position_setpoint_triplet.current.lon);
if (position_setpoint_triplet.current.valid) {
_curr_wp = Vector2d(position_setpoint_triplet.current.lat, position_setpoint_triplet.current.lon);
} else {
_curr_wp = Vector2d(0, 0);
}
if (position_setpoint_triplet.previous.valid) {
_prev_wp = Vector2d(position_setpoint_triplet.previous.lat, position_setpoint_triplet.previous.lon);
@@ -178,7 +227,7 @@ void RoverAckermannGuidance::updateWaypoints()
_next_wp = Vector2d(position_setpoint_triplet.next.lat, position_setpoint_triplet.next.lon);
} else {
_next_wp = _curr_wp;
_next_wp = _home_position; // Enables corner slow down with RTL
}
// Local waypoint coordinates
@@ -187,9 +236,15 @@ void RoverAckermannGuidance::updateWaypoints()
_next_wp_local = _global_local_proj_ref.project(_next_wp(0), _next_wp(1));
// Update acceptance radius
_prev_acc_rad = _acceptance_radius;
_acceptance_radius = updateAcceptanceRadius(_curr_wp_local, _prev_wp_local, _next_wp_local, _param_ra_acc_rad_def.get(),
_param_ra_acc_rad_gain.get(), _param_ra_acc_rad_max.get(), _param_ra_wheel_base.get(), _param_ra_max_steer_angle.get());
_prev_acceptance_radius = _acceptance_radius;
if (_param_ra_acc_rad_max.get() >= _param_nav_acc_rad.get()) {
_acceptance_radius = updateAcceptanceRadius(_curr_wp_local, _prev_wp_local, _next_wp_local, _param_nav_acc_rad.get(),
_param_ra_acc_rad_gain.get(), _param_ra_acc_rad_max.get(), _param_ra_wheel_base.get(), _param_ra_max_steer_angle.get());
} else {
_acceptance_radius = _param_nav_acc_rad.get();
}
}
float RoverAckermannGuidance::updateAcceptanceRadius(const Vector2f &curr_wp_local, const Vector2f &prev_wp_local,
@@ -43,10 +43,11 @@
#include <uORB/topics/position_setpoint_triplet.h>
#include <uORB/topics/vehicle_global_position.h>
#include <uORB/topics/vehicle_local_position.h>
#include <uORB/topics/home_position.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/position_controller_status.h>
#include <uORB/topics/mission_result.h>
#include <uORB/topics/home_position.h>
// Standard library includes
#include <matrix/matrix/math.hpp>
@@ -78,8 +79,9 @@ public:
/**
* @brief Compute guidance for ackermann rover and return motor_setpoint for throttle and steering.
* @param nav_state Vehicle navigation state
*/
motor_setpoint purePursuit();
motor_setpoint purePursuit(const int nav_state);
/**
* @brief Update global/local waypoint coordinates and acceptance radius
@@ -143,6 +145,7 @@ private:
uORB::Subscription _local_position_sub{ORB_ID(vehicle_local_position)};
uORB::Subscription _vehicle_attitude_sub{ORB_ID(vehicle_attitude)};
uORB::Subscription _mission_result_sub{ORB_ID(mission_result)};
uORB::Subscription _home_position_sub{ORB_ID(home_position)};
// uORB publications
uORB::Publication<rover_ackermann_guidance_status_s> _rover_ackermann_guidance_status_pub{ORB_ID(rover_ackermann_guidance_status)};
@@ -156,18 +159,18 @@ private:
Vector2d _curr_pos{};
Vector2f _curr_pos_local{};
PID_t _pid_throttle;
hrt_abstime _time_stamp_last{0};
hrt_abstime _timestamp{0};
// Waypoint variables
Vector2d _curr_wp{};
Vector2d _next_wp{};
Vector2d _prev_wp{};
Vector2d _home_position{};
Vector2f _curr_wp_local{};
Vector2f _prev_wp_local{};
Vector2f _next_wp_local{};
float _acceptance_radius{0.5f};
float _prev_acc_rad{0.f};
bool _mission_finished{false};
float _prev_acceptance_radius{0.5f};
// Parameters
DEFINE_PARAMETERS(
@@ -177,7 +180,6 @@ private:
(ParamFloat<px4::params::RA_LOOKAHD_MAX>) _param_ra_lookahd_max,
(ParamFloat<px4::params::RA_LOOKAHD_MIN>) _param_ra_lookahd_min,
(ParamFloat<px4::params::RA_ACC_RAD_MAX>) _param_ra_acc_rad_max,
(ParamFloat<px4::params::RA_ACC_RAD_DEF>) _param_ra_acc_rad_def,
(ParamFloat<px4::params::RA_ACC_RAD_GAIN>) _param_ra_acc_rad_gain,
(ParamFloat<px4::params::RA_MISS_VEL_DEF>) _param_ra_miss_vel_def,
(ParamFloat<px4::params::RA_MISS_VEL_MIN>) _param_ra_miss_vel_min,
@@ -185,6 +187,8 @@ private:
(ParamFloat<px4::params::RA_SPEED_P>) _param_ra_p_speed,
(ParamFloat<px4::params::RA_SPEED_I>) _param_ra_i_speed,
(ParamFloat<px4::params::RA_MAX_SPEED>) _param_ra_max_speed,
(ParamFloat<px4::params::RA_MAX_JERK>) _param_ra_max_jerk,
(ParamFloat<px4::params::RA_MAX_ACCEL>) _param_ra_max_accel,
(ParamFloat<px4::params::NAV_ACC_RAD>) _param_nav_acc_rad
)
};
+56 -21
View File
@@ -66,31 +66,20 @@ parameters:
RA_ACC_RAD_MAX:
description:
short: Maximum acceptance radius
short: Maximum acceptance radius for the waypoints
long: |
The controller scales the acceptance radius based on the angle between
the previous, current and next waypoint. Used as tuning parameter.
the previous, current and next waypoint.
Higher value -> smoother trajectory at the cost of how close the rover gets
to the waypoint (Set equal to RA_ACC_RAD_DEF to disable corner cutting).
to the waypoint (Set to -1 to disable corner cutting).
type: float
unit: m
min: 0.1
min: -1
max: 100
increment: 0.01
decimal: 2
default: 3
RA_ACC_RAD_DEF:
description:
short: Default acceptance radius
type: float
unit: m
min: 0.1
max: 100
increment: 0.01
decimal: 2
default: 0.5
RA_ACC_RAD_GAIN:
description:
short: Tuning parameter for corner cutting
@@ -110,21 +99,21 @@ parameters:
short: Default rover velocity during a mission
type: float
unit: m/s
min: 0.1
min: 0
max: 100
increment: 0.01
decimal: 2
default: 3
default: 2
RA_MISS_VEL_MIN:
description:
short: Minimum rover velocity during a mission
long: |
The velocity off the rover is reduced based on the corner it has to take
to smooth the trajectory (To disable this feature set it equal to RA_MISSION_VEL_DEF)
to smooth the trajectory (Set to -1 to disable)
type: float
unit: m/s
min: 0.1
min: -1
max: 100
increment: 0.01
decimal: 2
@@ -133,9 +122,12 @@ parameters:
RA_MISS_VEL_GAIN:
description:
short: Tuning parameter for the velocity reduction during cornering
long: Lower value -> More velocity reduction during cornering
long: |
The cornering speed is equal to the inverse of the acceptance radius
of the WP multiplied with this factor.
Lower value -> More velocity reduction during cornering.
type: float
min: 0.1
min: 0.05
max: 100
increment: 0.01
decimal: 2
@@ -175,3 +167,46 @@ parameters:
increment: 0.01
decimal: 2
default: -1
RA_MAX_ACCEL:
description:
short: Maximum acceleration for the rover
long: |
This is used for the acceleration slew rate, the feed-forward term
for the speed controller during missions and the corner slow down effect.
Note: For the corner slow down effect RA_MAX_JERK, RA_MISS_VEL_GAIN and
RA_MISS_VEL_MIN also have to be set.
type: float
unit: m/s^2
min: -1
max: 100
increment: 0.01
decimal: 2
default: -1
RA_MAX_JERK:
description:
short: Maximum jerk
long: |
Limit for forwards acc/deceleration change.
This is used for the corner slow down effect.
Note: RA_MAX_ACCEL, RA_MISS_VEL_GAIN and RA_MISS_VEL_MIN also have to be set
for this to be enabled.
type: float
unit: m/s^3
min: -1
max: 100
increment: 0.01
decimal: 2
default: -1
RA_MAX_STR_RATE:
description:
short: Maximum steering rate for the rover
type: float
unit: deg/s
min: -1
max: 1000
increment: 0.01
decimal: 2
default: -1
+2 -2
View File
@@ -243,8 +243,8 @@ void Sih::parameters_updated()
_KDW = _sih_kdw.get();
_H0 = _sih_h0.get();
_LAT0 = (double)_sih_lat0.get() * 1.0e-7;
_LON0 = (double)_sih_lon0.get() * 1.0e-7;
_LAT0 = (double)_sih_lat0.get();
_LON0 = (double)_sih_lon0.get();
_COS_LAT0 = cosl((long double)radians(_LAT0));
_MASS = _sih_mass.get();
+2 -2
View File
@@ -273,8 +273,8 @@ private:
(ParamFloat<px4::params::SIH_L_PITCH>) _sih_l_pitch,
(ParamFloat<px4::params::SIH_KDV>) _sih_kdv,
(ParamFloat<px4::params::SIH_KDW>) _sih_kdw,
(ParamInt<px4::params::SIH_LOC_LAT0>) _sih_lat0,
(ParamInt<px4::params::SIH_LOC_LON0>) _sih_lon0,
(ParamFloat<px4::params::SIH_LOC_LAT0>) _sih_lat0,
(ParamFloat<px4::params::SIH_LOC_LON0>) _sih_lon0,
(ParamFloat<px4::params::SIH_LOC_H0>) _sih_h0,
(ParamFloat<px4::params::SIH_DISTSNSR_MIN>) _sih_distance_snsr_min,
(ParamFloat<px4::params::SIH_DISTSNSR_MAX>) _sih_distance_snsr_max,
@@ -235,33 +235,31 @@ PARAM_DEFINE_FLOAT(SIH_KDW, 0.025f);
* Initial geodetic latitude
*
* This value represents the North-South location on Earth where the simulation begins.
* A value of 45 deg should be written 450000000.
*
* LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others
* to represent a physical ground location on Earth.
*
* @unit deg*1e7
* @min -850000000
* @max 850000000
* @unit deg
* @min -90
* @max 90
* @group Simulation In Hardware
*/
PARAM_DEFINE_INT32(SIH_LOC_LAT0, 454671160);
PARAM_DEFINE_FLOAT(SIH_LOC_LAT0, 47.397742f);
/**
* Initial geodetic longitude
*
* This value represents the East-West location on Earth where the simulation begins.
* A value of 45 deg should be written 450000000.
*
* LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others
* to represent a physical ground location on Earth.
*
* @unit deg*1e7
* @min -1800000000
* @max 1800000000
* @unit deg
* @min -180
* @max 180
* @group Simulation In Hardware
*/
PARAM_DEFINE_INT32(SIH_LOC_LON0, -737578370);
PARAM_DEFINE_FLOAT(SIH_LOC_LON0, 8.545594f);
/**
* Initial AMSL ground altitude
@@ -282,7 +280,7 @@ PARAM_DEFINE_INT32(SIH_LOC_LON0, -737578370);
* @increment 0.01
* @group Simulation In Hardware
*/
PARAM_DEFINE_FLOAT(SIH_LOC_H0, 32.34f);
PARAM_DEFINE_FLOAT(SIH_LOC_H0, 489.4f);
/**
* distance sensor minimum range