summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--.gitmodules15
-rw-r--r--CMakeLists.txt55
m---------include/FreeRTOS-Kernel0
-rw-r--r--include/FreeRTOSConfig.h164
-rw-r--r--include/adxl375.hpp265
-rw-r--r--include/altimeter.hpp31
-rw-r--r--include/altitude-pa.h476
-rw-r--r--include/heartbeat.hpp21
-rw-r--r--include/iim42653.hpp177
-rw-r--r--include/imu.hpp207
m---------include/libfixkalman0
m---------include/libfixmath0
m---------include/libfixmatrix0
-rw-r--r--include/log_format.hpp69
-rw-r--r--include/mmc5983ma.hpp168
-rw-r--r--include/ms5607.hpp133
-rw-r--r--include/ohio_test_data.h23352
m---------include/pico-logger0
m---------include/pico-sdk0
-rw-r--r--include/pwm.hpp1
-rw-r--r--include/rp2040_micro.h111
-rw-r--r--include/serial.hpp86
-rw-r--r--include/spi_flash.h55
-rw-r--r--notes.txt15
-rw-r--r--src/CMakeLists.txt34
-rw-r--r--src/active_drag_system.cpp1131
-rw-r--r--src/adxl375.cpp60
-rw-r--r--src/altimeter.cpp145
-rw-r--r--src/heartbeat.cpp48
-rw-r--r--src/iim42653.cpp108
-rw-r--r--src/imu.cpp160
-rw-r--r--src/log_format.cpp66
-rw-r--r--src/mmc5983ma.cpp158
-rw-r--r--src/ms5607.cpp208
-rw-r--r--src/pwm.cpp6
-rw-r--r--src/serial.cpp134
-rw-r--r--src/spi_flash.c267
-rw-r--r--tools/CMakeLists.txt42
-rw-r--r--tools/alt_test.cpp51
-rw-r--r--tools/clock_gen_test.cpp22
-rw-r--r--tools/imu_calib.cpp222
-rw-r--r--tools/read_flash.c78
-rw-r--r--tools/read_flash.cpp538
-rw-r--r--tools/servo_test.cpp8
44 files changed, 27289 insertions, 1598 deletions
diff --git a/.gitmodules b/.gitmodules
index 4d3602d..b2f620f 100644
--- a/.gitmodules
+++ b/.gitmodules
@@ -4,3 +4,18 @@
[submodule "include/eigen"]
path = include/eigen
url = https://gitlab.com/libeigen/eigen.git
+[submodule "include/pico-logger"]
+ path = include/pico-logger
+ url = https://github.com/rocketryvt/pico-logger.git
+[submodule "include/FreeRTOS-Kernel"]
+ path = include/FreeRTOS-Kernel
+ url = https://github.com/FreeRTOS/FreeRTOS-Kernel.git
+[submodule "include/libfixmath"]
+ path = include/libfixmath
+ url = https://github.com/PetteriAimonen/libfixmath.git
+[submodule "include/libfixmatrix"]
+ path = include/libfixmatrix
+ url = https://github.com/PetteriAimonen/libfixmatrix.git
+[submodule "include/libfixkalman"]
+ path = include/libfixkalman
+ url = https://github.com/sunsided/libfixkalman.git
diff --git a/CMakeLists.txt b/CMakeLists.txt
index 933710e..86ab72b 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -1,13 +1,17 @@
-cmake_minimum_required(VERSION 3.12)
+cmake_minimum_required(VERSION 3.10)
-set(PICO_BOARD pico_w)
+set(PICO_BOARD rp2040_micro)
+set(PICO_BOARD_HEADER_DIRS ${CMAKE_CURRENT_LIST_DIR}/include)
# Pull in SDK (must be before project)
-include(include/pico-sdk/pico_sdk_init.cmake)
-include_directories(include/eigen)
+include(${CMAKE_CURRENT_LIST_DIR}/include/pico-sdk/pico_sdk_init.cmake)
+include(${CMAKE_CURRENT_LIST_DIR}/include/FreeRTOS-Kernel/portable/ThirdParty/GCC/RP2040/FreeRTOS_Kernel_import.cmake)
+include(${CMAKE_CURRENT_LIST_DIR}/include/pico-logger/CMakeLists.txt)
+include_directories(${CMAKE_CURRENT_LIST_DIR}/include/eigen)
set(CMAKE_EXPORT_COMPILE_COMMANDS ON)
set(CMAKE_C_COMPILER arm-none-eabi-gcc)
set(CMAKE_CXX_COMPILER arm-none-eabi-g++)
+set(CMAKE_TRY_COMPILE_TARGET_TYPE "STATIC_LIBRARY")
project(active-drag-system C CXX ASM)
set(CMAKE_C_STANDARD 11)
@@ -20,13 +24,54 @@ endif()
# Initialize the SDK
pico_sdk_init()
+# BEGIN libfixmath, libfixmatrix, and libfixkalman library generation
+ add_library(libfixmath INTERFACE)
+
+ file(GLOB libfixmath-srcs ${CMAKE_CURRENT_LIST_DIR}/include/libfixmath/libfixmath/*.c)
+ target_sources(libfixmath INTERFACE ${libfixmath-srcs})
+ target_include_directories(libfixmath INTERFACE
+ ${CMAKE_CURRENT_LIST_DIR}/include/libfixmath/libfixmath
+ )
+ target_compile_definitions(libfixmath INTERFACE
+ FIXMATH_FAST_SIN
+ # FIXMATH_NO_64BIT
+ # FIXMATH_SIN_LUT
+ # FIXMATH_NO_CACHE
+ # FIXMATH_NO_HARD_DIVISION
+ FIXMATH_NO_OVERFLOW
+ # FIXMATH_NO_ROUNDING
+ # FIXMATH_OPTIMIZE_8BIT
+ )
+
+ add_library(libfixmatrix INTERFACE)
+
+ file(GLOB libfixmatrix-srcs ${CMAKE_CURRENT_LIST_DIR}/include/libfixmatrix/*.c)
+ list(FILTER libfixmatrix-srcs EXCLUDE REGEX ".*unittests\\.c$")
+ target_sources(libfixmatrix INTERFACE ${libfixmatrix-srcs})
+ target_include_directories(libfixmatrix INTERFACE
+ ${CMAKE_CURRENT_LIST_DIR}/include/libfixmatrix
+ )
+ target_compile_definitions(libfixmatrix INTERFACE FIXMATRIX_MAX_SIZE=3)
+ target_link_libraries(libfixmatrix INTERFACE libfixmath)
+
+ add_library(libfixkalman INTERFACE)
+
+ target_sources(libfixkalman INTERFACE ${CMAKE_CURRENT_LIST_DIR}/include/libfixkalman/fixkalman.c)
+ target_include_directories(libfixkalman INTERFACE ${CMAKE_CURRENT_LIST_DIR}/include/libfixkalman)
+ target_compile_definitions(libfixkalman INTERFACE
+ KALMAN_DISABLE_UC
+ KALMAN_TIME_VARYING
+ )
+ target_link_libraries(libfixkalman INTERFACE libfixmath libfixmatrix)
+# END libfixmath, libfixmatrix, and libfixkalman library generation
+
add_subdirectory(src)
add_subdirectory(tools)
-
add_compile_options(-Wall
-Wno-format # int != int32_t as far as the compiler is concerned because gcc has int32_t as long int
-Wno-unused-function # we have some for the docs that aren't called
+ -fpermissive
)
if (CMAKE_C_COMPILER_ID STREQUAL "GNU")
add_compile_options(-Wno-maybe-uninitialized)
diff --git a/include/FreeRTOS-Kernel b/include/FreeRTOS-Kernel
new file mode 160000
+Subproject 03db672b8f45db24aa99f12051f7cf86746b9ed
diff --git a/include/FreeRTOSConfig.h b/include/FreeRTOSConfig.h
new file mode 100644
index 0000000..028ae77
--- /dev/null
+++ b/include/FreeRTOSConfig.h
@@ -0,0 +1,164 @@
+/*
+ * FreeRTOS V202107.00
+ * Copyright (C) 2020 Amazon.com, Inc. or its affiliates. All Rights Reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy of
+ * this software and associated documentation files (the "Software"), to deal in
+ * the Software without restriction, including without limitation the rights to
+ * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of
+ * the Software, and to permit persons to whom the Software is furnished to do so,
+ * subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in all
+ * copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS
+ * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR
+ * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER
+ * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
+ * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
+ *
+ * http://www.FreeRTOS.org
+ * http://aws.amazon.com/freertos
+ *
+ * 1 tab == 4 spaces!
+ */
+
+ #ifndef FREERTOS_CONFIG_H
+ #define FREERTOS_CONFIG_H
+
+/* *INDENT-OFF* */
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+ /*-----------------------------------------------------------
+ * Application specific definitions.
+ *
+ * These definitions should be adjusted for your particular hardware and
+ * application requirements.
+ *
+ * THESE PARAMETERS ARE DESCRIBED WITHIN THE 'CONFIGURATION' SECTION OF THE
+ * FreeRTOS API DOCUMENTATION AVAILABLE ON THE FreeRTOS.org WEB SITE.
+ *
+ * See http://www.freertos.org/a00110.html
+ *----------------------------------------------------------*/
+
+ /* Scheduler Related */
+ #define configUSE_PREEMPTION 1
+ #define configUSE_TICKLESS_IDLE 0
+ #define configUSE_IDLE_HOOK 0
+ #define configUSE_TICK_HOOK 1
+ #define configTICK_RATE_HZ ( ( TickType_t ) 1000 )
+ #define configMAX_PRIORITIES 32
+ #define configMINIMAL_STACK_SIZE ( configSTACK_DEPTH_TYPE ) 256
+ #define configUSE_16_BIT_TICKS 0
+
+ #define configIDLE_SHOULD_YIELD 1
+
+ /* Synchronization Related */
+ #define configUSE_MUTEXES 1
+ #define configUSE_RECURSIVE_MUTEXES 1
+ #define configUSE_APPLICATION_TASK_TAG 0
+ #define configUSE_COUNTING_SEMAPHORES 1
+ #define configQUEUE_REGISTRY_SIZE 8
+ #define configUSE_QUEUE_SETS 1
+ #define configUSE_TIME_SLICING 1
+ #define configUSE_NEWLIB_REENTRANT 0
+ #define configENABLE_BACKWARD_COMPATIBILITY 0
+ #define configNUM_THREAD_LOCAL_STORAGE_POINTERS 5
+
+ #define configUSE_TASK_NOTIFICATIONS 1
+ #define configTASK_NOTIFICATION_ARRAY_ENTRIES 32
+
+ /* System */
+ #define configSTACK_DEPTH_TYPE uint32_t
+ #define configMESSAGE_BUFFER_LENGTH_TYPE size_t
+
+ /* Memory allocation related definitions. */
+ #define configSUPPORT_STATIC_ALLOCATION 0
+ #define configSUPPORT_DYNAMIC_ALLOCATION 1
+ #define configTOTAL_HEAP_SIZE (72*1024)
+ #define configAPPLICATION_ALLOCATED_HEAP 0
+
+ /* Hook function related definitions. */
+ #define configCHECK_FOR_STACK_OVERFLOW 2
+ #define configUSE_MALLOC_FAILED_HOOK 1
+ #define configUSE_DAEMON_TASK_STARTUP_HOOK 0
+
+ /* Run time and task stats gathering related definitions. */
+ #define configGENERATE_RUN_TIME_STATS 1
+ #define configUSE_TRACE_FACILITY 1
+ #define configUSE_STATS_FORMATTING_FUNCTIONS 1
+
+ /* Co-routine related definitions. */
+ #define configUSE_CO_ROUTINES 0
+ #define configMAX_CO_ROUTINE_PRIORITIES 1
+
+ /* Software timer related definitions. */
+ #define configUSE_TIMERS 1
+ #define configTIMER_TASK_PRIORITY ( configMAX_PRIORITIES - 1 )
+ #define configTIMER_QUEUE_LENGTH 10
+ #define configTIMER_TASK_STACK_DEPTH 1024
+
+ /* Interrupt nesting behaviour configuration. */
+ /*
+ #define configKERNEL_INTERRUPT_PRIORITY [dependent of processor]
+ #define configMAX_SYSCALL_INTERRUPT_PRIORITY [dependent on processor and application]
+ #define configMAX_API_CALL_INTERRUPT_PRIORITY [dependent on processor and application]
+ */
+
+#define FREE_RTOS_KERNEL_SMP 1
+#if FREE_RTOS_KERNEL_SMP // set by the RP2040 SMP port of FreeRTOS
+/* SMP port only */
+#define configNUM_CORES 2
+#define configTICK_CORE 0
+#define configRUN_MULTIPLE_PRIORITIES 1
+#define configUSE_CORE_AFFINITY 1
+#define configUSE_PASSIVE_IDLE_HOOK 0
+#else
+#define configNUM_CORES 1
+#endif
+#define configNUMBER_OF_CORES configNUM_CORES
+
+ /* RP2040 specific */
+ #define configSUPPORT_PICO_SYNC_INTEROP 1
+ #define configSUPPORT_PICO_TIME_INTEROP 1
+
+ #include <assert.h>
+ /* Define to trap errors during development. */
+ #define configASSERT(x) assert(x)
+
+ /* Set the following definitions to 1 to include the API function, or zero
+ to exclude the API function. */
+ #define INCLUDE_vTaskPrioritySet 1
+ #define INCLUDE_uxTaskPriorityGet 1
+ #define INCLUDE_vTaskDelete 1
+ #define INCLUDE_vTaskSuspend 1
+ #define INCLUDE_vTaskDelayUntil 1
+ #define INCLUDE_vTaskDelay 1
+ #define INCLUDE_xTaskGetSchedulerState 1
+ #define INCLUDE_xTaskGetCurrentTaskHandle 1
+ #define INCLUDE_uxTaskGetStackHighWaterMark 1
+ #define INCLUDE_xTaskGetIdleTaskHandle 1
+ #define INCLUDE_eTaskGetState 1
+ #define INCLUDE_xTimerPendFunctionCall 1
+ #define INCLUDE_xTaskAbortDelay 1
+ #define INCLUDE_xTaskGetHandle 1
+ #define INCLUDE_xTaskResumeFromISR 1
+ #define INCLUDE_xQueueGetMutexHolder 1
+
+ /* A header file that defines trace macro can be included here. */
+#define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS()
+extern uint64_t time_us_64(void); // "hardware/timer.h"
+#define RUN_TIME_STAT_time_us_64Divider 1000 // stat granularity is mS
+#define portGET_RUN_TIME_COUNTER_VALUE() (time_us_64()/RUN_TIME_STAT_time_us_64Divider) // runtime counter in mS
+
+/* *INDENT-OFF* */
+#ifdef __cplusplus
+ }
+#endif
+
+#endif /* FREERTOS_CONFIG_H */
+
diff --git a/include/adxl375.hpp b/include/adxl375.hpp
new file mode 100644
index 0000000..21fe82c
--- /dev/null
+++ b/include/adxl375.hpp
@@ -0,0 +1,265 @@
+#pragma once
+
+#include <stdint.h>
+
+#include <hardware/i2c.h>
+
+#if ( USE_FREERTOS == 1)
+#include "FreeRTOS.h"
+#include "FreeRTOSConfig.h"
+#include "portmacro.h"
+#include "projdefs.h"
+#include "serial.hpp"
+#include "task.h"
+#include "semphr.h"
+#endif
+
+#define ADXL375_I2C_ADDRESS 0x1D
+
+// DEVID [Validation]
+#define R_ADXL375_DEVID 0x00
+#define B_ADXL375_DEVID_VALUE 0xE5
+
+// THRESH_SHOCK [Configuration, Threshold for shock interrupt (780mG/LSB)]
+#define R_ADXL375_THRESH_SHOCK 0x1D
+typedef uint8_t ADXL375_THRESH_SHOCK;
+
+// OFSX, OFSY, OFSZ [Configuration, User-configured offset of (0.196 g/LSB)]
+#define R_ADXL375_OFFSET_X 0x1E
+typedef uint8_t ADXL375_OFFSET_X;
+
+#define R_ADXL375_OFFSET_Y 0x1F
+typedef uint8_t ADXL375_OFFSET_Y;
+
+#define R_ADXL375_OFFSET_Z 0x20
+typedef uint8_t ADXL375_OFFSET_Z;
+
+// DUR [Configuration, Time above threshold as single shock interrupt (625us/LSB)]
+#define R_ADXL375_DUR 0x21
+typedef uint8_t ADXL375_DURATION;
+
+// LATENT [Configuration, Time after first shock interrupt second can occur (1.25ms/LSB)]
+#define R_ADXL375_LATENT 0x22
+typedef uint8_t ADXL375_LATENT;
+
+// WINDOW [Configuration, Time after latent period second shock can begin (1.25ms/LSB)]
+#define R_ADXL375_WINDOW 0x23
+typedef uint8_t ADXL375_WINDOW;
+
+// THRESH_ACT [Configuration, Threshold value for detecting activity (780mg/LSB)]
+#define R_ADXL375_THRESH_ACT 0x24
+typedef uint8_t ADXL375_THRESH_ACT;
+
+// THRESH_INACT [Configuration, Threshold value for detecting inactivity (780mg/LSB)]
+#define R_ADXL375_THRESH_INACT 0x25
+typedef uint8_t ADXL375_THRESH_INACT;
+
+// TIME_INACT [Configuration, Time below threshold as inactivity (1s/LSB)]
+#define R_ADXL375_TIME_INACT 0x26
+typedef uint8_t ADXL375_TIME_INACT;
+
+// ACT_INACT_CTL [Configuration, Activity/Inactivity interrupts enable and AC/DC coupling]
+#define R_ADXL375_ACT_INACT_CTL 0x27
+typedef union {
+ struct {
+ bool INACT_Z_ENABLE :1;
+ bool INACT_Y_ENABLE :1;
+ bool INACT_X_ENABLE :1;
+ bool INACT_AC_DC :1;
+ bool ACT_Z_ENABLE :1;
+ bool ACT_Y_ENABLE :1;
+ bool ACT_X_ENABLE :1;
+ bool ACT_AC_DC :1;
+ } fields;
+ uint8_t data;
+} ADXL375_ACT_INACT_CTL;
+
+// SHOCK_AXES [Configuration, axes used in shock interrupt]
+#define R_ADXL375_SHOCK_AXES 0x2A
+typedef union {
+ struct {
+ bool SHOCK_Z_ENABLE :1; //Z-Axis shock interrupt enable
+ bool SHOCK_Y_ENABLE :1; //Y-Axis shock interrupt enable
+ bool SHOCK_X_ENABLE :1; //X-Axis shock interrupt enable
+ bool SUPPRESS :1; //Suppresses double shock detection
+ uint8_t RESERVED :4; //Reserved
+ } fields;
+ uint8_t data;
+} ADXL375_SHOCK_AXES;
+
+// ACT_SHOCK_STATUS [Status, First axis involved in an activity or shock event]
+#define R_ADXL375_ACT_SHOCK_STATUS 0x2B
+typedef union {
+ struct {
+ bool SHOCK_Z_SOURCE :1;
+ bool SHOCK_Y_SOURCE :1;
+ bool SHOCK_X_SOURCE :1;
+ bool ASLEEP :1;
+ bool ACT_Z_SOURCE :1;
+ bool ACT_Y_SOURCE :1;
+ bool ACT_X_SOURCE :1;
+ bool RESERVED :1;
+ } fields;
+ uint8_t data;
+} ADXL375_ACT_SHOCK_STATUS;
+
+// BW_RATE [Configuration, Low Power Mode and ODR]
+#define R_ADXL375_BW_RATE 0x2C
+typedef union {
+ struct {
+ uint8_t RATE :4; //ODR configuration
+ bool LOW_POWER :1; //Low-power/Normal mode configuration
+ uint8_t RESERVED :3; //Reserved
+ } fields;
+ uint8_t data;
+} ADXL375_BW_RATE;
+#define B_ADXL375_ODR_100_HZ 0x0A
+#define B_ADXL375_ODR_400_HZ 0x0C
+#define B_ADXL375_ODR_800_HZ 0x0D
+#define B_ADXL375_ODR_3200_HZ 0x0F
+#define B_ADXL375_BW_RATE_LOW_POWER_MODE 0b1
+#define B_ADXL375_BW_RATE_NORMAL_POWER_MODE 0b0
+
+// POWER_CTL [State Configuration, Measurement mode (and sleep settings)]
+#define R_ADXL375_POWER_CTL 0x2D
+typedef union {
+ struct {
+ uint8_t WAKEUP :2; //Sampling rate control during sleep mode
+ bool SLEEP :1; //Sleep mode configuration
+ bool MEASURE :1; //Measurement/Standby mode configuration
+ bool AUTO_SLEEP :1; //Auto sleep function enable
+ bool LINK :1; //Link activity and inactivity functions
+ bool RESERVED :1; //Reserved
+ } fields;
+ uint8_t data;
+} ADXL375_POWER_CTL;
+
+// INT_ENABLE [State Configuration, interrupt enabling]
+#define R_ADXL375_INT_ENABLE 0x2E
+typedef union {
+ struct {
+ bool OVERRUN :1; //FIFO buffer overwrite interrupt enable
+ bool WATERMARK :1; //??? TODO: Figure out watermark bits
+ bool RESERVED :1; //Reserved
+ bool INACTIVITY :1; //Inactivity interrupt enable
+ bool ACTIVITY :1; //Activity interrupt enable
+ bool DOUBLE_SHOCK :1; //Double shock interrupt enable
+ bool SINGLE_SHOCK :1; //Single shock interrupt enable
+ bool DATA_READY :1; //FIFO buffer new data interrupt enable
+ } fields;
+ uint8_t data;
+} ADXL375_INT_ENABLE;
+
+// INT_MAP [Configuration, Interrupt --> Pin mapping (0 = INT1, 1 = INT2) */
+#define R_ADXL375_INT_MAP 0x2F
+typedef union {
+ struct {
+ bool OVERRUN :1; //FIFO buffer overwrite interrupt
+ bool WATERMARK :1; //??? TODO: Figure out watermark bits
+ bool RESERVED :1; //Reserved
+ bool INACTIVITY :1; //Inactivity interrupt
+ bool ACTIVITY :1; //Activity interrupt
+ bool DOUBLE_SHOCK :1; //Double shock interrupt
+ bool SINGLE_SHOCK :1; //Single shock interrupt
+ bool DATA_READY :1; //FIFO buffer new data interrupt
+ } fields;
+ uint8_t data;
+} ADXL375_INT_MAP;
+
+// INT_SOURCE [Status, Source of interrupt (read to clear SINGLE_SHOCK interrupt) */
+#define R_ADXL375_INT_SOURCE 0x30
+typedef union {
+ struct {
+ bool OVERRUN :1; //FIFO buffer overwrite interrupt
+ bool WATERMARK :1; //??? TODO: Figure out watermark bits
+ bool RESERVED :1; //Reserved
+ bool INACTIVITY :1; //Inactivity interrupt
+ bool ACTIVITY :1; //Activity interrupt
+ bool DOUBLE_SHOCK :1; //Double shock interrupt
+ bool SINGLE_SHOCK :1; //Single shock interrupt
+ bool DATA_READY :1; //FIFO buffer new data interrupt
+ } fields;
+ uint8_t data;
+} ADXL375_INT_SOURCE;
+
+// DATA_FORMAT [Configuration, Data output style/formatting (variety of things)] */
+#define R_ADXL375_DATA_FORMAT 0x31
+typedef union {
+ struct {
+ uint8_t RESERVED :2; //Reserved
+ bool JUSTIFY :1; //Left(MSB)/Right(LSB, Sign extended) output justification
+ uint8_t RESERVED_ :2; //Reserved
+ bool INT_INVERT :1; //Interrupt pin polarity configuration
+ bool SPI :1; //SPI 3/4 wire mode configuration
+ bool SELF_TEST :1; //Configure self-test mode
+ } fields;
+ uint8_t data;
+} ADXL375_DATA_FORMAT;
+#define B_ADXL375_DATA_FORMAT_JUSTIFY_RIGHT 0b0
+#define B_ADXL375_DATA_FORMAT_JUSTIFY_LEFT 0b1
+#define B_ADXL375_DATA_FORMAT_INTERRUPT_ACTIVE_HIGH 0b0
+#define B_ADXL375_DATA_FORMAT_INTERRUPT_ACTIVE_LOW 0b1
+#define B_ADXL375_DATA_FORMAT_ENABLE_SELF_TEST 0b1
+#define B_ADXL375_DATA_FORMAT_DISABLE_SELF_TEST 0b0
+
+// DATAX0-DATAZ1 [Output, 16b data for X/Y/Z (DATA_1 is MSByte, DATA_0 is LSByte)
+#define R_ADXL375_DATAX0 0x32
+#define R_ADXL375_DATAX1 0x33
+#define R_ADXL375_DATAY0 0x34
+#define R_ADXL375_DATAY1 0x35
+#define R_ADXL375_DATAZ0 0x36
+#define R_ADXL375_DATAZ1 0x37
+#define S_ADXL375_SCALE_FACTOR 20.5 // 1 LSB / 20.5
+
+#define ADXL375_SAMPLE_RATE_HZ 500
+
+class ADXL375 {
+ public:
+ ADXL375(i2c_inst_t* i2c) : i2c {i2c} {};
+
+ void initialize();
+
+ void sample();
+
+ int16_t get_ax() { return ax; }
+ int16_t get_ay() { return ay; }
+ int16_t get_az() { return az; }
+
+ static float scale(int16_t unscaled) { return ((float) unscaled) / S_ADXL375_SCALE_FACTOR; }
+
+#if (USE_FREERTOS == 1)
+ static void update_adxl375_task(void *pvParameters);
+
+ TaskHandle_t update_task_handle = NULL;
+#endif
+
+ private:
+ const uint8_t addr = ADXL375_I2C_ADDRESS;
+
+ i2c_inst_t* i2c;
+
+ uint8_t buffer[16];
+
+ ADXL375_THRESH_SHOCK shock_threshold;
+ ADXL375_OFFSET_X offset_ax;
+ ADXL375_OFFSET_Y offset_ay;
+ ADXL375_OFFSET_Z offset_az;
+ ADXL375_DURATION shock_duration;
+ ADXL375_LATENT latent_shock;
+ ADXL375_WINDOW window_shock;
+ ADXL375_THRESH_ACT activity_threshold;
+ ADXL375_THRESH_INACT inactivity_threshold;
+ ADXL375_TIME_INACT inactivity_duraction;
+ ADXL375_ACT_INACT_CTL act_inact_ctl;
+ ADXL375_SHOCK_AXES shock_axes;
+ ADXL375_ACT_SHOCK_STATUS act_shock_status;
+ ADXL375_BW_RATE bw_rate;
+ ADXL375_POWER_CTL power_ctl;
+ ADXL375_INT_ENABLE int_enable;
+ ADXL375_INT_MAP int_map;
+ ADXL375_INT_SOURCE int_source;
+ ADXL375_DATA_FORMAT data_format;
+
+ int16_t ax, ay, az;
+};
+
diff --git a/include/altimeter.hpp b/include/altimeter.hpp
deleted file mode 100644
index bf7effd..0000000
--- a/include/altimeter.hpp
+++ /dev/null
@@ -1,31 +0,0 @@
-#pragma once
-
-#include "pico/stdlib.h"
-#include "hardware/i2c.h"
-#include "hardware/gpio.h"
-#include <cstdint>
-
-class altimeter {
- private:
- uint8_t altitude_buffer[4];
- uint8_t buffer[4];
- uint8_t addr;
- i2c_inst_t* inst;
- public:
- altimeter(i2c_inst_t* inst, uint8_t addr);
-
- void initialize();
-
- void initialize(float threshold_altitude, uint8_t interrupt_pin, gpio_irq_callback_t callback);
-
- void set_threshold_altitude(float threshold_altitude, uint8_t interrupt_pin, gpio_irq_callback_t callback);
-
- void unset_threshold_altitude(uint8_t interrupt_pin);
-
- float get_altitude_converted();
-
- void get_altitude_raw(uint8_t* buffer);
-
- uint32_t expose_buffer(uint8_t** buffer);
-};
-
diff --git a/include/altitude-pa.h b/include/altitude-pa.h
new file mode 100644
index 0000000..5e946b9
--- /dev/null
+++ b/include/altitude-pa.h
@@ -0,0 +1,476 @@
+/*max error 24389.3 at 0.000 kPa. Average error 8.505350466889926*/
+#define NALT 470
+#define ALT_SHIFT 8
+#ifndef ALT_VALUE
+#define ALT_VALUE(x) (int32_t) (x)
+#endif
+ALT_VALUE( 604627), /* 0.00 kPa error 24389.m */
+ALT_VALUE( 382693), /* 0.26 kPa error 2325.8m */
+ALT_VALUE( 354186), /* 0.51 kPa error 192.03m */
+ALT_VALUE( 327499), /* 0.77 kPa error 73.58m */
+ALT_VALUE( 308588), /* 1.02 kPa error 37.81m */
+ALT_VALUE( 293917), /* 1.28 kPa error 23.49m */
+ALT_VALUE( 281959), /* 1.54 kPa error 16.04m */
+ALT_VALUE( 271879), /* 1.79 kPa error 11.71m */
+ALT_VALUE( 263175), /* 2.05 kPa error 8.87m */
+ALT_VALUE( 255520), /* 2.30 kPa error 6.95m */
+ALT_VALUE( 248691), /* 2.56 kPa error 5.60m */
+ALT_VALUE( 242529), /* 2.82 kPa error 4.64m */
+ALT_VALUE( 236917), /* 3.07 kPa error 3.92m */
+ALT_VALUE( 231767), /* 3.33 kPa error 3.27m */
+ALT_VALUE( 227008), /* 3.58 kPa error 2.82m */
+ALT_VALUE( 222586), /* 3.84 kPa error 2.48m */
+ALT_VALUE( 218458), /* 4.10 kPa error 2.12m */
+ALT_VALUE( 214586), /* 4.35 kPa error 1.93m */
+ALT_VALUE( 210942), /* 4.61 kPa error 1.71m */
+ALT_VALUE( 207501), /* 4.86 kPa error 1.48m */
+ALT_VALUE( 204240), /* 5.12 kPa error 1.41m */
+ALT_VALUE( 201144), /* 5.38 kPa error 1.22m */
+ALT_VALUE( 198195), /* 5.63 kPa error 1.07m */
+ALT_VALUE( 195377), /* 5.89 kPa error 0.98m */
+ALT_VALUE( 192679), /* 6.14 kPa error 0.88m */
+ALT_VALUE( 190091), /* 6.40 kPa error 0.80m */
+ALT_VALUE( 187604), /* 6.66 kPa error 0.78m */
+ALT_VALUE( 185211), /* 6.91 kPa error 0.75m */
+ALT_VALUE( 182905), /* 7.17 kPa error 0.72m */
+ALT_VALUE( 180681), /* 7.42 kPa error 0.58m */
+ALT_VALUE( 178531), /* 7.68 kPa error 0.59m */
+ALT_VALUE( 176452), /* 7.94 kPa error 0.55m */
+ALT_VALUE( 174439), /* 8.19 kPa error 0.51m */
+ALT_VALUE( 172488), /* 8.45 kPa error 0.47m */
+ALT_VALUE( 170595), /* 8.70 kPa error 0.45m */
+ALT_VALUE( 168757), /* 8.96 kPa error 0.42m */
+ALT_VALUE( 166971), /* 9.22 kPa error 0.39m */
+ALT_VALUE( 165233), /* 9.47 kPa error 0.42m */
+ALT_VALUE( 163542), /* 9.73 kPa error 0.40m */
+ALT_VALUE( 161895), /* 9.98 kPa error 0.38m */
+ALT_VALUE( 160290), /* 10.24 kPa error 0.32m */
+ALT_VALUE( 158724), /* 10.50 kPa error 0.33m */
+ALT_VALUE( 157196), /* 10.75 kPa error 0.31m */
+ALT_VALUE( 155704), /* 11.01 kPa error 0.29m */
+ALT_VALUE( 154246), /* 11.26 kPa error 0.30m */
+ALT_VALUE( 152821), /* 11.52 kPa error 0.28m */
+ALT_VALUE( 151428), /* 11.78 kPa error 0.20m */
+ALT_VALUE( 150064), /* 12.03 kPa error 0.22m */
+ALT_VALUE( 148729), /* 12.29 kPa error 0.23m */
+ALT_VALUE( 147421), /* 12.54 kPa error 0.25m */
+ALT_VALUE( 146140), /* 12.80 kPa error 0.23m */
+ALT_VALUE( 144884), /* 13.06 kPa error 0.25m */
+ALT_VALUE( 143653), /* 13.31 kPa error 0.21m */
+ALT_VALUE( 142445), /* 13.57 kPa error 0.21m */
+ALT_VALUE( 141260), /* 13.82 kPa error 0.19m */
+ALT_VALUE( 140096), /* 14.08 kPa error 0.21m */
+ALT_VALUE( 138954), /* 14.34 kPa error 0.18m */
+ALT_VALUE( 137831), /* 14.59 kPa error 0.20m */
+ALT_VALUE( 136728), /* 14.85 kPa error 0.21m */
+ALT_VALUE( 135644), /* 15.10 kPa error 0.20m */
+ALT_VALUE( 134579), /* 15.36 kPa error 0.11m */
+ALT_VALUE( 133531), /* 15.62 kPa error 0.16m */
+ALT_VALUE( 132499), /* 15.87 kPa error 0.17m */
+ALT_VALUE( 131485), /* 16.13 kPa error 0.12m */
+ALT_VALUE( 130486), /* 16.38 kPa error 0.14m */
+ALT_VALUE( 129503), /* 16.64 kPa error 0.11m */
+ALT_VALUE( 128535), /* 16.90 kPa error 0.12m */
+ALT_VALUE( 127581), /* 17.15 kPa error 0.13m */
+ALT_VALUE( 126642), /* 17.41 kPa error 0.09m */
+ALT_VALUE( 125716), /* 17.66 kPa error 0.14m */
+ALT_VALUE( 124803), /* 17.92 kPa error 0.15m */
+ALT_VALUE( 123904), /* 18.18 kPa error 0.10m */
+ALT_VALUE( 123017), /* 18.43 kPa error 0.12m */
+ALT_VALUE( 122142), /* 18.69 kPa error 0.13m */
+ALT_VALUE( 121280), /* 18.94 kPa error 0.11m */
+ALT_VALUE( 120428), /* 19.20 kPa error 0.12m */
+ALT_VALUE( 119588), /* 19.46 kPa error 0.13m */
+ALT_VALUE( 118759), /* 19.71 kPa error 0.13m */
+ALT_VALUE( 117941), /* 19.97 kPa error 0.11m */
+ALT_VALUE( 117133), /* 20.22 kPa error 0.11m */
+ALT_VALUE( 116336), /* 20.48 kPa error 0.07m */
+ALT_VALUE( 115548), /* 20.74 kPa error 0.07m */
+ALT_VALUE( 114770), /* 20.99 kPa error 0.08m */
+ALT_VALUE( 114001), /* 21.25 kPa error 0.08m */
+ALT_VALUE( 113242), /* 21.50 kPa error 0.08m */
+ALT_VALUE( 112491), /* 21.76 kPa error 0.11m */
+ALT_VALUE( 111749), /* 22.02 kPa error 0.11m */
+ALT_VALUE( 111016), /* 22.27 kPa error 0.10m */
+ALT_VALUE( 110292), /* 22.53 kPa error 0.06m */
+ALT_VALUE( 109575), /* 22.78 kPa error 0.05m */
+ALT_VALUE( 108865), /* 23.04 kPa error 0.05m */
+ALT_VALUE( 108161), /* 23.30 kPa error 0.06m */
+ALT_VALUE( 107463), /* 23.55 kPa error 0.07m */
+ALT_VALUE( 106772), /* 23.81 kPa error 0.06m */
+ALT_VALUE( 106086), /* 24.06 kPa error 0.06m */
+ALT_VALUE( 105407), /* 24.32 kPa error 0.06m */
+ALT_VALUE( 104733), /* 24.58 kPa error 0.09m */
+ALT_VALUE( 104064), /* 24.83 kPa error 0.09m */
+ALT_VALUE( 103402), /* 25.09 kPa error 0.05m */
+ALT_VALUE( 102745), /* 25.34 kPa error 0.05m */
+ALT_VALUE( 102093), /* 25.60 kPa error 0.06m */
+ALT_VALUE( 101446), /* 25.86 kPa error 0.06m */
+ALT_VALUE( 100805), /* 26.11 kPa error 0.08m */
+ALT_VALUE( 100168), /* 26.37 kPa error 0.08m */
+ALT_VALUE( 99537), /* 26.62 kPa error 0.05m */
+ALT_VALUE( 98911), /* 26.88 kPa error 0.05m */
+ALT_VALUE( 98289), /* 27.14 kPa error 0.03m */
+ALT_VALUE( 97672), /* 27.39 kPa error 0.04m */
+ALT_VALUE( 97060), /* 27.65 kPa error 0.03m */
+ALT_VALUE( 96452), /* 27.90 kPa error 0.04m */
+ALT_VALUE( 95849), /* 28.16 kPa error 0.04m */
+ALT_VALUE( 95250), /* 28.42 kPa error 0.04m */
+ALT_VALUE( 94656), /* 28.67 kPa error 0.08m */
+ALT_VALUE( 94065), /* 28.93 kPa error 0.08m */
+ALT_VALUE( 93480), /* 29.18 kPa error 0.06m */
+ALT_VALUE( 92898), /* 29.44 kPa error 0.03m */
+ALT_VALUE( 92320), /* 29.70 kPa error 0.06m */
+ALT_VALUE( 91746), /* 29.95 kPa error 0.07m */
+ALT_VALUE( 91177), /* 30.21 kPa error 0.05m */
+ALT_VALUE( 90611), /* 30.46 kPa error 0.04m */
+ALT_VALUE( 90049), /* 30.72 kPa error 0.05m */
+ALT_VALUE( 89491), /* 30.98 kPa error 0.04m */
+ALT_VALUE( 88936), /* 31.23 kPa error 0.05m */
+ALT_VALUE( 88385), /* 31.49 kPa error 0.06m */
+ALT_VALUE( 87838), /* 31.74 kPa error 0.07m */
+ALT_VALUE( 87294), /* 32.00 kPa error 0.07m */
+ALT_VALUE( 86754), /* 32.26 kPa error 0.05m */
+ALT_VALUE( 86218), /* 32.51 kPa error 0.06m */
+ALT_VALUE( 85684), /* 32.77 kPa error 0.07m */
+ALT_VALUE( 85154), /* 33.02 kPa error 0.07m */
+ALT_VALUE( 84628), /* 33.28 kPa error 0.07m */
+ALT_VALUE( 84104), /* 33.54 kPa error 0.08m */
+ALT_VALUE( 83584), /* 33.79 kPa error 0.07m */
+ALT_VALUE( 83067), /* 34.05 kPa error 0.08m */
+ALT_VALUE( 82554), /* 34.30 kPa error 0.03m */
+ALT_VALUE( 82043), /* 34.56 kPa error 0.06m */
+ALT_VALUE( 81535), /* 34.82 kPa error 0.07m */
+ALT_VALUE( 81031), /* 35.07 kPa error 0.04m */
+ALT_VALUE( 80529), /* 35.33 kPa error 0.07m */
+ALT_VALUE( 80030), /* 35.58 kPa error 0.07m */
+ALT_VALUE( 79535), /* 35.84 kPa error 0.05m */
+ALT_VALUE( 79042), /* 36.10 kPa error 0.05m */
+ALT_VALUE( 78552), /* 36.35 kPa error 0.04m */
+ALT_VALUE( 78064), /* 36.61 kPa error 0.05m */
+ALT_VALUE( 77580), /* 36.86 kPa error 0.04m */
+ALT_VALUE( 77098), /* 37.12 kPa error 0.04m */
+ALT_VALUE( 76619), /* 37.38 kPa error 0.03m */
+ALT_VALUE( 76142), /* 37.63 kPa error 0.03m */
+ALT_VALUE( 75668), /* 37.89 kPa error 0.03m */
+ALT_VALUE( 75197), /* 38.14 kPa error 0.02m */
+ALT_VALUE( 74728), /* 38.40 kPa error 0.02m */
+ALT_VALUE( 74262), /* 38.66 kPa error 0.02m */
+ALT_VALUE( 73798), /* 38.91 kPa error 0.03m */
+ALT_VALUE( 73337), /* 39.17 kPa error 0.03m */
+ALT_VALUE( 72878), /* 39.42 kPa error 0.06m */
+ALT_VALUE( 72421), /* 39.68 kPa error 0.06m */
+ALT_VALUE( 71967), /* 39.94 kPa error 0.05m */
+ALT_VALUE( 71516), /* 40.19 kPa error 0.03m */
+ALT_VALUE( 71066), /* 40.45 kPa error 0.04m */
+ALT_VALUE( 70619), /* 40.70 kPa error 0.04m */
+ALT_VALUE( 70174), /* 40.96 kPa error 0.04m */
+ALT_VALUE( 69732), /* 41.22 kPa error 0.04m */
+ALT_VALUE( 69291), /* 41.47 kPa error 0.05m */
+ALT_VALUE( 68853), /* 41.73 kPa error 0.03m */
+ALT_VALUE( 68417), /* 41.98 kPa error 0.04m */
+ALT_VALUE( 67983), /* 42.24 kPa error 0.04m */
+ALT_VALUE( 67552), /* 42.50 kPa error 0.04m */
+ALT_VALUE( 67122), /* 42.75 kPa error 0.05m */
+ALT_VALUE( 66694), /* 43.01 kPa error 0.05m */
+ALT_VALUE( 66269), /* 43.26 kPa error 0.05m */
+ALT_VALUE( 65845), /* 43.52 kPa error 0.05m */
+ALT_VALUE( 65424), /* 43.78 kPa error 0.06m */
+ALT_VALUE( 65004), /* 44.03 kPa error 0.06m */
+ALT_VALUE( 64587), /* 44.29 kPa error 0.06m */
+ALT_VALUE( 64171), /* 44.54 kPa error 0.06m */
+ALT_VALUE( 63758), /* 44.80 kPa error 0.03m */
+ALT_VALUE( 63346), /* 45.06 kPa error 0.05m */
+ALT_VALUE( 62936), /* 45.31 kPa error 0.05m */
+ALT_VALUE( 62528), /* 45.57 kPa error 0.05m */
+ALT_VALUE( 62122), /* 45.82 kPa error 0.04m */
+ALT_VALUE( 61718), /* 46.08 kPa error 0.03m */
+ALT_VALUE( 61316), /* 46.34 kPa error 0.03m */
+ALT_VALUE( 60915), /* 46.59 kPa error 0.02m */
+ALT_VALUE( 60516), /* 46.85 kPa error 0.02m */
+ALT_VALUE( 60119), /* 47.10 kPa error 0.03m */
+ALT_VALUE( 59724), /* 47.36 kPa error 0.03m */
+ALT_VALUE( 59330), /* 47.62 kPa error 0.02m */
+ALT_VALUE( 58938), /* 47.87 kPa error 0.02m */
+ALT_VALUE( 58548), /* 48.13 kPa error 0.04m */
+ALT_VALUE( 58159), /* 48.38 kPa error 0.05m */
+ALT_VALUE( 57772), /* 48.64 kPa error 0.05m */
+ALT_VALUE( 57387), /* 48.90 kPa error 0.04m */
+ALT_VALUE( 57004), /* 49.15 kPa error 0.06m */
+ALT_VALUE( 56622), /* 49.41 kPa error 0.04m */
+ALT_VALUE( 56241), /* 49.66 kPa error 0.04m */
+ALT_VALUE( 55862), /* 49.92 kPa error 0.04m */
+ALT_VALUE( 55485), /* 50.18 kPa error 0.05m */
+ALT_VALUE( 55109), /* 50.43 kPa error 0.05m */
+ALT_VALUE( 54735), /* 50.69 kPa error 0.03m */
+ALT_VALUE( 54363), /* 50.94 kPa error 0.06m */
+ALT_VALUE( 53991), /* 51.20 kPa error 0.06m */
+ALT_VALUE( 53622), /* 51.46 kPa error 0.03m */
+ALT_VALUE( 53254), /* 51.71 kPa error 0.02m */
+ALT_VALUE( 52887), /* 51.97 kPa error 0.02m */
+ALT_VALUE( 52522), /* 52.22 kPa error 0.02m */
+ALT_VALUE( 52158), /* 52.48 kPa error 0.02m */
+ALT_VALUE( 51796), /* 52.74 kPa error 0.02m */
+ALT_VALUE( 51435), /* 52.99 kPa error 0.05m */
+ALT_VALUE( 51075), /* 53.25 kPa error 0.05m */
+ALT_VALUE( 50717), /* 53.50 kPa error 0.04m */
+ALT_VALUE( 50361), /* 53.76 kPa error 0.04m */
+ALT_VALUE( 50005), /* 54.02 kPa error 0.04m */
+ALT_VALUE( 49651), /* 54.27 kPa error 0.04m */
+ALT_VALUE( 49299), /* 54.53 kPa error 0.05m */
+ALT_VALUE( 48947), /* 54.78 kPa error 0.06m */
+ALT_VALUE( 48597), /* 55.04 kPa error 0.06m */
+ALT_VALUE( 48249), /* 55.30 kPa error 0.06m */
+ALT_VALUE( 47901), /* 55.55 kPa error 0.06m */
+ALT_VALUE( 47555), /* 55.81 kPa error 0.06m */
+ALT_VALUE( 47211), /* 56.06 kPa error 0.03m */
+ALT_VALUE( 46867), /* 56.32 kPa error 0.03m */
+ALT_VALUE( 46525), /* 56.58 kPa error 0.01m */
+ALT_VALUE( 46184), /* 56.83 kPa error 0.04m */
+ALT_VALUE( 45844), /* 57.09 kPa error 0.04m */
+ALT_VALUE( 45506), /* 57.34 kPa error 0.06m */
+ALT_VALUE( 45168), /* 57.60 kPa error 0.06m */
+ALT_VALUE( 44832), /* 57.86 kPa error 0.05m */
+ALT_VALUE( 44498), /* 58.11 kPa error 0.04m */
+ALT_VALUE( 44164), /* 58.37 kPa error 0.05m */
+ALT_VALUE( 43831), /* 58.62 kPa error 0.05m */
+ALT_VALUE( 43500), /* 58.88 kPa error 0.02m */
+ALT_VALUE( 43170), /* 59.14 kPa error 0.01m */
+ALT_VALUE( 42841), /* 59.39 kPa error 0.02m */
+ALT_VALUE( 42513), /* 59.65 kPa error 0.05m */
+ALT_VALUE( 42186), /* 59.90 kPa error 0.05m */
+ALT_VALUE( 41861), /* 60.16 kPa error 0.04m */
+ALT_VALUE( 41536), /* 60.42 kPa error 0.04m */
+ALT_VALUE( 41213), /* 60.67 kPa error 0.02m */
+ALT_VALUE( 40891), /* 60.93 kPa error 0.04m */
+ALT_VALUE( 40570), /* 61.18 kPa error 0.06m */
+ALT_VALUE( 40249), /* 61.44 kPa error 0.06m */
+ALT_VALUE( 39931), /* 61.70 kPa error 0.05m */
+ALT_VALUE( 39613), /* 61.95 kPa error 0.04m */
+ALT_VALUE( 39296), /* 62.21 kPa error 0.02m */
+ALT_VALUE( 38980), /* 62.46 kPa error 0.02m */
+ALT_VALUE( 38665), /* 62.72 kPa error 0.05m */
+ALT_VALUE( 38351), /* 62.98 kPa error 0.05m */
+ALT_VALUE( 38039), /* 63.23 kPa error 0.02m */
+ALT_VALUE( 37727), /* 63.49 kPa error 0.05m */
+ALT_VALUE( 37416), /* 63.74 kPa error 0.05m */
+ALT_VALUE( 37107), /* 64.00 kPa error 0.02m */
+ALT_VALUE( 36798), /* 64.26 kPa error 0.04m */
+ALT_VALUE( 36491), /* 64.51 kPa error 0.04m */
+ALT_VALUE( 36184), /* 64.77 kPa error 0.02m */
+ALT_VALUE( 35878), /* 65.02 kPa error 0.05m */
+ALT_VALUE( 35573), /* 65.28 kPa error 0.05m */
+ALT_VALUE( 35270), /* 65.54 kPa error 0.02m */
+ALT_VALUE( 34967), /* 65.79 kPa error 0.02m */
+ALT_VALUE( 34665), /* 66.05 kPa error 0.03m */
+ALT_VALUE( 34364), /* 66.30 kPa error 0.04m */
+ALT_VALUE( 34064), /* 66.56 kPa error 0.04m */
+ALT_VALUE( 33765), /* 66.82 kPa error 0.04m */
+ALT_VALUE( 33467), /* 67.07 kPa error 0.03m */
+ALT_VALUE( 33170), /* 67.33 kPa error 0.02m */
+ALT_VALUE( 32874), /* 67.58 kPa error 0.05m */
+ALT_VALUE( 32578), /* 67.84 kPa error 0.05m */
+ALT_VALUE( 32284), /* 68.10 kPa error 0.05m */
+ALT_VALUE( 31990), /* 68.35 kPa error 0.05m */
+ALT_VALUE( 31698), /* 68.61 kPa error 0.02m */
+ALT_VALUE( 31406), /* 68.86 kPa error 0.02m */
+ALT_VALUE( 31115), /* 69.12 kPa error 0.02m */
+ALT_VALUE( 30825), /* 69.38 kPa error 0.01m */
+ALT_VALUE( 30536), /* 69.63 kPa error 0.03m */
+ALT_VALUE( 30248), /* 69.89 kPa error 0.03m */
+ALT_VALUE( 29960), /* 70.14 kPa error 0.04m */
+ALT_VALUE( 29674), /* 70.40 kPa error 0.04m */
+ALT_VALUE( 29388), /* 70.66 kPa error 0.02m */
+ALT_VALUE( 29103), /* 70.91 kPa error 0.02m */
+ALT_VALUE( 28819), /* 71.17 kPa error 0.04m */
+ALT_VALUE( 28536), /* 71.42 kPa error 0.04m */
+ALT_VALUE( 28253), /* 71.68 kPa error 0.05m */
+ALT_VALUE( 27971), /* 71.94 kPa error 0.05m */
+ALT_VALUE( 27691), /* 72.19 kPa error 0.04m */
+ALT_VALUE( 27411), /* 72.45 kPa error 0.05m */
+ALT_VALUE( 27131), /* 72.70 kPa error 0.05m */
+ALT_VALUE( 26853), /* 72.96 kPa error 0.04m */
+ALT_VALUE( 26575), /* 73.22 kPa error 0.04m */
+ALT_VALUE( 26299), /* 73.47 kPa error 0.05m */
+ALT_VALUE( 26022), /* 73.73 kPa error 0.05m */
+ALT_VALUE( 25747), /* 73.98 kPa error 0.03m */
+ALT_VALUE( 25473), /* 74.24 kPa error 0.03m */
+ALT_VALUE( 25199), /* 74.50 kPa error 0.01m */
+ALT_VALUE( 24926), /* 74.75 kPa error 0.03m */
+ALT_VALUE( 24654), /* 75.01 kPa error 0.03m */
+ALT_VALUE( 24382), /* 75.26 kPa error 0.05m */
+ALT_VALUE( 24111), /* 75.52 kPa error 0.05m */
+ALT_VALUE( 23841), /* 75.78 kPa error 0.05m */
+ALT_VALUE( 23572), /* 76.03 kPa error 0.03m */
+ALT_VALUE( 23304), /* 76.29 kPa error 0.03m */
+ALT_VALUE( 23036), /* 76.54 kPa error 0.02m */
+ALT_VALUE( 22769), /* 76.80 kPa error 0.05m */
+ALT_VALUE( 22502), /* 77.06 kPa error 0.05m */
+ALT_VALUE( 22237), /* 77.31 kPa error 0.01m */
+ALT_VALUE( 21972), /* 77.57 kPa error 0.02m */
+ALT_VALUE( 21708), /* 77.82 kPa error 0.02m */
+ALT_VALUE( 21444), /* 78.08 kPa error 0.04m */
+ALT_VALUE( 21181), /* 78.34 kPa error 0.04m */
+ALT_VALUE( 20919), /* 78.59 kPa error 0.03m */
+ALT_VALUE( 20658), /* 78.85 kPa error 0.01m */
+ALT_VALUE( 20397), /* 79.10 kPa error 0.01m */
+ALT_VALUE( 20137), /* 79.36 kPa error 0.03m */
+ALT_VALUE( 19878), /* 79.62 kPa error 0.03m */
+ALT_VALUE( 19619), /* 79.87 kPa error 0.01m */
+ALT_VALUE( 19361), /* 80.13 kPa error 0.04m */
+ALT_VALUE( 19104), /* 80.38 kPa error 0.04m */
+ALT_VALUE( 18847), /* 80.64 kPa error 0.02m */
+ALT_VALUE( 18591), /* 80.90 kPa error 0.04m */
+ALT_VALUE( 18335), /* 81.15 kPa error 0.04m */
+ALT_VALUE( 18081), /* 81.41 kPa error 0.05m */
+ALT_VALUE( 17827), /* 81.66 kPa error 0.04m */
+ALT_VALUE( 17573), /* 81.92 kPa error 0.03m */
+ALT_VALUE( 17320), /* 82.18 kPa error 0.03m */
+ALT_VALUE( 17068), /* 82.43 kPa error 0.04m */
+ALT_VALUE( 16817), /* 82.69 kPa error 0.04m */
+ALT_VALUE( 16566), /* 82.94 kPa error 0.04m */
+ALT_VALUE( 16315), /* 83.20 kPa error 0.04m */
+ALT_VALUE( 16066), /* 83.46 kPa error 0.03m */
+ALT_VALUE( 15817), /* 83.71 kPa error 0.03m */
+ALT_VALUE( 15568), /* 83.97 kPa error 0.05m */
+ALT_VALUE( 15320), /* 84.22 kPa error 0.05m */
+ALT_VALUE( 15073), /* 84.48 kPa error 0.03m */
+ALT_VALUE( 14827), /* 84.74 kPa error 0.04m */
+ALT_VALUE( 14581), /* 84.99 kPa error 0.03m */
+ALT_VALUE( 14335), /* 85.25 kPa error 0.05m */
+ALT_VALUE( 14090), /* 85.50 kPa error 0.05m */
+ALT_VALUE( 13846), /* 85.76 kPa error 0.03m */
+ALT_VALUE( 13603), /* 86.02 kPa error 0.04m */
+ALT_VALUE( 13360), /* 86.27 kPa error 0.04m */
+ALT_VALUE( 13117), /* 86.53 kPa error 0.03m */
+ALT_VALUE( 12875), /* 86.78 kPa error 0.03m */
+ALT_VALUE( 12634), /* 87.04 kPa error 0.03m */
+ALT_VALUE( 12393), /* 87.30 kPa error 0.03m */
+ALT_VALUE( 12153), /* 87.55 kPa error 0.04m */
+ALT_VALUE( 11914), /* 87.81 kPa error 0.05m */
+ALT_VALUE( 11675), /* 88.06 kPa error 0.04m */
+ALT_VALUE( 11436), /* 88.32 kPa error 0.02m */
+ALT_VALUE( 11198), /* 88.58 kPa error 0.02m */
+ALT_VALUE( 10961), /* 88.83 kPa error 0.01m */
+ALT_VALUE( 10724), /* 89.09 kPa error 0.01m */
+ALT_VALUE( 10488), /* 89.34 kPa error 0.02m */
+ALT_VALUE( 10252), /* 89.60 kPa error 0.02m */
+ALT_VALUE( 10017), /* 89.86 kPa error 0.04m */
+ALT_VALUE( 9782), /* 90.11 kPa error 0.04m */
+ALT_VALUE( 9548), /* 90.37 kPa error 0.04m */
+ALT_VALUE( 9315), /* 90.62 kPa error 0.02m */
+ALT_VALUE( 9082), /* 90.88 kPa error 0.04m */
+ALT_VALUE( 8849), /* 91.14 kPa error 0.05m */
+ALT_VALUE( 8617), /* 91.39 kPa error 0.05m */
+ALT_VALUE( 8386), /* 91.65 kPa error 0.02m */
+ALT_VALUE( 8155), /* 91.90 kPa error 0.02m */
+ALT_VALUE( 7925), /* 92.16 kPa error 0.02m */
+ALT_VALUE( 7695), /* 92.42 kPa error 0.04m */
+ALT_VALUE( 7466), /* 92.67 kPa error 0.04m */
+ALT_VALUE( 7237), /* 92.93 kPa error 0.05m */
+ALT_VALUE( 7008), /* 93.18 kPa error 0.05m */
+ALT_VALUE( 6781), /* 93.44 kPa error 0.04m */
+ALT_VALUE( 6553), /* 93.70 kPa error 0.04m */
+ALT_VALUE( 6327), /* 93.95 kPa error 0.04m */
+ALT_VALUE( 6100), /* 94.21 kPa error 0.05m */
+ALT_VALUE( 5874), /* 94.46 kPa error 0.05m */
+ALT_VALUE( 5649), /* 94.72 kPa error 0.04m */
+ALT_VALUE( 5424), /* 94.98 kPa error 0.04m */
+ALT_VALUE( 5200), /* 95.23 kPa error 0.03m */
+ALT_VALUE( 4976), /* 95.49 kPa error 0.03m */
+ALT_VALUE( 4753), /* 95.74 kPa error 0.01m */
+ALT_VALUE( 4530), /* 96.00 kPa error 0.03m */
+ALT_VALUE( 4308), /* 96.26 kPa error 0.03m */
+ALT_VALUE( 4086), /* 96.51 kPa error 0.03m */
+ALT_VALUE( 3864), /* 96.77 kPa error 0.04m */
+ALT_VALUE( 3643), /* 97.02 kPa error 0.04m */
+ALT_VALUE( 3423), /* 97.28 kPa error 0.01m */
+ALT_VALUE( 3203), /* 97.54 kPa error 0.03m */
+ALT_VALUE( 2983), /* 97.79 kPa error 0.04m */
+ALT_VALUE( 2764), /* 98.05 kPa error 0.03m */
+ALT_VALUE( 2546), /* 98.30 kPa error 0.05m */
+ALT_VALUE( 2327), /* 98.56 kPa error 0.05m */
+ALT_VALUE( 2110), /* 98.82 kPa error 0.04m */
+ALT_VALUE( 1893), /* 99.07 kPa error 0.04m */
+ALT_VALUE( 1676), /* 99.33 kPa error 0.04m */
+ALT_VALUE( 1459), /* 99.58 kPa error 0.04m */
+ALT_VALUE( 1244), /* 99.84 kPa error 0.05m */
+ALT_VALUE( 1028), /* 100.10 kPa error 0.01m */
+ALT_VALUE( 813), /* 100.35 kPa error 0.04m */
+ALT_VALUE( 599), /* 100.61 kPa error 0.04m */
+ALT_VALUE( 384), /* 100.86 kPa error 0.05m */
+ALT_VALUE( 171), /* 101.12 kPa error 0.04m */
+ALT_VALUE( -42), /* 101.38 kPa error 0.04m */
+ALT_VALUE( -255), /* 101.63 kPa error 0.04m */
+ALT_VALUE( -468), /* 101.89 kPa error 0.05m */
+ALT_VALUE( -680), /* 102.14 kPa error 0.05m */
+ALT_VALUE( -891), /* 102.40 kPa error 0.01m */
+ALT_VALUE( -1102), /* 102.66 kPa error 0.02m */
+ALT_VALUE( -1313), /* 102.91 kPa error 0.02m */
+ALT_VALUE( -1523), /* 103.17 kPa error 0.02m */
+ALT_VALUE( -1733), /* 103.42 kPa error 0.02m */
+ALT_VALUE( -1942), /* 103.68 kPa error 0.02m */
+ALT_VALUE( -2151), /* 103.94 kPa error 0.03m */
+ALT_VALUE( -2360), /* 104.19 kPa error 0.03m */
+ALT_VALUE( -2568), /* 104.45 kPa error 0.05m */
+ALT_VALUE( -2776), /* 104.70 kPa error 0.05m */
+ALT_VALUE( -2983), /* 104.96 kPa error 0.03m */
+ALT_VALUE( -3190), /* 105.22 kPa error 0.03m */
+ALT_VALUE( -3396), /* 105.47 kPa error 0.03m */
+ALT_VALUE( -3602), /* 105.73 kPa error 0.03m */
+ALT_VALUE( -3808), /* 105.98 kPa error 0.03m */
+ALT_VALUE( -4013), /* 106.24 kPa error 0.03m */
+ALT_VALUE( -4218), /* 106.50 kPa error 0.03m */
+ALT_VALUE( -4423), /* 106.75 kPa error 0.04m */
+ALT_VALUE( -4627), /* 107.01 kPa error 0.04m */
+ALT_VALUE( -4830), /* 107.26 kPa error 0.04m */
+ALT_VALUE( -5034), /* 107.52 kPa error 0.04m */
+ALT_VALUE( -5237), /* 107.78 kPa error 0.04m */
+ALT_VALUE( -5439), /* 108.03 kPa error 0.03m */
+ALT_VALUE( -5641), /* 108.29 kPa error 0.03m */
+ALT_VALUE( -5843), /* 108.54 kPa error 0.04m */
+ALT_VALUE( -6044), /* 108.80 kPa error 0.04m */
+ALT_VALUE( -6245), /* 109.06 kPa error 0.03m */
+ALT_VALUE( -6446), /* 109.31 kPa error 0.01m */
+ALT_VALUE( -6646), /* 109.57 kPa error 0.01m */
+ALT_VALUE( -6846), /* 109.82 kPa error 0.04m */
+ALT_VALUE( -7045), /* 110.08 kPa error 0.05m */
+ALT_VALUE( -7245), /* 110.34 kPa error 0.05m */
+ALT_VALUE( -7443), /* 110.59 kPa error 0.04m */
+ALT_VALUE( -7642), /* 110.85 kPa error 0.05m */
+ALT_VALUE( -7840), /* 111.10 kPa error 0.05m */
+ALT_VALUE( -8037), /* 111.36 kPa error 0.04m */
+ALT_VALUE( -8234), /* 111.62 kPa error 0.04m */
+ALT_VALUE( -8431), /* 111.87 kPa error 0.03m */
+ALT_VALUE( -8628), /* 112.13 kPa error 0.03m */
+ALT_VALUE( -8824), /* 112.38 kPa error 0.04m */
+ALT_VALUE( -9020), /* 112.64 kPa error 0.04m */
+ALT_VALUE( -9215), /* 112.90 kPa error 0.01m */
+ALT_VALUE( -9410), /* 113.15 kPa error 0.02m */
+ALT_VALUE( -9605), /* 113.41 kPa error 0.02m */
+ALT_VALUE( -9799), /* 113.66 kPa error 0.02m */
+ALT_VALUE( -9993), /* 113.92 kPa error 0.02m */
+ALT_VALUE( -10187), /* 114.18 kPa error 0.02m */
+ALT_VALUE( -10380), /* 114.43 kPa error 0.01m */
+ALT_VALUE( -10573), /* 114.69 kPa error 0.04m */
+ALT_VALUE( -10766), /* 114.94 kPa error 0.04m */
+ALT_VALUE( -10958), /* 115.20 kPa error 0.03m */
+ALT_VALUE( -11150), /* 115.46 kPa error 0.03m */
+ALT_VALUE( -11341), /* 115.71 kPa error 0.05m */
+ALT_VALUE( -11532), /* 115.97 kPa error 0.05m */
+ALT_VALUE( -11723), /* 116.22 kPa error 0.03m */
+ALT_VALUE( -11914), /* 116.48 kPa error 0.02m */
+ALT_VALUE( -12104), /* 116.74 kPa error 0.01m */
+ALT_VALUE( -12294), /* 116.99 kPa error 0.04m */
+ALT_VALUE( -12483), /* 117.25 kPa error 0.04m */
+ALT_VALUE( -12673), /* 117.50 kPa error 0.04m */
+ALT_VALUE( -12861), /* 117.76 kPa error 0.04m */
+ALT_VALUE( -13050), /* 118.02 kPa error 0.01m */
+ALT_VALUE( -13238), /* 118.27 kPa error 0.01m */
+ALT_VALUE( -13426), /* 118.53 kPa error 0.05m */
+ALT_VALUE( -13614), /* 118.78 kPa error 0.05m */
+ALT_VALUE( -13801), /* 119.04 kPa error 0.04m */
+ALT_VALUE( -13988), /* 119.30 kPa error 0.04m */
+ALT_VALUE( -14174), /* 119.55 kPa error 0.03m */
+ALT_VALUE( -14360), /* 119.81 kPa error 0.03m */
+ALT_VALUE( -14546), /* 120.06 kPa error 0.00m */
diff --git a/include/heartbeat.hpp b/include/heartbeat.hpp
new file mode 100644
index 0000000..f724c8f
--- /dev/null
+++ b/include/heartbeat.hpp
@@ -0,0 +1,21 @@
+#pragma once
+
+#include "hardware/gpio.h"
+#include <stdio.h>
+#include "pico/time.h"
+
+#define HEART_RATE_HZ 5
+
+void heartbeat_initialize(int gpio);
+
+#if (USE_FREERTOS == 1)
+#include "FreeRTOS.h"
+#include "FreeRTOSConfig.h"
+#include "portmacro.h"
+#include "projdefs.h"
+#include "serial.hpp"
+#include "task.h"
+#include "semphr.h"
+
+void heartbeat_task( void *pvParameters );
+#endif
diff --git a/include/iim42653.hpp b/include/iim42653.hpp
new file mode 100644
index 0000000..ac64edc
--- /dev/null
+++ b/include/iim42653.hpp
@@ -0,0 +1,177 @@
+#pragma once
+
+#include "serial.hpp"
+#include <stdint.h>
+
+#include <hardware/i2c.h>
+#include <hardware/clocks.h>
+
+#if (USE_FREERTOS == 1)
+#include "FreeRTOS.h"
+#include "FreeRTOSConfig.h"
+#include "portmacro.h"
+#include "projdefs.h"
+#include "serial.hpp"
+#include "task.h"
+#include "semphr.h"
+#endif
+
+#define IIM42653_I2C_ADDR 0x68
+#define IIM42653_CLOCK_SOURCE_SYSTEM 0x6 //Use system clock as source
+#define IIM42653_CLOCK_DIVISOR 3125 //125MHz --> 40kHz
+
+// DEVICE_CONFIG [State Configuration, SPI mode and Reset]
+#define R_IIM42653_DEVICE_CONFIG 0x11
+typedef union {
+ struct {
+ bool SOFT_RESET_CONFIG :1; //Enable/disable soft reset
+ uint8_t RESERVED :3; //Reserved
+ bool SPI_MODE :1; //SPI Mode (internal), 0/3 or 1/2
+ uint8_t RESERVED_ :3; //Reserved
+ } fields;
+ uint8_t data;
+} IIM42653_DEVICE_CONFIG;
+#define b_IIM42653_DEVICE_CONFIG_ENABLE_SOFT_RESET 0b1
+#define b_IIM42653_DEVICE_CONFIG_DISABLE_SOFT_RESET 0b0
+
+// DRIVE_CONFIG [Configuration, SPI/I2C Speed]
+#define R_IIM42653_DRIVE_CONFIG 0x13
+typedef union {
+ struct {
+ uint8_t SPI_SLEW_RATE :3; //SPI slew rate on Pin 14
+ uint8_t I2C_SLEW_RATE :3; //I2C slew rate on Pin 14
+ uint8_t RESERVED :2; //Reserved
+ } fields;
+ uint8_t data;
+} IIM42653_DRIVE_CONFIG;
+#define B_IIM42653_DRIVE_CONFIG_SLEW_20_TO_60_nS 0x00
+#define B_IIM42653_DRIVE_CONFIG_SLEW_2_TO_6_nS 0x20
+
+// TEMP_DATA1_UI - TEMP_DATA0_UI [Output, Temperature Sensor]
+#define R_IIM42653_TEMP_DATA1_UI 0x1D
+#define R_IIM42653_TEMP_DATA0_UI 0x1E
+
+// ACCEL_DATA_X1_UI - GYRO_DATA_Z0_UI [Output, 3-Axis Gyro and Accel Data]
+#define R_IIM42653_ACCEL_DATA_X1_UI 0x1F
+#define R_IIM42653_ACCEL_DATA_X0_UI 0x20
+#define R_IIM42653_ACCEL_DATA_Y1_UI 0x21
+#define R_IIM42653_ACCEL_DATA_Y0_UI 0x22
+#define R_IIM42653_ACCEL_DATA_Z1_UI 0x23
+#define R_IIM42653_ACCEL_DATA_Z0_UI 0x24
+#define R_IIM42653_GYRO_DATA_X1_UI 0x25
+#define R_IIM42653_GYRO_DATA_X0_UI 0x26
+#define R_IIM42653_GYRO_DATA_Y1_UI 0x27
+#define R_IIM42653_GYRO_DATA_Y0_UI 0x28
+#define R_IIM42653_GYRO_DATA_Z1_UI 0x29
+#define R_IIM42653_GYRO_DATA_Z0_UI 0x2A
+#define S_IIM42653_ACCEL_SENSITIVITY_FACTOR 1024.0f
+#define S_IIM42653_GYRO_SENSITIVITY_FACTOR 8.2f
+
+// PWR_MGMT0 [State Configuration, Sensor enabling]
+#define R_IIM42653_PWR_MGMT0 0x4E
+typedef union {
+ struct {
+ uint8_t ACCEL_MODE :2; //Accelerometer power mode
+ uint8_t GYRO_MODE :2; //Gyroscope power mode
+ bool IDLE :1; //Run RC oscillator even if Accel/Gyro are off
+ bool TEMP_DIS :1; //Disable the temperature sensor
+ bool S4S_ENABLE :1; //Enable synchronous timing control (???) with custom command
+ bool RESERVED :1; //Reserved
+ } fields;
+ uint8_t data;
+} IIM42653_PWR_MGMT0;
+#define B_IIM42653_PWR_MGMT0_ACCEL_MODE_OFF 0x00
+#define B_IIM42653_PWR_MGMT0_ACCEL_MODE_LOW_NOISE 0x03
+#define B_IIM42653_PWR_MGMT0_GYRO_MODE_OFF 0x00
+#define B_IIM42653_PWR_MGMT0_GYRO_MODE_LOW_NOISE 0x03
+#define B_IIM42653_PWR_MGMT0_TEMP_DISABLE 0b1
+#define B_IIM42653_PWR_MGMT0_TEMP_ENABLE 0b0
+
+// GYRO_CONFIG0 [Configuration, Sensor FSR/ODR]
+#define R_IIM42653_GYRO_CONFIG0 0x4F
+typedef union {
+ struct {
+ uint8_t GYRO_ODR :4; //ODR, see datasheet for range
+ bool RESERVED :1; //Reserved
+ uint8_t GYRO_UI_FS_SEL :3; //FSR, see datasheet for range
+ } fields;
+ uint8_t data;
+} IIM42653_GYRO_CONFIG0;
+#define B_IIM42653_GYRO_CONFIG0_ODR_100HZ 0x08
+#define B_IIM42653_GYRO_CONFIG0_ODR_200HZ 0x07
+#define B_IIM42653_GYRO_CONFIG0_ODR_500HZ 0x0F
+#define B_IIM42653_GYRO_CONFIG0_FSR_4000DPS 0x00
+#define B_IIM42653_GYRO_CONFIG0_FSR_250DPS 0x04
+
+// ACCEL_CONFIG0 [Configuration, Sensor FSR/ODR]
+#define R_IIM42653_ACCEL_CONFIG0 0x50
+typedef union {
+ struct {
+ uint8_t ACCEL_ODR :4; //ODR, see datasheet for range
+ bool RESERVED :1; //Reserved
+ uint8_t ACCEL_UI_FS_SEL :3; //FSR, see datasheet for range
+ } fields;
+ uint8_t data;
+} IIM42653_ACCEL_CONFIG0;
+#define B_IIM42653_ACCEL_CONFIG0_ODR_100HZ 0x08
+#define B_IIM42653_ACCEL_CONFIG0_ODR_200HZ 0x07
+#define B_IIM42653_ACCEL_CONFIG0_ODR_500HZ 0x0F
+#define B_IIM42653_ACCEL_CONFIG0_FSR_32G 0x00
+#define B_IIM42653_ACCEL_CONFIG_FSR_4G 0x03
+
+// WHO_AM_I [Validation]
+#define R_IIM42653_WHO_AM_I 0x75
+#define B_IIM42653_WHO_AM_I_VALUE 0x56
+
+#define IIM42653_SAMPLE_RATE_HZ 500
+
+class IIM42653 {
+ public:
+ IIM42653(i2c_inst_t* i2c) : i2c {i2c} {};
+
+ void initialize();
+
+ void calibrate_gyro();
+
+ void sample();
+
+ void apply_gyro_offset();
+
+ int16_t get_ax() { return ax; }
+ int16_t get_ay() { return ay; }
+ int16_t get_az() { return az; }
+ int16_t get_gx() { return gx; }
+ int16_t get_gy() { return gy; }
+ int16_t get_gz() { return gz; }
+
+ static float scale_accel(int16_t unscaled) { return ((float) unscaled) / S_IIM42653_ACCEL_SENSITIVITY_FACTOR; }
+ static float scale_gyro(int16_t unscaled) { return ((float) unscaled) / S_IIM42653_GYRO_SENSITIVITY_FACTOR; }
+
+#if ( USE_FREERTOS == 1 )
+ static void update_iim42653_task(void* pvParameters);
+
+ TaskHandle_t update_task_handle = NULL;
+#endif
+
+ private:
+ static int16_t sat_sub(int16_t a, int16_t b);
+
+ const uint8_t addr = IIM42653_I2C_ADDR;
+
+ i2c_inst_t* i2c;
+
+ uint8_t buffer[16];
+
+ IIM42653_DEVICE_CONFIG device_config;
+ IIM42653_DRIVE_CONFIG drive_config;
+ IIM42653_PWR_MGMT0 pwr_mgmt0;
+ IIM42653_GYRO_CONFIG0 gyro_config0;
+ IIM42653_ACCEL_CONFIG0 accel_config0;
+
+ //Internal data fields
+ int16_t bias_gx = 0, bias_gy = 0, bias_gz = 0;
+ int16_t raw_gx = 0, raw_gy = 0, raw_gz = 0;
+ int16_t ax, ay, az, gx, gy, gz;
+
+ const int64_t n_gyro_bias_readings = 50;
+};
diff --git a/include/imu.hpp b/include/imu.hpp
deleted file mode 100644
index a1b72ef..0000000
--- a/include/imu.hpp
+++ /dev/null
@@ -1,207 +0,0 @@
-#pragma once
-
-#include <stdint.h>
-#include "hardware/i2c.h"
-
-#include <Eigen/Dense>
-
-
-#define BNO055_NUM_OFFSET_REGISTERS 22
-
-
-typedef enum {
- CONFIG = 0x00,
- ACCELERATON_ONLY = 0x01,
- MAGNETOMETER_ONLY = 0x02,
- GYROSCOPE_ONLY = 0x03,
- ACCEL_MAG = 0x04,
- ACCEL_GYRO = 0x05,
- MAG_GYRO = 0x06,
- ACCEL_MAG_GYRO = 0x07,
- IMU_PLUS = 0x08,
- COMPASS = 0x09,
- M4G = 0x0A,
- NDOF_FMC_OFF = 0x0B,
- NDOF = 0x0C
-} imu_opmode_t;
-
-typedef enum {
- PAGE_ID = 0x07,
-
- CHIP_ID = 0x00,
- ACCEL_REV_ID = 0x01,
- MAG_REV_ID = 0x02,
- GYRO_REV_ID = 0x03,
- SW_REV_ID_LSB = 0x04,
- SW_REV_ID_MSB = 0x05,
- BL_REV_ID = 0x06,
-
- ACCELERATION_X_LSB = 0x08,
- ACCELERATION_X_MSB = 0x09,
- ACCELERATION_Y_LSB = 0x0A,
- ACCELERATION_Y_MSB = 0x0B,
- ACCELERATION_Z_LSB = 0x0C,
- ACCELERATION_Z_MSB = 0x0D,
-
- MAGNETOMETER_X_LSB = 0x0E,
- MAGNETOMETER_X_MSB = 0x0F,
- MAGNETOMETER_Y_LSB = 0x10,
- MAGNETOMETER_Y_MSB = 0x11,
- MAGNETOMETER_Z_LSB = 0x12,
- MAGNETOMETER_Z_MSB = 0x13,
-
- GYROSCOPE_X_LSB = 0x14,
- GYROSCOPE_X_MSB = 0x15,
- GYROSCOPE_Y_LSB = 0x16,
- GYROSCOPE_Y_MSB = 0x17,
- GYROSCOPE_Z_LSB = 0x18,
- GYROSCOPE_Z_MSB = 0x19,
-
- EULER_H_LSB = 0x1A,
- EULER_H_MSB = 0x1B,
- EULER_R_LSB = 0x1C,
- EULER_R_MSB = 0x1D,
- EULER_P_LSB = 0x1E,
- EULER_P_MSB = 0x1F,
-
- QUATERNION_W_LSB = 0x20,
- QUATERNION_W_MSB = 0x21,
- QUATERNION_X_LSB = 0x22,
- QUATERNION_X_MSB = 0x23,
- QUATERNION_Y_LSB = 0x24,
- QUATERNION_Y_MSB = 0x25,
- QUATERNION_Z_LSB = 0x26,
- QUATERNION_Z_MSB = 0x27,
-
- LINEAR_ACCELERATION_X_LSB = 0x28,
- LINEAR_ACCELERATION_X_MSB = 0x29,
- LINEAR_ACCELERATION_Y_LSB = 0x2A,
- LINEAR_ACCELERATION_Y_MSB = 0x2B,
- LINEAR_ACCELERATION_Z_LSB = 0x2C,
- LINEAR_ACCELERATION_Z_MSB = 0x2D,
-
- GRAVITY_X_LSB = 0x2E,
- GRAVITY_X_MSB = 0x2F,
- GRAVITY_Y_LSB = 0x30,
- GRAVITY_Y_MSB = 0x31,
- GRAVITY_Z_LSB = 0x32,
- GRAVITY_Z_MSB = 0x33,
-
- TEMPERATURE = 0x34,
-
- CALIBRATION_STATUS = 0x35,
- SELF_TEST_RESULT = 0x36,
- INTERRUPT_STATUS = 0x37,
-
- SYS_CLK_STATUS = 0x38,
- SYS_STATUS = 0x39,
- SYS_ERROR = 0x3A,
-
- UNIT_SELECTION = 0x3B,
-
- OPERATION_MODE = 0x3D,
- POWER_MODE = 0x3E,
-
- SYS_TRIGGER = 0x3F,
- TEMP_SOURCE = 0x40,
-
- AXIS_MAP_CONFIG = 0x41,
- AXIS_MAP_SIGN = 0x42,
-
- SIC_MATRIX_0_LSB = 0x43,
- SIC_MATRIX_0_MSB = 0x44,
- SIC_MATRIX_1_LSB = 0x45,
- SIC_MATRIX_1_MSB = 0x46,
- SIC_MATRIX_2_LSB = 0x47,
- SIC_MATRIX_2_MSB = 0x48,
- SIC_MATRIX_3_LSB = 0x49,
- SIC_MATRIX_3_MSB = 0x4A,
- SIC_MATRIX_4_LSB = 0x4B,
- SIC_MATRIX_4_MSB = 0x4C,
- SIC_MATRIX_5_LSB = 0x4D,
- SIC_MATRIX_5_MSB = 0x4E,
- SIC_MATRIX_6_LSB = 0x4F,
- SIC_MATRIX_6_MSB = 0x50,
- SIC_MATRIX_7_LSB = 0x51,
- SIC_MATRIX_7_MSB = 0x52,
- SIC_MATRIX_8_LSB = 0x53,
- SIC_MATRIX_8_MSB = 0x54,
-
- ACCELERATION_OFFSET_X_LSB = 0x55,
- ACCELERATION_OFFSET_X_MSB = 0x56,
- ACCELERATION_OFFSET_Y_LSB = 0x57,
- ACCELERATION_OFFSET_Y_MSB = 0x58,
- ACCELERATION_OFFSET_Z_LSB = 0x59,
- ACCELERATION_OFFSET_Z_MSB = 0x5A,
-
- MAGNETOMETER_OFFSET_X_LSB = 0x5B,
- MAGNETOMETER_OFFSET_X_MSB = 0x5C,
- MAGNETOMETER_OFFSET_Y_LSB = 0x5D,
- MAGNETOMETER_OFFSET_Y_MSB = 0x5E,
- MAGNETOMETER_OFFSET_Z_LSB = 0x5F,
- MAGNETOMETER_OFFSET_Z_MSB = 0x60,
-
- GYROSCOPE_OFFSET_X_LSB = 0x61,
- GYROSCOPE_OFFSET_X_MSB = 0x62,
- GYROSCOPE_OFFSET_Y_LSB = 0x63,
- GYROSCOPE_OFFSET_Y_MSB = 0x64,
- GYROSCOPE_OFFSET_Z_LSB = 0x65,
- GYROSCOPE_OFFSET_Z_MSB = 0x66,
-
- ACCEL_RADIUS_LSB = 0x67,
- ACCEL_RADIUS_MSB = 0x68,
- MAG_RADIUS_LSB = 0x69,
- MAG_RADIUS_MSB = 0x6A,
-
- RESET_INTERRUPT = 0x01,
-
- NO_MOTION_INTERRUPT = 0x00,
- SLOW_NO_MOTION_INTERRUPT = 0x01,
- THRESHOLD_INTERRUPT = 0x02,
-} imu_reg_t;
-
-typedef enum {
- NORMAL = 0x00,
- LOW_POWER = 0x01,
- SUSPEND = 0x02
-} imu_power_mode_t;
-
-typedef struct {
- uint8_t sys;
- uint8_t gyro;
- uint8_t accel;
- uint8_t mag;
-} calibration_status_t ;
-
-class imu {
- private:
- i2c_inst_t* inst;
- uint8_t addr;
- uint8_t id;
- imu_opmode_t mode;
-
- uint8_t buffer[10];
- uint8_t accel_buffer[6];
- uint8_t quat_buffer[8];
-
- void read_register(uint8_t reg, size_t len, uint8_t* buffer);
-
- public:
- imu(i2c_inst_t* inst, uint8_t addr, uint8_t id, imu_opmode_t mode);
-
- void initialize();
-
- void reset();
-
- void linear_acceleration(Eigen::Vector3f& vec);
-
- void quaternion(Eigen::Vector4f& vec);
-
- void quaternion_euler(Eigen::Vector3f& angles, Eigen::Vector4f& quat);
-
- void calibration_status(calibration_status_t* status);
-
- uint32_t expose_acceleration_buffer(uint8_t** buffer);
-
- uint32_t expose_quaternion_buffer(uint8_t** buffer);
-};
diff --git a/include/libfixkalman b/include/libfixkalman
new file mode 160000
+Subproject 77d3e745793ce993a0c4fc01fa3982cb03ea631
diff --git a/include/libfixmath b/include/libfixmath
new file mode 160000
+Subproject d308e466e1a09118d03f677c52e5fbf402f6fdd
diff --git a/include/libfixmatrix b/include/libfixmatrix
new file mode 160000
+Subproject a8d583e4fe1fa27ba2e0ec55970f73a1b1e6928
diff --git a/include/log_format.hpp b/include/log_format.hpp
new file mode 100644
index 0000000..013f9a4
--- /dev/null
+++ b/include/log_format.hpp
@@ -0,0 +1,69 @@
+#pragma once
+
+#include <stdint.h>
+#include <inttypes.h>
+
+#include "iim42653.hpp"
+#include "adxl375.hpp"
+#include "mmc5983ma.hpp"
+#include "ms5607.hpp"
+extern "C" {
+#include "fix16.h"
+}
+
+
+#define PACKET_SIZE 64
+#define PAD_SECONDS 2
+#define LOG_RATE_HZ 100
+#define PAD_BUFFER_SIZE (PACKET_SIZE * PAD_SECONDS * LOG_RATE_HZ)
+
+typedef enum {
+ PAD = 0,
+ BOOST,
+ COAST,
+ APOGEE,
+ RECOVERY,
+ END
+} state_t;
+
+typedef struct {
+ // 11 bytes General time and state data
+ uint64_t time_us :64;
+ state_t state :4;
+ uint16_t temperature_chip :12;
+ uint8_t deploy_percent :8;
+
+ // 16 bytes MS5607 data
+ uint32_t pressure :24; // 3
+ int32_t altitude :24; // 3
+ int32_t altitude_filt :32; // 4
+ int32_t velocity_filt:32; // 4
+ int16_t temperature_alt :16; // 2
+
+ // 12 bytes IMU data
+ int16_t ax :16;
+ int16_t ay :16;
+ int16_t az :16;
+ int16_t gx :16;
+ int16_t gy :16;
+ int16_t gz :16;
+
+ // 6 bytes MAG data
+ int16_t mag_x :16;
+ int16_t mag_y :16;
+ int16_t mag_z :16;
+
+ // 6 bytes High G Accel data
+ int16_t high_g_x :16;
+ int16_t high_g_y :16;
+ int16_t high_g_z :16;
+
+ // 12 bytes controls information
+ int32_t drag_force: 32; // 4
+ int32_t apogee_prediction: 32; // 4
+ int32_t desired_drag_force: 32; // 4
+
+ uint8_t data0: 8;
+} __attribute__((packed)) log_entry_t;
+
+void print_log_entry(const uint8_t* entry);
diff --git a/include/mmc5983ma.hpp b/include/mmc5983ma.hpp
new file mode 100644
index 0000000..825db8d
--- /dev/null
+++ b/include/mmc5983ma.hpp
@@ -0,0 +1,168 @@
+#pragma once
+
+#include "hardware/gpio.h"
+#include "hardware/i2c.h"
+#include "serial.hpp"
+
+#if ( DEBUG == 1 )
+#include <stdio.h>
+#include <inttypes.h>
+#include "pico/stdio.h"
+#endif
+
+#if ( USE_FREERTOS == 1)
+#include "FreeRTOS.h"
+#include "FreeRTOSConfig.h"
+#include "portmacro.h"
+#include "projdefs.h"
+#include "serial.hpp"
+#include "task.h"
+#include "semphr.h"
+#endif
+
+#define MMC5983MA_I2C_ADDR 0x30
+
+#define R_MMC5983MA_XOUT0 0x00
+#define R_MMC5983MA_XOUT1 0x01
+#define R_MMC5983MA_YOUT0 0x02
+#define R_MMC5983MA_YOUT1 0x03
+#define R_MMC5983MA_ZOUT0 0x04
+#define R_MMC5983MA_ZOUT1 0x05
+#define R_MMC5983MA_XYZOUT2 0x06
+#define R_MMC5983MA_TEMPERATURE_OUT 0x07
+#define S_MMC5983MA_SCALE_FACTOR_16BIT 4096
+#define S_MMC5983MA_SCALE_FACTOR_18BIT 16384
+
+#define R_MMC5983MA_DEV_STATUS 0x08
+typedef union {
+ struct {
+ bool MEAS_M_DONE :1;
+ bool MEAS_T_DONE :1;
+ uint8_t RESERVED0 :2;
+ bool OTP_READ_DONE :1;
+ uint8_t RESERVED1 :3;
+ } fields;
+ uint8_t data;
+} MMC5983MA_DEV_STATUS;
+
+#define R_MMC5983MA_INTERNAL_CTL0 0x09
+typedef union {
+ struct {
+ bool TAKE_MAG_MEAS :1;
+ bool TAKE_TEMP_MEAS :1;
+ bool MEAS_INT_ENABLE :1;
+ bool SET_CMD :1;
+ bool RESET_CMD :1;
+ bool AUTO_SR_ENABLE :1;
+ bool OTP_READ :1;
+ uint8_t RESERVED :1;
+ } fields;
+ uint8_t data;
+} MMC5983MA_INTERNAL_CTL0;
+
+#define R_MMC5983MA_INTERNAL_CTL1 0x0A
+typedef union {
+ struct {
+ uint8_t BANDWIDTH: 2;
+ bool X_INHIBIT: 1;
+ bool Y_INHIBIT: 1;
+ bool Z_INHIBIT: 1;
+ uint8_t RESERVED :2;
+ bool RESTART :1;
+ } fields;
+ uint8_t data;
+} MMC5983MA_INTERNAL_CTL1;
+#define B_MMC5983MA_BANDWIDTH_100HZ 0b00
+#define B_MMC5983MA_BANDWIDTH_200HZ 0b01
+#define B_MMC5983MA_BANDWIDTH_400HZ 0b10
+#define B_MMC5983MA_BANDWIDTH_800HZ 0b11
+
+#define R_MMC5983MA_INTERNAL_CTL2 0x0B
+typedef union {
+ struct {
+ bool CONTINUOUS_MODE_FREQ :3;
+ bool CONTINUOUS_MODE_ENABLE :1;
+ uint8_t PERIODIC_SET_RATE :3;
+ bool PERIODIC_SET_ENABLE :1;
+ } fields;
+ uint8_t data;
+} MMC5983MA_INTERNAL_CTL2;
+#define B_MMC5983_CONTINUOUS_MODE_OFF 0b000
+#define B_MMC5983_CONTINUOUS_MODE_FREQ_1HZ 0b001
+#define B_MMC5983_CONTINUOUS_MODE_FREQ_10HZ 0b010
+#define B_MMC5983_CONTINUOUS_MODE_FREQ_20HZ 0b011
+#define B_MMC5983_CONTINUOUS_MODE_FREQ_50HZ 0b100
+#define B_MMC5983_CONTINUOUS_MODE_FREQ_100HZ 0b101
+#define B_MMC5983_CONTINUOUS_MODE_FREQ_200HZ 0b110
+#define B_MMC5983_CONTINUOUS_MODE_FREQ_1000HZ 0b111
+
+#define B_MMC5983_PERIODIC_SET_RATE_MEAS_TIMES_1 0b000
+#define B_MMC5983_PERIODIC_SET_RATE_MEAS_TIMES_25 0b001
+#define B_MMC5983_PERIODIC_SET_RATE_MEAS_TIMES_75 0b010
+#define B_MMC5983_PERIODIC_SET_RATE_MEAS_TIMES_100 0b011
+#define B_MMC5983_PERIODIC_SET_RATE_MEAS_TIMES_250 0b100
+#define B_MMC5983_PERIODIC_SET_RATE_MEAS_TIMES_500 0b101
+#define B_MMC5983_PERIODIC_SET_RATE_MEAS_TIMES_1000 0b110
+#define B_MMC5983_PERIODIC_SET_RATE_MEAS_TIMES_2000 0b111
+
+#define R_MMC5983MA_INTERNAL_CTL3 0x0C
+typedef union {
+ struct {
+ uint8_t RESERVED0 :1;
+ bool ST_ENABLE_POS_NEG :1;
+ bool ST_ENABLE_NEG_POS :1;
+ uint8_t RESERVED1 :3;
+ bool SPI_3_WIRE_ENABLE :1;
+ uint8_t RESERVED2 :1;
+ } fields;
+ uint8_t data;
+} MMC5983MA_INTERNAL_CTL3;
+
+#define R_MMC5983MA_PRODUCT_ID 0x2F
+#define B_MMC5983MA_PRODUCT_ID 0x30
+
+#define MMC5983_SAMPLE_RATE_HZ 200
+
+class MMC5983MA {
+ public:
+ MMC5983MA(i2c_inst_t* i2c) : i2c {i2c} {};
+
+ void initialize();
+
+ void calibrate();
+
+ void sample();
+
+ void apply_offset();
+
+ int16_t get_ax() { return ax; }
+ int16_t get_ay() { return ay; }
+ int16_t get_az() { return az; }
+
+ static float scale_mag(int16_t unscaled) { return ((float) unscaled) / S_MMC5983MA_SCALE_FACTOR_16BIT; }
+
+#if (USE_FREERTOS == 1)
+ static void update_mmc5983ma_task(void* pvParameters);
+
+ TaskHandle_t update_task_handle = NULL;
+#endif
+
+ private:
+ static int16_t sat_sub(int16_t a, int16_t b);
+
+ const uint8_t addr = MMC5983MA_I2C_ADDR;
+
+ i2c_inst_t* i2c;
+
+ uint8_t buffer[16];
+
+ MMC5983MA_DEV_STATUS dev_status;
+ MMC5983MA_INTERNAL_CTL0 internal_ctl0;
+ MMC5983MA_INTERNAL_CTL1 internal_ctl1;
+ MMC5983MA_INTERNAL_CTL2 internal_ctl2;
+ MMC5983MA_INTERNAL_CTL3 internal_ctl3;
+
+ int16_t offset_x = 0, offset_y = 0, offset_z = 0;
+ int16_t raw_x = 0, raw_y = 0, raw_z = 0;
+ int16_t ax = 0, ay = 0, az = 0;
+};
diff --git a/include/ms5607.hpp b/include/ms5607.hpp
new file mode 100644
index 0000000..d1bdd76
--- /dev/null
+++ b/include/ms5607.hpp
@@ -0,0 +1,133 @@
+#pragma once
+
+#include <stdint.h>
+
+#include "hardware/gpio.h"
+#include "pico/stdlib.h"
+#include "hardware/i2c.h"
+
+#include "pico/time.h"
+
+#if ( USE_FREERTOS == 1 )
+#include "FreeRTOS.h"
+#include "FreeRTOSConfig.h"
+#include "portmacro.h"
+#include "projdefs.h"
+#include "task.h"
+#include "semphr.h"
+#endif
+
+#define MS5607_I2C_ADDRESS 0x77
+
+#define PROM_MANUFACTURER_RESERVED_ADDR 0x0
+#define PROM_CALIBRATION_COEFFICENT_1_ADDR 0x1
+#define PROM_CALIBRATION_COEFFICENT_2_ADDR 0x2
+#define PROM_CALIBRATION_COEFFICENT_3_ADDR 0x3
+#define PROM_CALIBRATION_COEFFICENT_4_ADDR 0x4
+#define PROM_CALIBRATION_COEFFICENT_5_ADDR 0x5
+#define PROM_CALIBRATION_COEFFICENT_6_ADDR 0x6
+#define PROM_CRC_ADDR 0x7
+
+#define OSR_CONVERT_256 0x0
+#define OSR_CONVERT_512 0x1
+#define OSR_CONVERT_1024 0x2
+#define OSR_CONVERT_2048 0x3
+#define OSR_CONVERT_4096 0x4
+
+#define OSR_256_CONVERSION_TIME_US 600
+
+#define TYPE_UNCOMPENSATED_PRESSURE 0
+#define TYPE_UNCOMPENSATED_TEMPERATURE 1
+
+#define RESET_COMMAND 0x1E
+
+#define ADC_READ_COMMAND 0x0
+
+#define ALTITUDE_SCALE_F 10.0f
+#define PRESSURE_SCALE_F 100.0f
+#define TEMPERATURE_SCALE_F 100.0f
+
+#define ALTITUDE_SCALE 10
+#define PRESSURE_SCALE 100
+#define TEMPERATURE_SCALE 100
+
+#define MS5607_SAMPLE_RATE_HZ 500
+
+typedef union {
+ struct {
+ uint8_t RESERVED: 1;
+ uint8_t ADDR_OSR: 3;
+ uint8_t TYPE :1;
+ bool PROM2 :1;
+ bool CONVERT :1;
+ bool PROM: 1;
+ } fields;
+ uint8_t data;
+} ms5607_cmd;
+
+typedef enum {
+ NOT_SAMPLING,
+ PRESSURE_CONVERT,
+ TEMPERATURE_CONVERT,
+ COMPENSATE
+} sample_state_t;
+
+class MS5607 {
+ public:
+ MS5607(i2c_inst_t* i2c) : i2c {i2c} {};
+
+ void initialize();
+
+ void ms5607_write_cmd(ms5607_cmd* cmd);
+
+ void ms5607_start_sample();
+
+ void ms5607_sample();
+
+ static int64_t ms5607_sample_callback(alarm_id_t id, void* user_data);
+#if (USE_FREERTOS == 1)
+ static void ms5607_sample_handler(void* pvParameters);
+ static void update_ms5607_task(void* pvParameters);
+#endif
+
+ int32_t pressure_to_altitude(int32_t pressure);
+
+ int32_t get_pressure() { return pressure; }
+ int32_t get_temperature() { return temperature; }
+ int32_t get_altitude() { return altitude; }
+
+ void set_threshold_altitude(int32_t threshold_altitude, alarm_callback_t callback);
+
+ void clear_threshold_altitude();
+
+#if ( USE_FREERTOS == 1 )
+ TaskHandle_t sample_handler_task_handle = NULL;
+ TaskHandle_t update_task_handle = NULL;
+#endif
+ private:
+ void ms5607_compensate();
+
+ uint8_t buffer[3];
+
+ uint16_t prom[6];
+
+ uint32_t uncompensated_pressure;
+ uint32_t uncompensated_temperature;
+
+ int32_t pressure;
+
+ int32_t temperature;
+
+ int32_t altitude;
+
+ sample_state_t sample_state;
+
+ int32_t threshold_altitude;
+
+ alarm_callback_t threshold_callback = NULL;
+
+ bool positive_crossing;
+
+ i2c_inst_t* i2c;
+ const uint8_t addr = MS5607_I2C_ADDRESS;
+};
diff --git a/include/ohio_test_data.h b/include/ohio_test_data.h
new file mode 100644
index 0000000..7e372ef
--- /dev/null
+++ b/include/ohio_test_data.h
@@ -0,0 +1,23352 @@
+#pragma once
+
+#include <fix16.h>
+#include "pico/platform.h"
+
+const fix16_t __in_flash() altitude_test_data[] = { F16(0),
+ F16(0),
+ F16(0),
+ F16(0),
+ F16(0),
+ F16(0),
+ F16(-0.0999999999999943),
+ F16(-0.0999999999999943),
+ F16(-0.0999999999999943),
+ F16(-0.0999999999999943),
+ F16(-0.0999999999999943),
+ F16(0),
+ F16(0),
+ F16(0),
+ F16(0),
+ F16(-0.0999999999999943),
+ F16(-0.0999999999999943),
+ F16(-0.0999999999999943),
+ F16(-0.0999999999999943),
+ F16(0),
+ F16(0),
+ F16(0),
+ F16(0),
+ F16(0),
+ F16(0),
+ F16(0),
+ F16(0),
+ F16(0),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0),
+ F16(0),
+ F16(0),
+ F16(0.0999999999999943),
+ F16(0),
+ F16(0.0999999999999943),
+ F16(0),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.300000000000011),
+ F16(0.300000000000011),
+ F16(0.300000000000011),
+ F16(0.300000000000011),
+ F16(0.300000000000011),
+ F16(0.300000000000011),
+ F16(0.200000000000017),
+ F16(0.300000000000011),
+ F16(0.200000000000017),
+ F16(0.300000000000011),
+ F16(0.300000000000011),
+ F16(0.200000000000017),
+ F16(0.300000000000011),
+ F16(0.300000000000011),
+ F16(0.300000000000011),
+ F16(0.200000000000017),
+ F16(0.300000000000011),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.300000000000011),
+ F16(0.300000000000011),
+ F16(0.300000000000011),
+ F16(0.300000000000011),
+ F16(0.200000000000017),
+ F16(0.300000000000011),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.300000000000011),
+ F16(0.300000000000011),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.300000000000011),
+ F16(0.300000000000011),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.300000000000011),
+ F16(0.200000000000017),
+ F16(0.300000000000011),
+ F16(0.200000000000017),
+ F16(0.300000000000011),
+ F16(0.300000000000011),
+ F16(0.300000000000011),
+ F16(0.300000000000011),
+ F16(0.300000000000011),
+ F16(0.300000000000011),
+ F16(0.300000000000011),
+ F16(0.300000000000011),
+ F16(0.300000000000011),
+ F16(0.300000000000011),
+ F16(0.300000000000011),
+ F16(0.300000000000011),
+ F16(0.300000000000011),
+ F16(0.300000000000011),
+ F16(0.300000000000011),
+ F16(0.400000000000006),
+ F16(0.400000000000006),
+ F16(0.400000000000006),
+ F16(0.400000000000006),
+ F16(0.400000000000006),
+ F16(0.400000000000006),
+ F16(0.400000000000006),
+ F16(0.5),
+ F16(0.400000000000006),
+ F16(0.400000000000006),
+ F16(0.400000000000006),
+ F16(0.400000000000006),
+ F16(0.300000000000011),
+ F16(0.300000000000011),
+ F16(0.300000000000011),
+ F16(0.300000000000011),
+ F16(0.300000000000011),
+ F16(0.300000000000011),
+ F16(0.300000000000011),
+ F16(0.300000000000011),
+ F16(0.300000000000011),
+ F16(0.400000000000006),
+ F16(0.400000000000006),
+ F16(0.400000000000006),
+ F16(0.400000000000006),
+ F16(0.400000000000006),
+ F16(0.400000000000006),
+ F16(0.400000000000006),
+ F16(0.400000000000006),
+ F16(0.400000000000006),
+ F16(0.400000000000006),
+ F16(0.400000000000006),
+ F16(0.400000000000006),
+ F16(0.400000000000006),
+ F16(0.400000000000006),
+ F16(0.300000000000011),
+ F16(0.300000000000011),
+ F16(0.300000000000011),
+ F16(0.300000000000011),
+ F16(0.300000000000011),
+ F16(0.300000000000011),
+ F16(0.300000000000011),
+ F16(0.200000000000017),
+ F16(0.300000000000011),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.200000000000017),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0),
+ F16(0),
+ F16(0),
+ F16(0),
+ F16(0),
+ F16(0),
+ F16(0),
+ F16(0),
+ F16(0),
+ F16(-0.0999999999999943),
+ F16(-0.0999999999999943),
+ F16(-0.0999999999999943),
+ F16(-0.0999999999999943),
+ F16(-0.0999999999999943),
+ F16(-0.0999999999999943),
+ F16(-0.0999999999999943),
+ F16(0),
+ F16(0),
+ F16(-0.0999999999999943),
+ F16(0),
+ F16(0),
+ F16(0),
+ F16(0),
+ F16(0),
+ F16(0),
+ F16(0),
+ F16(0),
+ F16(0),
+ F16(0),
+ F16(0),
+ F16(0),
+ F16(0),
+ F16(0.0999999999999943),
+ F16(0),
+ F16(0),
+ F16(0),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0),
+ F16(0),
+ F16(0),
+ F16(0),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.300000000000011),
+ F16(0.200000000000017),
+ F16(0.300000000000011),
+ F16(0.300000000000011),
+ F16(0.300000000000011),
+ F16(0.200000000000017),
+ F16(0.300000000000011),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.200000000000017),
+ F16(0.0999999999999943),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.200000000000017),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0.0999999999999943),
+ F16(0),
+ F16(0.0999999999999943),
+ F16(0),
+ F16(0.0999999999999943),
+ F16(0),
+ F16(0.0999999999999943),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(0.599999999999994),
+ F16(1.20000000000002),
+ F16(1.30000000000001),
+ F16(1.5),
+ F16(1.09999999999999),
+ F16(1.70000000000002),
+ F16(1.90000000000001),
+ F16(2),
+ F16(1.59999999999999),
+ F16(2.40000000000001),
+ F16(2.59999999999999),
+ F16(2.80000000000001),
+ F16(2.20000000000002),
+ F16(3.09999999999999),
+ F16(3.30000000000001),
+ F16(3.59999999999999),
+ F16(2.90000000000001),
+ F16(4.20000000000002),
+ F16(4.59999999999999),
+ F16(4.80000000000001),
+ F16(4),
+ F16(5.59999999999999),
+ F16(6),
+ F16(6.30000000000001),
+ F16(5.20000000000002),
+ F16(7.20000000000002),
+ F16(7.70000000000002),
+ F16(8.09999999999999),
+ F16(6.80000000000001),
+ F16(9.20000000000002),
+ F16(9.80000000000001),
+ F16(10.5),
+ F16(8.70000000000002),
+ F16(11.8),
+ F16(12.2),
+ F16(13),
+ F16(11.1),
+ F16(14.1),
+ F16(15.1),
+ F16(15.9),
+ F16(13.6),
+ F16(17.5),
+ F16(18.6),
+ F16(19.5),
+ F16(16.7),
+ F16(21.2),
+ F16(22.2),
+ F16(23),
+ F16(20.5),
+ F16(25.3),
+ F16(26.4),
+ F16(27.6),
+ F16(24.1),
+ F16(30),
+ F16(31.2),
+ F16(32.6),
+ F16(28.8),
+ F16(35.1),
+ F16(36.4),
+ F16(37.8),
+ F16(33.9),
+ F16(40.5),
+ F16(41.9),
+ F16(43.5),
+ F16(39.1),
+ F16(46.4),
+ F16(47.7),
+ F16(49.3),
+ F16(45),
+ F16(52.2),
+ F16(53.9),
+ F16(55.4),
+ F16(50.7),
+ F16(58.6),
+ F16(60.3),
+ F16(61.9),
+ F16(56.9),
+ F16(65.5),
+ F16(67.2),
+ F16(69.1),
+ F16(63.7),
+ F16(73),
+ F16(75),
+ F16(76.9),
+ F16(71.1),
+ F16(81),
+ F16(83),
+ F16(85),
+ F16(78.9),
+ F16(89.2),
+ F16(91.3),
+ F16(93.4),
+ F16(87.1),
+ F16(97.5),
+ F16(99.4),
+ F16(101.5),
+ F16(95.4),
+ F16(105.6),
+ F16(107.6),
+ F16(109.7),
+ F16(103.5),
+ F16(113.9),
+ F16(116.2),
+ F16(118.3),
+ F16(111.8),
+ F16(122.6),
+ F16(124.8),
+ F16(127.1),
+ F16(120.5),
+ F16(131.7),
+ F16(134),
+ F16(136.4),
+ F16(129.4),
+ F16(141.2),
+ F16(143.6),
+ F16(146.2),
+ F16(138.8),
+ F16(151.3),
+ F16(153.8),
+ F16(156.4),
+ F16(148.8),
+ F16(161.5),
+ F16(164.2),
+ F16(166.8),
+ F16(158.9),
+ F16(172.1),
+ F16(174.6),
+ F16(177.3),
+ F16(169.4),
+ F16(182.6),
+ F16(185.3),
+ F16(188),
+ F16(180),
+ F16(193.6),
+ F16(196.5),
+ F16(199.3),
+ F16(190.7),
+ F16(205.2),
+ F16(208),
+ F16(211),
+ F16(202.2),
+ F16(216.9),
+ F16(220.1),
+ F16(223.3),
+ F16(214),
+ F16(229.7),
+ F16(233),
+ F16(236.3),
+ F16(226.6),
+ F16(243),
+ F16(246.4),
+ F16(249.8),
+ F16(239.7),
+ F16(256.6),
+ F16(260.1),
+ F16(263.7),
+ F16(253.2),
+ F16(270.9),
+ F16(274.6),
+ F16(278.3),
+ F16(267.3),
+ F16(285.9),
+ F16(289.6),
+ F16(293.4),
+ F16(282.1),
+ F16(301),
+ F16(304.7),
+ F16(308.5),
+ F16(297.2),
+ F16(316.3),
+ F16(320.3),
+ F16(324.3),
+ F16(312.4),
+ F16(332.3),
+ F16(336.3),
+ F16(340.5),
+ F16(328.3),
+ F16(349),
+ F16(353.4),
+ F16(357.7),
+ F16(344.7),
+ F16(366.3),
+ F16(370.6),
+ F16(375),
+ F16(362),
+ F16(383.7),
+ F16(388.1),
+ F16(392.4),
+ F16(379.2),
+ F16(401.4),
+ F16(405.8),
+ F16(410.3),
+ F16(396.9),
+ F16(419.1),
+ F16(423.5),
+ F16(428),
+ F16(414.7),
+ F16(437),
+ F16(441.5),
+ F16(446.1),
+ F16(432.5),
+ F16(455.4),
+ F16(460.1),
+ F16(464.8),
+ F16(450.7),
+ F16(474.2),
+ F16(478.9),
+ F16(483.6),
+ F16(469.5),
+ F16(493),
+ F16(497.7),
+ F16(502.4),
+ F16(488.3),
+ F16(511.9),
+ F16(516.7),
+ F16(521.5),
+ F16(507.1),
+ F16(531.3),
+ F16(536.2),
+ F16(541.1),
+ F16(526.4),
+ F16(551.1),
+ F16(556.2),
+ F16(561.2),
+ F16(546.1),
+ F16(571.4),
+ F16(576.3),
+ F16(581.3),
+ F16(566.3),
+ F16(591.1),
+ F16(596.1),
+ F16(601.1),
+ F16(586.1),
+ F16(611.2),
+ F16(616.2),
+ F16(621.1),
+ F16(606.2),
+ F16(630.8),
+ F16(635.7),
+ F16(640.7),
+ F16(625.9),
+ F16(650.9),
+ F16(656.2),
+ F16(661.5),
+ F16(645.8),
+ F16(672.1),
+ F16(677.4),
+ F16(682.7),
+ F16(666.8),
+ F16(693.1),
+ F16(698.3),
+ F16(703.5),
+ F16(688),
+ F16(713.9),
+ F16(719.2),
+ F16(724.5),
+ F16(708.7),
+ F16(735.1),
+ F16(740.4),
+ F16(745.7),
+ F16(729.8),
+ F16(756.2),
+ F16(761.4),
+ F16(766.8),
+ F16(751),
+ F16(777.3),
+ F16(782.5),
+ F16(787.7),
+ F16(772),
+ F16(798.3),
+ F16(803.6),
+ F16(808.9),
+ F16(793.1),
+ F16(819.4),
+ F16(824.7),
+ F16(830),
+ F16(814.2),
+ F16(840.4),
+ F16(845.7),
+ F16(850.9),
+ F16(835.2),
+ F16(861.3),
+ F16(866.4),
+ F16(871.6),
+ F16(856.1),
+ F16(882.2),
+ F16(887.7),
+ F16(893),
+ F16(876.9),
+ F16(903.7),
+ F16(909),
+ F16(914.1),
+ F16(898.4),
+ F16(924.4),
+ F16(929.5),
+ F16(934.6),
+ F16(919.3),
+ F16(945.4),
+ F16(951.6),
+ F16(957.9),
+ F16(939.7),
+ F16(971.1),
+ F16(977.7),
+ F16(984.2),
+ F16(964.4),
+ F16(997.2),
+ F16(1003.9),
+ F16(1010.8),
+ F16(990.7),
+ F16(1024.6),
+ F16(1031.5),
+ F16(1038.5),
+ F16(1017.6),
+ F16(1052.5),
+ F16(1059.5),
+ F16(1066.6),
+ F16(1045.6),
+ F16(1081.4),
+ F16(1088.6),
+ F16(1096.5),
+ F16(1074.1),
+ F16(1111.6),
+ F16(1119.1),
+ F16(1126.6),
+ F16(1103.9),
+ F16(1142.1),
+ F16(1150),
+ F16(1158.1),
+ F16(1134.2),
+ F16(1174.5),
+ F16(1182.4),
+ F16(1190.3),
+ F16(1166.2),
+ F16(1206.5),
+ F16(1214.3),
+ F16(1222.3),
+ F16(1198.3),
+ F16(1238.4),
+ F16(1246.1),
+ F16(1254.1),
+ F16(1230.4),
+ F16(1269.1),
+ F16(1276.7),
+ F16(1284),
+ F16(1261.5),
+ F16(1299.2),
+ F16(1306.5),
+ F16(1313.6),
+ F16(1291.6),
+ F16(1326.6),
+ F16(1332.7),
+ F16(1338.8),
+ F16(1320.1),
+ F16(1351.3),
+ F16(1357.1),
+ F16(1363.5),
+ F16(1345),
+ F16(1374.5),
+ F16(1379.8),
+ F16(1385.5),
+ F16(1369),
+ F16(1396),
+ F16(1401.2),
+ F16(1406.8),
+ F16(1390.5),
+ F16(1417.3),
+ F16(1422.1),
+ F16(1427.1),
+ F16(1411.9),
+ F16(1436.5),
+ F16(1441.3),
+ F16(1445.4),
+ F16(1432),
+ F16(1454.8),
+ F16(1458.8),
+ F16(1463.1),
+ F16(1450.2),
+ F16(1470.9),
+ F16(1474.8),
+ F16(1478.7),
+ F16(1467.4),
+ F16(1486.2),
+ F16(1490.3),
+ F16(1493.9),
+ F16(1482.2),
+ F16(1501.5),
+ F16(1505.2),
+ F16(1508.5),
+ F16(1497.6),
+ F16(1515.4),
+ F16(1519.7),
+ F16(1523.9),
+ F16(1511.9),
+ F16(1531.6),
+ F16(1535.6),
+ F16(1539.9),
+ F16(1527.5),
+ F16(1547.5),
+ F16(1550.9),
+ F16(1555),
+ F16(1544.1),
+ F16(1562.6),
+ F16(1565.9),
+ F16(1569.5),
+ F16(1559),
+ F16(1576.7),
+ F16(1580.4),
+ F16(1584.2),
+ F16(1573.2),
+ F16(1591.6),
+ F16(1595.8),
+ F16(1599.4),
+ F16(1588.1),
+ F16(1606.5),
+ F16(1610.3),
+ F16(1613.8),
+ F16(1603.2),
+ F16(1620.8),
+ F16(1624.5),
+ F16(1628),
+ F16(1617.3),
+ F16(1635.3),
+ F16(1638.5),
+ F16(1642.2),
+ F16(1631.5),
+ F16(1649.4),
+ F16(1652.8),
+ F16(1656.9),
+ F16(1646.2),
+ F16(1663.4),
+ F16(1667.4),
+ F16(1670.8),
+ F16(1660.2),
+ F16(1677.2),
+ F16(1680.9),
+ F16(1684.1),
+ F16(1673.8),
+ F16(1691.2),
+ F16(1695.1),
+ F16(1698.5),
+ F16(1687.4),
+ F16(1704.9),
+ F16(1708.5),
+ F16(1711.9),
+ F16(1701.6),
+ F16(1718),
+ F16(1721.3),
+ F16(1724.9),
+ F16(1715.1),
+ F16(1731.7),
+ F16(1734.7),
+ F16(1738.1),
+ F16(1728.6),
+ F16(1744.8),
+ F16(1748.4),
+ F16(1751.6),
+ F16(1741.7),
+ F16(1758.5),
+ F16(1762),
+ F16(1765.3),
+ F16(1755.2),
+ F16(1771.8),
+ F16(1775.3),
+ F16(1778.7),
+ F16(1768.6),
+ F16(1785.5),
+ F16(1788.9),
+ F16(1792.3),
+ F16(1782.1),
+ F16(1798.9),
+ F16(1802.1),
+ F16(1805.4),
+ F16(1795.6),
+ F16(1811.8),
+ F16(1815.1),
+ F16(1818.4),
+ F16(1808.7),
+ F16(1824.7),
+ F16(1828),
+ F16(1831.4),
+ F16(1821.7),
+ F16(1838.1),
+ F16(1841.5),
+ F16(1844.9),
+ F16(1834.6),
+ F16(1851.5),
+ F16(1854.8),
+ F16(1858.1),
+ F16(1848.2),
+ F16(1864.7),
+ F16(1868),
+ F16(1871.2),
+ F16(1861.4),
+ F16(1877.8),
+ F16(1881),
+ F16(1884.4),
+ F16(1874.6),
+ F16(1890.9),
+ F16(1894.3),
+ F16(1897.6),
+ F16(1887.7),
+ F16(1904.1),
+ F16(1907.4),
+ F16(1910.7),
+ F16(1900.8),
+ F16(1917.1),
+ F16(1920.4),
+ F16(1923.6),
+ F16(1914),
+ F16(1929.9),
+ F16(1933),
+ F16(1936.2),
+ F16(1926.7),
+ F16(1942.5),
+ F16(1945.9),
+ F16(1949.1),
+ F16(1939.3),
+ F16(1955.3),
+ F16(1958.4),
+ F16(1961.5),
+ F16(1952.2),
+ F16(1968),
+ F16(1971.3),
+ F16(1974.5),
+ F16(1964.8),
+ F16(1980.6),
+ F16(1983.7),
+ F16(1986.9),
+ F16(1977.5),
+ F16(1993.3),
+ F16(1996.6),
+ F16(1999.6),
+ F16(1990.1),
+ F16(2005.6),
+ F16(2008.8),
+ F16(2011.9),
+ F16(2002.6),
+ F16(2018.2),
+ F16(2021.2),
+ F16(2024.4),
+ F16(2015),
+ F16(2030.7),
+ F16(2033.8),
+ F16(2036.9),
+ F16(2027.6),
+ F16(2042.9),
+ F16(2045.9),
+ F16(2049),
+ F16(2039.9),
+ F16(2055),
+ F16(2058.1),
+ F16(2061.1),
+ F16(2052),
+ F16(2067.2),
+ F16(2070.3),
+ F16(2073.5),
+ F16(2064.1),
+ F16(2079.5),
+ F16(2082.4),
+ F16(2085.4),
+ F16(2076.5),
+ F16(2091.5),
+ F16(2094.6),
+ F16(2097.6),
+ F16(2088.4),
+ F16(2103.6),
+ F16(2106.6),
+ F16(2109.7),
+ F16(2100.5),
+ F16(2115.7),
+ F16(2118.7),
+ F16(2121.7),
+ F16(2112.7),
+ F16(2127.4),
+ F16(2130.4),
+ F16(2133.3),
+ F16(2124.5),
+ F16(2139.2),
+ F16(2142.1),
+ F16(2144.9),
+ F16(2136.2),
+ F16(2150.7),
+ F16(2153.6),
+ F16(2156.6),
+ F16(2147.8),
+ F16(2162.4),
+ F16(2165.3),
+ F16(2168.2),
+ F16(2159.5),
+ F16(2174),
+ F16(2176.8),
+ F16(2179.7),
+ F16(2171.1),
+ F16(2185.6),
+ F16(2188.5),
+ F16(2191.4),
+ F16(2182.6),
+ F16(2197.2),
+ F16(2200),
+ F16(2202.8),
+ F16(2194.2),
+ F16(2208.5),
+ F16(2211.2),
+ F16(2214),
+ F16(2205.6),
+ F16(2219.7),
+ F16(2222.5),
+ F16(2225.3),
+ F16(2216.9),
+ F16(2231),
+ F16(2233.8),
+ F16(2236.6),
+ F16(2228.1),
+ F16(2242.2),
+ F16(2245),
+ F16(2247.5),
+ F16(2239.4),
+ F16(2253),
+ F16(2255.7),
+ F16(2258.4),
+ F16(2250.3),
+ F16(2263.9),
+ F16(2266.7),
+ F16(2269.5),
+ F16(2261.1),
+ F16(2275),
+ F16(2277.8),
+ F16(2280.6),
+ F16(2272.2),
+ F16(2286),
+ F16(2288.7),
+ F16(2291.4),
+ F16(2283.3),
+ F16(2297),
+ F16(2299.7),
+ F16(2302.4),
+ F16(2294.3),
+ F16(2307.8),
+ F16(2310.3),
+ F16(2312.9),
+ F16(2305.1),
+ F16(2318.2),
+ F16(2320.8),
+ F16(2323.4),
+ F16(2315.6),
+ F16(2328.7),
+ F16(2331.4),
+ F16(2333.9),
+ F16(2326),
+ F16(2339.4),
+ F16(2342.2),
+ F16(2344.7),
+ F16(2336.7),
+ F16(2349.9),
+ F16(2352.4),
+ F16(2355),
+ F16(2347.3),
+ F16(2360.2),
+ F16(2362.7),
+ F16(2365.3),
+ F16(2357.6),
+ F16(2370.4),
+ F16(2372.9),
+ F16(2375.3),
+ F16(2367.9),
+ F16(2380.4),
+ F16(2383),
+ F16(2385.5),
+ F16(2377.8),
+ F16(2390.7),
+ F16(2393.1),
+ F16(2395.6),
+ F16(2388),
+ F16(2400.6),
+ F16(2403),
+ F16(2405.5),
+ F16(2398.1),
+ F16(2410.3),
+ F16(2412.7),
+ F16(2415.3),
+ F16(2407.9),
+ F16(2420.1),
+ F16(2422.5),
+ F16(2424.9),
+ F16(2417.8),
+ F16(2429.9),
+ F16(2432.4),
+ F16(2434.8),
+ F16(2427.4),
+ F16(2439.6),
+ F16(2442.1),
+ F16(2444.4),
+ F16(2437.2),
+ F16(2449.2),
+ F16(2451.6),
+ F16(2453.9),
+ F16(2446.9),
+ F16(2458.8),
+ F16(2461),
+ F16(2463.4),
+ F16(2456.4),
+ F16(2468),
+ F16(2470.4),
+ F16(2472.8),
+ F16(2465.7),
+ F16(2477.4),
+ F16(2479.7),
+ F16(2482.1),
+ F16(2475.1),
+ F16(2486.8),
+ F16(2489.1),
+ F16(2491.4),
+ F16(2484.4),
+ F16(2496.1),
+ F16(2498.5),
+ F16(2500.9),
+ F16(2493.8),
+ F16(2505.2),
+ F16(2507.6),
+ F16(2509.8),
+ F16(2503.1),
+ F16(2514.3),
+ F16(2516.5),
+ F16(2518.8),
+ F16(2512),
+ F16(2523.5),
+ F16(2525.8),
+ F16(2528),
+ F16(2521.1),
+ F16(2532.5),
+ F16(2534.7),
+ F16(2537.1),
+ F16(2530.3),
+ F16(2541.6),
+ F16(2543.7),
+ F16(2545.9),
+ F16(2539.4),
+ F16(2550.5),
+ F16(2552.7),
+ F16(2555.1),
+ F16(2548.1),
+ F16(2559.5),
+ F16(2561.7),
+ F16(2563.8),
+ F16(2557.3),
+ F16(2568.4),
+ F16(2570.5),
+ F16(2572.8),
+ F16(2566.1),
+ F16(2577.1),
+ F16(2579.2),
+ F16(2581.4),
+ F16(2575),
+ F16(2585.7),
+ F16(2587.9),
+ F16(2590.1),
+ F16(2583.6),
+ F16(2594.4),
+ F16(2596.5),
+ F16(2598.5),
+ F16(2592.3),
+ F16(2602.8),
+ F16(2604.9),
+ F16(2607.1),
+ F16(2600.7),
+ F16(2611.2),
+ F16(2613.3),
+ F16(2615.5),
+ F16(2609.1),
+ F16(2619.5),
+ F16(2621.6),
+ F16(2623.8),
+ F16(2617.5),
+ F16(2628),
+ F16(2630),
+ F16(2632),
+ F16(2625.9),
+ F16(2636.2),
+ F16(2638.2),
+ F16(2640.2),
+ F16(2634),
+ F16(2644.1),
+ F16(2646.1),
+ F16(2648),
+ F16(2642.2),
+ F16(2652),
+ F16(2654),
+ F16(2655.9),
+ F16(2650.1),
+ F16(2659.9),
+ F16(2661.7),
+ F16(2663.7),
+ F16(2657.9),
+ F16(2667.7),
+ F16(2669.7),
+ F16(2671.5),
+ F16(2665.7),
+ F16(2675.3),
+ F16(2677.3),
+ F16(2679.3),
+ F16(2673.4),
+ F16(2683.2),
+ F16(2685.1),
+ F16(2687),
+ F16(2681.2),
+ F16(2690.9),
+ F16(2692.8),
+ F16(2694.7),
+ F16(2689),
+ F16(2698.5),
+ F16(2700.4),
+ F16(2702.2),
+ F16(2696.6),
+ F16(2706),
+ F16(2707.9),
+ F16(2709.8),
+ F16(2704),
+ F16(2713.6),
+ F16(2715.5),
+ F16(2717.4),
+ F16(2711.6),
+ F16(2721.2),
+ F16(2722.9),
+ F16(2724.6),
+ F16(2719.3),
+ F16(2728.3),
+ F16(2730.2),
+ F16(2731.9),
+ F16(2726.4),
+ F16(2735.6),
+ F16(2737.4),
+ F16(2739.3),
+ F16(2733.8),
+ F16(2742.9),
+ F16(2744.7),
+ F16(2746.5),
+ F16(2741),
+ F16(2750.1),
+ F16(2751.8),
+ F16(2753.6),
+ F16(2748.3),
+ F16(2757.2),
+ F16(2759.1),
+ F16(2760.8),
+ F16(2755.4),
+ F16(2764.3),
+ F16(2766),
+ F16(2767.7),
+ F16(2762.4),
+ F16(2771.2),
+ F16(2773),
+ F16(2774.8),
+ F16(2769.4),
+ F16(2778.3),
+ F16(2780),
+ F16(2781.7),
+ F16(2776.6),
+ F16(2785.1),
+ F16(2786.8),
+ F16(2788.4),
+ F16(2783.3),
+ F16(2791.8),
+ F16(2793.5),
+ F16(2795.1),
+ F16(2790),
+ F16(2798.4),
+ F16(2800.1),
+ F16(2801.6),
+ F16(2796.7),
+ F16(2805),
+ F16(2806.5),
+ F16(2808.2),
+ F16(2803.3),
+ F16(2811.5),
+ F16(2813.2),
+ F16(2814.9),
+ F16(2809.8),
+ F16(2818.1),
+ F16(2819.7),
+ F16(2821.3),
+ F16(2816.5),
+ F16(2824.7),
+ F16(2826.3),
+ F16(2827.9),
+ F16(2823),
+ F16(2831.1),
+ F16(2832.8),
+ F16(2834.4),
+ F16(2829.5),
+ F16(2837.4),
+ F16(2839.1),
+ F16(2840.7),
+ F16(2835.9),
+ F16(2843.7),
+ F16(2845.4),
+ F16(2847),
+ F16(2842.2),
+ F16(2850.2),
+ F16(2851.8),
+ F16(2853.3),
+ F16(2848.6),
+ F16(2856.3),
+ F16(2857.7),
+ F16(2859.3),
+ F16(2854.7),
+ F16(2862.3),
+ F16(2863.9),
+ F16(2865.4),
+ F16(2860.8),
+ F16(2868.4),
+ F16(2869.9),
+ F16(2871.5),
+ F16(2866.8),
+ F16(2874.6),
+ F16(2876.1),
+ F16(2877.6),
+ F16(2873),
+ F16(2880.6),
+ F16(2882.1),
+ F16(2883.6),
+ F16(2879.1),
+ F16(2886.5),
+ F16(2888),
+ F16(2889.4),
+ F16(2885.1),
+ F16(2892.3),
+ F16(2893.7),
+ F16(2895.1),
+ F16(2890.9),
+ F16(2898.1),
+ F16(2899.4),
+ F16(2900.8),
+ F16(2896.6),
+ F16(2903.7),
+ F16(2905.1),
+ F16(2906.5),
+ F16(2902.3),
+ F16(2909.2),
+ F16(2910.6),
+ F16(2912),
+ F16(2907.8),
+ F16(2914.8),
+ F16(2916.1),
+ F16(2917.5),
+ F16(2913.4),
+ F16(2920.2),
+ F16(2921.5),
+ F16(2922.9),
+ F16(2918.9),
+ F16(2925.4),
+ F16(2926.8),
+ F16(2928.1),
+ F16(2924.1),
+ F16(2930.7),
+ F16(2932),
+ F16(2933.3),
+ F16(2929.4),
+ F16(2935.9),
+ F16(2937.4),
+ F16(2938.7),
+ F16(2934.6),
+ F16(2941.3),
+ F16(2942.6),
+ F16(2943.8),
+ F16(2940),
+ F16(2946.3),
+ F16(2947.5),
+ F16(2948.7),
+ F16(2945.1),
+ F16(2951.2),
+ F16(2952.4),
+ F16(2953.7),
+ F16(2949.9),
+ F16(2956.1),
+ F16(2957.3),
+ F16(2958.5),
+ F16(2954.9),
+ F16(2961),
+ F16(2962.2),
+ F16(2963.4),
+ F16(2959.8),
+ F16(2965.8),
+ F16(2966.9),
+ F16(2968.1),
+ F16(2964.6),
+ F16(2970.6),
+ F16(2971.9),
+ F16(2973),
+ F16(2969.4),
+ F16(2975.4),
+ F16(2976.6),
+ F16(2977.7),
+ F16(2974.2),
+ F16(2980.1),
+ F16(2981.3),
+ F16(2982.4),
+ F16(2978.9),
+ F16(2984.8),
+ F16(2985.9),
+ F16(2987),
+ F16(2983.6),
+ F16(2989.3),
+ F16(2990.4),
+ F16(2991.5),
+ F16(2988.2),
+ F16(2993.8),
+ F16(2994.9),
+ F16(2996),
+ F16(2992.6),
+ F16(2998.2),
+ F16(2999.3),
+ F16(3000.4),
+ F16(2997.2),
+ F16(3002.5),
+ F16(3003.6),
+ F16(3004.6),
+ F16(3001.5),
+ F16(3006.8),
+ F16(3007.9),
+ F16(3008.9),
+ F16(3005.7),
+ F16(3011),
+ F16(3012),
+ F16(3013.1),
+ F16(3010),
+ F16(3015.1),
+ F16(3016.1),
+ F16(3017.3),
+ F16(3014.1),
+ F16(3019.3),
+ F16(3020.4),
+ F16(3021.4),
+ F16(3018.3),
+ F16(3023.4),
+ F16(3024.4),
+ F16(3025.4),
+ F16(3022.4),
+ F16(3027.4),
+ F16(3028.4),
+ F16(3029.4),
+ F16(3026.4),
+ F16(3031.3),
+ F16(3032.3),
+ F16(3033.3),
+ F16(3030.3),
+ F16(3035.2),
+ F16(3036.1),
+ F16(3037),
+ F16(3034.2),
+ F16(3039),
+ F16(3039.9),
+ F16(3040.9),
+ F16(3038),
+ F16(3042.8),
+ F16(3043.7),
+ F16(3044.6),
+ F16(3041.8),
+ F16(3046.4),
+ F16(3047.3),
+ F16(3048.2),
+ F16(3045.5),
+ F16(3049.9),
+ F16(3050.8),
+ F16(3051.7),
+ F16(3049),
+ F16(3053.5),
+ F16(3054.5),
+ F16(3055.5),
+ F16(3052.6),
+ F16(3057.3),
+ F16(3058.2),
+ F16(3059),
+ F16(3056.4),
+ F16(3060.8),
+ F16(3061.7),
+ F16(3062.6),
+ F16(3060),
+ F16(3064.3),
+ F16(3065.1),
+ F16(3065.8),
+ F16(3063.5),
+ F16(3067.5),
+ F16(3068.3),
+ F16(3069.1),
+ F16(3066.6),
+ F16(3070.8),
+ F16(3071.6),
+ F16(3072.4),
+ F16(3070),
+ F16(3074),
+ F16(3074.9),
+ F16(3075.7),
+ F16(3073.2),
+ F16(3077.2),
+ F16(3077.9),
+ F16(3078.7),
+ F16(3076.4),
+ F16(3080.2),
+ F16(3081.1),
+ F16(3081.8),
+ F16(3079.5),
+ F16(3083.4),
+ F16(3084.1),
+ F16(3084.9),
+ F16(3082.6),
+ F16(3086.2),
+ F16(3086.9),
+ F16(3087.6),
+ F16(3085.6),
+ F16(3089.1),
+ F16(3089.8),
+ F16(3090.6),
+ F16(3088.4),
+ F16(3091.9),
+ F16(3092.6),
+ F16(3093.3),
+ F16(3091.3),
+ F16(3094.6),
+ F16(3095.1),
+ F16(3095.8),
+ F16(3094),
+ F16(3097.2),
+ F16(3097.8),
+ F16(3098.5),
+ F16(3096.5),
+ F16(3099.9),
+ F16(3100.4),
+ F16(3101.1),
+ F16(3099.2),
+ F16(3102.3),
+ F16(3103),
+ F16(3103.5),
+ F16(3101.7),
+ F16(3104.8),
+ F16(3105.4),
+ F16(3106),
+ F16(3104.2),
+ F16(3107.3),
+ F16(3107.9),
+ F16(3108.5),
+ F16(3106.7),
+ F16(3109.7),
+ F16(3110.3),
+ F16(3110.9),
+ F16(3109.1),
+ F16(3112.1),
+ F16(3112.7),
+ F16(3113.3),
+ F16(3111.5),
+ F16(3114.4),
+ F16(3115),
+ F16(3115.5),
+ F16(3113.8),
+ F16(3116.6),
+ F16(3117.2),
+ F16(3117.8),
+ F16(3116.1),
+ F16(3119),
+ F16(3119.5),
+ F16(3120),
+ F16(3118.4),
+ F16(3121),
+ F16(3121.6),
+ F16(3122.2),
+ F16(3120.6),
+ F16(3123.2),
+ F16(3123.7),
+ F16(3124.3),
+ F16(3122.7),
+ F16(3125.4),
+ F16(3125.9),
+ F16(3126.4),
+ F16(3124.9),
+ F16(3127.3),
+ F16(3127.8),
+ F16(3128.3),
+ F16(3126.9),
+ F16(3129.3),
+ F16(3129.8),
+ F16(3130.3),
+ F16(3128.8),
+ F16(3131.3),
+ F16(3131.7),
+ F16(3132.1),
+ F16(3130.8),
+ F16(3133),
+ F16(3133.4),
+ F16(3133.9),
+ F16(3132.5),
+ F16(3134.7),
+ F16(3135.1),
+ F16(3135.5),
+ F16(3134.3),
+ F16(3136.3),
+ F16(3136.7),
+ F16(3137.1),
+ F16(3135.9),
+ F16(3137.9),
+ F16(3138.3),
+ F16(3138.6),
+ F16(3137.5),
+ F16(3139.4),
+ F16(3139.8),
+ F16(3140.2),
+ F16(3139),
+ F16(3140.9),
+ F16(3141.2),
+ F16(3141.5),
+ F16(3140.5),
+ F16(3142.2),
+ F16(3142.6),
+ F16(3143),
+ F16(3141.9),
+ F16(3143.6),
+ F16(3143.9),
+ F16(3144.3),
+ F16(3143.3),
+ F16(3144.9),
+ F16(3145.2),
+ F16(3145.5),
+ F16(3144.6),
+ F16(3146.2),
+ F16(3146.5),
+ F16(3146.7),
+ F16(3145.8),
+ F16(3147.3),
+ F16(3147.6),
+ F16(3147.9),
+ F16(3147.1),
+ F16(3148.6),
+ F16(3148.9),
+ F16(3148.9),
+ F16(3148.2),
+ F16(3149.3),
+ F16(3149.6),
+ F16(3149.8),
+ F16(3149.1),
+ F16(3150.2),
+ F16(3150.3),
+ F16(3150.6),
+ F16(3150),
+ F16(3151),
+ F16(3151.1),
+ F16(3151.3),
+ F16(3150.8),
+ F16(3151.6),
+ F16(3151.7),
+ F16(3151.9),
+ F16(3151.5),
+ F16(3152.1),
+ F16(3152.3),
+ F16(3152.5),
+ F16(3152),
+ F16(3152.7),
+ F16(3152.8),
+ F16(3152.9),
+ F16(3152.6),
+ F16(3153.2),
+ F16(3153.3),
+ F16(3153.3),
+ F16(3153.1),
+ F16(3153.5),
+ F16(3153.6),
+ F16(3153.7),
+ F16(3153.4),
+ F16(3153.8),
+ F16(3153.9),
+ F16(3153.9),
+ F16(3153.8),
+ F16(3154),
+ F16(3154.1),
+ F16(3154.2),
+ F16(3154),
+ F16(3154.3),
+ F16(3154.3),
+ F16(3154.3),
+ F16(3154.2),
+ F16(3154.4),
+ F16(3154.5),
+ F16(3154.5),
+ F16(3154.4),
+ F16(3154.5),
+ F16(3154.5),
+ F16(3154.6),
+ F16(3154.5),
+ F16(3154.7),
+ F16(3154.8),
+ F16(3154.9),
+ F16(3154.6),
+ F16(3155),
+ F16(3155),
+ F16(3155.1),
+ F16(3155),
+ F16(3155.1),
+ F16(3155.2),
+ F16(3155.2),
+ F16(3155.1),
+ F16(3155.4),
+ F16(3155.4),
+ F16(3155.4),
+ F16(3155.3),
+ F16(3155.3),
+ F16(3155.4),
+ F16(3155.4),
+ F16(3155.4),
+ F16(3155.4),
+ F16(3155.4),
+ F16(3155.3),
+ F16(3155.4),
+ F16(3155.5),
+ F16(3155.5),
+ F16(3155.5),
+ F16(3155.4),
+ F16(3155.4),
+ F16(3155.3),
+ F16(3155.3),
+ F16(3155.4),
+ F16(3155.3),
+ F16(3155.2),
+ F16(3155.2),
+ F16(3155.3),
+ F16(3155),
+ F16(3155),
+ F16(3154.9),
+ F16(3155.1),
+ F16(3154.7),
+ F16(3154.6),
+ F16(3154.4),
+ F16(3154.8),
+ F16(3154.2),
+ F16(3154.1),
+ F16(3154),
+ F16(3154.3),
+ F16(3153.7),
+ F16(3153.6),
+ F16(3153.4),
+ F16(3153.9),
+ F16(3153.2),
+ F16(3153),
+ F16(3152.9),
+ F16(3153.3),
+ F16(3152.7),
+ F16(3152.6),
+ F16(3152.5),
+ F16(3152.8),
+ F16(3152.2),
+ F16(3152.1),
+ F16(3151.9),
+ F16(3152.4),
+ F16(3151.7),
+ F16(3151.6),
+ F16(3151.4),
+ F16(3151.8),
+ F16(3151.2),
+ F16(3151),
+ F16(3150.8),
+ F16(3151.4),
+ F16(3150.5),
+ F16(3150.3),
+ F16(3150.1),
+ F16(3150.7),
+ F16(3149.8),
+ F16(3149.6),
+ F16(3149.4),
+ F16(3149.9),
+ F16(3148.9),
+ F16(3148.7),
+ F16(3148.5),
+ F16(3149.2),
+ F16(3148.1),
+ F16(3147.9),
+ F16(3147.7),
+ F16(3148.3),
+ F16(3147.3),
+ F16(3147.1),
+ F16(3146.9),
+ F16(3147.5),
+ F16(3146.5),
+ F16(3146.4),
+ F16(3146.2),
+ F16(3146.7),
+ F16(3145.6),
+ F16(3145.4),
+ F16(3145.3),
+ F16(3145.9),
+ F16(3144.8),
+ F16(3144.4),
+ F16(3144.1),
+ F16(3145),
+ F16(3143.5),
+ F16(3143.3),
+ F16(3143),
+ F16(3143.9),
+ F16(3142.4),
+ F16(3142),
+ F16(3141.8),
+ F16(3142.6),
+ F16(3141.1),
+ F16(3140.7),
+ F16(3140.4),
+ F16(3141.4),
+ F16(3139.6),
+ F16(3139.2),
+ F16(3138.8),
+ F16(3140),
+ F16(3138.1),
+ F16(3137.7),
+ F16(3137.3),
+ F16(3138.4),
+ F16(3136.5),
+ F16(3136.2),
+ F16(3135.7),
+ F16(3137),
+ F16(3135),
+ F16(3134.6),
+ F16(3134.3),
+ F16(3135.3),
+ F16(3133.5),
+ F16(3133.1),
+ F16(3132.7),
+ F16(3133.9),
+ F16(3131.9),
+ F16(3131.6),
+ F16(3131.2),
+ F16(3132.3),
+ F16(3130.5),
+ F16(3130.2),
+ F16(3129.8),
+ F16(3130.8),
+ F16(3129.1),
+ F16(3128.7),
+ F16(3128.3),
+ F16(3129.4),
+ F16(3127.6),
+ F16(3127.3),
+ F16(3126.9),
+ F16(3128),
+ F16(3126.2),
+ F16(3125.9),
+ F16(3125.5),
+ F16(3126.6),
+ F16(3124.7),
+ F16(3124.4),
+ F16(3124),
+ F16(3125.1),
+ F16(3123.2),
+ F16(3122.9),
+ F16(3122.5),
+ F16(3123.6),
+ F16(3121.8),
+ F16(3121.5),
+ F16(3121.3),
+ F16(3122.2),
+ F16(3121.6),
+ F16(3122),
+ F16(3122.6),
+ F16(3121.4),
+ F16(3123.3),
+ F16(3123),
+ F16(3122.6),
+ F16(3123.2),
+ F16(3121.7),
+ F16(3121.3),
+ F16(3121),
+ F16(3122.1),
+ F16(3120.3),
+ F16(3120),
+ F16(3119.8),
+ F16(3120.7),
+ F16(3118.8),
+ F16(3118.2),
+ F16(3117.7),
+ F16(3119.3),
+ F16(3116.7),
+ F16(3116.1),
+ F16(3115.5),
+ F16(3117.3),
+ F16(3114.6),
+ F16(3114.2),
+ F16(3113.8),
+ F16(3115),
+ F16(3113),
+ F16(3112.5),
+ F16(3112.1),
+ F16(3113.5),
+ F16(3111),
+ F16(3110.4),
+ F16(3109.9),
+ F16(3111.5),
+ F16(3108.8),
+ F16(3108.2),
+ F16(3107.6),
+ F16(3109.3),
+ F16(3106.6),
+ F16(3106.1),
+ F16(3105.6),
+ F16(3107.1),
+ F16(3104.5),
+ F16(3104),
+ F16(3103.5),
+ F16(3105),
+ F16(3102.2),
+ F16(3101.3),
+ F16(3100.2),
+ F16(3102.9),
+ F16(3097.4),
+ F16(3095.8),
+ F16(3094.9),
+ F16(3098.9),
+ F16(3093.8),
+ F16(3093.4),
+ F16(3092.8),
+ F16(3094.3),
+ F16(3091.7),
+ F16(3091),
+ F16(3090.5),
+ F16(3092.3),
+ F16(3089.4),
+ F16(3089),
+ F16(3088.6),
+ F16(3090),
+ F16(3087.9),
+ F16(3087.5),
+ F16(3087.2),
+ F16(3088.3),
+ F16(3086.6),
+ F16(3086.3),
+ F16(3085.8),
+ F16(3086.9),
+ F16(3084.9),
+ F16(3084.6),
+ F16(3084.3),
+ F16(3085.4),
+ F16(3083.8),
+ F16(3083.6),
+ F16(3083.5),
+ F16(3084.1),
+ F16(3083.1),
+ F16(3082.9),
+ F16(3082.9),
+ F16(3083.3),
+ F16(3082.5),
+ F16(3082.3),
+ F16(3082),
+ F16(3082.7),
+ F16(3081.3),
+ F16(3081.1),
+ F16(3080.8),
+ F16(3081.7),
+ F16(3080.2),
+ F16(3079.9),
+ F16(3079.6),
+ F16(3080.5),
+ F16(3078.9),
+ F16(3078.5),
+ F16(3078.2),
+ F16(3079.2),
+ F16(3077.4),
+ F16(3077),
+ F16(3076.6),
+ F16(3077.8),
+ F16(3075.9),
+ F16(3075.6),
+ F16(3075.2),
+ F16(3076.2),
+ F16(3074.3),
+ F16(3073.9),
+ F16(3073.5),
+ F16(3074.8),
+ F16(3072.7),
+ F16(3072.2),
+ F16(3071.8),
+ F16(3073),
+ F16(3071),
+ F16(3070.7),
+ F16(3070.3),
+ F16(3071.4),
+ F16(3069.6),
+ F16(3069.3),
+ F16(3069),
+ F16(3069.9),
+ F16(3068.4),
+ F16(3068.2),
+ F16(3067.8),
+ F16(3068.7),
+ F16(3067),
+ F16(3066.7),
+ F16(3066.4),
+ F16(3067.5),
+ F16(3065.7),
+ F16(3065.4),
+ F16(3065.1),
+ F16(3066.1),
+ F16(3064.5),
+ F16(3064.3),
+ F16(3064.1),
+ F16(3064.8),
+ F16(3063.7),
+ F16(3063.5),
+ F16(3063.3),
+ F16(3063.9),
+ F16(3063),
+ F16(3062.8),
+ F16(3062.7),
+ F16(3063.2),
+ F16(3062.3),
+ F16(3062.2),
+ F16(3062),
+ F16(3062.5),
+ F16(3061.5),
+ F16(3061.2),
+ F16(3060.8),
+ F16(3061.8),
+ F16(3060),
+ F16(3059.6),
+ F16(3059.1),
+ F16(3060.4),
+ F16(3058.2),
+ F16(3057.7),
+ F16(3057.2),
+ F16(3058.7),
+ F16(3056.2),
+ F16(3055.7),
+ F16(3055.1),
+ F16(3056.7),
+ F16(3053.9),
+ F16(3053.3),
+ F16(3052.6),
+ F16(3054.5),
+ F16(3051.2),
+ F16(3050.4),
+ F16(3049.6),
+ F16(3051.9),
+ F16(3048.1),
+ F16(3047.2),
+ F16(3046.5),
+ F16(3048.8),
+ F16(3045),
+ F16(3044.2),
+ F16(3043.6),
+ F16(3045.7),
+ F16(3042.1),
+ F16(3041.4),
+ F16(3040.7),
+ F16(3042.9),
+ F16(3039.4),
+ F16(3038.7),
+ F16(3038),
+ F16(3040.1),
+ F16(3036.8),
+ F16(3036.1),
+ F16(3035.5),
+ F16(3037.4),
+ F16(3034.2),
+ F16(3033.6),
+ F16(3033.2),
+ F16(3034.8),
+ F16(3032.1),
+ F16(3031.8),
+ F16(3031.3),
+ F16(3032.6),
+ F16(3030.7),
+ F16(3030.4),
+ F16(3030.3),
+ F16(3031),
+ F16(3029.6),
+ F16(3029.3),
+ F16(3029),
+ F16(3030),
+ F16(3028.3),
+ F16(3027.9),
+ F16(3027.5),
+ F16(3028.7),
+ F16(3026.6),
+ F16(3026.1),
+ F16(3025.6),
+ F16(3027.1),
+ F16(3024.7),
+ F16(3024.2),
+ F16(3023.6),
+ F16(3025.2),
+ F16(3022.5),
+ F16(3022.1),
+ F16(3021.7),
+ F16(3023.1),
+ F16(3020.8),
+ F16(3020.5),
+ F16(3020),
+ F16(3021.3),
+ F16(3019.3),
+ F16(3018.9),
+ F16(3018.7),
+ F16(3019.7),
+ F16(3017.9),
+ F16(3017.4),
+ F16(3016.9),
+ F16(3018.3),
+ F16(3015.8),
+ F16(3015.1),
+ F16(3014.4),
+ F16(3016.4),
+ F16(3013.1),
+ F16(3012.4),
+ F16(3011.8),
+ F16(3013.7),
+ F16(3010.2),
+ F16(3009.5),
+ F16(3008.8),
+ F16(3011),
+ F16(3007.2),
+ F16(3006.5),
+ F16(3005.6),
+ F16(3008),
+ F16(3004),
+ F16(3003.3),
+ F16(3002.6),
+ F16(3004.9),
+ F16(3001.2),
+ F16(3000.6),
+ F16(3000.1),
+ F16(3002),
+ F16(2999),
+ F16(2998.5),
+ F16(2998.1),
+ F16(2999.5),
+ F16(2997.1),
+ F16(2996.6),
+ F16(2996.3),
+ F16(2997.6),
+ F16(2995.4),
+ F16(2995.1),
+ F16(2994.8),
+ F16(2995.7),
+ F16(2994),
+ F16(2993.6),
+ F16(2993.3),
+ F16(2994.4),
+ F16(2992.6),
+ F16(2992.2),
+ F16(2991.8),
+ F16(2992.9),
+ F16(2990.7),
+ F16(2990.1),
+ F16(2989.6),
+ F16(2991.2),
+ F16(2988.5),
+ F16(2988),
+ F16(2987.5),
+ F16(2989),
+ F16(2986.5),
+ F16(2986.1),
+ F16(2985.6),
+ F16(2987),
+ F16(2984.5),
+ F16(2984),
+ F16(2983.6),
+ F16(2985),
+ F16(2982.5),
+ F16(2982),
+ F16(2981.5),
+ F16(2983),
+ F16(2980.4),
+ F16(2979.8),
+ F16(2979.3),
+ F16(2980.9),
+ F16(2978.2),
+ F16(2977.7),
+ F16(2977.2),
+ F16(2978.8),
+ F16(2976),
+ F16(2975.4),
+ F16(2974.8),
+ F16(2976.6),
+ F16(2973.7),
+ F16(2973.1),
+ F16(2972.6),
+ F16(2974.3),
+ F16(2971.5),
+ F16(2971),
+ F16(2970.4),
+ F16(2972),
+ F16(2969.3),
+ F16(2968.6),
+ F16(2968),
+ F16(2969.9),
+ F16(2966.8),
+ F16(2966.2),
+ F16(2965.5),
+ F16(2967.5),
+ F16(2964.4),
+ F16(2964),
+ F16(2963.6),
+ F16(2965),
+ F16(2962.6),
+ F16(2962.2),
+ F16(2961.7),
+ F16(2963.2),
+ F16(2960.8),
+ F16(2960.3),
+ F16(2959.7),
+ F16(2961.3),
+ F16(2958.6),
+ F16(2958.1),
+ F16(2957.5),
+ F16(2959.1),
+ F16(2956.3),
+ F16(2955.7),
+ F16(2955.1),
+ F16(2956.9),
+ F16(2954.1),
+ F16(2953.6),
+ F16(2953.1),
+ F16(2954.6),
+ F16(2952.1),
+ F16(2951.7),
+ F16(2951.5),
+ F16(2952.6),
+ F16(2952.3),
+ F16(2953.1),
+ F16(2953.2),
+ F16(2951.8),
+ F16(2952.2),
+ F16(2951.7),
+ F16(2951.2),
+ F16(2952.7),
+ F16(2950.2),
+ F16(2949.7),
+ F16(2949.2),
+ F16(2950.7),
+ F16(2948.4),
+ F16(2947.9),
+ F16(2947.4),
+ F16(2948.8),
+ F16(2946.6),
+ F16(2946.2),
+ F16(2945.9),
+ F16(2947),
+ F16(2945.4),
+ F16(2944.9),
+ F16(2944.3),
+ F16(2945.7),
+ F16(2943.3),
+ F16(2942.7),
+ F16(2942.2),
+ F16(2943.8),
+ F16(2941.2),
+ F16(2940.7),
+ F16(2940.2),
+ F16(2941.7),
+ F16(2939.1),
+ F16(2938.7),
+ F16(2938.2),
+ F16(2939.7),
+ F16(2937.2),
+ F16(2936.7),
+ F16(2936.2),
+ F16(2937.7),
+ F16(2935.2),
+ F16(2934.7),
+ F16(2934.2),
+ F16(2935.7),
+ F16(2933.1),
+ F16(2932.6),
+ F16(2932.1),
+ F16(2933.6),
+ F16(2930.7),
+ F16(2929.5),
+ F16(2928),
+ F16(2931.6),
+ F16(2925.1),
+ F16(2924.5),
+ F16(2924),
+ F16(2926.2),
+ F16(2923.2),
+ F16(2924.1),
+ F16(2925.7),
+ F16(2923.5),
+ F16(2928.7),
+ F16(2928.6),
+ F16(2928),
+ F16(2927.3),
+ F16(2926.8),
+ F16(2926.1),
+ F16(2925.4),
+ F16(2927.4),
+ F16(2923.8),
+ F16(2923),
+ F16(2922),
+ F16(2924.6),
+ F16(2920.5),
+ F16(2919.7),
+ F16(2918.9),
+ F16(2921.2),
+ F16(2917.3),
+ F16(2916.5),
+ F16(2915.7),
+ F16(2918.1),
+ F16(2914.2),
+ F16(2913.5),
+ F16(2912.9),
+ F16(2915),
+ F16(2911.6),
+ F16(2911),
+ F16(2910.3),
+ F16(2912.3),
+ F16(2909.1),
+ F16(2908.5),
+ F16(2907.9),
+ F16(2909.7),
+ F16(2906.7),
+ F16(2906.1),
+ F16(2905.6),
+ F16(2907.3),
+ F16(2904.3),
+ F16(2903.7),
+ F16(2903.1),
+ F16(2904.9),
+ F16(2901.8),
+ F16(2901.1),
+ F16(2900.6),
+ F16(2902.4),
+ F16(2899.3),
+ F16(2898.6),
+ F16(2897.8),
+ F16(2899.9),
+ F16(2892.9),
+ F16(2890.1),
+ F16(2887.5),
+ F16(2895.7),
+ F16(2885.6),
+ F16(2884.9),
+ F16(2884.2),
+ F16(2886.2),
+ F16(2883),
+ F16(2882.3),
+ F16(2881.6),
+ F16(2883.6),
+ F16(2880.2),
+ F16(2879.6),
+ F16(2879),
+ F16(2880.9),
+ F16(2877.9),
+ F16(2877.4),
+ F16(2876.9),
+ F16(2878.4),
+ F16(2876),
+ F16(2875.4),
+ F16(2875),
+ F16(2876.5),
+ F16(2874),
+ F16(2873.5),
+ F16(2873.1),
+ F16(2874.5),
+ F16(2872.3),
+ F16(2871.9),
+ F16(2871.5),
+ F16(2872.7),
+ F16(2870.5),
+ F16(2870),
+ F16(2869.5),
+ F16(2871),
+ F16(2868.6),
+ F16(2868.2),
+ F16(2867.7),
+ F16(2869.1),
+ F16(2866.7),
+ F16(2866.2),
+ F16(2865.6),
+ F16(2867.2),
+ F16(2864.5),
+ F16(2864),
+ F16(2863.5),
+ F16(2865.2),
+ F16(2862.3),
+ F16(2861.8),
+ F16(2861.3),
+ F16(2862.9),
+ F16(2860.3),
+ F16(2859.8),
+ F16(2859.1),
+ F16(2860.8),
+ F16(2858.1),
+ F16(2857.6),
+ F16(2857.1),
+ F16(2858.7),
+ F16(2856.2),
+ F16(2855.8),
+ F16(2855.3),
+ F16(2856.7),
+ F16(2854.1),
+ F16(2853.6),
+ F16(2853),
+ F16(2854.8),
+ F16(2851.9),
+ F16(2851.3),
+ F16(2850.9),
+ F16(2852.4),
+ F16(2849.8),
+ F16(2849.3),
+ F16(2848.7),
+ F16(2850.4),
+ F16(2847.6),
+ F16(2846.9),
+ F16(2846.3),
+ F16(2848.2),
+ F16(2845),
+ F16(2844.4),
+ F16(2843.9),
+ F16(2845.6),
+ F16(2842.7),
+ F16(2842),
+ F16(2841.5),
+ F16(2843.4),
+ F16(2840.1),
+ F16(2839.6),
+ F16(2839),
+ F16(2840.7),
+ F16(2837.8),
+ F16(2837.2),
+ F16(2836.7),
+ F16(2838.4),
+ F16(2835.5),
+ F16(2835),
+ F16(2834.4),
+ F16(2836.1),
+ F16(2833.3),
+ F16(2832.7),
+ F16(2832.1),
+ F16(2833.9),
+ F16(2831),
+ F16(2830.4),
+ F16(2829.8),
+ F16(2831.5),
+ F16(2828.7),
+ F16(2828.1),
+ F16(2827.4),
+ F16(2829.3),
+ F16(2826.1),
+ F16(2825.5),
+ F16(2825),
+ F16(2826.7),
+ F16(2823.8),
+ F16(2823.3),
+ F16(2822.8),
+ F16(2824.4),
+ F16(2821.6),
+ F16(2821.1),
+ F16(2820.6),
+ F16(2822.2),
+ F16(2819.7),
+ F16(2819.2),
+ F16(2818.8),
+ F16(2820.1),
+ F16(2818),
+ F16(2817.6),
+ F16(2817.1),
+ F16(2818.3),
+ F16(2816.3),
+ F16(2815.9),
+ F16(2815.5),
+ F16(2816.7),
+ F16(2814.7),
+ F16(2814.3),
+ F16(2813.9),
+ F16(2815.1),
+ F16(2813.1),
+ F16(2812.7),
+ F16(2812.3),
+ F16(2813.5),
+ F16(2811.6),
+ F16(2811.3),
+ F16(2810.9),
+ F16(2812),
+ F16(2810.2),
+ F16(2809.8),
+ F16(2809.5),
+ F16(2810.6),
+ F16(2808.7),
+ F16(2808.3),
+ F16(2807.9),
+ F16(2809.1),
+ F16(2806.9),
+ F16(2806.4),
+ F16(2805.9),
+ F16(2807.4),
+ F16(2804.9),
+ F16(2804.5),
+ F16(2803.9),
+ F16(2805.4),
+ F16(2802.9),
+ F16(2802.3),
+ F16(2801.8),
+ F16(2803.4),
+ F16(2800.6),
+ F16(2799.9),
+ F16(2799.4),
+ F16(2801.2),
+ F16(2798.2),
+ F16(2797.6),
+ F16(2797),
+ F16(2798.8),
+ F16(2795.7),
+ F16(2795.1),
+ F16(2794.5),
+ F16(2796.3),
+ F16(2793.1),
+ F16(2792.5),
+ F16(2791.8),
+ F16(2793.8),
+ F16(2790.5),
+ F16(2789.9),
+ F16(2789.2),
+ F16(2791.1),
+ F16(2788),
+ F16(2787.4),
+ F16(2786.8),
+ F16(2788.6),
+ F16(2785.5),
+ F16(2784.9),
+ F16(2784.2),
+ F16(2786.2),
+ F16(2782.9),
+ F16(2782.3),
+ F16(2781.6),
+ F16(2783.6),
+ F16(2780.3),
+ F16(2779.6),
+ F16(2779),
+ F16(2781),
+ F16(2778),
+ F16(2777.4),
+ F16(2776.9),
+ F16(2778.5),
+ F16(2775.9),
+ F16(2775.3),
+ F16(2774.9),
+ F16(2776.4),
+ F16(2774.1),
+ F16(2773.6),
+ F16(2773.1),
+ F16(2774.5),
+ F16(2772),
+ F16(2771.5),
+ F16(2771),
+ F16(2772.6),
+ F16(2769.9),
+ F16(2769.4),
+ F16(2768.8),
+ F16(2770.5),
+ F16(2767.8),
+ F16(2767.2),
+ F16(2766.7),
+ F16(2768.3),
+ F16(2765.6),
+ F16(2765.2),
+ F16(2764.8),
+ F16(2766.1),
+ F16(2764.2),
+ F16(2763.8),
+ F16(2763.4),
+ F16(2764.6),
+ F16(2762.4),
+ F16(2761.9),
+ F16(2761.4),
+ F16(2762.9),
+ F16(2760.5),
+ F16(2760),
+ F16(2759.5),
+ F16(2761),
+ F16(2758.6),
+ F16(2758.1),
+ F16(2757.7),
+ F16(2759),
+ F16(2756.9),
+ F16(2756.6),
+ F16(2756.3),
+ F16(2757.3),
+ F16(2755.6),
+ F16(2755.3),
+ F16(2755),
+ F16(2755.9),
+ F16(2754.4),
+ F16(2754.1),
+ F16(2753.8),
+ F16(2754.7),
+ F16(2753.1),
+ F16(2752.8),
+ F16(2752.6),
+ F16(2753.5),
+ F16(2752.1),
+ F16(2751.9),
+ F16(2751.6),
+ F16(2752.4),
+ F16(2751),
+ F16(2750.7),
+ F16(2750.5),
+ F16(2751.4),
+ F16(2749.8),
+ F16(2749.4),
+ F16(2749),
+ F16(2750.2),
+ F16(2748.1),
+ F16(2747.6),
+ F16(2747.1),
+ F16(2748.6),
+ F16(2745.9),
+ F16(2745.1),
+ F16(2744.5),
+ F16(2746.6),
+ F16(2743.3),
+ F16(2742.8),
+ F16(2742.3),
+ F16(2743.9),
+ F16(2741.2),
+ F16(2740.6),
+ F16(2740.1),
+ F16(2741.7),
+ F16(2739.1),
+ F16(2738.6),
+ F16(2738.2),
+ F16(2739.6),
+ F16(2737.2),
+ F16(2736.6),
+ F16(2736.2),
+ F16(2737.7),
+ F16(2735.2),
+ F16(2734.7),
+ F16(2734.2),
+ F16(2735.7),
+ F16(2733),
+ F16(2732.4),
+ F16(2731.8),
+ F16(2733.7),
+ F16(2730.8),
+ F16(2730.4),
+ F16(2730),
+ F16(2731.3),
+ F16(2729),
+ F16(2728.4),
+ F16(2728),
+ F16(2729.5),
+ F16(2726.8),
+ F16(2726.3),
+ F16(2726),
+ F16(2727.4),
+ F16(2725.1),
+ F16(2724.7),
+ F16(2724.3),
+ F16(2725.5),
+ F16(2723.4),
+ F16(2723),
+ F16(2722.7),
+ F16(2723.9),
+ F16(2722.1),
+ F16(2721.9),
+ F16(2721.5),
+ F16(2722.4),
+ F16(2721),
+ F16(2720.6),
+ F16(2720.2),
+ F16(2721.3),
+ F16(2719.3),
+ F16(2718.9),
+ F16(2718.4),
+ F16(2719.8),
+ F16(2717.3),
+ F16(2716.7),
+ F16(2716.3),
+ F16(2717.9),
+ F16(2716.7),
+ F16(2717.9),
+ F16(2719.2),
+ F16(2716),
+ F16(2720.1),
+ F16(2719.5),
+ F16(2718.8),
+ F16(2720.1),
+ F16(2717.5),
+ F16(2716.9),
+ F16(2716.3),
+ F16(2718.2),
+ F16(2715.1),
+ F16(2714.4),
+ F16(2713.6),
+ F16(2715.7),
+ F16(2712.1),
+ F16(2711.3),
+ F16(2710.6),
+ F16(2712.9),
+ F16(2709.2),
+ F16(2708.4),
+ F16(2707.8),
+ F16(2709.9),
+ F16(2706.5),
+ F16(2705.9),
+ F16(2705.2),
+ F16(2707.2),
+ F16(2703.9),
+ F16(2703.2),
+ F16(2702.7),
+ F16(2704.5),
+ F16(2701.3),
+ F16(2700.6),
+ F16(2699.9),
+ F16(2702.1),
+ F16(2698.5),
+ F16(2697.8),
+ F16(2697.1),
+ F16(2699.1),
+ F16(2695.9),
+ F16(2695.3),
+ F16(2694.8),
+ F16(2696.5),
+ F16(2693.6),
+ F16(2693),
+ F16(2692.6),
+ F16(2694.2),
+ F16(2691.6),
+ F16(2690.8),
+ F16(2689),
+ F16(2692.1),
+ F16(2684.4),
+ F16(2682.4),
+ F16(2681.2),
+ F16(2686.8),
+ F16(2680.1),
+ F16(2679.7),
+ F16(2679.1),
+ F16(2680.6),
+ F16(2678.1),
+ F16(2677.7),
+ F16(2677.3),
+ F16(2678.6),
+ F16(2676.5),
+ F16(2676.2),
+ F16(2675.8),
+ F16(2676.9),
+ F16(2675.1),
+ F16(2674.6),
+ F16(2674.2),
+ F16(2675.4),
+ F16(2673.1),
+ F16(2672.6),
+ F16(2672),
+ F16(2673.7),
+ F16(2670.7),
+ F16(2670.1),
+ F16(2669.5),
+ F16(2671.3),
+ F16(2668.3),
+ F16(2667.7),
+ F16(2667.3),
+ F16(2669),
+ F16(2666.1),
+ F16(2665.6),
+ F16(2665.1),
+ F16(2666.7),
+ F16(2663.9),
+ F16(2663.4),
+ F16(2663),
+ F16(2664.5),
+ F16(2662.1),
+ F16(2661.6),
+ F16(2661.2),
+ F16(2662.6),
+ F16(2660.3),
+ F16(2659.9),
+ F16(2659.4),
+ F16(2660.8),
+ F16(2658.5),
+ F16(2658),
+ F16(2657.6),
+ F16(2658.9),
+ F16(2657),
+ F16(2656.7),
+ F16(2656.4),
+ F16(2657.3),
+ F16(2655.7),
+ F16(2655.5),
+ F16(2655.2),
+ F16(2656),
+ F16(2654.4),
+ F16(2654),
+ F16(2653.6),
+ F16(2654.8),
+ F16(2652.9),
+ F16(2652.5),
+ F16(2652),
+ F16(2653.3),
+ F16(2651.3),
+ F16(2650.9),
+ F16(2650.6),
+ F16(2651.7),
+ F16(2649.9),
+ F16(2649.5),
+ F16(2649.2),
+ F16(2650.2),
+ F16(2648.4),
+ F16(2648),
+ F16(2647.6),
+ F16(2648.8),
+ F16(2646.7),
+ F16(2646.2),
+ F16(2645.7),
+ F16(2647.1),
+ F16(2644.7),
+ F16(2644.3),
+ F16(2643.7),
+ F16(2645.2),
+ F16(2642.6),
+ F16(2642.1),
+ F16(2641.5),
+ F16(2643.2),
+ F16(2640.5),
+ F16(2640),
+ F16(2639.4),
+ F16(2641),
+ F16(2638.3),
+ F16(2637.7),
+ F16(2637.2),
+ F16(2638.8),
+ F16(2636.1),
+ F16(2635.5),
+ F16(2634.9),
+ F16(2636.7),
+ F16(2633.7),
+ F16(2633.1),
+ F16(2632.5),
+ F16(2634.3),
+ F16(2631.4),
+ F16(2630.7),
+ F16(2630.1),
+ F16(2631.9),
+ F16(2628.8),
+ F16(2628.1),
+ F16(2627.4),
+ F16(2629.5),
+ F16(2626),
+ F16(2625.3),
+ F16(2624.6),
+ F16(2626.7),
+ F16(2623.1),
+ F16(2622.4),
+ F16(2621.8),
+ F16(2623.9),
+ F16(2620.4),
+ F16(2619.8),
+ F16(2619.2),
+ F16(2621.1),
+ F16(2618.1),
+ F16(2617.7),
+ F16(2617.2),
+ F16(2618.7),
+ F16(2616.2),
+ F16(2615.7),
+ F16(2615.2),
+ F16(2616.6),
+ F16(2614.3),
+ F16(2613.8),
+ F16(2613.3),
+ F16(2614.7),
+ F16(2612.5),
+ F16(2612.1),
+ F16(2611.7),
+ F16(2612.9),
+ F16(2610.9),
+ F16(2610.5),
+ F16(2610),
+ F16(2611.3),
+ F16(2609.1),
+ F16(2608.6),
+ F16(2608.2),
+ F16(2609.6),
+ F16(2607.4),
+ F16(2606.9),
+ F16(2606.4),
+ F16(2607.8),
+ F16(2605.4),
+ F16(2604.9),
+ F16(2604.4),
+ F16(2606),
+ F16(2603.4),
+ F16(2602.8),
+ F16(2602.2),
+ F16(2603.9),
+ F16(2601.2),
+ F16(2600.5),
+ F16(2600),
+ F16(2601.7),
+ F16(2598.9),
+ F16(2598.3),
+ F16(2597.8),
+ F16(2599.4),
+ F16(2596.7),
+ F16(2596.2),
+ F16(2595.8),
+ F16(2597.2),
+ F16(2594.7),
+ F16(2594.1),
+ F16(2593.5),
+ F16(2595.2),
+ F16(2592.4),
+ F16(2591.9),
+ F16(2591.4),
+ F16(2593),
+ F16(2590.4),
+ F16(2589.9),
+ F16(2589.4),
+ F16(2590.9),
+ F16(2588.6),
+ F16(2588.2),
+ F16(2587.8),
+ F16(2589),
+ F16(2587.1),
+ F16(2586.7),
+ F16(2586.3),
+ F16(2587.5),
+ F16(2585.7),
+ F16(2585.3),
+ F16(2585),
+ F16(2586),
+ F16(2584.1),
+ F16(2583.5),
+ F16(2582.9),
+ F16(2584.6),
+ F16(2581.6),
+ F16(2580.9),
+ F16(2580.3),
+ F16(2582.2),
+ F16(2579),
+ F16(2578.3),
+ F16(2577.7),
+ F16(2579.6),
+ F16(2576.4),
+ F16(2575.9),
+ F16(2575.3),
+ F16(2577),
+ F16(2574.3),
+ F16(2573.8),
+ F16(2573.3),
+ F16(2574.8),
+ F16(2572.4),
+ F16(2571.9),
+ F16(2571.5),
+ F16(2572.8),
+ F16(2570.6),
+ F16(2570.2),
+ F16(2569.7),
+ F16(2571),
+ F16(2568.9),
+ F16(2568.4),
+ F16(2568.1),
+ F16(2569.2),
+ F16(2567.2),
+ F16(2566.8),
+ F16(2566.4),
+ F16(2567.7),
+ F16(2565.5),
+ F16(2564.9),
+ F16(2564.4),
+ F16(2565.9),
+ F16(2563.2),
+ F16(2562.6),
+ F16(2562.1),
+ F16(2563.8),
+ F16(2560.9),
+ F16(2560.2),
+ F16(2559.6),
+ F16(2561.5),
+ F16(2558.4),
+ F16(2557.8),
+ F16(2557.3),
+ F16(2559),
+ F16(2556.2),
+ F16(2555.8),
+ F16(2555.2),
+ F16(2556.7),
+ F16(2554.2),
+ F16(2553.8),
+ F16(2553.2),
+ F16(2554.8),
+ F16(2552.2),
+ F16(2551.8),
+ F16(2551.4),
+ F16(2552.7),
+ F16(2550.4),
+ F16(2549.8),
+ F16(2549.4),
+ F16(2550.9),
+ F16(2548.4),
+ F16(2547.9),
+ F16(2547.3),
+ F16(2548.9),
+ F16(2546.3),
+ F16(2545.7),
+ F16(2545.1),
+ F16(2546.8),
+ F16(2544),
+ F16(2543.4),
+ F16(2542.7),
+ F16(2544.5),
+ F16(2541.5),
+ F16(2541),
+ F16(2540.4),
+ F16(2542.2),
+ F16(2539.4),
+ F16(2538.9),
+ F16(2538.5),
+ F16(2539.9),
+ F16(2537.6),
+ F16(2537.3),
+ F16(2537),
+ F16(2538.1),
+ F16(2536),
+ F16(2535.4),
+ F16(2534.9),
+ F16(2536.5),
+ F16(2533.9),
+ F16(2533.4),
+ F16(2533),
+ F16(2534.5),
+ F16(2531.8),
+ F16(2531.3),
+ F16(2530.7),
+ F16(2532.4),
+ F16(2529.6),
+ F16(2529),
+ F16(2528.5),
+ F16(2530.1),
+ F16(2527.4),
+ F16(2527),
+ F16(2526.6),
+ F16(2527.9),
+ F16(2526.4),
+ F16(2526.5),
+ F16(2526.5),
+ F16(2526.5),
+ F16(2526),
+ F16(2525.6),
+ F16(2525.2),
+ F16(2526.4),
+ F16(2524.1),
+ F16(2523.7),
+ F16(2523.2),
+ F16(2524.6),
+ F16(2522.2),
+ F16(2521.8),
+ F16(2521.4),
+ F16(2522.7),
+ F16(2520.5),
+ F16(2520),
+ F16(2519.6),
+ F16(2521),
+ F16(2518.7),
+ F16(2518.1),
+ F16(2517.7),
+ F16(2519.1),
+ F16(2516.5),
+ F16(2515.9),
+ F16(2515.4),
+ F16(2517.1),
+ F16(2514),
+ F16(2513.4),
+ F16(2512.8),
+ F16(2514.7),
+ F16(2511.6),
+ F16(2510.9),
+ F16(2510.3),
+ F16(2512.2),
+ F16(2509.1),
+ F16(2508.6),
+ F16(2508.1),
+ F16(2509.7),
+ F16(2507.2),
+ F16(2506.7),
+ F16(2506.2),
+ F16(2507.6),
+ F16(2505.3),
+ F16(2504.9),
+ F16(2504.4),
+ F16(2505.7),
+ F16(2503.2),
+ F16(2502.2),
+ F16(2501.2),
+ F16(2503.8),
+ F16(2499),
+ F16(2498.1),
+ F16(2497.4),
+ F16(2500.1),
+ F16(2496.3),
+ F16(2495.8),
+ F16(2495.3),
+ F16(2496.9),
+ F16(2494.2),
+ F16(2493.7),
+ F16(2493.2),
+ F16(2494.7),
+ F16(2492.3),
+ F16(2491.7),
+ F16(2491.3),
+ F16(2492.7),
+ F16(2490.3),
+ F16(2489.7),
+ F16(2489.1),
+ F16(2490.8),
+ F16(2488.1),
+ F16(2487.5),
+ F16(2486.9),
+ F16(2488.6),
+ F16(2485.7),
+ F16(2485.1),
+ F16(2484.5),
+ F16(2486.3),
+ F16(2483.3),
+ F16(2482.7),
+ F16(2482.1),
+ F16(2484),
+ F16(2481),
+ F16(2480.4),
+ F16(2479.8),
+ F16(2481.5),
+ F16(2478.6),
+ F16(2478.1),
+ F16(2477.4),
+ F16(2479.2),
+ F16(2476.3),
+ F16(2475.7),
+ F16(2475.1),
+ F16(2476.9),
+ F16(2474),
+ F16(2473.5),
+ F16(2472.9),
+ F16(2474.6),
+ F16(2471.8),
+ F16(2471.3),
+ F16(2470.9),
+ F16(2472.4),
+ F16(2469.9),
+ F16(2469.4),
+ F16(2469),
+ F16(2470.4),
+ F16(2468.2),
+ F16(2467.8),
+ F16(2467.4),
+ F16(2468.6),
+ F16(2466.7),
+ F16(2466.2),
+ F16(2465.7),
+ F16(2467),
+ F16(2464.8),
+ F16(2464.3),
+ F16(2463.9),
+ F16(2465.3),
+ F16(2463.1),
+ F16(2462.6),
+ F16(2462.1),
+ F16(2463.5),
+ F16(2460.9),
+ F16(2460.4),
+ F16(2459.8),
+ F16(2461.5),
+ F16(2458.7),
+ F16(2458.1),
+ F16(2457.5),
+ F16(2459.2),
+ F16(2456.5),
+ F16(2456),
+ F16(2455.5),
+ F16(2457),
+ F16(2454.5),
+ F16(2454.1),
+ F16(2453.6),
+ F16(2455),
+ F16(2452.7),
+ F16(2452.3),
+ F16(2451.9),
+ F16(2453.2),
+ F16(2451),
+ F16(2450.4),
+ F16(2450),
+ F16(2451.4),
+ F16(2449.1),
+ F16(2448.6),
+ F16(2448.2),
+ F16(2449.6),
+ F16(2447.1),
+ F16(2446.6),
+ F16(2446.2),
+ F16(2447.6),
+ F16(2445.2),
+ F16(2444.7),
+ F16(2444.1),
+ F16(2445.7),
+ F16(2443),
+ F16(2442.4),
+ F16(2441.8),
+ F16(2443.6),
+ F16(2440.8),
+ F16(2440.1),
+ F16(2439.5),
+ F16(2441.3),
+ F16(2438.1),
+ F16(2437.4),
+ F16(2436.8),
+ F16(2438.8),
+ F16(2435.5),
+ F16(2434.9),
+ F16(2434.4),
+ F16(2436.1),
+ F16(2433.3),
+ F16(2432.8),
+ F16(2432.3),
+ F16(2433.8),
+ F16(2431.4),
+ F16(2430.8),
+ F16(2430.3),
+ F16(2431.8),
+ F16(2429.3),
+ F16(2428.7),
+ F16(2428.2),
+ F16(2429.8),
+ F16(2427.2),
+ F16(2426.7),
+ F16(2426.2),
+ F16(2427.7),
+ F16(2425.3),
+ F16(2424.9),
+ F16(2424.6),
+ F16(2425.7),
+ F16(2423.9),
+ F16(2423.7),
+ F16(2423.5),
+ F16(2424.2),
+ F16(2423),
+ F16(2422.8),
+ F16(2422.6),
+ F16(2423.2),
+ F16(2422.2),
+ F16(2422),
+ F16(2421.7),
+ F16(2422.4),
+ F16(2421.1),
+ F16(2420.8),
+ F16(2420.4),
+ F16(2421.4),
+ F16(2419.6),
+ F16(2419),
+ F16(2418.6),
+ F16(2419.9),
+ F16(2417.6),
+ F16(2417.1),
+ F16(2416.5),
+ F16(2418),
+ F16(2415.3),
+ F16(2414.8),
+ F16(2414.2),
+ F16(2416),
+ F16(2413.1),
+ F16(2412.7),
+ F16(2412.5),
+ F16(2413.7),
+ F16(2413.3),
+ F16(2414.2),
+ F16(2415.1),
+ F16(2412.7),
+ F16(2414.7),
+ F16(2414.2),
+ F16(2413.6),
+ F16(2415.2),
+ F16(2412.6),
+ F16(2412.1),
+ F16(2411.5),
+ F16(2413.1),
+ F16(2410.3),
+ F16(2409.8),
+ F16(2409.3),
+ F16(2410.9),
+ F16(2408.2),
+ F16(2407.7),
+ F16(2407.2),
+ F16(2408.7),
+ F16(2406.2),
+ F16(2405.6),
+ F16(2405),
+ F16(2406.7),
+ F16(2403.9),
+ F16(2403.2),
+ F16(2402.5),
+ F16(2404.5),
+ F16(2401.2),
+ F16(2400.6),
+ F16(2400.1),
+ F16(2401.8),
+ F16(2399),
+ F16(2398.6),
+ F16(2398.1),
+ F16(2399.5),
+ F16(2397.3),
+ F16(2396.9),
+ F16(2396.5),
+ F16(2397.7),
+ F16(2395.9),
+ F16(2395.7),
+ F16(2395.5),
+ F16(2396.2),
+ F16(2394.9),
+ F16(2394.5),
+ F16(2394),
+ F16(2395.2),
+ F16(2392.8),
+ F16(2391.5),
+ F16(2389.9),
+ F16(2393.5),
+ F16(2387.1),
+ F16(2388),
+ F16(2389.9),
+ F16(2388.1),
+ F16(2394),
+ F16(2396),
+ F16(2397.9),
+ F16(2391.9),
+ F16(2401.4),
+ F16(2403),
+ F16(2404.4),
+ F16(2399.8),
+ F16(2406.9),
+ F16(2407.9),
+ F16(2408.6),
+ F16(2405.7),
+ F16(2408),
+ F16(2407.2),
+ F16(2406.3),
+ F16(2408.5),
+ F16(2404.7),
+ F16(2403.9),
+ F16(2403.1),
+ F16(2405.5),
+ F16(2401.7),
+ F16(2401),
+ F16(2400.3),
+ F16(2402.4),
+ F16(2398.8),
+ F16(2398.1),
+ F16(2397.4),
+ F16(2399.6),
+ F16(2396),
+ F16(2395.4),
+ F16(2394.7),
+ F16(2396.8),
+ F16(2393.5),
+ F16(2392.7),
+ F16(2392),
+ F16(2394.1),
+ F16(2390.5),
+ F16(2389.8),
+ F16(2389),
+ F16(2391.3),
+ F16(2387.8),
+ F16(2387.2),
+ F16(2386.8),
+ F16(2388.3),
+ F16(2386.2),
+ F16(2385.5),
+ F16(2384.1),
+ F16(2386.5),
+ F16(2378.6),
+ F16(2375.5),
+ F16(2372.3),
+ F16(2381.6),
+ F16(2366.2),
+ F16(2363.3),
+ F16(2360.6),
+ F16(2369.2),
+ F16(2355.7),
+ F16(2353.3),
+ F16(2351.1),
+ F16(2358),
+ F16(2347.2),
+ F16(2346.1),
+ F16(2345.4),
+ F16(2349),
+ F16(2344.6),
+ F16(2344.3),
+ F16(2343.8),
+ F16(2344.9),
+ F16(2343),
+ F16(2342.5),
+ F16(2342.1),
+ F16(2343.4),
+ F16(2341.1),
+ F16(2340.6),
+ F16(2340.2),
+ F16(2341.5),
+ F16(2339.4),
+ F16(2338.9),
+ F16(2338.5),
+ F16(2339.8),
+ F16(2337.5),
+ F16(2337),
+ F16(2336.6),
+ F16(2337.9),
+ F16(2335.9),
+ F16(2335.5),
+ F16(2335.2),
+ F16(2336.3),
+ F16(2334.6),
+ F16(2334.3),
+ F16(2333.9),
+ F16(2334.9),
+ F16(2333),
+ F16(2332.3),
+ F16(2331.7),
+ F16(2333.5),
+ F16(2330.9),
+ F16(2330.4),
+ F16(2330),
+ F16(2331.3),
+ F16(2329.1),
+ F16(2328.7),
+ F16(2328.3),
+ F16(2329.5),
+ F16(2327.3),
+ F16(2326.7),
+ F16(2326.1),
+ F16(2327.8),
+ F16(2324.9),
+ F16(2324.2),
+ F16(2323.6),
+ F16(2325.5),
+ F16(2322.3),
+ F16(2321.7),
+ F16(2320.9),
+ F16(2323),
+ F16(2319.8),
+ F16(2319.3),
+ F16(2318.7),
+ F16(2320.3),
+ F16(2317.8),
+ F16(2317.4),
+ F16(2316.9),
+ F16(2318.3),
+ F16(2316.1),
+ F16(2315.7),
+ F16(2315.2),
+ F16(2316.5),
+ F16(2314.5),
+ F16(2314.1),
+ F16(2313.6),
+ F16(2314.8),
+ F16(2312.8),
+ F16(2312.3),
+ F16(2311.8),
+ F16(2313.2),
+ F16(2310.8),
+ F16(2310.2),
+ F16(2309.6),
+ F16(2311.3),
+ F16(2308.5),
+ F16(2308),
+ F16(2307.4),
+ F16(2309.1),
+ F16(2306.2),
+ F16(2305.5),
+ F16(2304.9),
+ F16(2306.8),
+ F16(2303.7),
+ F16(2303.1),
+ F16(2302.6),
+ F16(2304.3),
+ F16(2301.3),
+ F16(2300.7),
+ F16(2300.2),
+ F16(2301.9),
+ F16(2299.2),
+ F16(2298.8),
+ F16(2298.3),
+ F16(2299.7),
+ F16(2297.3),
+ F16(2296.9),
+ F16(2296.5),
+ F16(2297.8),
+ F16(2295.7),
+ F16(2295.3),
+ F16(2294.9),
+ F16(2296.1),
+ F16(2293.9),
+ F16(2293.2),
+ F16(2292.7),
+ F16(2294.4),
+ F16(2291.5),
+ F16(2290.8),
+ F16(2290),
+ F16(2292.1),
+ F16(2288.5),
+ F16(2287.8),
+ F16(2286.9),
+ F16(2289.2),
+ F16(2285.3),
+ F16(2284.6),
+ F16(2283.8),
+ F16(2286.1),
+ F16(2282.5),
+ F16(2281.8),
+ F16(2281.2),
+ F16(2283.1),
+ F16(2280.2),
+ F16(2279.7),
+ F16(2279.3),
+ F16(2280.7),
+ F16(2278.5),
+ F16(2278.2),
+ F16(2277.7),
+ F16(2278.9),
+ F16(2277.1),
+ F16(2276.8),
+ F16(2276.5),
+ F16(2277.4),
+ F16(2275.7),
+ F16(2275.3),
+ F16(2274.9),
+ F16(2276.1),
+ F16(2274),
+ F16(2273.6),
+ F16(2273),
+ F16(2274.5),
+ F16(2272),
+ F16(2271.6),
+ F16(2271),
+ F16(2272.5),
+ F16(2269.9),
+ F16(2269.4),
+ F16(2268.8),
+ F16(2270.5),
+ F16(2267.6),
+ F16(2267),
+ F16(2266.3),
+ F16(2268.2),
+ F16(2265),
+ F16(2264.4),
+ F16(2263.8),
+ F16(2265.7),
+ F16(2262.6),
+ F16(2262.1),
+ F16(2261.6),
+ F16(2263.2),
+ F16(2260.6),
+ F16(2260.3),
+ F16(2259.8),
+ F16(2261.1),
+ F16(2258.9),
+ F16(2258.4),
+ F16(2257.9),
+ F16(2259.4),
+ F16(2257),
+ F16(2256.4),
+ F16(2255.8),
+ F16(2257.5),
+ F16(2254.7),
+ F16(2254.1),
+ F16(2253.5),
+ F16(2255.2),
+ F16(2252.3),
+ F16(2251.6),
+ F16(2251.1),
+ F16(2252.9),
+ F16(2249.9),
+ F16(2249.3),
+ F16(2248.8),
+ F16(2250.5),
+ F16(2247.7),
+ F16(2247.1),
+ F16(2246.6),
+ F16(2248.2),
+ F16(2245.6),
+ F16(2245),
+ F16(2244.4),
+ F16(2246.1),
+ F16(2243.2),
+ F16(2242.6),
+ F16(2242),
+ F16(2243.7),
+ F16(2240.8),
+ F16(2240.2),
+ F16(2239.5),
+ F16(2241.4),
+ F16(2238.5),
+ F16(2238.1),
+ F16(2237.6),
+ F16(2239),
+ F16(2236.8),
+ F16(2236.4),
+ F16(2236),
+ F16(2237.2),
+ F16(2235.1),
+ F16(2234.6),
+ F16(2234.1),
+ F16(2235.6),
+ F16(2233.2),
+ F16(2232.7),
+ F16(2232.3),
+ F16(2233.6),
+ F16(2231.3),
+ F16(2230.8),
+ F16(2230.3),
+ F16(2231.8),
+ F16(2229.3),
+ F16(2228.9),
+ F16(2228.3),
+ F16(2229.7),
+ F16(2227.5),
+ F16(2227),
+ F16(2226.5),
+ F16(2227.9),
+ F16(2225.4),
+ F16(2224.9),
+ F16(2224.3),
+ F16(2226),
+ F16(2223.3),
+ F16(2222.8),
+ F16(2222.2),
+ F16(2223.8),
+ F16(2221.1),
+ F16(2220.5),
+ F16(2220),
+ F16(2221.7),
+ F16(2219.1),
+ F16(2218.9),
+ F16(2219.4),
+ F16(2219.5),
+ F16(2221.7),
+ F16(2223.4),
+ F16(2225.4),
+ F16(2220.3),
+ F16(2228.8),
+ F16(2228.9),
+ F16(2228.5),
+ F16(2227.4),
+ F16(2227.4),
+ F16(2226.8),
+ F16(2226.3),
+ F16(2228),
+ F16(2225.1),
+ F16(2224.5),
+ F16(2224),
+ F16(2225.7),
+ F16(2222.9),
+ F16(2222.3),
+ F16(2221.7),
+ F16(2223.4),
+ F16(2220.6),
+ F16(2220),
+ F16(2219.4),
+ F16(2221.1),
+ F16(2218.5),
+ F16(2218),
+ F16(2217.5),
+ F16(2218.9),
+ F16(2216.6),
+ F16(2216),
+ F16(2215.4),
+ F16(2217),
+ F16(2214.3),
+ F16(2213.8),
+ F16(2213.2),
+ F16(2214.9),
+ F16(2212.2),
+ F16(2211.6),
+ F16(2210.9),
+ F16(2212.6),
+ F16(2209.8),
+ F16(2209.3),
+ F16(2208.8),
+ F16(2210.4),
+ F16(2207.8),
+ F16(2207.2),
+ F16(2206.5),
+ F16(2208.3),
+ F16(2204.2),
+ F16(2202.3),
+ F16(2199.8),
+ F16(2205.7),
+ F16(2194.1),
+ F16(2191.1),
+ F16(2188.8),
+ F16(2197.1),
+ F16(2187.1),
+ F16(2186.6),
+ F16(2186.1),
+ F16(2187.7),
+ F16(2185.1),
+ F16(2184.7),
+ F16(2184.2),
+ F16(2185.6),
+ F16(2183.3),
+ F16(2182.8),
+ F16(2182.4),
+ F16(2183.7),
+ F16(2181.5),
+ F16(2181.1),
+ F16(2180.7),
+ F16(2181.9),
+ F16(2179.9),
+ F16(2179.5),
+ F16(2179.1),
+ F16(2180.3),
+ F16(2178.1),
+ F16(2177.6),
+ F16(2177),
+ F16(2178.7),
+ F16(2175.9),
+ F16(2175.3),
+ F16(2174.6),
+ F16(2176.4),
+ F16(2173.5),
+ F16(2172.9),
+ F16(2172.3),
+ F16(2174.1),
+ F16(2171.3),
+ F16(2170.8),
+ F16(2170.3),
+ F16(2171.8),
+ F16(2169.2),
+ F16(2168.6),
+ F16(2168.1),
+ F16(2169.7),
+ F16(2167.1),
+ F16(2166.8),
+ F16(2166.5),
+ F16(2167.6),
+ F16(2165.8),
+ F16(2165.5),
+ F16(2165.2),
+ F16(2166.1),
+ F16(2164.4),
+ F16(2164),
+ F16(2163.6),
+ F16(2164.8),
+ F16(2162.8),
+ F16(2162.4),
+ F16(2161.9),
+ F16(2163.2),
+ F16(2161.2),
+ F16(2160.8),
+ F16(2160.4),
+ F16(2161.5),
+ F16(2159.5),
+ F16(2159),
+ F16(2158.6),
+ F16(2160),
+ F16(2157.5),
+ F16(2156.9),
+ F16(2156.3),
+ F16(2158),
+ F16(2155),
+ F16(2154.5),
+ F16(2153.9),
+ F16(2155.7),
+ F16(2152.8),
+ F16(2152.3),
+ F16(2151.9),
+ F16(2153.4),
+ F16(2150.9),
+ F16(2150.4),
+ F16(2150),
+ F16(2151.4),
+ F16(2149.2),
+ F16(2148.7),
+ F16(2148.2),
+ F16(2149.6),
+ F16(2147.3),
+ F16(2146.9),
+ F16(2146.5),
+ F16(2147.8),
+ F16(2145.8),
+ F16(2145.3),
+ F16(2144.9),
+ F16(2146.2),
+ F16(2144),
+ F16(2143.5),
+ F16(2143.1),
+ F16(2144.4),
+ F16(2142),
+ F16(2141.5),
+ F16(2140.9),
+ F16(2142.5),
+ F16(2140),
+ F16(2139.5),
+ F16(2139),
+ F16(2140.4),
+ F16(2138),
+ F16(2137.3),
+ F16(2136.7),
+ F16(2138.4),
+ F16(2135.4),
+ F16(2134.8),
+ F16(2134.2),
+ F16(2136),
+ F16(2133.1),
+ F16(2132.5),
+ F16(2131.9),
+ F16(2133.6),
+ F16(2130.9),
+ F16(2130.4),
+ F16(2129.9),
+ F16(2131.4),
+ F16(2128.8),
+ F16(2128.2),
+ F16(2127.8),
+ F16(2129.4),
+ F16(2126.8),
+ F16(2126.4),
+ F16(2125.9),
+ F16(2127.3),
+ F16(2125),
+ F16(2124.5),
+ F16(2124),
+ F16(2125.4),
+ F16(2123.1),
+ F16(2122.7),
+ F16(2122.2),
+ F16(2123.6),
+ F16(2121.2),
+ F16(2120.7),
+ F16(2120.2),
+ F16(2121.7),
+ F16(2119.1),
+ F16(2118.6),
+ F16(2118),
+ F16(2119.6),
+ F16(2116.6),
+ F16(2116.1),
+ F16(2115.4),
+ F16(2117.3),
+ F16(2114.3),
+ F16(2113.7),
+ F16(2113.1),
+ F16(2114.9),
+ F16(2112.1),
+ F16(2111.6),
+ F16(2110.9),
+ F16(2112.6),
+ F16(2110),
+ F16(2109.6),
+ F16(2109.2),
+ F16(2110.6),
+ F16(2108.2),
+ F16(2107.8),
+ F16(2107.4),
+ F16(2108.7),
+ F16(2106.6),
+ F16(2106.1),
+ F16(2105.7),
+ F16(2107),
+ F16(2104.9),
+ F16(2104.5),
+ F16(2104),
+ F16(2105.3),
+ F16(2103),
+ F16(2102.6),
+ F16(2102.2),
+ F16(2103.6),
+ F16(2101.1),
+ F16(2100.6),
+ F16(2100),
+ F16(2101.6),
+ F16(2098.8),
+ F16(2098.3),
+ F16(2097.7),
+ F16(2099.4),
+ F16(2096.5),
+ F16(2096),
+ F16(2095.4),
+ F16(2097.1),
+ F16(2094.2),
+ F16(2093.7),
+ F16(2093),
+ F16(2094.8),
+ F16(2091.8),
+ F16(2091.3),
+ F16(2090.8),
+ F16(2092.4),
+ F16(2089.8),
+ F16(2089.3),
+ F16(2088.8),
+ F16(2090.3),
+ F16(2087.9),
+ F16(2087.4),
+ F16(2086.9),
+ F16(2088.4),
+ F16(2086.2),
+ F16(2085.8),
+ F16(2085.5),
+ F16(2086.5),
+ F16(2084.8),
+ F16(2084.5),
+ F16(2084.1),
+ F16(2085.2),
+ F16(2083.3),
+ F16(2082.9),
+ F16(2082.4),
+ F16(2083.7),
+ F16(2081.5),
+ F16(2081.1),
+ F16(2080.7),
+ F16(2082),
+ F16(2080),
+ F16(2079.6),
+ F16(2079.2),
+ F16(2080.4),
+ F16(2078.1),
+ F16(2077.6),
+ F16(2077.1),
+ F16(2078.7),
+ F16(2076.1),
+ F16(2075.5),
+ F16(2075),
+ F16(2076.5),
+ F16(2073.9),
+ F16(2073.4),
+ F16(2072.9),
+ F16(2074.4),
+ F16(2071.9),
+ F16(2071.4),
+ F16(2070.9),
+ F16(2072.3),
+ F16(2070.1),
+ F16(2069.7),
+ F16(2069.2),
+ F16(2070.5),
+ F16(2068.3),
+ F16(2067.9),
+ F16(2067.4),
+ F16(2068.7),
+ F16(2066.4),
+ F16(2065.9),
+ F16(2065.5),
+ F16(2066.8),
+ F16(2064.6),
+ F16(2064.2),
+ F16(2063.6),
+ F16(2065.1),
+ F16(2062.5),
+ F16(2061.9),
+ F16(2061.3),
+ F16(2063),
+ F16(2060.1),
+ F16(2059.6),
+ F16(2059),
+ F16(2060.7),
+ F16(2058),
+ F16(2057.4),
+ F16(2056.7),
+ F16(2058.5),
+ F16(2055.4),
+ F16(2054.7),
+ F16(2054),
+ F16(2056.1),
+ F16(2052.8),
+ F16(2052.2),
+ F16(2051.5),
+ F16(2053.3),
+ F16(2050.3),
+ F16(2049.8),
+ F16(2049.3),
+ F16(2050.9),
+ F16(2048.3),
+ F16(2047.8),
+ F16(2047.3),
+ F16(2048.8),
+ F16(2046.2),
+ F16(2045.7),
+ F16(2045.2),
+ F16(2046.7),
+ F16(2044.1),
+ F16(2043.6),
+ F16(2043),
+ F16(2044.6),
+ F16(2041.8),
+ F16(2041.2),
+ F16(2040.6),
+ F16(2042.4),
+ F16(2039.7),
+ F16(2039.3),
+ F16(2038.9),
+ F16(2040.1),
+ F16(2037.9),
+ F16(2037.5),
+ F16(2037.1),
+ F16(2038.4),
+ F16(2036.3),
+ F16(2035.8),
+ F16(2035.4),
+ F16(2036.7),
+ F16(2034.5),
+ F16(2034.1),
+ F16(2033.6),
+ F16(2034.9),
+ F16(2032.5),
+ F16(2032),
+ F16(2031.3),
+ F16(2033.1),
+ F16(2030.1),
+ F16(2029.5),
+ F16(2029),
+ F16(2030.7),
+ F16(2027.7),
+ F16(2027.2),
+ F16(2026.6),
+ F16(2028.3),
+ F16(2026.9),
+ F16(2028.1),
+ F16(2029.5),
+ F16(2026.4),
+ F16(2032.7),
+ F16(2034.1),
+ F16(2035.4),
+ F16(2031.1),
+ F16(2036.3),
+ F16(2036),
+ F16(2035.5),
+ F16(2036.1),
+ F16(2034.5),
+ F16(2034),
+ F16(2033.5),
+ F16(2035),
+ F16(2032.5),
+ F16(2032.1),
+ F16(2031.7),
+ F16(2033),
+ F16(2031),
+ F16(2030.7),
+ F16(2030.3),
+ F16(2031.2),
+ F16(2029.4),
+ F16(2029),
+ F16(2028.6),
+ F16(2029.9),
+ F16(2027.5),
+ F16(2026.9),
+ F16(2026.3),
+ F16(2028.1),
+ F16(2025.1),
+ F16(2024.5),
+ F16(2023.9),
+ F16(2025.6),
+ F16(2022.7),
+ F16(2022.2),
+ F16(2021.6),
+ F16(2023.3),
+ F16(2020.4),
+ F16(2019.9),
+ F16(2019.4),
+ F16(2021),
+ F16(2018.3),
+ F16(2017.7),
+ F16(2017.1),
+ F16(2018.8),
+ F16(2015.9),
+ F16(2015.1),
+ F16(2013.5),
+ F16(2016.6),
+ F16(2008.9),
+ F16(2006.2),
+ F16(2003.5),
+ F16(2011.4),
+ F16(1998.7),
+ F16(1996.9),
+ F16(1995.6),
+ F16(2001),
+ F16(1994.4),
+ F16(1993.8),
+ F16(1993.3),
+ F16(1994.9),
+ F16(1992.3),
+ F16(1991.8),
+ F16(1991.3),
+ F16(1992.8),
+ F16(1990.2),
+ F16(1989.6),
+ F16(1988.9),
+ F16(1990.8),
+ F16(1987.5),
+ F16(1986.8),
+ F16(1986.2),
+ F16(1988.2),
+ F16(1984.9),
+ F16(1984.3),
+ F16(1983.8),
+ F16(1985.5),
+ F16(1982.8),
+ F16(1982.4),
+ F16(1981.9),
+ F16(1983.2),
+ F16(1980.9),
+ F16(1980.4),
+ F16(1979.9),
+ F16(1981.4),
+ F16(1978.9),
+ F16(1978.3),
+ F16(1977.8),
+ F16(1979.4),
+ F16(1976.8),
+ F16(1976.3),
+ F16(1975.8),
+ F16(1977.3),
+ F16(1974.9),
+ F16(1974.7),
+ F16(1975.1),
+ F16(1975.4),
+ F16(1975.5),
+ F16(1975),
+ F16(1974.5),
+ F16(1975.7),
+ F16(1973.5),
+ F16(1973),
+ F16(1972.4),
+ F16(1974),
+ F16(1971.3),
+ F16(1970.8),
+ F16(1970.2),
+ F16(1971.9),
+ F16(1969.2),
+ F16(1968.7),
+ F16(1968.3),
+ F16(1969.7),
+ F16(1967.3),
+ F16(1966.9),
+ F16(1966.4),
+ F16(1967.8),
+ F16(1965.6),
+ F16(1965.2),
+ F16(1964.7),
+ F16(1966),
+ F16(1963.9),
+ F16(1963.5),
+ F16(1963),
+ F16(1964.4),
+ F16(1962),
+ F16(1961.4),
+ F16(1960.9),
+ F16(1962.5),
+ F16(1959.7),
+ F16(1959.2),
+ F16(1958.7),
+ F16(1960.3),
+ F16(1957.8),
+ F16(1957.3),
+ F16(1956.8),
+ F16(1958.2),
+ F16(1956),
+ F16(1955.5),
+ F16(1955),
+ F16(1956.5),
+ F16(1954.1),
+ F16(1953.7),
+ F16(1953.1),
+ F16(1954.5),
+ F16(1950.9),
+ F16(1949.4),
+ F16(1948.5),
+ F16(1952.3),
+ F16(1947.6),
+ F16(1947.1),
+ F16(1946.6),
+ F16(1948),
+ F16(1945.7),
+ F16(1945.1),
+ F16(1944.7),
+ F16(1946.2),
+ F16(1943.8),
+ F16(1943.3),
+ F16(1942.7),
+ F16(1944.2),
+ F16(1941.4),
+ F16(1940.8),
+ F16(1940.2),
+ F16(1942),
+ F16(1939),
+ F16(1938.4),
+ F16(1937.8),
+ F16(1939.6),
+ F16(1936.4),
+ F16(1935.7),
+ F16(1934.9),
+ F16(1937.1),
+ F16(1933.5),
+ F16(1932.8),
+ F16(1932),
+ F16(1934.2),
+ F16(1930.6),
+ F16(1930),
+ F16(1929.3),
+ F16(1931.4),
+ F16(1928),
+ F16(1927.2),
+ F16(1926.4),
+ F16(1928.7),
+ F16(1924.9),
+ F16(1924.3),
+ F16(1923.6),
+ F16(1925.7),
+ F16(1922.3),
+ F16(1921.7),
+ F16(1921),
+ F16(1922.9),
+ F16(1919.8),
+ F16(1919.3),
+ F16(1918.7),
+ F16(1920.4),
+ F16(1917.5),
+ F16(1917),
+ F16(1916.4),
+ F16(1918.1),
+ F16(1915.3),
+ F16(1914.7),
+ F16(1914.2),
+ F16(1915.8),
+ F16(1913.2),
+ F16(1912.7),
+ F16(1912.1),
+ F16(1913.7),
+ F16(1911.1),
+ F16(1910.7),
+ F16(1910.3),
+ F16(1911.6),
+ F16(1909.4),
+ F16(1909),
+ F16(1908.5),
+ F16(1909.8),
+ F16(1907.8),
+ F16(1907.3),
+ F16(1906.9),
+ F16(1908.1),
+ F16(1906.1),
+ F16(1905.8),
+ F16(1905.4),
+ F16(1906.5),
+ F16(1904.6),
+ F16(1904.2),
+ F16(1903.7),
+ F16(1905),
+ F16(1902.8),
+ F16(1902.3),
+ F16(1901.7),
+ F16(1903.2),
+ F16(1900.8),
+ F16(1900.4),
+ F16(1900),
+ F16(1901.2),
+ F16(1899),
+ F16(1898.6),
+ F16(1898.1),
+ F16(1899.4),
+ F16(1897.3),
+ F16(1896.8),
+ F16(1896.4),
+ F16(1897.7),
+ F16(1895.5),
+ F16(1895.1),
+ F16(1894.6),
+ F16(1896),
+ F16(1893.7),
+ F16(1893.3),
+ F16(1892.8),
+ F16(1894.2),
+ F16(1891.9),
+ F16(1891.4),
+ F16(1890.9),
+ F16(1892.4),
+ F16(1889.9),
+ F16(1889.4),
+ F16(1888.9),
+ F16(1890.3),
+ F16(1887.9),
+ F16(1887.4),
+ F16(1886.8),
+ F16(1888.4),
+ F16(1885.7),
+ F16(1885),
+ F16(1884.4),
+ F16(1886.2),
+ F16(1883.3),
+ F16(1882.8),
+ F16(1882.2),
+ F16(1883.9),
+ F16(1881),
+ F16(1880.3),
+ F16(1879.7),
+ F16(1881.6),
+ F16(1878.5),
+ F16(1878),
+ F16(1877.5),
+ F16(1879.1),
+ F16(1876.5),
+ F16(1876),
+ F16(1875.4),
+ F16(1877),
+ F16(1874.4),
+ F16(1874),
+ F16(1873.5),
+ F16(1874.8),
+ F16(1872.5),
+ F16(1872.1),
+ F16(1871.6),
+ F16(1873),
+ F16(1870.5),
+ F16(1870),
+ F16(1869.4),
+ F16(1871),
+ F16(1868.4),
+ F16(1867.9),
+ F16(1867.3),
+ F16(1868.9),
+ F16(1866.2),
+ F16(1865.7),
+ F16(1865.2),
+ F16(1866.8),
+ F16(1864.1),
+ F16(1863.6),
+ F16(1863.1),
+ F16(1864.6),
+ F16(1862),
+ F16(1861.5),
+ F16(1861),
+ F16(1862.6),
+ F16(1859.9),
+ F16(1859.4),
+ F16(1858.9),
+ F16(1860.4),
+ F16(1857.9),
+ F16(1857.4),
+ F16(1856.9),
+ F16(1858.4),
+ F16(1856),
+ F16(1855.5),
+ F16(1855),
+ F16(1856.4),
+ F16(1854.1),
+ F16(1853.7),
+ F16(1853.2),
+ F16(1854.5),
+ F16(1852.1),
+ F16(1851.5),
+ F16(1851.1),
+ F16(1852.6),
+ F16(1850),
+ F16(1849.6),
+ F16(1849.1),
+ F16(1850.5),
+ F16(1847.9),
+ F16(1847.3),
+ F16(1846.7),
+ F16(1848.5),
+ F16(1845.7),
+ F16(1845.2),
+ F16(1844.7),
+ F16(1846.2),
+ F16(1843.7),
+ F16(1843.1),
+ F16(1842.6),
+ F16(1844.2),
+ F16(1841.6),
+ F16(1841.1),
+ F16(1840.7),
+ F16(1842.1),
+ F16(1839.9),
+ F16(1839.5),
+ F16(1839.2),
+ F16(1840.2),
+ F16(1838.6),
+ F16(1838.4),
+ F16(1838.1),
+ F16(1839),
+ F16(1837.5),
+ F16(1837.2),
+ F16(1836.9),
+ F16(1837.8),
+ F16(1836.3),
+ F16(1836),
+ F16(1835.7),
+ F16(1836.7),
+ F16(1835),
+ F16(1834.6),
+ F16(1834.3),
+ F16(1835.4),
+ F16(1833.8),
+ F16(1833.5),
+ F16(1833.2),
+ F16(1834),
+ F16(1832.6),
+ F16(1832.4),
+ F16(1832.1),
+ F16(1832.9),
+ F16(1831.4),
+ F16(1831),
+ F16(1830.6),
+ F16(1831.7),
+ F16(1829.9),
+ F16(1829.5),
+ F16(1829.1),
+ F16(1830.2),
+ F16(1828.3),
+ F16(1827.9),
+ F16(1827.4),
+ F16(1828.7),
+ F16(1826.4),
+ F16(1825.8),
+ F16(1825.3),
+ F16(1826.9),
+ F16(1824.3),
+ F16(1823.7),
+ F16(1823.2),
+ F16(1824.8),
+ F16(1822.1),
+ F16(1821.5),
+ F16(1820.8),
+ F16(1822.6),
+ F16(1819.3),
+ F16(1818.5),
+ F16(1817.8),
+ F16(1820.1),
+ F16(1816.2),
+ F16(1815.5),
+ F16(1814.8),
+ F16(1817),
+ F16(1813.4),
+ F16(1812.7),
+ F16(1812.1),
+ F16(1814.1),
+ F16(1810.7),
+ F16(1810.2),
+ F16(1809.6),
+ F16(1811.4),
+ F16(1808.6),
+ F16(1808),
+ F16(1807.5),
+ F16(1809.1),
+ F16(1806.2),
+ F16(1805.7),
+ F16(1805.1),
+ F16(1806.9),
+ F16(1803.9),
+ F16(1803.3),
+ F16(1802.8),
+ F16(1804.4),
+ F16(1801.8),
+ F16(1801.2),
+ F16(1800.6),
+ F16(1802.3),
+ F16(1799.5),
+ F16(1799),
+ F16(1798.5),
+ F16(1800.1),
+ F16(1797.3),
+ F16(1796.7),
+ F16(1796.2),
+ F16(1797.9),
+ F16(1795.1),
+ F16(1794.6),
+ F16(1794.1),
+ F16(1795.6),
+ F16(1793.1),
+ F16(1792.6),
+ F16(1792.1),
+ F16(1793.6),
+ F16(1791.1),
+ F16(1790.6),
+ F16(1790.2),
+ F16(1791.6),
+ F16(1789.3),
+ F16(1788.9),
+ F16(1788.4),
+ F16(1789.7),
+ F16(1787.6),
+ F16(1787.2),
+ F16(1786.8),
+ F16(1788),
+ F16(1786.1),
+ F16(1785.8),
+ F16(1785.4),
+ F16(1786.5),
+ F16(1784.4),
+ F16(1783.8),
+ F16(1783.2),
+ F16(1784.9),
+ F16(1782),
+ F16(1781.5),
+ F16(1781),
+ F16(1782.6),
+ F16(1779.9),
+ F16(1779.4),
+ F16(1778.7),
+ F16(1780.5),
+ F16(1777.6),
+ F16(1777),
+ F16(1776.4),
+ F16(1778.2),
+ F16(1775.2),
+ F16(1774.7),
+ F16(1774.1),
+ F16(1775.8),
+ F16(1772.9),
+ F16(1772.5),
+ F16(1772),
+ F16(1773.5),
+ F16(1771),
+ F16(1770.6),
+ F16(1770.2),
+ F16(1771.5),
+ F16(1769.3),
+ F16(1768.9),
+ F16(1768.5),
+ F16(1769.7),
+ F16(1767.8),
+ F16(1767.4),
+ F16(1766.9),
+ F16(1768.2),
+ F16(1766.1),
+ F16(1765.7),
+ F16(1765.4),
+ F16(1766.5),
+ F16(1764.7),
+ F16(1764.3),
+ F16(1763.8),
+ F16(1765.1),
+ F16(1762.8),
+ F16(1762.3),
+ F16(1761.8),
+ F16(1763.3),
+ F16(1760.6),
+ F16(1760.2),
+ F16(1759.7),
+ F16(1761.2),
+ F16(1758.8),
+ F16(1758.2),
+ F16(1757.5),
+ F16(1759.3),
+ F16(1756.2),
+ F16(1755.6),
+ F16(1755),
+ F16(1756.9),
+ F16(1753.8),
+ F16(1753.2),
+ F16(1752.6),
+ F16(1754.4),
+ F16(1751.4),
+ F16(1750.9),
+ F16(1750.3),
+ F16(1752),
+ F16(1749.2),
+ F16(1748.7),
+ F16(1748.2),
+ F16(1749.7),
+ F16(1747.3),
+ F16(1746.8),
+ F16(1746.4),
+ F16(1747.7),
+ F16(1745.4),
+ F16(1745),
+ F16(1744.5),
+ F16(1745.9),
+ F16(1743.6),
+ F16(1743.2),
+ F16(1742.8),
+ F16(1744.1),
+ F16(1741.9),
+ F16(1741.4),
+ F16(1741),
+ F16(1742.3),
+ F16(1739.9),
+ F16(1739.4),
+ F16(1739),
+ F16(1740.5),
+ F16(1738),
+ F16(1737.5),
+ F16(1737),
+ F16(1738.4),
+ F16(1736),
+ F16(1735.5),
+ F16(1734.9),
+ F16(1736.5),
+ F16(1734),
+ F16(1733.4),
+ F16(1732.8),
+ F16(1734.5),
+ F16(1732),
+ F16(1731.5),
+ F16(1731.1),
+ F16(1732.4),
+ F16(1730.2),
+ F16(1729.7),
+ F16(1729.2),
+ F16(1730.6),
+ F16(1728.2),
+ F16(1727.6),
+ F16(1727.2),
+ F16(1728.7),
+ F16(1726.4),
+ F16(1726),
+ F16(1725.5),
+ F16(1726.8),
+ F16(1724.5),
+ F16(1724),
+ F16(1723.5),
+ F16(1725),
+ F16(1722.5),
+ F16(1722),
+ F16(1721.6),
+ F16(1722.9),
+ F16(1720.8),
+ F16(1720.2),
+ F16(1719.7),
+ F16(1721.2),
+ F16(1718.8),
+ F16(1718.3),
+ F16(1717.9),
+ F16(1719.2),
+ F16(1717.1),
+ F16(1716.7),
+ F16(1716.2),
+ F16(1717.6),
+ F16(1715.4),
+ F16(1714.9),
+ F16(1714.5),
+ F16(1715.8),
+ F16(1713.7),
+ F16(1713.3),
+ F16(1712.9),
+ F16(1714.1),
+ F16(1712.2),
+ F16(1711.6),
+ F16(1711.1),
+ F16(1712.6),
+ F16(1710.2),
+ F16(1709.6),
+ F16(1709),
+ F16(1710.6),
+ F16(1707.8),
+ F16(1707.3),
+ F16(1706.8),
+ F16(1708.4),
+ F16(1705.8),
+ F16(1705.4),
+ F16(1704.9),
+ F16(1706.3),
+ F16(1703.8),
+ F16(1703.3),
+ F16(1702.7),
+ F16(1704.4),
+ F16(1701.6),
+ F16(1701.2),
+ F16(1700.7),
+ F16(1702.1),
+ F16(1699.7),
+ F16(1699.2),
+ F16(1698.7),
+ F16(1700.2),
+ F16(1697.8),
+ F16(1697.4),
+ F16(1697),
+ F16(1698.2),
+ F16(1696.2),
+ F16(1695.8),
+ F16(1695.4),
+ F16(1696.6),
+ F16(1694.5),
+ F16(1694.2),
+ F16(1693.8),
+ F16(1695),
+ F16(1693),
+ F16(1692.5),
+ F16(1692),
+ F16(1693.4),
+ F16(1691),
+ F16(1690.6),
+ F16(1690.1),
+ F16(1691.5),
+ F16(1689.2),
+ F16(1688.6),
+ F16(1688.1),
+ F16(1689.7),
+ F16(1687),
+ F16(1686.6),
+ F16(1686.1),
+ F16(1687.6),
+ F16(1685),
+ F16(1684.5),
+ F16(1684),
+ F16(1685.5),
+ F16(1682.8),
+ F16(1682.3),
+ F16(1681.7),
+ F16(1683.4),
+ F16(1680.7),
+ F16(1680.2),
+ F16(1679.7),
+ F16(1681.2),
+ F16(1678.8),
+ F16(1678.3),
+ F16(1677.9),
+ F16(1679.3),
+ F16(1676.9),
+ F16(1676.5),
+ F16(1676),
+ F16(1677.4),
+ F16(1675.2),
+ F16(1674.9),
+ F16(1674.4),
+ F16(1675.6),
+ F16(1673.5),
+ F16(1672.9),
+ F16(1672.4),
+ F16(1673.9),
+ F16(1671.5),
+ F16(1671),
+ F16(1670.5),
+ F16(1672),
+ F16(1669.3),
+ F16(1668.9),
+ F16(1668.3),
+ F16(1669.8),
+ F16(1667.3),
+ F16(1666.8),
+ F16(1666.3),
+ F16(1667.8),
+ F16(1665.2),
+ F16(1664.5),
+ F16(1664),
+ F16(1665.7),
+ F16(1663.1),
+ F16(1662.6),
+ F16(1662),
+ F16(1663.6),
+ F16(1660.9),
+ F16(1660.5),
+ F16(1660),
+ F16(1661.4),
+ F16(1659.1),
+ F16(1658.6),
+ F16(1658.1),
+ F16(1659.5),
+ F16(1657),
+ F16(1656.5),
+ F16(1656),
+ F16(1657.6),
+ F16(1654.9),
+ F16(1654.4),
+ F16(1653.8),
+ F16(1655.5),
+ F16(1652.7),
+ F16(1652.1),
+ F16(1651.6),
+ F16(1653.2),
+ F16(1650.6),
+ F16(1650.1),
+ F16(1649.6),
+ F16(1651.2),
+ F16(1648.6),
+ F16(1648),
+ F16(1647.5),
+ F16(1649.1),
+ F16(1646.6),
+ F16(1646.2),
+ F16(1645.7),
+ F16(1647),
+ F16(1644.7),
+ F16(1644.3),
+ F16(1643.8),
+ F16(1645.2),
+ F16(1642.6),
+ F16(1642.1),
+ F16(1641.6),
+ F16(1643.2),
+ F16(1640.7),
+ F16(1640.1),
+ F16(1639.6),
+ F16(1641.2),
+ F16(1638.4),
+ F16(1637.7),
+ F16(1637.2),
+ F16(1639),
+ F16(1636.2),
+ F16(1635.8),
+ F16(1635.2),
+ F16(1636.6),
+ F16(1634),
+ F16(1633.5),
+ F16(1632.9),
+ F16(1634.6),
+ F16(1631.9),
+ F16(1631.5),
+ F16(1631),
+ F16(1632.4),
+ F16(1630.1),
+ F16(1629.6),
+ F16(1629.1),
+ F16(1630.5),
+ F16(1628.2),
+ F16(1627.7),
+ F16(1627.1),
+ F16(1628.6),
+ F16(1626),
+ F16(1625.5),
+ F16(1625),
+ F16(1626.6),
+ F16(1624),
+ F16(1623.4),
+ F16(1622.8),
+ F16(1624.5),
+ F16(1621.9),
+ F16(1621.4),
+ F16(1620.9),
+ F16(1622.3),
+ F16(1619.8),
+ F16(1619.3),
+ F16(1618.8),
+ F16(1620.3),
+ F16(1617.9),
+ F16(1617.5),
+ F16(1617),
+ F16(1618.3),
+ F16(1616),
+ F16(1615.4),
+ F16(1614.9),
+ F16(1616.5),
+ F16(1613.8),
+ F16(1613.4),
+ F16(1613),
+ F16(1614.3),
+ F16(1612.1),
+ F16(1611.6),
+ F16(1611),
+ F16(1612.6),
+ F16(1610.1),
+ F16(1609.8),
+ F16(1609.3),
+ F16(1610.5),
+ F16(1608.3),
+ F16(1607.8),
+ F16(1607.2),
+ F16(1608.8),
+ F16(1606.2),
+ F16(1605.7),
+ F16(1605.2),
+ F16(1606.7),
+ F16(1604.2),
+ F16(1603.7),
+ F16(1603.2),
+ F16(1604.7),
+ F16(1602.3),
+ F16(1601.8),
+ F16(1601.4),
+ F16(1602.8),
+ F16(1600.5),
+ F16(1600),
+ F16(1599.5),
+ F16(1600.9),
+ F16(1598.8),
+ F16(1598.4),
+ F16(1597.8),
+ F16(1599.2),
+ F16(1596.8),
+ F16(1596.3),
+ F16(1595.9),
+ F16(1597.3),
+ F16(1594.9),
+ F16(1594.3),
+ F16(1593.7),
+ F16(1595.4),
+ F16(1592.6),
+ F16(1592),
+ F16(1591.5),
+ F16(1593.1),
+ F16(1590.5),
+ F16(1590),
+ F16(1589.5),
+ F16(1590.9),
+ F16(1588.3),
+ F16(1587.8),
+ F16(1587.2),
+ F16(1588.9),
+ F16(1586.1),
+ F16(1585.5),
+ F16(1584.8),
+ F16(1586.6),
+ F16(1583.7),
+ F16(1583.1),
+ F16(1582.7),
+ F16(1584.2),
+ F16(1581.7),
+ F16(1581.2),
+ F16(1580.7),
+ F16(1582.2),
+ F16(1579.7),
+ F16(1579.2),
+ F16(1578.7),
+ F16(1580.3),
+ F16(1577.8),
+ F16(1577.3),
+ F16(1576.9),
+ F16(1578.3),
+ F16(1576.2),
+ F16(1575.7),
+ F16(1575.3),
+ F16(1576.5),
+ F16(1574.6),
+ F16(1574),
+ F16(1573.4),
+ F16(1575),
+ F16(1572.4),
+ F16(1571.9),
+ F16(1571.3),
+ F16(1572.9),
+ F16(1570.2),
+ F16(1569.7),
+ F16(1569.1),
+ F16(1570.7),
+ F16(1568.1),
+ F16(1567.7),
+ F16(1567.2),
+ F16(1568.6),
+ F16(1566.2),
+ F16(1565.7),
+ F16(1565.2),
+ F16(1566.7),
+ F16(1564.1),
+ F16(1563.5),
+ F16(1563),
+ F16(1564.7),
+ F16(1561.7),
+ F16(1561.3),
+ F16(1560.7),
+ F16(1562.3),
+ F16(1559.7),
+ F16(1559.2),
+ F16(1558.7),
+ F16(1560.2),
+ F16(1557.7),
+ F16(1557.3),
+ F16(1556.9),
+ F16(1558.3),
+ F16(1556),
+ F16(1555.6),
+ F16(1555.2),
+ F16(1556.4),
+ F16(1554.5),
+ F16(1554),
+ F16(1553.7),
+ F16(1554.8),
+ F16(1552.8),
+ F16(1552.4),
+ F16(1552),
+ F16(1553.2),
+ F16(1551.1),
+ F16(1550.6),
+ F16(1550.2),
+ F16(1551.6),
+ F16(1549.1),
+ F16(1548.6),
+ F16(1548),
+ F16(1549.6),
+ F16(1546.9),
+ F16(1546.3),
+ F16(1545.6),
+ F16(1547.4),
+ F16(1544.5),
+ F16(1544),
+ F16(1543.3),
+ F16(1545),
+ F16(1542.2),
+ F16(1541.7),
+ F16(1541.2),
+ F16(1542.8),
+ F16(1540),
+ F16(1539.4),
+ F16(1539),
+ F16(1540.6),
+ F16(1538),
+ F16(1537.5),
+ F16(1537.1),
+ F16(1538.5),
+ F16(1536.1),
+ F16(1535.8),
+ F16(1535.3),
+ F16(1536.6),
+ F16(1534.3),
+ F16(1533.8),
+ F16(1533.4),
+ F16(1534.8),
+ F16(1532.5),
+ F16(1532),
+ F16(1531.6),
+ F16(1533),
+ F16(1530.8),
+ F16(1530.5),
+ F16(1530.1),
+ F16(1531.2),
+ F16(1529.2),
+ F16(1528.7),
+ F16(1528.3),
+ F16(1529.7),
+ F16(1527.1),
+ F16(1526.6),
+ F16(1526.1),
+ F16(1527.7),
+ F16(1525),
+ F16(1524.6),
+ F16(1524.2),
+ F16(1525.6),
+ F16(1523.2),
+ F16(1522.7),
+ F16(1522.2),
+ F16(1523.6),
+ F16(1521.3),
+ F16(1520.8),
+ F16(1520.3),
+ F16(1521.8),
+ F16(1519.2),
+ F16(1518.7),
+ F16(1518.2),
+ F16(1519.7),
+ F16(1517.2),
+ F16(1516.6),
+ F16(1516.1),
+ F16(1517.7),
+ F16(1515),
+ F16(1514.5),
+ F16(1514),
+ F16(1515.5),
+ F16(1513),
+ F16(1512.6),
+ F16(1512.1),
+ F16(1513.5),
+ F16(1511.2),
+ F16(1510.8),
+ F16(1510.4),
+ F16(1511.6),
+ F16(1509.6),
+ F16(1509.2),
+ F16(1508.8),
+ F16(1510),
+ F16(1508),
+ F16(1507.6),
+ F16(1507.2),
+ F16(1508.5),
+ F16(1506.3),
+ F16(1505.9),
+ F16(1505.4),
+ F16(1506.8),
+ F16(1504.6),
+ F16(1504.2),
+ F16(1503.7),
+ F16(1505.1),
+ F16(1502.8),
+ F16(1502.3),
+ F16(1501.9),
+ F16(1503.3),
+ F16(1500.7),
+ F16(1500.2),
+ F16(1499.6),
+ F16(1501.2),
+ F16(1498.7),
+ F16(1498.1),
+ F16(1497.7),
+ F16(1499.2),
+ F16(1496.6),
+ F16(1496.2),
+ F16(1495.7),
+ F16(1497.2),
+ F16(1494.6),
+ F16(1494.1),
+ F16(1493.5),
+ F16(1495.1),
+ F16(1492.6),
+ F16(1492.2),
+ F16(1491.8),
+ F16(1493),
+ F16(1491),
+ F16(1490.6),
+ F16(1490.1),
+ F16(1491.4),
+ F16(1489.4),
+ F16(1489),
+ F16(1488.5),
+ F16(1489.7),
+ F16(1487.8),
+ F16(1487.5),
+ F16(1487.1),
+ F16(1488.2),
+ F16(1486.3),
+ F16(1485.7),
+ F16(1485.3),
+ F16(1486.7),
+ F16(1484.2),
+ F16(1483.7),
+ F16(1483.2),
+ F16(1484.8),
+ F16(1482.2),
+ F16(1481.8),
+ F16(1481.3),
+ F16(1482.8),
+ F16(1480.2),
+ F16(1479.7),
+ F16(1479.2),
+ F16(1480.7),
+ F16(1478.1),
+ F16(1477.6),
+ F16(1477.1),
+ F16(1478.7),
+ F16(1476.1),
+ F16(1475.6),
+ F16(1475.1),
+ F16(1476.6),
+ F16(1474.2),
+ F16(1473.8),
+ F16(1473.3),
+ F16(1474.7),
+ F16(1472.4),
+ F16(1471.9),
+ F16(1471.4),
+ F16(1472.8),
+ F16(1470.6),
+ F16(1470.1),
+ F16(1469.7),
+ F16(1471),
+ F16(1468.9),
+ F16(1468.4),
+ F16(1468),
+ F16(1469.3),
+ F16(1467),
+ F16(1466.6),
+ F16(1466),
+ F16(1467.4),
+ F16(1465.1),
+ F16(1464.6),
+ F16(1464.2),
+ F16(1465.6),
+ F16(1463),
+ F16(1462.5),
+ F16(1462),
+ F16(1463.6),
+ F16(1461),
+ F16(1460.7),
+ F16(1460.1),
+ F16(1461.5),
+ F16(1459.2),
+ F16(1458.6),
+ F16(1458.2),
+ F16(1459.7),
+ F16(1457.2),
+ F16(1456.8),
+ F16(1456.3),
+ F16(1457.7),
+ F16(1455.4),
+ F16(1455),
+ F16(1454.5),
+ F16(1455.9),
+ F16(1453.6),
+ F16(1453.1),
+ F16(1452.7),
+ F16(1454),
+ F16(1452),
+ F16(1451.5),
+ F16(1451.1),
+ F16(1452.4),
+ F16(1450.1),
+ F16(1449.6),
+ F16(1449.1),
+ F16(1450.6),
+ F16(1448.3),
+ F16(1448),
+ F16(1447.5),
+ F16(1448.7),
+ F16(1446.6),
+ F16(1446.1),
+ F16(1445.6),
+ F16(1447.1),
+ F16(1444.6),
+ F16(1444.2),
+ F16(1443.8),
+ F16(1445.1),
+ F16(1443),
+ F16(1442.4),
+ F16(1441.9),
+ F16(1443.4),
+ F16(1440.9),
+ F16(1440.5),
+ F16(1440.1),
+ F16(1441.5),
+ F16(1439.2),
+ F16(1438.8),
+ F16(1438.3),
+ F16(1439.6),
+ F16(1437.3),
+ F16(1436.8),
+ F16(1436.4),
+ F16(1437.8),
+ F16(1435.5),
+ F16(1435),
+ F16(1434.6),
+ F16(1436),
+ F16(1433.6),
+ F16(1433.1),
+ F16(1432.6),
+ F16(1434.1),
+ F16(1431.6),
+ F16(1431.2),
+ F16(1430.8),
+ F16(1432.1),
+ F16(1429.8),
+ F16(1429.2),
+ F16(1428.6),
+ F16(1430.3),
+ F16(1427.6),
+ F16(1427.2),
+ F16(1426.8),
+ F16(1428.2),
+ F16(1425.9),
+ F16(1425.4),
+ F16(1425),
+ F16(1426.4),
+ F16(1423.9),
+ F16(1423.4),
+ F16(1422.9),
+ F16(1424.4),
+ F16(1422.1),
+ F16(1421.6),
+ F16(1421.1),
+ F16(1422.5),
+ F16(1420),
+ F16(1419.5),
+ F16(1419),
+ F16(1420.6),
+ F16(1418.1),
+ F16(1417.6),
+ F16(1417.1),
+ F16(1418.5),
+ F16(1416.2),
+ F16(1415.7),
+ F16(1415.2),
+ F16(1416.6),
+ F16(1414.2),
+ F16(1413.7),
+ F16(1413.2),
+ F16(1414.7),
+ F16(1412.2),
+ F16(1411.7),
+ F16(1411.2),
+ F16(1412.7),
+ F16(1410.4),
+ F16(1409.9),
+ F16(1409.4),
+ F16(1410.8),
+ F16(1408.6),
+ F16(1408.1),
+ F16(1407.7),
+ F16(1409),
+ F16(1406.8),
+ F16(1406.3),
+ F16(1405.8),
+ F16(1407.2),
+ F16(1405),
+ F16(1404.6),
+ F16(1404.1),
+ F16(1405.4),
+ F16(1403.2),
+ F16(1402.7),
+ F16(1402.2),
+ F16(1403.6),
+ F16(1401.3),
+ F16(1400.9),
+ F16(1400.5),
+ F16(1401.7),
+ F16(1399.6),
+ F16(1399),
+ F16(1398.6),
+ F16(1400),
+ F16(1397.7),
+ F16(1397.3),
+ F16(1396.8),
+ F16(1398.1),
+ F16(1395.9),
+ F16(1395.4),
+ F16(1394.9),
+ F16(1396.3),
+ F16(1394),
+ F16(1393.5),
+ F16(1393),
+ F16(1394.5),
+ F16(1392),
+ F16(1391.4),
+ F16(1390.8),
+ F16(1392.5),
+ F16(1389.9),
+ F16(1389.5),
+ F16(1388.9),
+ F16(1390.3),
+ F16(1388.1),
+ F16(1387.5),
+ F16(1386.9),
+ F16(1388.5),
+ F16(1386),
+ F16(1385.5),
+ F16(1385.1),
+ F16(1386.5),
+ F16(1384.1),
+ F16(1383.6),
+ F16(1383),
+ F16(1384.6),
+ F16(1382.1),
+ F16(1381.7),
+ F16(1381.2),
+ F16(1382.6),
+ F16(1380.2),
+ F16(1379.7),
+ F16(1379.2),
+ F16(1380.7),
+ F16(1378.3),
+ F16(1377.8),
+ F16(1377.4),
+ F16(1378.7),
+ F16(1376.4),
+ F16(1375.9),
+ F16(1375.4),
+ F16(1376.8),
+ F16(1374.5),
+ F16(1374),
+ F16(1373.5),
+ F16(1374.9),
+ F16(1372.5),
+ F16(1372),
+ F16(1371.5),
+ F16(1373),
+ F16(1370.5),
+ F16(1370),
+ F16(1369.6),
+ F16(1371),
+ F16(1368.7),
+ F16(1368.3),
+ F16(1367.8),
+ F16(1369.1),
+ F16(1367.1),
+ F16(1366.6),
+ F16(1366.2),
+ F16(1367.5),
+ F16(1365.3),
+ F16(1364.7),
+ F16(1364.2),
+ F16(1365.7),
+ F16(1363.3),
+ F16(1362.8),
+ F16(1362.3),
+ F16(1363.7),
+ F16(1361.4),
+ F16(1360.9),
+ F16(1360.5),
+ F16(1361.8),
+ F16(1359.5),
+ F16(1359),
+ F16(1358.5),
+ F16(1360),
+ F16(1357.5),
+ F16(1357),
+ F16(1356.6),
+ F16(1358),
+ F16(1355.7),
+ F16(1355.3),
+ F16(1354.8),
+ F16(1356.1),
+ F16(1353.8),
+ F16(1353.3),
+ F16(1352.8),
+ F16(1354.3),
+ F16(1351.8),
+ F16(1351.3),
+ F16(1350.8),
+ F16(1352.3),
+ F16(1349.8),
+ F16(1349.4),
+ F16(1349),
+ F16(1350.3),
+ F16(1348.1),
+ F16(1347.7),
+ F16(1347.2),
+ F16(1348.6),
+ F16(1346.2),
+ F16(1345.7),
+ F16(1345.2),
+ F16(1346.7),
+ F16(1344.2),
+ F16(1343.7),
+ F16(1343.3),
+ F16(1344.7),
+ F16(1342.2),
+ F16(1341.6),
+ F16(1341.2),
+ F16(1342.8),
+ F16(1340.2),
+ F16(1339.8),
+ F16(1339.3),
+ F16(1340.7),
+ F16(1338.2),
+ F16(1337.7),
+ F16(1337.2),
+ F16(1338.8),
+ F16(1336.3),
+ F16(1335.8),
+ F16(1335.3),
+ F16(1336.8),
+ F16(1334.3),
+ F16(1333.8),
+ F16(1333.4),
+ F16(1334.8),
+ F16(1332.4),
+ F16(1331.8),
+ F16(1331.3),
+ F16(1332.9),
+ F16(1330.3),
+ F16(1329.9),
+ F16(1329.5),
+ F16(1330.8),
+ F16(1328.7),
+ F16(1328.3),
+ F16(1327.9),
+ F16(1329.1),
+ F16(1327),
+ F16(1326.6),
+ F16(1326.1),
+ F16(1327.5),
+ F16(1325.2),
+ F16(1324.7),
+ F16(1324.3),
+ F16(1325.7),
+ F16(1323.3),
+ F16(1322.9),
+ F16(1322.4),
+ F16(1323.7),
+ F16(1321.4),
+ F16(1320.9),
+ F16(1320.5),
+ F16(1321.9),
+ F16(1319.4),
+ F16(1319),
+ F16(1318.6),
+ F16(1320),
+ F16(1317.7),
+ F16(1317.2),
+ F16(1316.7),
+ F16(1318.2),
+ F16(1315.7),
+ F16(1315.3),
+ F16(1314.8),
+ F16(1316.2),
+ F16(1313.8),
+ F16(1313.3),
+ F16(1312.8),
+ F16(1314.3),
+ F16(1311.9),
+ F16(1311.5),
+ F16(1311),
+ F16(1312.3),
+ F16(1310.1),
+ F16(1309.7),
+ F16(1309.2),
+ F16(1310.5),
+ F16(1308.4),
+ F16(1308),
+ F16(1307.5),
+ F16(1308.9),
+ F16(1306.4),
+ F16(1305.9),
+ F16(1305.3),
+ F16(1307),
+ F16(1304.4),
+ F16(1303.9),
+ F16(1303.5),
+ F16(1304.9),
+ F16(1302.6),
+ F16(1302),
+ F16(1301.6),
+ F16(1303),
+ F16(1300.7),
+ F16(1300.3),
+ F16(1299.8),
+ F16(1301.2),
+ F16(1298.7),
+ F16(1298.3),
+ F16(1297.9),
+ F16(1299.3),
+ F16(1296.8),
+ F16(1296.3),
+ F16(1295.9),
+ F16(1297.3),
+ F16(1294.8),
+ F16(1294.4),
+ F16(1293.9),
+ F16(1295.4),
+ F16(1292.9),
+ F16(1292.4),
+ F16(1292),
+ F16(1293.4),
+ F16(1291.1),
+ F16(1290.7),
+ F16(1290.2),
+ F16(1291.5),
+ F16(1289.3),
+ F16(1288.9),
+ F16(1288.3),
+ F16(1289.7),
+ F16(1287.4),
+ F16(1286.9),
+ F16(1286.4),
+ F16(1287.9),
+ F16(1285.6),
+ F16(1285),
+ F16(1284.5),
+ F16(1286),
+ F16(1283.5),
+ F16(1283),
+ F16(1282.6),
+ F16(1284),
+ F16(1281.5),
+ F16(1281),
+ F16(1280.5),
+ F16(1282),
+ F16(1279.4),
+ F16(1278.9),
+ F16(1278.3),
+ F16(1280),
+ F16(1277.3),
+ F16(1276.7),
+ F16(1276.2),
+ F16(1277.8),
+ F16(1275.1),
+ F16(1274.6),
+ F16(1274.1),
+ F16(1275.6),
+ F16(1273.1),
+ F16(1272.7),
+ F16(1272.2),
+ F16(1273.6),
+ F16(1271.2),
+ F16(1270.6),
+ F16(1270.2),
+ F16(1271.7),
+ F16(1269.3),
+ F16(1268.8),
+ F16(1268.3),
+ F16(1269.7),
+ F16(1267.2),
+ F16(1266.8),
+ F16(1266.2),
+ F16(1267.7),
+ F16(1265.3),
+ F16(1264.8),
+ F16(1264.3),
+ F16(1265.8),
+ F16(1263.3),
+ F16(1262.8),
+ F16(1262.4),
+ F16(1263.8),
+ F16(1261.4),
+ F16(1260.8),
+ F16(1260.3),
+ F16(1261.9),
+ F16(1259.4),
+ F16(1258.9),
+ F16(1258.6),
+ F16(1259.8),
+ F16(1257.7),
+ F16(1257.3),
+ F16(1256.8),
+ F16(1258.2),
+ F16(1255.8),
+ F16(1255.4),
+ F16(1255),
+ F16(1256.3),
+ F16(1254),
+ F16(1253.5),
+ F16(1253),
+ F16(1254.5),
+ F16(1252.1),
+ F16(1251.6),
+ F16(1251.1),
+ F16(1252.5),
+ F16(1250.2),
+ F16(1249.7),
+ F16(1249.3),
+ F16(1250.7),
+ F16(1248.3),
+ F16(1247.9),
+ F16(1247.4),
+ F16(1248.8),
+ F16(1246.5),
+ F16(1246),
+ F16(1245.5),
+ F16(1247),
+ F16(1244.6),
+ F16(1244.1),
+ F16(1243.7),
+ F16(1245.1),
+ F16(1242.6),
+ F16(1242.1),
+ F16(1241.7),
+ F16(1243.1),
+ F16(1240.6),
+ F16(1240.1),
+ F16(1239.6),
+ F16(1241.1),
+ F16(1238.5),
+ F16(1238),
+ F16(1237.5),
+ F16(1239.1),
+ F16(1236.5),
+ F16(1236),
+ F16(1235.4),
+ F16(1237),
+ F16(1234.2),
+ F16(1233.7),
+ F16(1233.2),
+ F16(1234.9),
+ F16(1232.1),
+ F16(1231.6),
+ F16(1231.1),
+ F16(1232.6),
+ F16(1230.1),
+ F16(1229.6),
+ F16(1229),
+ F16(1230.6),
+ F16(1227.9),
+ F16(1227.4),
+ F16(1226.9),
+ F16(1228.5),
+ F16(1226),
+ F16(1225.5),
+ F16(1225),
+ F16(1226.4),
+ F16(1224),
+ F16(1223.5),
+ F16(1222.9),
+ F16(1224.5),
+ F16(1221.9),
+ F16(1221.4),
+ F16(1220.9),
+ F16(1222.4),
+ F16(1219.8),
+ F16(1219.3),
+ F16(1218.8),
+ F16(1220.4),
+ F16(1217.9),
+ F16(1217.4),
+ F16(1217),
+ F16(1218.4),
+ F16(1216),
+ F16(1215.5),
+ F16(1215.1),
+ F16(1216.5),
+ F16(1214.2),
+ F16(1213.7),
+ F16(1213.3),
+ F16(1214.7),
+ F16(1212.4),
+ F16(1212),
+ F16(1211.6),
+ F16(1212.8),
+ F16(1210.6),
+ F16(1210.2),
+ F16(1209.7),
+ F16(1211.1),
+ F16(1208.9),
+ F16(1208.5),
+ F16(1208.1),
+ F16(1209.3),
+ F16(1207),
+ F16(1206.5),
+ F16(1206.1),
+ F16(1207.6),
+ F16(1205.2),
+ F16(1204.8),
+ F16(1204.3),
+ F16(1205.6),
+ F16(1203.3),
+ F16(1202.8),
+ F16(1202.2),
+ F16(1203.8),
+ F16(1201.2),
+ F16(1200.8),
+ F16(1200.2),
+ F16(1201.7),
+ F16(1199.2),
+ F16(1198.6),
+ F16(1198.1),
+ F16(1199.7),
+ F16(1197.1),
+ F16(1196.5),
+ F16(1196),
+ F16(1197.6),
+ F16(1195),
+ F16(1194.5),
+ F16(1194),
+ F16(1195.5),
+ F16(1193),
+ F16(1192.4),
+ F16(1191.9),
+ F16(1193.5),
+ F16(1190.9),
+ F16(1190.3),
+ F16(1189.9),
+ F16(1191.4),
+ F16(1188.9),
+ F16(1188.3),
+ F16(1187.8),
+ F16(1189.4),
+ F16(1186.7),
+ F16(1186.2),
+ F16(1185.8),
+ F16(1187.2),
+ F16(1184.7),
+ F16(1184.2),
+ F16(1183.7),
+ F16(1185.3),
+ F16(1182.6),
+ F16(1182.1),
+ F16(1181.6),
+ F16(1183.1),
+ F16(1180.6),
+ F16(1180),
+ F16(1179.6),
+ F16(1181.1),
+ F16(1178.7),
+ F16(1178.2),
+ F16(1177.8),
+ F16(1179.1),
+ F16(1176.9),
+ F16(1176.4),
+ F16(1176),
+ F16(1177.3),
+ F16(1175.1),
+ F16(1174.6),
+ F16(1174.2),
+ F16(1175.5),
+ F16(1173.2),
+ F16(1172.7),
+ F16(1172.2),
+ F16(1173.7),
+ F16(1171.4),
+ F16(1170.8),
+ F16(1170.4),
+ F16(1171.8),
+ F16(1169.4),
+ F16(1168.9),
+ F16(1168.3),
+ F16(1169.9),
+ F16(1167.5),
+ F16(1167),
+ F16(1166.5),
+ F16(1167.9),
+ F16(1165.5),
+ F16(1165),
+ F16(1164.5),
+ F16(1166),
+ F16(1163.7),
+ F16(1163.2),
+ F16(1162.7),
+ F16(1164.1),
+ F16(1161.7),
+ F16(1161.1),
+ F16(1160.6),
+ F16(1162.2),
+ F16(1159.6),
+ F16(1159.1),
+ F16(1158.6),
+ F16(1160.2),
+ F16(1157.6),
+ F16(1157.1),
+ F16(1156.6),
+ F16(1158.1),
+ F16(1155.6),
+ F16(1155.1),
+ F16(1154.5),
+ F16(1156.2),
+ F16(1153.5),
+ F16(1153),
+ F16(1152.5),
+ F16(1154),
+ F16(1151.5),
+ F16(1150.9),
+ F16(1150.4),
+ F16(1152),
+ F16(1149.3),
+ F16(1148.8),
+ F16(1148.3),
+ F16(1149.8),
+ F16(1147.3),
+ F16(1146.8),
+ F16(1146.3),
+ F16(1147.8),
+ F16(1145.3),
+ F16(1144.9),
+ F16(1144.4),
+ F16(1145.8),
+ F16(1143.5),
+ F16(1143),
+ F16(1142.6),
+ F16(1143.9),
+ F16(1141.7),
+ F16(1141.2),
+ F16(1140.7),
+ F16(1142.1),
+ F16(1139.8),
+ F16(1139.2),
+ F16(1138.7),
+ F16(1140.2),
+ F16(1137.8),
+ F16(1137.3),
+ F16(1136.8),
+ F16(1138.3),
+ F16(1135.9),
+ F16(1135.5),
+ F16(1135.1),
+ F16(1136.4),
+ F16(1134.2),
+ F16(1133.8),
+ F16(1133.3),
+ F16(1134.6),
+ F16(1132.4),
+ F16(1132.1),
+ F16(1131.6),
+ F16(1132.9),
+ F16(1130.8),
+ F16(1130.2),
+ F16(1129.8),
+ F16(1131.1),
+ F16(1128.9),
+ F16(1128.5),
+ F16(1128),
+ F16(1129.3),
+ F16(1127.1),
+ F16(1126.7),
+ F16(1126.2),
+ F16(1127.6),
+ F16(1125.3),
+ F16(1124.9),
+ F16(1124.4),
+ F16(1125.8),
+ F16(1123.4),
+ F16(1123),
+ F16(1122.5),
+ F16(1123.9),
+ F16(1121.4),
+ F16(1120.9),
+ F16(1120.4),
+ F16(1122),
+ F16(1119.4),
+ F16(1118.9),
+ F16(1118.4),
+ F16(1119.9),
+ F16(1117.4),
+ F16(1116.9),
+ F16(1116.4),
+ F16(1117.8),
+ F16(1115.4),
+ F16(1114.9),
+ F16(1114.4),
+ F16(1115.9),
+ F16(1113.4),
+ F16(1112.9),
+ F16(1112.4),
+ F16(1113.9),
+ F16(1111.4),
+ F16(1110.9),
+ F16(1110.5),
+ F16(1112),
+ F16(1109.4),
+ F16(1108.9),
+ F16(1108.5),
+ F16(1109.9),
+ F16(1107.5),
+ F16(1107),
+ F16(1106.5),
+ F16(1107.9),
+ F16(1105.5),
+ F16(1105),
+ F16(1104.5),
+ F16(1106),
+ F16(1103.6),
+ F16(1103.1),
+ F16(1102.6),
+ F16(1104),
+ F16(1101.7),
+ F16(1101.1),
+ F16(1100.7),
+ F16(1102.1),
+ F16(1099.8),
+ F16(1099.3),
+ F16(1098.9),
+ F16(1100.3),
+ F16(1097.9),
+ F16(1097.4),
+ F16(1097),
+ F16(1098.4),
+ F16(1096.1),
+ F16(1095.6),
+ F16(1095.1),
+ F16(1096.6),
+ F16(1094.1),
+ F16(1093.6),
+ F16(1093),
+ F16(1094.5),
+ F16(1092),
+ F16(1091.5),
+ F16(1090.9),
+ F16(1092.5),
+ F16(1089.8),
+ F16(1089.3),
+ F16(1088.8),
+ F16(1090.3),
+ F16(1087.7),
+ F16(1087.1),
+ F16(1086.7),
+ F16(1088.3),
+ F16(1085.6),
+ F16(1085.1),
+ F16(1084.6),
+ F16(1086.2),
+ F16(1083.5),
+ F16(1083.1),
+ F16(1082.6),
+ F16(1084.1),
+ F16(1081.5),
+ F16(1081),
+ F16(1080.5),
+ F16(1082.1),
+ F16(1079.5),
+ F16(1079),
+ F16(1078.4),
+ F16(1080),
+ F16(1077.5),
+ F16(1076.9),
+ F16(1076.4),
+ F16(1078),
+ F16(1075.4),
+ F16(1074.9),
+ F16(1074.4),
+ F16(1075.9),
+ F16(1073.4),
+ F16(1072.9),
+ F16(1072.4),
+ F16(1074),
+ F16(1071.5),
+ F16(1071),
+ F16(1070.4),
+ F16(1071.9),
+ F16(1069.4),
+ F16(1068.9),
+ F16(1068.4),
+ F16(1069.9),
+ F16(1067.5),
+ F16(1067),
+ F16(1066.5),
+ F16(1067.9),
+ F16(1065.8),
+ F16(1065.4),
+ F16(1064.9),
+ F16(1066.2),
+ F16(1063.9),
+ F16(1063.4),
+ F16(1063),
+ F16(1064.4),
+ F16(1062.1),
+ F16(1061.5),
+ F16(1061.1),
+ F16(1062.6),
+ F16(1060.2),
+ F16(1059.8),
+ F16(1059.3),
+ F16(1060.7),
+ F16(1058.3),
+ F16(1057.9),
+ F16(1057.4),
+ F16(1058.8),
+ F16(1056.5),
+ F16(1056),
+ F16(1055.5),
+ F16(1056.9),
+ F16(1054.5),
+ F16(1054),
+ F16(1053.5),
+ F16(1055),
+ F16(1052.6),
+ F16(1052.1),
+ F16(1051.6),
+ F16(1053.1),
+ F16(1050.5),
+ F16(1050),
+ F16(1049.5),
+ F16(1051.1),
+ F16(1048.5),
+ F16(1048),
+ F16(1047.4),
+ F16(1049),
+ F16(1046.2),
+ F16(1045.8),
+ F16(1045.3),
+ F16(1046.8),
+ F16(1044.3),
+ F16(1043.8),
+ F16(1043.2),
+ F16(1044.8),
+ F16(1042.2),
+ F16(1041.7),
+ F16(1041.2),
+ F16(1042.7),
+ F16(1040.1),
+ F16(1039.6),
+ F16(1039.1),
+ F16(1040.7),
+ F16(1038.2),
+ F16(1037.7),
+ F16(1037.2),
+ F16(1038.7),
+ F16(1036.3),
+ F16(1035.7),
+ F16(1035.3),
+ F16(1036.8),
+ F16(1034.2),
+ F16(1033.8),
+ F16(1033.4),
+ F16(1034.7),
+ F16(1032.3),
+ F16(1031.9),
+ F16(1031.4),
+ F16(1032.9),
+ F16(1030.5),
+ F16(1030),
+ F16(1029.5),
+ F16(1031),
+ F16(1028.6),
+ F16(1028.1),
+ F16(1027.6),
+ F16(1029),
+ F16(1026.7),
+ F16(1026.2),
+ F16(1025.7),
+ F16(1027.2),
+ F16(1024.7),
+ F16(1024.2),
+ F16(1023.8),
+ F16(1025.2),
+ F16(1022.9),
+ F16(1022.5),
+ F16(1022),
+ F16(1023.4),
+ F16(1021.1),
+ F16(1020.7),
+ F16(1020.1),
+ F16(1021.7),
+ F16(1019.1),
+ F16(1018.6),
+ F16(1018.2),
+ F16(1019.6),
+ F16(1017.3),
+ F16(1016.8),
+ F16(1016.3),
+ F16(1017.7),
+ F16(1015.4),
+ F16(1014.9),
+ F16(1014.4),
+ F16(1015.9),
+ F16(1013.3),
+ F16(1012.8),
+ F16(1012.3),
+ F16(1013.9),
+ F16(1011.2),
+ F16(1010.7),
+ F16(1010.2),
+ F16(1011.8),
+ F16(1009.1),
+ F16(1008.5),
+ F16(1008),
+ F16(1009.6),
+ F16(1007),
+ F16(1006.5),
+ F16(1005.9),
+ F16(1007.5),
+ F16(1004.9),
+ F16(1004.5),
+ F16(1004),
+ F16(1005.5),
+ F16(1003),
+ F16(1002.4),
+ F16(1001.9),
+ F16(1003.4),
+ F16(1000.9),
+ F16(1000.5),
+ F16(1000),
+ F16(1001.5),
+ F16(998.9),
+ F16(998.4),
+ F16(998),
+ F16(999.4),
+ F16(997),
+ F16(996.5),
+ F16(996),
+ F16(997.5),
+ F16(995.1),
+ F16(994.7),
+ F16(994.2),
+ F16(995.5),
+ F16(993.3),
+ F16(992.8),
+ F16(992.3),
+ F16(993.8),
+ F16(991.4),
+ F16(991),
+ F16(990.5),
+ F16(991.9),
+ F16(989.5),
+ F16(989.1),
+ F16(988.6),
+ F16(990),
+ F16(987.6),
+ F16(987.2),
+ F16(986.7),
+ F16(988.1),
+ F16(985.7),
+ F16(985.2),
+ F16(984.8),
+ F16(986.3),
+ F16(983.9),
+ F16(983.4),
+ F16(982.9),
+ F16(984.4),
+ F16(982),
+ F16(981.5),
+ F16(981.1),
+ F16(982.4),
+ F16(980.1),
+ F16(979.6),
+ F16(979.1),
+ F16(980.6),
+ F16(978.1),
+ F16(977.6),
+ F16(977.1),
+ F16(978.6),
+ F16(976.1),
+ F16(975.7),
+ F16(975.2),
+ F16(976.6),
+ F16(974.2),
+ F16(973.7),
+ F16(973.2),
+ F16(974.7),
+ F16(972.3),
+ F16(971.8),
+ F16(971.2),
+ F16(972.7),
+ F16(970.3),
+ F16(969.7),
+ F16(969.2),
+ F16(970.8),
+ F16(968.2),
+ F16(967.7),
+ F16(967.2),
+ F16(968.7),
+ F16(966.1),
+ F16(965.7),
+ F16(965.2),
+ F16(966.7),
+ F16(964.2),
+ F16(963.8),
+ F16(963.4),
+ F16(964.7),
+ F16(962.4),
+ F16(961.9),
+ F16(961.5),
+ F16(962.9),
+ F16(960.7),
+ F16(960.2),
+ F16(959.7),
+ F16(961.1),
+ F16(958.7),
+ F16(958.2),
+ F16(957.7),
+ F16(959.2),
+ F16(956.7),
+ F16(956.2),
+ F16(955.7),
+ F16(957.1),
+ F16(954.7),
+ F16(954.3),
+ F16(953.8),
+ F16(955.2),
+ F16(952.9),
+ F16(952.4),
+ F16(952),
+ F16(953.3),
+ F16(951.1),
+ F16(950.6),
+ F16(950.2),
+ F16(951.5),
+ F16(949.3),
+ F16(948.8),
+ F16(948.4),
+ F16(949.8),
+ F16(947.5),
+ F16(947),
+ F16(946.6),
+ F16(947.9),
+ F16(945.7),
+ F16(945.3),
+ F16(944.8),
+ F16(946.2),
+ F16(943.8),
+ F16(943.3),
+ F16(943),
+ F16(944.3),
+ F16(942),
+ F16(941.5),
+ F16(941),
+ F16(942.5),
+ F16(940.1),
+ F16(939.7),
+ F16(939.2),
+ F16(940.6),
+ F16(938.1),
+ F16(937.6),
+ F16(937.1),
+ F16(938.6),
+ F16(936.1),
+ F16(935.7),
+ F16(935.2),
+ F16(936.6),
+ F16(934.3),
+ F16(933.9),
+ F16(933.3),
+ F16(934.8),
+ F16(932.5),
+ F16(932.1),
+ F16(931.6),
+ F16(932.9),
+ F16(930.7),
+ F16(930.2),
+ F16(929.7),
+ F16(931.1),
+ F16(928.8),
+ F16(928.3),
+ F16(927.8),
+ F16(929.3),
+ F16(926.9),
+ F16(926.4),
+ F16(926),
+ F16(927.4),
+ F16(925.1),
+ F16(924.5),
+ F16(924.1),
+ F16(925.6),
+ F16(923.1),
+ F16(922.6),
+ F16(922.2),
+ F16(923.6),
+ F16(921.2),
+ F16(920.8),
+ F16(920.3),
+ F16(921.7),
+ F16(919.4),
+ F16(919),
+ F16(918.5),
+ F16(919.9),
+ F16(917.5),
+ F16(917),
+ F16(916.5),
+ F16(918),
+ F16(915.6),
+ F16(915.2),
+ F16(914.8),
+ F16(916),
+ F16(913.8),
+ F16(913.4),
+ F16(912.9),
+ F16(914.3),
+ F16(912),
+ F16(911.5),
+ F16(911),
+ F16(912.4),
+ F16(910),
+ F16(909.6),
+ F16(909.1),
+ F16(910.5),
+ F16(908.1),
+ F16(907.6),
+ F16(907),
+ F16(908.6),
+ F16(906.1),
+ F16(905.6),
+ F16(905.1),
+ F16(906.6),
+ F16(904.2),
+ F16(903.7),
+ F16(903.2),
+ F16(904.7),
+ F16(902.2),
+ F16(901.7),
+ F16(901.3),
+ F16(902.7),
+ F16(900.3),
+ F16(899.9),
+ F16(899.4),
+ F16(900.9),
+ F16(898.4),
+ F16(898),
+ F16(897.5),
+ F16(899),
+ F16(896.6),
+ F16(896.1),
+ F16(895.7),
+ F16(897.1),
+ F16(894.8),
+ F16(894.4),
+ F16(893.9),
+ F16(895.2),
+ F16(892.9),
+ F16(892.5),
+ F16(892),
+ F16(893.4),
+ F16(890.9),
+ F16(890.5),
+ F16(890),
+ F16(891.4),
+ F16(889.1),
+ F16(888.6),
+ F16(888.1),
+ F16(889.5),
+ F16(887.2),
+ F16(886.7),
+ F16(886.4),
+ F16(887.6),
+ F16(885.4),
+ F16(885),
+ F16(884.6),
+ F16(885.9),
+ F16(883.7),
+ F16(883.2),
+ F16(882.7),
+ F16(884.1),
+ F16(881.9),
+ F16(881.5),
+ F16(881.1),
+ F16(882.3),
+ F16(880.1),
+ F16(879.6),
+ F16(879.2),
+ F16(880.6),
+ F16(878.2),
+ F16(877.8),
+ F16(877.4),
+ F16(878.7),
+ F16(876.4),
+ F16(875.9),
+ F16(875.5),
+ F16(876.9),
+ F16(874.5),
+ F16(874),
+ F16(873.5),
+ F16(875),
+ F16(872.5),
+ F16(872),
+ F16(871.5),
+ F16(873),
+ F16(870.6),
+ F16(870.1),
+ F16(869.6),
+ F16(871),
+ F16(868.6),
+ F16(868.2),
+ F16(867.7),
+ F16(869.1),
+ F16(866.8),
+ F16(866.3),
+ F16(865.8),
+ F16(867.3),
+ F16(864.8),
+ F16(864.3),
+ F16(863.8),
+ F16(865.3),
+ F16(862.8),
+ F16(862.3),
+ F16(861.8),
+ F16(863.3),
+ F16(860.9),
+ F16(860.4),
+ F16(860),
+ F16(861.4),
+ F16(859.1),
+ F16(858.6),
+ F16(858.1),
+ F16(859.5),
+ F16(856.9),
+ F16(856.5),
+ F16(856),
+ F16(857.5),
+ F16(855),
+ F16(854.6),
+ F16(854.1),
+ F16(855.5),
+ F16(853.2),
+ F16(852.7),
+ F16(852.3),
+ F16(853.6),
+ F16(851.3),
+ F16(850.8),
+ F16(850.4),
+ F16(851.8),
+ F16(849.4),
+ F16(849),
+ F16(848.5),
+ F16(849.9),
+ F16(847.7),
+ F16(847.2),
+ F16(846.8),
+ F16(848.1),
+ F16(845.9),
+ F16(845.4),
+ F16(844.9),
+ F16(846.3),
+ F16(844),
+ F16(843.5),
+ F16(843),
+ F16(844.5),
+ F16(842),
+ F16(841.5),
+ F16(841),
+ F16(842.5),
+ F16(840.1),
+ F16(839.6),
+ F16(839.1),
+ F16(840.6),
+ F16(838.1),
+ F16(837.5),
+ F16(837),
+ F16(838.6),
+ F16(836),
+ F16(835.5),
+ F16(835),
+ F16(836.5),
+ F16(834.1),
+ F16(833.7),
+ F16(833.2),
+ F16(834.5),
+ F16(832.2),
+ F16(831.7),
+ F16(831.2),
+ F16(832.7),
+ F16(830.2),
+ F16(829.6),
+ F16(829.1),
+ F16(830.7),
+ F16(828.1),
+ F16(827.6),
+ F16(827),
+ F16(828.6),
+ F16(826.1),
+ F16(825.5),
+ F16(825),
+ F16(826.6),
+ F16(823.9),
+ F16(823.4),
+ F16(822.9),
+ F16(824.4),
+ F16(822),
+ F16(821.5),
+ F16(821.1),
+ F16(822.5),
+ F16(820.1),
+ F16(819.6),
+ F16(819.1),
+ F16(820.6),
+ F16(818.2),
+ F16(817.7),
+ F16(817.2),
+ F16(818.6),
+ F16(816.2),
+ F16(815.7),
+ F16(815.3),
+ F16(816.7),
+ F16(814.4),
+ F16(814),
+ F16(813.6),
+ F16(814.8),
+ F16(812.7),
+ F16(812.3),
+ F16(811.8),
+ F16(813.1),
+ F16(810.8),
+ F16(810.3),
+ F16(809.9),
+ F16(811.3),
+ F16(808.9),
+ F16(808.4),
+ F16(807.9),
+ F16(809.3),
+ F16(806.9),
+ F16(806.5),
+ F16(806),
+ F16(807.3),
+ F16(805),
+ F16(804.5),
+ F16(804),
+ F16(805.5),
+ F16(803.1),
+ F16(802.6),
+ F16(802.1),
+ F16(803.5),
+ F16(801.2),
+ F16(800.7),
+ F16(800.2),
+ F16(801.7),
+ F16(799.2),
+ F16(798.6),
+ F16(798.1),
+ F16(799.7),
+ F16(797.1),
+ F16(796.6),
+ F16(796),
+ F16(797.6),
+ F16(794.9),
+ F16(794.5),
+ F16(794),
+ F16(795.5),
+ F16(793.1),
+ F16(792.6),
+ F16(792.1),
+ F16(793.5),
+ F16(791.1),
+ F16(790.6),
+ F16(790),
+ F16(791.6),
+ F16(788.9),
+ F16(788.4),
+ F16(787.8),
+ F16(789.4),
+ F16(786.8),
+ F16(786.3),
+ F16(785.8),
+ F16(787.3),
+ F16(784.7),
+ F16(784.2),
+ F16(783.7),
+ F16(785.2),
+ F16(782.8),
+ F16(782.3),
+ F16(781.8),
+ F16(783.2),
+ F16(780.8),
+ F16(780.3),
+ F16(779.8),
+ F16(781.3),
+ F16(778.9),
+ F16(778.4),
+ F16(777.9),
+ F16(779.3),
+ F16(777),
+ F16(776.5),
+ F16(776),
+ F16(777.4),
+ F16(775),
+ F16(774.5),
+ F16(774),
+ F16(775.5),
+ F16(772.9),
+ F16(772.4),
+ F16(771.9),
+ F16(773.5),
+ F16(770.9),
+ F16(770.5),
+ F16(770),
+ F16(771.4),
+ F16(769),
+ F16(768.5),
+ F16(768),
+ F16(769.5),
+ F16(766.9),
+ F16(766.4),
+ F16(765.9),
+ F16(767.4),
+ F16(765),
+ F16(764.6),
+ F16(764),
+ F16(765.5),
+ F16(763.1),
+ F16(762.5),
+ F16(762.1),
+ F16(763.5),
+ F16(761.1),
+ F16(760.6),
+ F16(760.1),
+ F16(761.5),
+ F16(759.1),
+ F16(758.6),
+ F16(758),
+ F16(759.6),
+ F16(757),
+ F16(756.5),
+ F16(756),
+ F16(757.5),
+ F16(755.1),
+ F16(754.6),
+ F16(754),
+ F16(755.6),
+ F16(753.1),
+ F16(752.6),
+ F16(752.1),
+ F16(753.6),
+ F16(751),
+ F16(750.6),
+ F16(750.2),
+ F16(751.6),
+ F16(749.2),
+ F16(748.7),
+ F16(748.2),
+ F16(749.7),
+ F16(747.3),
+ F16(746.8),
+ F16(746.4),
+ F16(747.7),
+ F16(745.3),
+ F16(744.7),
+ F16(744.2),
+ F16(745.8),
+ F16(743.2),
+ F16(742.8),
+ F16(742.3),
+ F16(743.7),
+ F16(741.3),
+ F16(740.8),
+ F16(740.4),
+ F16(741.8),
+ F16(739.6),
+ F16(739.1),
+ F16(738.6),
+ F16(739.9),
+ F16(737.7),
+ F16(737.3),
+ F16(736.8),
+ F16(738.2),
+ F16(735.8),
+ F16(735.3),
+ F16(734.8),
+ F16(736.2),
+ F16(733.9),
+ F16(733.4),
+ F16(732.9),
+ F16(734.3),
+ F16(732),
+ F16(731.4),
+ F16(730.9),
+ F16(732.4),
+ F16(730),
+ F16(729.5),
+ F16(729),
+ F16(730.5),
+ F16(728.1),
+ F16(727.6),
+ F16(727.2),
+ F16(728.6),
+ F16(726.2),
+ F16(725.7),
+ F16(725.3),
+ F16(726.7),
+ F16(724.4),
+ F16(723.9),
+ F16(723.4),
+ F16(724.9),
+ F16(722.4),
+ F16(721.9),
+ F16(721.5),
+ F16(722.9),
+ F16(720.6),
+ F16(720.2),
+ F16(719.7),
+ F16(721),
+ F16(718.7),
+ F16(718.4),
+ F16(717.9),
+ F16(719.2),
+ F16(716.9),
+ F16(716.3),
+ F16(715.8),
+ F16(717.3),
+ F16(714.9),
+ F16(714.3),
+ F16(713.9),
+ F16(715.3),
+ F16(713.1),
+ F16(712.7),
+ F16(712.2),
+ F16(713.4),
+ F16(711.3),
+ F16(710.8),
+ F16(710.3),
+ F16(711.8),
+ F16(709.5),
+ F16(708.9),
+ F16(708.4),
+ F16(709.9),
+ F16(707.5),
+ F16(707.1),
+ F16(706.6),
+ F16(708),
+ F16(705.7),
+ F16(705.2),
+ F16(704.7),
+ F16(706.2),
+ F16(703.7),
+ F16(703.2),
+ F16(702.7),
+ F16(704.2),
+ F16(701.6),
+ F16(701.1),
+ F16(700.6),
+ F16(702.2),
+ F16(699.7),
+ F16(699.2),
+ F16(698.6),
+ F16(700.1),
+ F16(697.7),
+ F16(697.3),
+ F16(696.8),
+ F16(698.2),
+ F16(695.8),
+ F16(695.4),
+ F16(694.9),
+ F16(696.3),
+ F16(694),
+ F16(693.6),
+ F16(693),
+ F16(694.4),
+ F16(692.1),
+ F16(691.6),
+ F16(691.1),
+ F16(692.5),
+ F16(690.1),
+ F16(689.6),
+ F16(689),
+ F16(690.6),
+ F16(688),
+ F16(687.5),
+ F16(687),
+ F16(688.5),
+ F16(686),
+ F16(685.6),
+ F16(685.1),
+ F16(686.5),
+ F16(684.2),
+ F16(683.6),
+ F16(683.1),
+ F16(684.6),
+ F16(682.1),
+ F16(681.5),
+ F16(681),
+ F16(682.6),
+ F16(680),
+ F16(679.6),
+ F16(679.1),
+ F16(680.6),
+ F16(678.3),
+ F16(677.8),
+ F16(677.3),
+ F16(678.7),
+ F16(676.3),
+ F16(675.9),
+ F16(675.5),
+ F16(676.8),
+ F16(674.6),
+ F16(674.1),
+ F16(673.6),
+ F16(675.1),
+ F16(672.6),
+ F16(672.2),
+ F16(671.7),
+ F16(673.1),
+ F16(670.7),
+ F16(670.2),
+ F16(669.6),
+ F16(671.2),
+ F16(668.6),
+ F16(668.2),
+ F16(667.6),
+ F16(669.1),
+ F16(666.8),
+ F16(666.3),
+ F16(665.9),
+ F16(667.2),
+ F16(664.9),
+ F16(664.5),
+ F16(664.1),
+ F16(665.4),
+ F16(663.2),
+ F16(662.6),
+ F16(662.2),
+ F16(663.7),
+ F16(661.2),
+ F16(660.7),
+ F16(660.3),
+ F16(661.7),
+ F16(659.4),
+ F16(659),
+ F16(658.5),
+ F16(659.8),
+ F16(657.7),
+ F16(657.2),
+ F16(656.7),
+ F16(658.1),
+ F16(655.7),
+ F16(655.2),
+ F16(654.7),
+ F16(656.1),
+ F16(653.8),
+ F16(653.4),
+ F16(652.8),
+ F16(654.3),
+ F16(651.8),
+ F16(651.2),
+ F16(650.8),
+ F16(652.3),
+ F16(649.8),
+ F16(649.5),
+ F16(649),
+ F16(650.3),
+ F16(648),
+ F16(647.4),
+ F16(646.9),
+ F16(648.5),
+ F16(646.1),
+ F16(645.6),
+ F16(645.2),
+ F16(646.5),
+ F16(644.2),
+ F16(643.6),
+ F16(643.1),
+ F16(644.6),
+ F16(642.2),
+ F16(641.7),
+ F16(641.2),
+ F16(642.6),
+ F16(640.1),
+ F16(639.5),
+ F16(639),
+ F16(640.7),
+ F16(638.2),
+ F16(637.7),
+ F16(637.2),
+ F16(638.6),
+ F16(636.2),
+ F16(635.7),
+ F16(635.3),
+ F16(636.7),
+ F16(634.3),
+ F16(633.9),
+ F16(633.4),
+ F16(634.8),
+ F16(632.5),
+ F16(632),
+ F16(631.5),
+ F16(632.9),
+ F16(630.6),
+ F16(630.1),
+ F16(629.5),
+ F16(630.9),
+ F16(628.7),
+ F16(628.2),
+ F16(627.8),
+ F16(629),
+ F16(626.7),
+ F16(626.2),
+ F16(625.7),
+ F16(627.3),
+ F16(624.7),
+ F16(624.3),
+ F16(623.7),
+ F16(625.2),
+ F16(622.8),
+ F16(622.3),
+ F16(621.8),
+ F16(623.2),
+ F16(620.8),
+ F16(620.4),
+ F16(620),
+ F16(621.3),
+ F16(619.1),
+ F16(618.6),
+ F16(618.1),
+ F16(619.6),
+ F16(617.2),
+ F16(616.8),
+ F16(616.2),
+ F16(617.6),
+ F16(615.3),
+ F16(614.9),
+ F16(614.3),
+ F16(615.8),
+ F16(613.3),
+ F16(612.8),
+ F16(612.4),
+ F16(613.8),
+ F16(611.4),
+ F16(610.9),
+ F16(610.3),
+ F16(611.9),
+ F16(609.3),
+ F16(608.9),
+ F16(608.3),
+ F16(609.7),
+ F16(607.4),
+ F16(606.9),
+ F16(606.4),
+ F16(607.8),
+ F16(605.4),
+ F16(604.9),
+ F16(604.4),
+ F16(605.9),
+ F16(603.4),
+ F16(602.9),
+ F16(602.5),
+ F16(603.8),
+ F16(601.6),
+ F16(601.1),
+ F16(600.6),
+ F16(602.1),
+ F16(599.6),
+ F16(599.2),
+ F16(598.6),
+ F16(600.1),
+ F16(597.6),
+ F16(597.1),
+ F16(596.6),
+ F16(598.2),
+ F16(595.6),
+ F16(595),
+ F16(594.6),
+ F16(596.1),
+ F16(593.6),
+ F16(593.1),
+ F16(592.6),
+ F16(594.1),
+ F16(591.6),
+ F16(591.1),
+ F16(590.6),
+ F16(592),
+ F16(589.7),
+ F16(589.2),
+ F16(588.7),
+ F16(590.1),
+ F16(587.7),
+ F16(587.3),
+ F16(586.7),
+ F16(588.2),
+ F16(585.8),
+ F16(585.3),
+ F16(584.8),
+ F16(586.2),
+ F16(583.7),
+ F16(583.2),
+ F16(582.7),
+ F16(584.2),
+ F16(581.8),
+ F16(581.3),
+ F16(580.7),
+ F16(582.2),
+ F16(579.8),
+ F16(579.4),
+ F16(578.9),
+ F16(580.2),
+ F16(577.8),
+ F16(577.3),
+ F16(576.7),
+ F16(578.4),
+ F16(575.7),
+ F16(575.3),
+ F16(574.9),
+ F16(576.2),
+ F16(573.9),
+ F16(573.3),
+ F16(572.8),
+ F16(574.4),
+ F16(571.8),
+ F16(571.3),
+ F16(570.8),
+ F16(572.3),
+ F16(569.7),
+ F16(569.3),
+ F16(568.8),
+ F16(570.3),
+ F16(567.8),
+ F16(567.4),
+ F16(566.8),
+ F16(568.3),
+ F16(565.7),
+ F16(565.3),
+ F16(564.8),
+ F16(566.2),
+ F16(563.8),
+ F16(563.2),
+ F16(562.7),
+ F16(564.2),
+ F16(561.6),
+ F16(561.1),
+ F16(560.6),
+ F16(562.1),
+ F16(559.5),
+ F16(559.1),
+ F16(558.6),
+ F16(560.1),
+ F16(557.6),
+ F16(557.1),
+ F16(556.6),
+ F16(558),
+ F16(555.7),
+ F16(555.2),
+ F16(554.7),
+ F16(556.1),
+ F16(553.7),
+ F16(553.2),
+ F16(552.7),
+ F16(554.2),
+ F16(551.8),
+ F16(551.4),
+ F16(551),
+ F16(552.2),
+ F16(549.9),
+ F16(549.4),
+ F16(548.8),
+ F16(550.4),
+ F16(548),
+ F16(547.6),
+ F16(547.1),
+ F16(548.4),
+ F16(546.2),
+ F16(545.6),
+ F16(545.1),
+ F16(546.6),
+ F16(544),
+ F16(543.5),
+ F16(542.9),
+ F16(544.5),
+ F16(541.9),
+ F16(541.5),
+ F16(541),
+ F16(542.4),
+ F16(539.8),
+ F16(539.5),
+ F16(538.9),
+ F16(540.4),
+ F16(538),
+ F16(537.5),
+ F16(537.1),
+ F16(538.4),
+ F16(536.1),
+ F16(535.6),
+ F16(535.1),
+ F16(536.6),
+ F16(534.1),
+ F16(533.7),
+ F16(533.1),
+ F16(534.6),
+ F16(532.1),
+ F16(531.6),
+ F16(531),
+ F16(532.6),
+ F16(530.1),
+ F16(529.6),
+ F16(529.1),
+ F16(530.5),
+ F16(528.1),
+ F16(527.6),
+ F16(527.1),
+ F16(528.6),
+ F16(526.1),
+ F16(525.7),
+ F16(525.1),
+ F16(526.6),
+ F16(524.2),
+ F16(523.8),
+ F16(523.3),
+ F16(524.7),
+ F16(522.3),
+ F16(521.8),
+ F16(521.3),
+ F16(522.8),
+ F16(520.4),
+ F16(520),
+ F16(519.5),
+ F16(520.8),
+ F16(518.5),
+ F16(518.1),
+ F16(517.6),
+ F16(519),
+ F16(516.6),
+ F16(516.1),
+ F16(515.7),
+ F16(517),
+ F16(514.7),
+ F16(514.2),
+ F16(513.7),
+ F16(515.1),
+ F16(512.8),
+ F16(512.3),
+ F16(511.8),
+ F16(513.3),
+ F16(510.9),
+ F16(510.5),
+ F16(510),
+ F16(511.3),
+ F16(509),
+ F16(508.6),
+ F16(508.2),
+ F16(509.4),
+ F16(507.2),
+ F16(506.7),
+ F16(506.2),
+ F16(507.6),
+ F16(505.3),
+ F16(504.8),
+ F16(504.3),
+ F16(505.7),
+ F16(503.4),
+ F16(503),
+ F16(502.4),
+ F16(503.8),
+ F16(501.4),
+ F16(500.9),
+ F16(500.4),
+ F16(501.9),
+ F16(499.4),
+ F16(498.8),
+ F16(498.3),
+ F16(499.9),
+ F16(497.3),
+ F16(496.9),
+ F16(496.3),
+ F16(497.8),
+ F16(495.3),
+ F16(494.9),
+ F16(494.5),
+ F16(495.9),
+ F16(493.5),
+ F16(493.1),
+ F16(492.6),
+ F16(494),
+ F16(491.7),
+ F16(491.1),
+ F16(490.6),
+ F16(492.2),
+ F16(489.7),
+ F16(489.2),
+ F16(488.7),
+ F16(490.2),
+ F16(487.7),
+ F16(487.2),
+ F16(486.8),
+ F16(488.2),
+ F16(485.7),
+ F16(485.3),
+ F16(484.8),
+ F16(486.2),
+ F16(483.8),
+ F16(483.4),
+ F16(483),
+ F16(484.3),
+ F16(482),
+ F16(481.5),
+ F16(480.9),
+ F16(482.4),
+ F16(480),
+ F16(479.5),
+ F16(478.9),
+ F16(480.5),
+ F16(478),
+ F16(477.6),
+ F16(477.2),
+ F16(478.4),
+ F16(476.3),
+ F16(475.8),
+ F16(475.3),
+ F16(476.8),
+ F16(474.4),
+ F16(474),
+ F16(473.6),
+ F16(474.9),
+ F16(472.7),
+ F16(472.3),
+ F16(471.8),
+ F16(473.1),
+ F16(470.8),
+ F16(470.3),
+ F16(469.8),
+ F16(471.2),
+ F16(468.9),
+ F16(468.4),
+ F16(467.9),
+ F16(469.4),
+ F16(467),
+ F16(466.6),
+ F16(466.1),
+ F16(467.5),
+ F16(465.2),
+ F16(464.7),
+ F16(464.2),
+ F16(465.6),
+ F16(463.3),
+ F16(462.8),
+ F16(462.3),
+ F16(463.8),
+ F16(461.2),
+ F16(460.7),
+ F16(460.3),
+ F16(461.7),
+ F16(459.3),
+ F16(458.9),
+ F16(458.3),
+ F16(459.8),
+ F16(457.3),
+ F16(456.9),
+ F16(456.4),
+ F16(457.8),
+ F16(455.5),
+ F16(455),
+ F16(454.4),
+ F16(455.9),
+ F16(453.4),
+ F16(452.9),
+ F16(452.4),
+ F16(453.9),
+ F16(451.5),
+ F16(451),
+ F16(450.6),
+ F16(452),
+ F16(449.6),
+ F16(449.2),
+ F16(448.6),
+ F16(450.1),
+ F16(447.8),
+ F16(447.4),
+ F16(446.9),
+ F16(448.2),
+ F16(446),
+ F16(445.5),
+ F16(445),
+ F16(446.4),
+ F16(444.2),
+ F16(443.8),
+ F16(443.3),
+ F16(444.6),
+ F16(442.4),
+ F16(441.9),
+ F16(441.4),
+ F16(442.8),
+ F16(440.5),
+ F16(440.1),
+ F16(439.7),
+ F16(441),
+ F16(438.8),
+ F16(438.4),
+ F16(438),
+ F16(439.2),
+ F16(437),
+ F16(436.5),
+ F16(436.1),
+ F16(437.5),
+ F16(435.2),
+ F16(434.8),
+ F16(434.3),
+ F16(435.6),
+ F16(433.4),
+ F16(433),
+ F16(432.5),
+ F16(433.8),
+ F16(431.6),
+ F16(431.1),
+ F16(430.6),
+ F16(432),
+ F16(429.8),
+ F16(429.4),
+ F16(428.9),
+ F16(430.2),
+ F16(428),
+ F16(427.5),
+ F16(427.1),
+ F16(428.5),
+ F16(426.1),
+ F16(425.7),
+ F16(425.2),
+ F16(426.6),
+ F16(424.3),
+ F16(423.8),
+ F16(423.3),
+ F16(424.7),
+ F16(422.4),
+ F16(422),
+ F16(421.4),
+ F16(422.8),
+ F16(420.6),
+ F16(420.1),
+ F16(419.6),
+ F16(420.9),
+ F16(418.6),
+ F16(418.2),
+ F16(417.7),
+ F16(419.1),
+ F16(416.7),
+ F16(416.3),
+ F16(415.8),
+ F16(417.2),
+ F16(414.9),
+ F16(414.4),
+ F16(414),
+ F16(415.3),
+ F16(413.1),
+ F16(412.7),
+ F16(412.2),
+ F16(413.6),
+ F16(411.3),
+ F16(410.8),
+ F16(410.4),
+ F16(411.7),
+ F16(409.4),
+ F16(409),
+ F16(408.6),
+ F16(409.9),
+ F16(407.7),
+ F16(407.2),
+ F16(406.7),
+ F16(408.1),
+ F16(405.8),
+ F16(405.2),
+ F16(404.7),
+ F16(406.2),
+ F16(403.9),
+ F16(403.5),
+ F16(403),
+ F16(404.4),
+ F16(401.9),
+ F16(401.4),
+ F16(401),
+ F16(402.5),
+ F16(400.1),
+ F16(399.6),
+ F16(399),
+ F16(400.6),
+ F16(398.2),
+ F16(397.6),
+ F16(397.1),
+ F16(398.6),
+ F16(396.1),
+ F16(395.7),
+ F16(395.2),
+ F16(396.6),
+ F16(394.3),
+ F16(393.9),
+ F16(393.4),
+ F16(394.7),
+ F16(392.6),
+ F16(392.1),
+ F16(391.6),
+ F16(393),
+ F16(390.7),
+ F16(390.1),
+ F16(389.6),
+ F16(391.1),
+ F16(388.6),
+ F16(388.2),
+ F16(387.7),
+ F16(389.1),
+ F16(386.8),
+ F16(386.3),
+ F16(385.8),
+ F16(387.3),
+ F16(384.9),
+ F16(384.4),
+ F16(383.9),
+ F16(385.4),
+ F16(383.1),
+ F16(382.5),
+ F16(382),
+ F16(383.5),
+ F16(381),
+ F16(380.6),
+ F16(380),
+ F16(381.6),
+ F16(379.1),
+ F16(378.6),
+ F16(378.2),
+ F16(379.5),
+ F16(377.2),
+ F16(376.7),
+ F16(376.3),
+ F16(377.7),
+ F16(375.4),
+ F16(374.9),
+ F16(374.5),
+ F16(375.8),
+ F16(373.5),
+ F16(373.1),
+ F16(372.6),
+ F16(374),
+ F16(371.7),
+ F16(371.2),
+ F16(370.7),
+ F16(372.1),
+ F16(369.7),
+ F16(369.2),
+ F16(368.6),
+ F16(370.1),
+ F16(367.7),
+ F16(367.2),
+ F16(366.8),
+ F16(368.1),
+ F16(365.9),
+ F16(365.4),
+ F16(365),
+ F16(366.3),
+ F16(364),
+ F16(363.5),
+ F16(363.1),
+ F16(364.5),
+ F16(362.1),
+ F16(361.6),
+ F16(361.1),
+ F16(362.5),
+ F16(360.2),
+ F16(359.7),
+ F16(359.2),
+ F16(360.6),
+ F16(358.3),
+ F16(357.8),
+ F16(357.3),
+ F16(358.7),
+ F16(356.4),
+ F16(355.9),
+ F16(355.3),
+ F16(356.8),
+ F16(354.4),
+ F16(353.9),
+ F16(353.5),
+ F16(354.8),
+ F16(352.5),
+ F16(352.1),
+ F16(351.6),
+ F16(353),
+ F16(350.6),
+ F16(350.1),
+ F16(349.6),
+ F16(351.1),
+ F16(348.6),
+ F16(348.1),
+ F16(347.6),
+ F16(349.1),
+ F16(346.6),
+ F16(346.1),
+ F16(345.6),
+ F16(347.1),
+ F16(344.6),
+ F16(344.2),
+ F16(343.8),
+ F16(345.1),
+ F16(342.9),
+ F16(342.3),
+ F16(341.9),
+ F16(343.4),
+ F16(340.9),
+ F16(340.5),
+ F16(340.1),
+ F16(341.4),
+ F16(339.1),
+ F16(338.7),
+ F16(338.1),
+ F16(339.6),
+ F16(337.1),
+ F16(336.6),
+ F16(336.1),
+ F16(337.6),
+ F16(335.2),
+ F16(334.7),
+ F16(334.2),
+ F16(335.6),
+ F16(333.3),
+ F16(332.8),
+ F16(332.4),
+ F16(333.7),
+ F16(331.5),
+ F16(331),
+ F16(330.5),
+ F16(331.8),
+ F16(329.5),
+ F16(329),
+ F16(328.5),
+ F16(330),
+ F16(327.6),
+ F16(327.1),
+ F16(326.7),
+ F16(328),
+ F16(325.8),
+ F16(325.4),
+ F16(325),
+ F16(326.3),
+ F16(324.2),
+ F16(323.8),
+ F16(323.3),
+ F16(324.6),
+ F16(322.4),
+ F16(321.9),
+ F16(321.5),
+ F16(322.9),
+ F16(320.4),
+ F16(319.9),
+ F16(319.3),
+ F16(320.9),
+ F16(318.4),
+ F16(318),
+ F16(317.5),
+ F16(318.9),
+ F16(316.5),
+ F16(316.1),
+ F16(315.6),
+ F16(316.9),
+ F16(314.8),
+ F16(314.3),
+ F16(313.9),
+ F16(315.2),
+ F16(313.1),
+ F16(312.7),
+ F16(312.2),
+ F16(313.5),
+ F16(311.4),
+ F16(310.9),
+ F16(310.4),
+ F16(311.8),
+ F16(309.5),
+ F16(309.1),
+ F16(308.6),
+ F16(309.9),
+ F16(307.8),
+ F16(307.3),
+ F16(306.9),
+ F16(308.2),
+ F16(305.9),
+ F16(305.5),
+ F16(305),
+ F16(306.4),
+ F16(304.1),
+ F16(303.6),
+ F16(303.2),
+ F16(304.6),
+ F16(302.2),
+ F16(301.8),
+ F16(301.3),
+ F16(302.7),
+ F16(300.4),
+ F16(299.9),
+ F16(299.5),
+ F16(300.8),
+ F16(298.7),
+ F16(298.3),
+ F16(298),
+ F16(299.2),
+ F16(297.2),
+ F16(296.7),
+ F16(296.2),
+ F16(297.6),
+ F16(295.4),
+ F16(295),
+ F16(294.5),
+ F16(295.8),
+ F16(293.6),
+ F16(293),
+ F16(292.6),
+ F16(294),
+ F16(291.7),
+ F16(291.2),
+ F16(290.6),
+ F16(292.2),
+ F16(289.7),
+ F16(289.2),
+ F16(288.7),
+ F16(290.1),
+ F16(287.7),
+ F16(287.3),
+ F16(286.8),
+ F16(288.2),
+ F16(285.8),
+ F16(285.3),
+ F16(284.8),
+ F16(286.3),
+ F16(283.8),
+ F16(283.4),
+ F16(282.9),
+ F16(284.3),
+ F16(281.9),
+ F16(281.3),
+ F16(280.8),
+ F16(282.4),
+ F16(279.8),
+ F16(279.4),
+ F16(278.9),
+ F16(280.4),
+ F16(277.8),
+ F16(277.2),
+ F16(276.8),
+ F16(278.3),
+ F16(275.8),
+ F16(275.2),
+ F16(274.6),
+ F16(276.3),
+ F16(273.6),
+ F16(273),
+ F16(272.6),
+ F16(274.1),
+ F16(271.6),
+ F16(271),
+ F16(270.5),
+ F16(272.1),
+ F16(269.5),
+ F16(269),
+ F16(268.5),
+ F16(270),
+ F16(267.5),
+ F16(267),
+ F16(266.5),
+ F16(268),
+ F16(265.7),
+ F16(265.3),
+ F16(264.8),
+ F16(266),
+ F16(263.9),
+ F16(263.4),
+ F16(263),
+ F16(264.3),
+ F16(262.1),
+ F16(261.5),
+ F16(261.1),
+ F16(262.5),
+ F16(260.2),
+ F16(259.8),
+ F16(259.3),
+ F16(260.6),
+ F16(258.4),
+ F16(258),
+ F16(257.5),
+ F16(258.9),
+ F16(256.6),
+ F16(256.2),
+ F16(255.7),
+ F16(257.1),
+ F16(254.7),
+ F16(254.2),
+ F16(253.7),
+ F16(255.1),
+ F16(252.7),
+ F16(252.2),
+ F16(251.6),
+ F16(253.1),
+ F16(250.7),
+ F16(250.2),
+ F16(249.7),
+ F16(251.2),
+ F16(248.6),
+ F16(248),
+ F16(247.6),
+ F16(249.2),
+ F16(246.5),
+ F16(245.8),
+ F16(245.3),
+ F16(247),
+ F16(244.1),
+ F16(243.5),
+ F16(242.8),
+ F16(244.6),
+ F16(241.6),
+ F16(240.9),
+ F16(240.2),
+ F16(242.2),
+ F16(239),
+ F16(238.3),
+ F16(237.6),
+ F16(239.6),
+ F16(236.3),
+ F16(235.7),
+ F16(235.1),
+ F16(237),
+ F16(234),
+ F16(233.4),
+ F16(232.7),
+ F16(234.6),
+ F16(231.6),
+ F16(231),
+ F16(230.6),
+ F16(232.2),
+ F16(229.6),
+ F16(229.1),
+ F16(228.6),
+ F16(230),
+ F16(227.7),
+ F16(227.3),
+ F16(226.9),
+ F16(228.1),
+ F16(226.1),
+ F16(225.8),
+ F16(225.3),
+ F16(226.4),
+ F16(224.5),
+ F16(224.1),
+ F16(223.7),
+ F16(224.9),
+ F16(222.8),
+ F16(222.4),
+ F16(222),
+ F16(223.2),
+ F16(221.1),
+ F16(220.7),
+ F16(220.2),
+ F16(221.6),
+ F16(219.5),
+ F16(219),
+ F16(218.5),
+ F16(219.9),
+ F16(217.6),
+ F16(217),
+ F16(216.5),
+ F16(218.1),
+ F16(215.5),
+ F16(215),
+ F16(214.5),
+ F16(216),
+ F16(213.6),
+ F16(213),
+ F16(212.5),
+ F16(214),
+ F16(211.4),
+ F16(210.9),
+ F16(210.3),
+ F16(212),
+ F16(209.2),
+ F16(208.7),
+ F16(208.2),
+ F16(209.8),
+ F16(206.9),
+ F16(206.4),
+ F16(205.7),
+ F16(207.6),
+ F16(204.5),
+ F16(203.9),
+ F16(203.2),
+ F16(205.1),
+ F16(201.8),
+ F16(201.2),
+ F16(200.5),
+ F16(202.6),
+ F16(199.1),
+ F16(198.4),
+ F16(197.8),
+ F16(199.8),
+ F16(196.5),
+ F16(195.8),
+ F16(195.1),
+ F16(197.1),
+ F16(193.8),
+ F16(193.1),
+ F16(192.5),
+ F16(194.4),
+ F16(191.3),
+ F16(190.8),
+ F16(190.2),
+ F16(191.9),
+ F16(189.2),
+ F16(188.7),
+ F16(188.3),
+ F16(189.7),
+ F16(187.5),
+ F16(187.2),
+ F16(186.7),
+ F16(187.9),
+ F16(185.9),
+ F16(185.4),
+ F16(185),
+ F16(186.3),
+ F16(184.2),
+ F16(183.8),
+ F16(183.5),
+ F16(184.6),
+ F16(182.7),
+ F16(182.3),
+ F16(182),
+ F16(183),
+ F16(181.3),
+ F16(181),
+ F16(180.6),
+ F16(181.7),
+ F16(179.9),
+ F16(179.6),
+ F16(179.3),
+ F16(180.3),
+ F16(178.6),
+ F16(178.4),
+ F16(178.2),
+ F16(178.9),
+ F16(177.6),
+ F16(177.4),
+ F16(177.2),
+ F16(177.9),
+ F16(176.7),
+ F16(176.5),
+ F16(176.2),
+ F16(177),
+ F16(175.9),
+ F16(175.7),
+ F16(175.5),
+ F16(176.1),
+ F16(175.2),
+ F16(175),
+ F16(174.8),
+ F16(175.4),
+ F16(174.5),
+ F16(174.2),
+ F16(174),
+ F16(174.6),
+ F16(173.6),
+ F16(173.4),
+ F16(173.2),
+ F16(173.8),
+ F16(172.9),
+ F16(172.8),
+ F16(172.6),
+ F16(173.1),
+ F16(172.4),
+ F16(172.2),
+ F16(172),
+ F16(172.5),
+ F16(171.7),
+ F16(171.6),
+ F16(171.4),
+ F16(171.9),
+ F16(171),
+ F16(170.8),
+ F16(170.6),
+ F16(171.2),
+ F16(170.3),
+ F16(170.1),
+ F16(170),
+ F16(170.4),
+ F16(169.6),
+ F16(169.5),
+ F16(169.2),
+ F16(169.8),
+ F16(168.8),
+ F16(168.6),
+ F16(168.3),
+ F16(169),
+ F16(167.8),
+ F16(167.6),
+ F16(167.4),
+ F16(168),
+ F16(167),
+ F16(166.8),
+ F16(166.5),
+ F16(167.1),
+ F16(166),
+ F16(165.8),
+ F16(165.5),
+ F16(166.2),
+ F16(165.2),
+ F16(165),
+ F16(164.7),
+ F16(165.4),
+ F16(164.3),
+ F16(164.1),
+ F16(163.9),
+ F16(164.5),
+ F16(163.5),
+ F16(163.2),
+ F16(162.9),
+ F16(163.7),
+ F16(162.5),
+ F16(162.4),
+ F16(162.1),
+ F16(162.7),
+ F16(161.8),
+ F16(161.6),
+ F16(161.4),
+ F16(162),
+ F16(161),
+ F16(160.8),
+ F16(160.6),
+ F16(161.2),
+ F16(160.3),
+ F16(160.1),
+ F16(159.9),
+ F16(160.5),
+ F16(159.5),
+ F16(159.3),
+ F16(159.1),
+ F16(159.7),
+ F16(158.8),
+ F16(158.6),
+ F16(158.4),
+ F16(158.9),
+ F16(158.1),
+ F16(157.9),
+ F16(157.7),
+ F16(158.3),
+ F16(157.4),
+ F16(157.3),
+ F16(157.1),
+ F16(157.5),
+ F16(156.8),
+ F16(156.7),
+ F16(156.5),
+ F16(156.9),
+ F16(156.2),
+ F16(155.9),
+ F16(155.7),
+ F16(156.3),
+ F16(155.4),
+ F16(155.3),
+ F16(155.1),
+ F16(155.5),
+ F16(154.8),
+ F16(154.6),
+ F16(154.5),
+ F16(155),
+ F16(154.3),
+ F16(154.2),
+ F16(154),
+ F16(154.4),
+ F16(153.6),
+ F16(153.5),
+ F16(153.3),
+ F16(153.8),
+ F16(153),
+ F16(152.9),
+ F16(152.7),
+ F16(153.1),
+ F16(152.5),
+ F16(152.3),
+ F16(152.1),
+ F16(152.6),
+ F16(151.8),
+ F16(151.7),
+ F16(151.5),
+ F16(151.9),
+ F16(151.2),
+ F16(151),
+ F16(150.9),
+ F16(151.3),
+ F16(150.6),
+ F16(150.5),
+ F16(150.4),
+ F16(150.7),
+ F16(150.1),
+ F16(150),
+ F16(149.8),
+ F16(150.2),
+ F16(149.4),
+ F16(149.3),
+ F16(149.1),
+ F16(149.6),
+ F16(148.8),
+ F16(148.7),
+ F16(148.5),
+ F16(149),
+ F16(148.3),
+ F16(148.1),
+ F16(147.9),
+ F16(148.4),
+ F16(147.6),
+ F16(147.5),
+ F16(147.3),
+ F16(147.7),
+ F16(147.1),
+ F16(147),
+ F16(146.8),
+ F16(147.3),
+ F16(146.5),
+ F16(146.4),
+ F16(146.3),
+ F16(146.7),
+ F16(146),
+ F16(145.9),
+ F16(145.7),
+ F16(146.1),
+ F16(145.4),
+ F16(145.3),
+ F16(145.1),
+ F16(145.5),
+ F16(144.8),
+ F16(144.7),
+ F16(144.6),
+ F16(145),
+ F16(144.4),
+ F16(144.2),
+ F16(144.1),
+ F16(144.4),
+ F16(143.8),
+ F16(143.7),
+ F16(143.5),
+ F16(144),
+ F16(143.2),
+ F16(143.1),
+ F16(142.9),
+ F16(143.4),
+ F16(142.7),
+ F16(142.6),
+ F16(142.4),
+ F16(142.8),
+ F16(142.1),
+ F16(141.9),
+ F16(141.8),
+ F16(142.2),
+ F16(141.6),
+ F16(141.5),
+ F16(141.3),
+ F16(141.7),
+ F16(141),
+ F16(140.9),
+ F16(140.7),
+ F16(141.1),
+ F16(140.4),
+ F16(140.2),
+ F16(140),
+ F16(140.5),
+ F16(139.8),
+ F16(139.7),
+ F16(139.6),
+ F16(139.9),
+ F16(139.3),
+ F16(139.2),
+ F16(139),
+ F16(139.4),
+ F16(138.7),
+ F16(138.6),
+ F16(138.5),
+ F16(138.9),
+ F16(138.3),
+ F16(138.1),
+ F16(138),
+ F16(138.4),
+ F16(137.8),
+ F16(137.7),
+ F16(137.5),
+ F16(137.9),
+ F16(137.3),
+ F16(137.2),
+ F16(137.1),
+ F16(137.4),
+ F16(136.8),
+ F16(136.6),
+ F16(136.5),
+ F16(136.9),
+ F16(136.2),
+ F16(136.1),
+ F16(135.9),
+ F16(136.3),
+ F16(135.7),
+ F16(135.6),
+ F16(135.4),
+ F16(135.8),
+ F16(135.2),
+ F16(135),
+ F16(134.9),
+ F16(135.3),
+ F16(134.6),
+ F16(134.6),
+ F16(134.4),
+ F16(134.7),
+ F16(134.2),
+ F16(134),
+ F16(133.8),
+ F16(134.2),
+ F16(133.6),
+ F16(133.5),
+ F16(133.3),
+ F16(133.7),
+ F16(133),
+ F16(132.9),
+ F16(132.7),
+ F16(133.1),
+ F16(132.5),
+ F16(132.3),
+ F16(132.2),
+ F16(132.6),
+ F16(131.9),
+ F16(131.8),
+ F16(131.6),
+ F16(132),
+ F16(131.4),
+ F16(131.3),
+ F16(131.2),
+ F16(131.5),
+ F16(130.9),
+ F16(130.8),
+ F16(130.6),
+ F16(131.1),
+ F16(130.4),
+ F16(130.2),
+ F16(130.2),
+ F16(130.5),
+ F16(129.9),
+ F16(129.8),
+ F16(129.7),
+ F16(130),
+ F16(129.5),
+ F16(129.4),
+ F16(129.2),
+ F16(129.6),
+ F16(129),
+ F16(128.9),
+ F16(128.8),
+ F16(129.1),
+ F16(128.6),
+ F16(128.4),
+ F16(128.3),
+ F16(128.7),
+ F16(128),
+ F16(128),
+ F16(127.9),
+ F16(128.1),
+ F16(127.7),
+ F16(127.6),
+ F16(127.5),
+ F16(127.8),
+ F16(127.3),
+ F16(127.2),
+ F16(127.1),
+ F16(127.3),
+ F16(127),
+ F16(126.9),
+ F16(126.8),
+ F16(127),
+ F16(126.6),
+ F16(126.6),
+ F16(126.7),
+ F16(126.7),
+ F16(128.9),
+ F16(130.5),
+ F16(132.2),
+ F16(127.5),
+ F16(135.2),
+ F16(136.8),
+ F16(138.6),
+ F16(133.6),
+ F16(141.2),
+ F16(141.6),
+ F16(141.6),
+ F16(140.2),
+ F16(141.4),
+ F16(141.4),
+ F16(141.3),
+ F16(141.5),
+ F16(141.1),
+ F16(140.9),
+ F16(140.8),
+ F16(141.2),
+ F16(140.7),
+ F16(140.6),
+ F16(140.6),
+ F16(140.8),
+ F16(140.4),
+ F16(140.3),
+ F16(140.2),
+ F16(140.5),
+ F16(140.1),
+ F16(140.1),
+ F16(140),
+ F16(140.2),
+ F16(139.8),
+ F16(139.7),
+ F16(139.6),
+ F16(139.9),
+ F16(139.4),
+ F16(139.3),
+ F16(139.2),
+ F16(139.5),
+ F16(139),
+ F16(138.9),
+ F16(138.8),
+ F16(139.1),
+ F16(138.5),
+ F16(138.4),
+ F16(138.6),
+ F16(138.6),
+ F16(140.3),
+ F16(140.9),
+ F16(140.7),
+ F16(139.2),
+ F16(139.2),
+ F16(137.7),
+ F16(136),
+ F16(140.2),
+ F16(132),
+ F16(130.2),
+ F16(128.9),
+ F16(134),
+ F16(128.1),
+ F16(127.9),
+ F16(127.7),
+ F16(128.2),
+ F16(127.5),
+ F16(127.4),
+ F16(127.2),
+ F16(127.6),
+ F16(127),
+ F16(126.9),
+ F16(126.7),
+ F16(127.1),
+ F16(126.4),
+ F16(126.2),
+ F16(126.1),
+ F16(126.5),
+ F16(125.7),
+ F16(125.6),
+ F16(125.5),
+ F16(125.9),
+ F16(125.1),
+ F16(124.8),
+ F16(124.7),
+ F16(125.3),
+ F16(124.3),
+ F16(124.1),
+ F16(124),
+ F16(124.5),
+ F16(123.6),
+ F16(123.4),
+ F16(123.2),
+ F16(123.8),
+ F16(122.9),
+ F16(122.8),
+ F16(122.6),
+ F16(123.1),
+ F16(121.9),
+ F16(120.8),
+ F16(119.1),
+ F16(122.4),
+ F16(115.7),
+ F16(114.2),
+ F16(113.2),
+ F16(117.3),
+ F16(112.5),
+ F16(112.3),
+ F16(112.1),
+ F16(112.7),
+ F16(111.8),
+ F16(111.7),
+ F16(111.5),
+ F16(111.9),
+ F16(111.2),
+ F16(111),
+ F16(110.7),
+ F16(111.4),
+ F16(110.4),
+ F16(110.2),
+ F16(110),
+ F16(110.6),
+ F16(109.6),
+ F16(109.4),
+ F16(109.2),
+ F16(109.8),
+ F16(108.9),
+ F16(108.7),
+ F16(108.5),
+ F16(109.1),
+ F16(108.2),
+ F16(108),
+ F16(107.8),
+ F16(108.3),
+ F16(107.6),
+ F16(107.5),
+ F16(107.2),
+ F16(107.7),
+ F16(106.9),
+ F16(106.7),
+ F16(106.6),
+ F16(107.1),
+ F16(106.3),
+ F16(106.1),
+ F16(105.9),
+ F16(106.5),
+ F16(105.5),
+ F16(105.4),
+ F16(105.3),
+ F16(105.7),
+ F16(105),
+ F16(104.9),
+ F16(104.7),
+ F16(105.1),
+ F16(104.4),
+ F16(104.3),
+ F16(104.1),
+ F16(104.5),
+ F16(103.9),
+ F16(103.8),
+ F16(103.6),
+ F16(104),
+ F16(103.3),
+ F16(103.1),
+ F16(103),
+ F16(103.4),
+ F16(102.7),
+ F16(102.6),
+ F16(102.5),
+ F16(102.8),
+ F16(102.3),
+ F16(102.2),
+ F16(102.1),
+ F16(102.4),
+ F16(101.8),
+ F16(101.8),
+ F16(101.6),
+ F16(102),
+ F16(101.4),
+ F16(101.3),
+ F16(101.2),
+ F16(101.5),
+ F16(101),
+ F16(100.9),
+ F16(100.7),
+ F16(101.1),
+ F16(100.4),
+ F16(100.3),
+ F16(100.2),
+ F16(100.5),
+ F16(100),
+ F16(99.9),
+ F16(99.8),
+ F16(100.1),
+ F16(99.7),
+ F16(99.6),
+ F16(99.5),
+ F16(99.7),
+ F16(99.2),
+ F16(99.1),
+ F16(98.9),
+ F16(99.3),
+ F16(98.7),
+ F16(98.6),
+ F16(98.5),
+ F16(98.8),
+ F16(98.3),
+ F16(98.2),
+ F16(98.1),
+ F16(98.4),
+ F16(97.9),
+ F16(97.8),
+ F16(97.6),
+ F16(97.9),
+ F16(97.5),
+ F16(97.4),
+ F16(97.2),
+ F16(97.6),
+ F16(96.9),
+ F16(96.8),
+ F16(96.7),
+ F16(97.1),
+ F16(96.4),
+ F16(96.3),
+ F16(96.2),
+ F16(96.5),
+ F16(95.9),
+ F16(95.7),
+ F16(95.6),
+ F16(96),
+ F16(95.4),
+ F16(95.3),
+ F16(95.1),
+ F16(95.5),
+ F16(94.9),
+ F16(94.8),
+ F16(94.7),
+ F16(95),
+ F16(94.5),
+ F16(94.3),
+ F16(94.1),
+ F16(94.6),
+ F16(93.9),
+ F16(93.7),
+ F16(93.5),
+ F16(94),
+ F16(93.3),
+ F16(93.2),
+ F16(93.1),
+ F16(93.4),
+ F16(92.8),
+ F16(92.7),
+ F16(92.5),
+ F16(93),
+ F16(92.3),
+ F16(92.2),
+ F16(92),
+ F16(92.4),
+ F16(91.7),
+ F16(91.6),
+ F16(91.4),
+ F16(91.9),
+ F16(91.2),
+ F16(91),
+ F16(90.8),
+ F16(91.3),
+ F16(90.6),
+ F16(90.5),
+ F16(90.4),
+ F16(90.7),
+ F16(90.1),
+ F16(90),
+ F16(89.8),
+ F16(90.2),
+ F16(89.6),
+ F16(89.5),
+ F16(89.3),
+ F16(89.7),
+ F16(89.1),
+ F16(89),
+ F16(88.8),
+ F16(89.2),
+ F16(88.5),
+ F16(88.4),
+ F16(88.2),
+ F16(88.7),
+ F16(88),
+ F16(87.8),
+ F16(87.7),
+ F16(88.1),
+ F16(87.5),
+ F16(87.3),
+ F16(87.2),
+ F16(87.6),
+ F16(87),
+ F16(86.8),
+ F16(86.6),
+ F16(87.1),
+ F16(86.2),
+ F16(86.1),
+ F16(86),
+ F16(86.4),
+ F16(85.8),
+ F16(85.7),
+ F16(85.5),
+ F16(85.9),
+ F16(85.2),
+ F16(85.1),
+ F16(84.9),
+ F16(85.4),
+ F16(84.7),
+ F16(84.5),
+ F16(84.3),
+ F16(84.8),
+ F16(84.1),
+ F16(83.9),
+ F16(83.7),
+ F16(84.2),
+ F16(83.5),
+ F16(83.3),
+ F16(83.2),
+ F16(83.6),
+ F16(82.9),
+ F16(82.7),
+ F16(82.6),
+ F16(83),
+ F16(82.3),
+ F16(82.1),
+ F16(82),
+ F16(82.4),
+ F16(81.7),
+ F16(81.5),
+ F16(81.4),
+ F16(81.8),
+ F16(81.1),
+ F16(81),
+ F16(80.9),
+ F16(81.2),
+ F16(80.6),
+ F16(80.5),
+ F16(80.3),
+ F16(80.7),
+ F16(80),
+ F16(79.9),
+ F16(79.7),
+ F16(80.2),
+ F16(79.5),
+ F16(79.4),
+ F16(79.3),
+ F16(79.6),
+ F16(79.1),
+ F16(78.9),
+ F16(78.8),
+ F16(79.2),
+ F16(78.5),
+ F16(78.4),
+ F16(78.2),
+ F16(78.6),
+ F16(77.9),
+ F16(77.8),
+ F16(77.6),
+ F16(78.1),
+ F16(77.4),
+ F16(77.3),
+ F16(77.1),
+ F16(77.5),
+ F16(76.8),
+ F16(76.7),
+ F16(76.6),
+ F16(77),
+ F16(76.3),
+ F16(76.2),
+ F16(76),
+ F16(76.4),
+ F16(75.7),
+ F16(75.6),
+ F16(75.4),
+ F16(75.9),
+ F16(75.1),
+ F16(75),
+ F16(74.8),
+ F16(75.2),
+ F16(74.5),
+ F16(74.4),
+ F16(74.3),
+ F16(74.7),
+ F16(74),
+ F16(73.9),
+ F16(73.7),
+ F16(74.2),
+ F16(73.4),
+ F16(73.3),
+ F16(73.2),
+ F16(73.6),
+ F16(72.9),
+ F16(72.8),
+ F16(72.6),
+ F16(73.1),
+ F16(72.4),
+ F16(72.2),
+ F16(72.1),
+ F16(72.5),
+ F16(71.9),
+ F16(71.8),
+ F16(71.6),
+ F16(72),
+ F16(71.3),
+ F16(71.3),
+ F16(71.1),
+ F16(71.5),
+ F16(70.9),
+ F16(70.7),
+ F16(70.6),
+ F16(71),
+ F16(70.4),
+ F16(70.3),
+ F16(70.2),
+ F16(70.5),
+ F16(70),
+ F16(69.9),
+ F16(69.8),
+ F16(70.1),
+ F16(69.6),
+ F16(69.5),
+ F16(69.4),
+ F16(69.7),
+ F16(69.3),
+ F16(69.2),
+ F16(69.1),
+ F16(69.3),
+ F16(69),
+ F16(69),
+ F16(69.5),
+ F16(69),
+ F16(71),
+ F16(71.4),
+ F16(71.5),
+ F16(70.3),
+ F16(71.4),
+ F16(71.4),
+ F16(71.3),
+ F16(71.5),
+ F16(71.1),
+ F16(71),
+ F16(71),
+ F16(71.2),
+ F16(71.9),
+ F16(73.3),
+ F16(75.1),
+ F16(71.1),
+ F16(78.4),
+ F16(79.9),
+ F16(81.3),
+ F16(76.9),
+ F16(82.1),
+ F16(82),
+ F16(81.9),
+ F16(82),
+ F16(81.7),
+ F16(81.6),
+ F16(81.5),
+ F16(81.8),
+ F16(81.3),
+ F16(81.5),
+ F16(82),
+ F16(81.4),
+ F16(85),
+ F16(86.5),
+ F16(87.9),
+ F16(83.3),
+ F16(89.7),
+ F16(89.7),
+ F16(89.6),
+ F16(89),
+ F16(89.4),
+ F16(89.3),
+ F16(89.1),
+ F16(89.5),
+ F16(88.8),
+ F16(88.7),
+ F16(88.6),
+ F16(89),
+ F16(87.8),
+ F16(87.2),
+ F16(86.7),
+ F16(88.3),
+ F16(86.3),
+ F16(86.1),
+ F16(85.9),
+ F16(86.5),
+ F16(85.6),
+ F16(85.5),
+ F16(85.3),
+ F16(85.8),
+ F16(85),
+ F16(84.6),
+ F16(83.6),
+ F16(85.2),
+ F16(79.9),
+ F16(78),
+ F16(76.2),
+ F16(81.9),
+ F16(72.8),
+ F16(71.8),
+ F16(71.5),
+ F16(74.4),
+ F16(71.1),
+ F16(70.9),
+ F16(70.7),
+ F16(71.2),
+ F16(70.4),
+ F16(70.3),
+ F16(70.1),
+ F16(70.6),
+ F16(68.9),
+ F16(67.3),
+ F16(65.4),
+ F16(69.7),
+ F16(61.9),
+ F16(60.5),
+ F16(59.5),
+ F16(63.5),
+ F16(59),
+ F16(58.8),
+ F16(58.6),
+ F16(59.1),
+ F16(58.3),
+ F16(58.2),
+ F16(58),
+ F16(58.4),
+ F16(57.6),
+ F16(57.4),
+ F16(57),
+ F16(57.8),
+ F16(55.7),
+ F16(55.1),
+ F16(54.7),
+ F16(56.4),
+ F16(54.3),
+ F16(54.1),
+ F16(53.9),
+ F16(54.5),
+ F16(53.6),
+ F16(53.4),
+ F16(53.2),
+ F16(53.7),
+ F16(52.8),
+ F16(52.6),
+ F16(52.4),
+ F16(53),
+ F16(52),
+ F16(51.8),
+ F16(51.6),
+ F16(52.1),
+ F16(51.2),
+ F16(51),
+ F16(50.9),
+ F16(51.4),
+ F16(50.6),
+ F16(50.4),
+ F16(50.3),
+ F16(50.8),
+ F16(49.9),
+ F16(49.7),
+ F16(49.5),
+ F16(50.1),
+ F16(49.1),
+ F16(48.9),
+ F16(48.8),
+ F16(49.3),
+ F16(48.4),
+ F16(48.2),
+ F16(48),
+ F16(48.6),
+ F16(47.7),
+ F16(47.6),
+ F16(47.4),
+ F16(47.9),
+ F16(47),
+ F16(46.8),
+ F16(46.6),
+ F16(47.2),
+ F16(46.4),
+ F16(46.2),
+ F16(46.1),
+ F16(46.5),
+ F16(45.8),
+ F16(45.7),
+ F16(45.5),
+ F16(45.9),
+ F16(45.2),
+ F16(45.1),
+ F16(44.9),
+ F16(45.4),
+ F16(44.6),
+ F16(44.5),
+ F16(44.3),
+ F16(44.7),
+ F16(44.1),
+ F16(44),
+ F16(43.8),
+ F16(44.2),
+ F16(43.5),
+ F16(43.3),
+ F16(43.2),
+ F16(43.6),
+ F16(42.8),
+ F16(42.7),
+ F16(42.5),
+ F16(43),
+ F16(42.2),
+ F16(42),
+ F16(41.9),
+ F16(42.4),
+ F16(41.7),
+ F16(41.5),
+ F16(41.3),
+ F16(41.8),
+ F16(41.1),
+ F16(40.9),
+ F16(40.8),
+ F16(41.2),
+ F16(40.5),
+ F16(40.4),
+ F16(40.2),
+ F16(40.7),
+ F16(39.9),
+ F16(39.8),
+ F16(39.6),
+ F16(40.1),
+ F16(39.4),
+ F16(39.3),
+ F16(39.1),
+ F16(39.5),
+ F16(38.9),
+ F16(38.7),
+ F16(38.5),
+ F16(39),
+ F16(38.3),
+ F16(38.1),
+ F16(37.9),
+ F16(38.4),
+ F16(37.7),
+ F16(37.5),
+ F16(37.4),
+ F16(37.8),
+ F16(37.1),
+ F16(37),
+ F16(36.8),
+ F16(37.2),
+ F16(36.4),
+ F16(36.3),
+ F16(36.2),
+ F16(36.6),
+ F16(35.9),
+ F16(35.8),
+ F16(35.7),
+ F16(36.1),
+ F16(35.4),
+ F16(35.2),
+ F16(35.1),
+ F16(35.6),
+ F16(34.9),
+ F16(34.8),
+ F16(34.6),
+ F16(35),
+ F16(34.3),
+ F16(34.2),
+ F16(34.1),
+ F16(34.4),
+ F16(33.9),
+ F16(33.7),
+ F16(33.6),
+ F16(33.9),
+ F16(33.3),
+ F16(33.2),
+ F16(33),
+ F16(33.5),
+ F16(32.8),
+ F16(32.6),
+ F16(32.5),
+ F16(32.9),
+ F16(32.2),
+ F16(32),
+ F16(31.9),
+ F16(32.3),
+ F16(31.7),
+ F16(31.5),
+ F16(31.4),
+ F16(31.8),
+ F16(31.2),
+ F16(31),
+ F16(30.8),
+ F16(31.3),
+ F16(30.6),
+ F16(30.5),
+ F16(30.3),
+ F16(30.7),
+ F16(30.1),
+ F16(30),
+ F16(29.9),
+ F16(30.2),
+ F16(29.7),
+ F16(29.5),
+ F16(29.4),
+ F16(29.8),
+ F16(29.1),
+ F16(29),
+ F16(28.9),
+ F16(29.3),
+ F16(28.7),
+ F16(28.5),
+ F16(28.4),
+ F16(28.8),
+ F16(28.1),
+ F16(27.9),
+ F16(27.8),
+ F16(28.2),
+ F16(27.4),
+ F16(27.2),
+ F16(27.1),
+ F16(27.6),
+ F16(26.8),
+ F16(26.6),
+ F16(26.5),
+ F16(26.9),
+ F16(26.1),
+ F16(26),
+ F16(25.8),
+ F16(26.3),
+ F16(25.5),
+ F16(25.3),
+ F16(25.2),
+ F16(25.6),
+ F16(24.9),
+ F16(24.8),
+ F16(24.6),
+ F16(25.1),
+ F16(24.4),
+ F16(24.2),
+ F16(24.1),
+ F16(24.5),
+ F16(23.8),
+ F16(23.6),
+ F16(23.5),
+ F16(24),
+ F16(23.2),
+ F16(23),
+ F16(22.8),
+ F16(23.3),
+ F16(22.5),
+ F16(22.3),
+ F16(22.1),
+ F16(22.7),
+ F16(21.8),
+ F16(21.6),
+ F16(21.5),
+ F16(21.9),
+ F16(21.2),
+ F16(21),
+ F16(20.8),
+ F16(21.3),
+ F16(20.5),
+ F16(20.3),
+ F16(20.2),
+ F16(20.6),
+ F16(19.9),
+ F16(19.8),
+ F16(19.7),
+ F16(20.1),
+ F16(19.4),
+ F16(19.2),
+ F16(19.1),
+ F16(19.5),
+ F16(18.8),
+ F16(18.7),
+ F16(18.5),
+ F16(19),
+ F16(18.3),
+ F16(18.2),
+ F16(18.1),
+ F16(18.4),
+ F16(17.8),
+ F16(17.6),
+ F16(17.5),
+ F16(17.9),
+ F16(17.2),
+ F16(17),
+ F16(16.8),
+ F16(17.3),
+ F16(16.5),
+ F16(16.4),
+ F16(16.2),
+ F16(16.7),
+ F16(15.9),
+ F16(15.8),
+ F16(15.7),
+ F16(16.1),
+ F16(15.4),
+ F16(15.2),
+ F16(15),
+ F16(15.5),
+ F16(14.8),
+ F16(14.7),
+ F16(14.6),
+ F16(14.9),
+ F16(14.2),
+ F16(14),
+ F16(13.9),
+ F16(14.4),
+ F16(13.5),
+ F16(13.4),
+ F16(13.3),
+ F16(13.7),
+ F16(13),
+ F16(12.8),
+ F16(12.7),
+ F16(13.1),
+ F16(12.4),
+ F16(12.2),
+ F16(12.1),
+ F16(12.6),
+ F16(11.8),
+ F16(11.7),
+ F16(11.6),
+ F16(12),
+ F16(11.3),
+ F16(11.1),
+ F16(11),
+ F16(11.4),
+ F16(10.7),
+ F16(10.6),
+ F16(10.4),
+ F16(10.9),
+ F16(10.2),
+ F16(10.1),
+ F16(9.90000000000001),
+ F16(10.3),
+ F16(9.70000000000002),
+ F16(9.5),
+ F16(9.40000000000001),
+ F16(9.80000000000001),
+ F16(9.20000000000002),
+ F16(9.09999999999999),
+ F16(9),
+ F16(9.30000000000001),
+ F16(8.70000000000002),
+ F16(8.5),
+ F16(8.40000000000001),
+ F16(8.80000000000001),
+ F16(8.20000000000002),
+ F16(8.09999999999999),
+ F16(8),
+ F16(8.30000000000001),
+ F16(7.70000000000002),
+ F16(7.70000000000002),
+ F16(7.59999999999999),
+ F16(7.90000000000001),
+ F16(7.40000000000001),
+ F16(7.40000000000001),
+ F16(7.30000000000001),
+ F16(7.5),
+ F16(7),
+ F16(6.90000000000001),
+ F16(6.80000000000001),
+ F16(7.09999999999999),
+ F16(6.59999999999999),
+ F16(6.59999999999999),
+ F16(6.59999999999999),
+ F16(6.70000000000002),
+ F16(6.5),
+ F16(6.5),
+ F16(6.40000000000001),
+ F16(6.59999999999999),
+ F16(6.09999999999999),
+ F16(6),
+ F16(5.90000000000001),
+ F16(6.20000000000002),
+ F16(5.59999999999999),
+ F16(5.5),
+ F16(5.5),
+ F16(5.70000000000002),
+ F16(5.5),
+ F16(5.5),
+ F16(5.40000000000001),
+ F16(5.59999999999999),
+ F16(5.30000000000001),
+ F16(5.20000000000002),
+ F16(5),
+ F16(5.40000000000001),
+ F16(4.70000000000002),
+ F16(4.59999999999999),
+ F16(4.30000000000001),
+ F16(4.80000000000001),
+ F16(3.90000000000001),
+ F16(3.80000000000001),
+ F16(3.59999999999999),
+ F16(4.09999999999999),
+ F16(3.30000000000001),
+ F16(3.09999999999999),
+ F16(2.90000000000001),
+ F16(3.40000000000001),
+ F16(2.59999999999999),
+ F16(2.40000000000001),
+ F16(2.30000000000001),
+ F16(2.80000000000001),
+ F16(1.90000000000001),
+ F16(1.80000000000001),
+ F16(1.70000000000002),
+ F16(2.09999999999999),
+ F16(1.40000000000001),
+ F16(1.20000000000002),
+ F16(1.09999999999999),
+ F16(1.5),
+ F16(0.800000000000011),
+ F16(0.599999999999994),
+ F16(0.400000000000006),
+ F16(1),
+ F16(0),
+ F16(-0.199999999999989),
+ F16(-0.400000000000006),
+ F16(0.200000000000017),
+ F16(-0.699999999999989),
+ F16(-0.799999999999983),
+ F16(-0.900000000000006),
+ F16(-0.599999999999994),
+ F16(-1.09999999999999),
+ F16(-1.19999999999999),
+ F16(-1.40000000000001),
+ F16(-1),
+ F16(-1.69999999999999),
+ F16(-2),
+ F16(-2.09999999999999),
+ F16(-1.5),
+ F16(-2.40000000000001),
+ F16(-2.59999999999999),
+ F16(-2.69999999999999),
+ F16(-2.29999999999998),
+ F16(-2.79999999999998),
+ F16(-2.79999999999998),
+ F16(-2.90000000000001),
+ F16(-2.79999999999998),
+ F16(-2.90000000000001),
+ F16(-2.90000000000001),
+ F16(-2.79999999999998),
+ F16(-2.90000000000001),
+ F16(-2.79999999999998),
+ F16(-2.79999999999998),
+ F16(-2.90000000000001),
+ F16(-2.90000000000001),
+ F16(-2.90000000000001),
+ F16(-2.90000000000001),
+ F16(-2.79999999999998),
+ F16(-2.79999999999998),
+ F16(-2.90000000000001),
+ F16(-2.79999999999998),
+ F16(-2.90000000000001),
+ F16(-2.90000000000001),
+ F16(-2.90000000000001),
+ F16(-2.90000000000001),
+ F16(-2.90000000000001),
+ F16(-2.90000000000001),
+ F16(-2.90000000000001),
+ F16(-2.90000000000001),
+ F16(-2.90000000000001),
+ F16(-2.90000000000001),
+ F16(-2.79999999999998),
+ F16(-2.79999999999998),
+ F16(-2.79999999999998),
+ F16(-2.79999999999998),
+ F16(-2.69999999999999),
+ F16(-2.69999999999999),
+ F16(-2.59999999999999),
+ F16(-2.79999999999998),
+ F16(-2.69999999999999),
+ F16(-2.69999999999999),
+ F16(-2.69999999999999),
+ F16(-2.69999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.69999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.69999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.29999999999998),
+ F16(-2.40000000000001),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.40000000000001),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.40000000000001),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.69999999999999),
+ F16(-2.69999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.69999999999999),
+ F16(-2.69999999999999),
+ F16(-2.69999999999999),
+ F16(-2.69999999999999),
+ F16(-2.69999999999999),
+ F16(-2.79999999999998),
+ F16(-2.69999999999999),
+ F16(-2.79999999999998),
+ F16(-2.79999999999998),
+ F16(-2.79999999999998),
+ F16(-2.79999999999998),
+ F16(-2.79999999999998),
+ F16(-2.79999999999998),
+ F16(-2.69999999999999),
+ F16(-2.79999999999998),
+ F16(-2.79999999999998),
+ F16(-2.69999999999999),
+ F16(-2.79999999999998),
+ F16(-2.69999999999999),
+ F16(-2.69999999999999),
+ F16(-2.79999999999998),
+ F16(-2.79999999999998),
+ F16(-2.79999999999998),
+ F16(-2.79999999999998),
+ F16(-2.79999999999998),
+ F16(-2.79999999999998),
+ F16(-2.79999999999998),
+ F16(-2.79999999999998),
+ F16(-2.79999999999998),
+ F16(-2.79999999999998),
+ F16(-2.79999999999998),
+ F16(-2.79999999999998),
+ F16(-2.79999999999998),
+ F16(-2.79999999999998),
+ F16(-2.79999999999998),
+ F16(-2.79999999999998),
+ F16(-2.79999999999998),
+ F16(-2.79999999999998),
+ F16(-2.79999999999998),
+ F16(-2.79999999999998),
+ F16(-2.79999999999998),
+ F16(-2.79999999999998),
+ F16(-2.79999999999998),
+ F16(-2.79999999999998),
+ F16(-2.79999999999998),
+ F16(-2.79999999999998),
+ F16(-2.79999999999998),
+ F16(-2.69999999999999),
+ F16(-2.69999999999999),
+ F16(-2.69999999999999),
+ F16(-2.69999999999999),
+ F16(-2.69999999999999),
+ F16(-2.69999999999999),
+ F16(-2.69999999999999),
+ F16(-2.69999999999999),
+ F16(-2.69999999999999),
+ F16(-2.69999999999999),
+ F16(-2.69999999999999),
+ F16(-2.69999999999999),
+ F16(-2.69999999999999),
+ F16(-2.69999999999999),
+ F16(-2.69999999999999),
+ F16(-2.69999999999999),
+ F16(-2.69999999999999),
+ F16(-2.69999999999999),
+ F16(-2.69999999999999),
+ F16(-2.69999999999999),
+ F16(-2.69999999999999),
+ F16(-2.69999999999999),
+ F16(-2.69999999999999),
+ F16(-2.69999999999999),
+ F16(-2.59999999999999),
+ F16(-2.69999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.40000000000001),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.29999999999998),
+ F16(-2.40000000000001),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.40000000000001),
+ F16(-2.29999999999998),
+ F16(-2.40000000000001),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.40000000000001),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.29999999999998),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.69999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.69999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.69999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.19999999999999),
+ F16(-2.29999999999998),
+ F16(-2.19999999999999),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.40000000000001),
+ F16(-2.29999999999998),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.29999999999998),
+ F16(-2.40000000000001),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.29999999999998),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.40000000000001),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.19999999999999),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.29999999999998),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.29999999999998),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.40000000000001),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.19999999999999),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.19999999999999),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.19999999999999),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.29999999999998),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.59999999999999),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.5),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.29999999999998),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.19999999999999),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.19999999999999),
+ F16(-2.29999999999998),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.19999999999999),
+ F16(-2.29999999999998),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.19999999999999),
+ F16(-2.29999999999998),
+ F16(-2.19999999999999),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.09999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.29999999999998),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.29999999999998),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.29999999999998),
+ F16(-2.19999999999999),
+ F16(-2.29999999999998),
+ F16(-2.19999999999999),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.40000000000001),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.40000000000001),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.40000000000001),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.19999999999999),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.19999999999999),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.29999999999998),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.29999999999998),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.19999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.19999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.19999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2.09999999999999),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2.09999999999999),
+ F16(-2),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2),
+ F16(-2.09999999999999),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.09999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.29999999999998),
+ F16(-2.19999999999999),
+ F16(-2.29999999999998),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.29999999999998),
+ F16(-2.19999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.19999999999999),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.19999999999999),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.29999999999998),
+ F16(-2.19999999999999),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.19999999999999),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.40000000000001),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.29999999999998),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.19999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.19999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.09999999999999),
+ F16(-2.19999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.19999999999999),
+ F16(-2.09999999999999),
+ F16(-2.19999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.19999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.19999999999999),
+ F16(-2.09999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.09999999999999),
+ F16(-2.19999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.19999999999999),
+ F16(-2.09999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.09999999999999),
+ F16(-2.19999999999999),
+ F16(-2.09999999999999),
+ F16(-2.19999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-1.90000000000001),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-1.90000000000001),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-2),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-1.90000000000001),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2.09999999999999),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.19999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.09999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.19999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2),
+ F16(-2),
+ F16(-2.09999999999999),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2.09999999999999),
+ F16(-2),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-1.90000000000001),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2),
+ F16(-2),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.19999999999999),
+ F16(-2.09999999999999),
+ F16(-2.19999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.19999999999999),
+ F16(-2.09999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2),
+ F16(-2.09999999999999),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2),
+ F16(-2),
+ F16(-2.09999999999999),
+ F16(-2),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2),
+ F16(-2.09999999999999),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-2),
+ F16(-1.79999999999998),
+ F16(-1.79999999999998),
+ F16(-1.79999999999998),
+ F16(-1.90000000000001),
+ F16(-1.79999999999998),
+ F16(-1.79999999999998),
+ F16(-1.69999999999999),
+ F16(-1.90000000000001),
+ F16(-1.79999999999998),
+ F16(-1.69999999999999),
+ F16(-1.79999999999998),
+ F16(-1.69999999999999),
+ F16(-1.79999999999998),
+ F16(-1.79999999999998),
+ F16(-1.79999999999998),
+ F16(-1.69999999999999),
+ F16(-1.79999999999998),
+ F16(-1.79999999999998),
+ F16(-1.79999999999998),
+ F16(-1.79999999999998),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-2),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2),
+ F16(-2),
+ F16(-2.09999999999999),
+ F16(-2),
+ F16(-2.09999999999999),
+ F16(-2),
+ F16(-2),
+ F16(-1.90000000000001),
+ F16(-2),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-1.90000000000001),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-2),
+ F16(-2),
+ F16(-1.90000000000001),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-1.90000000000001),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-2),
+ F16(-2),
+ F16(-1.90000000000001),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-2),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.79999999999998),
+ F16(-1.79999999999998),
+ F16(-1.79999999999998),
+ F16(-1.90000000000001),
+ F16(-1.79999999999998),
+ F16(-1.79999999999998),
+ F16(-1.90000000000001),
+ F16(-1.79999999999998),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.79999999999998),
+ F16(-1.79999999999998),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.79999999999998),
+ F16(-1.79999999999998),
+ F16(-1.79999999999998),
+ F16(-1.79999999999998),
+ F16(-1.79999999999998),
+ F16(-1.79999999999998),
+ F16(-1.79999999999998),
+ F16(-1.79999999999998),
+ F16(-1.69999999999999),
+ F16(-1.79999999999998),
+ F16(-1.79999999999998),
+ F16(-1.69999999999999),
+ F16(-1.69999999999999),
+ F16(-1.79999999999998),
+ F16(-1.79999999999998),
+ F16(-1.79999999999998),
+ F16(-1.79999999999998),
+ F16(-1.69999999999999),
+ F16(-1.79999999999998),
+ F16(-1.79999999999998),
+ F16(-1.69999999999999),
+ F16(-1.79999999999998),
+ F16(-1.69999999999999),
+ F16(-1.69999999999999),
+ F16(-1.69999999999999),
+ F16(-1.69999999999999),
+ F16(-1.69999999999999),
+ F16(-1.79999999999998),
+ F16(-1.79999999999998),
+ F16(-1.69999999999999),
+ F16(-1.79999999999998),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.79999999999998),
+ F16(-1.79999999999998),
+ F16(-1.79999999999998),
+ F16(-1.79999999999998),
+ F16(-1.79999999999998),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-2),
+ F16(-2),
+ F16(-1.90000000000001),
+ F16(-2),
+ F16(-2),
+ F16(-1.90000000000001),
+ F16(-1.90000000000001),
+ F16(-2),
+ F16(-2),
+ F16(-2),
+ F16(-1.90000000000001),
+ F16(-2.09999999999999),
+ F16(-2),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.09999999999999),
+ F16(-2.19999999999999),
+ F16(-2.09999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.09999999999999),
+ F16(-2.19999999999999),
+ F16(-2.19999999999999),
+ F16(-2.29999999999998),
+ F16(-2.19999999999999),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.29999999999998),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001),
+ F16(-2.40000000000001)};
+
+const fix16_t __in_flash() acceleration_data[] = { F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1.01),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1),
+ F16(1.02),
+ F16(1.78),
+ F16(1.61),
+ F16(5.79),
+ F16(5.99),
+ F16(6.04),
+ F16(6.04),
+ F16(5.98),
+ F16(6.14),
+ F16(6.13),
+ F16(6.17),
+ F16(6.09),
+ F16(6.18),
+ F16(6.21),
+ F16(6.22),
+ F16(6.18),
+ F16(6.27),
+ F16(6.3),
+ F16(6.3),
+ F16(6.23),
+ F16(6.32),
+ F16(6.36),
+ F16(6.39),
+ F16(6.33),
+ F16(6.44),
+ F16(6.44),
+ F16(6.48),
+ F16(6.42),
+ F16(6.53),
+ F16(6.51),
+ F16(6.54),
+ F16(6.48),
+ F16(6.58),
+ F16(6.64),
+ F16(6.64),
+ F16(6.56),
+ F16(6.7),
+ F16(6.72),
+ F16(6.73),
+ F16(6.66),
+ F16(6.79),
+ F16(6.85),
+ F16(6.87),
+ F16(6.77),
+ F16(6.93),
+ F16(7),
+ F16(7.06),
+ F16(6.9),
+ F16(7.1),
+ F16(7.14),
+ F16(7.18),
+ F16(7.08),
+ F16(7.24),
+ F16(7.26),
+ F16(7.3),
+ F16(7.19),
+ F16(7.36),
+ F16(7.32),
+ F16(7.32),
+ F16(7.29),
+ F16(7.4),
+ F16(7.42),
+ F16(7.51),
+ F16(7.39),
+ F16(7.47),
+ F16(7.52),
+ F16(7.48),
+ F16(7.46),
+ F16(7.51),
+ F16(7.53),
+ F16(7.61),
+ F16(7.49),
+ F16(7.58),
+ F16(7.64),
+ F16(7.65),
+ F16(7.6),
+ F16(7.68),
+ F16(7.73),
+ F16(7.72),
+ F16(7.67),
+ F16(7.76),
+ F16(7.78),
+ F16(7.79),
+ F16(7.77),
+ F16(7.82),
+ F16(7.8),
+ F16(7.84),
+ F16(7.82),
+ F16(7.82),
+ F16(7.85),
+ F16(7.88),
+ F16(7.82),
+ F16(7.91),
+ F16(7.87),
+ F16(7.93),
+ F16(7.94),
+ F16(7.91),
+ F16(7.93),
+ F16(7.98),
+ F16(7.94),
+ F16(7.97),
+ F16(7.95),
+ F16(7.98),
+ F16(8.02),
+ F16(7.97),
+ F16(8.01),
+ F16(8.01),
+ F16(7.97),
+ F16(8.01),
+ F16(8.08),
+ F16(8.05),
+ F16(8.03),
+ F16(8.03),
+ F16(8.04),
+ F16(8.04),
+ F16(8.04),
+ F16(8.11),
+ F16(8.08),
+ F16(8.04),
+ F16(8.07),
+ F16(8.08),
+ F16(7.98),
+ F16(7.98),
+ F16(8.05),
+ F16(8),
+ F16(7.99),
+ F16(7.96),
+ F16(8.01),
+ F16(7.91),
+ F16(7.88),
+ F16(7.89),
+ F16(7.94),
+ F16(7.86),
+ F16(7.84),
+ F16(7.77),
+ F16(7.91),
+ F16(7.76),
+ F16(7.68),
+ F16(7.63),
+ F16(7.7),
+ F16(7.5),
+ F16(7.46),
+ F16(7.5),
+ F16(7.61),
+ F16(7.3),
+ F16(7.25),
+ F16(7.24),
+ F16(7.37),
+ F16(7.04),
+ F16(7.04),
+ F16(6.99),
+ F16(7.19),
+ F16(6.86),
+ F16(6.86),
+ F16(6.81),
+ F16(6.93),
+ F16(6.8),
+ F16(6.74),
+ F16(6.68),
+ F16(6.78),
+ F16(6.61),
+ F16(6.52),
+ F16(6.46),
+ F16(6.63),
+ F16(6.43),
+ F16(6.41),
+ F16(6.29),
+ F16(6.4),
+ F16(6.29),
+ F16(6.17),
+ F16(6.14),
+ F16(6.29),
+ F16(6.03),
+ F16(6.02),
+ F16(6.05),
+ F16(6.15),
+ F16(5.96),
+ F16(5.9),
+ F16(5.78),
+ F16(5.99),
+ F16(5.6),
+ F16(5.7),
+ F16(5.55),
+ F16(5.65),
+ F16(5.5),
+ F16(5.53),
+ F16(5.45),
+ F16(5.57),
+ F16(5.33),
+ F16(5.3),
+ F16(5.25),
+ F16(5.34),
+ F16(5.21),
+ F16(5.15),
+ F16(5.05),
+ F16(5.18),
+ F16(4.98),
+ F16(4.91),
+ F16(4.88),
+ F16(5),
+ F16(4.75),
+ F16(4.7),
+ F16(4.63),
+ F16(4.78),
+ F16(4.54),
+ F16(4.38),
+ F16(4.44),
+ F16(4.58),
+ F16(4.36),
+ F16(4.41),
+ F16(4.32),
+ F16(4.41),
+ F16(4.18),
+ F16(4.13),
+ F16(4.11),
+ F16(4.26),
+ F16(4.02),
+ F16(4.02),
+ F16(3.92),
+ F16(4.17),
+ F16(4.08),
+ F16(3.95),
+ F16(3.9),
+ F16(3.98),
+ F16(3.7),
+ F16(3.8),
+ F16(3.72),
+ F16(3.82),
+ F16(3.6),
+ F16(3.63),
+ F16(3.59),
+ F16(3.65),
+ F16(3.55),
+ F16(3.75),
+ F16(3.56),
+ F16(3.53),
+ F16(3.47),
+ F16(3.36),
+ F16(3.25),
+ F16(3.44),
+ F16(3.23),
+ F16(3.14),
+ F16(3.04),
+ F16(3.2),
+ F16(2.98),
+ F16(2.94),
+ F16(2.88),
+ F16(3.09),
+ F16(2.62),
+ F16(2.6),
+ F16(2.38),
+ F16(2.76),
+ F16(2.09),
+ F16(2.04),
+ F16(1.88),
+ F16(2.22),
+ F16(1.54),
+ F16(1.43),
+ F16(1.4),
+ F16(1.62),
+ F16(1.21),
+ F16(1.21),
+ F16(1.17),
+ F16(1.37),
+ F16(1.13),
+ F16(1.05),
+ F16(0.97),
+ F16(1.19),
+ F16(0.96),
+ F16(0.94),
+ F16(0.85),
+ F16(1.03),
+ F16(0.89),
+ F16(0.78),
+ F16(0.9),
+ F16(0.88),
+ F16(0.74),
+ F16(0.71),
+ F16(0.57),
+ F16(0.84),
+ F16(0.52),
+ F16(0.44),
+ F16(0.36),
+ F16(0.56),
+ F16(0.24),
+ F16(0.17),
+ F16(0.09),
+ F16(0.36),
+ F16(0.02),
+ F16(-0.14),
+ F16(-0.19),
+ F16(0.07),
+ F16(-0.28),
+ F16(-0.32),
+ F16(-0.43),
+ F16(-0.17),
+ F16(-0.56),
+ F16(-0.63),
+ F16(-0.56),
+ F16(-0.46),
+ F16(-0.6),
+ F16(-0.62),
+ F16(-0.73),
+ F16(-0.65),
+ F16(-0.81),
+ F16(-0.81),
+ F16(-0.9),
+ F16(-0.68),
+ F16(-0.92),
+ F16(-0.98),
+ F16(-0.86),
+ F16(-0.81),
+ F16(-1.14),
+ F16(-0.95),
+ F16(-1.01),
+ F16(-1.06),
+ F16(-0.94),
+ F16(-0.96),
+ F16(-1.11),
+ F16(-0.96),
+ F16(-1.05),
+ F16(-0.92),
+ F16(-1),
+ F16(-0.94),
+ F16(-2.33),
+ F16(-1.09),
+ F16(0.39),
+ F16(-2.65),
+ F16(-0.08),
+ F16(-0.58),
+ F16(-1.06),
+ F16(-0.58),
+ F16(0.22),
+ F16(0.13),
+ F16(-2.04),
+ F16(-1.79),
+ F16(-1.49),
+ F16(-1.5),
+ F16(-1.31),
+ F16(-1.4),
+ F16(0.03),
+ F16(-1.32),
+ F16(-1.75),
+ F16(-1.49),
+ F16(-1.14),
+ F16(-2.35),
+ F16(-0.89),
+ F16(-0.65),
+ F16(0.3),
+ F16(-1.81),
+ F16(-0.29),
+ F16(-1.59),
+ F16(-2.02),
+ F16(0.05),
+ F16(-1.2),
+ F16(-2.16),
+ F16(-2.34),
+ F16(-0.8),
+ F16(-0.91),
+ F16(-1.67),
+ F16(-0.59),
+ F16(-2.32),
+ F16(-0.75),
+ F16(-1.28),
+ F16(-2.91),
+ F16(-0.47),
+ F16(-0.25),
+ F16(-1.68),
+ F16(0.23),
+ F16(-1.71),
+ F16(-0.72),
+ F16(-1.06),
+ F16(-1.17),
+ F16(0.11),
+ F16(-0.55),
+ F16(-1.4),
+ F16(-1.29),
+ F16(-0.62),
+ F16(0.18),
+ F16(-0.48),
+ F16(-0.62),
+ F16(-0.85),
+ F16(-0.62),
+ F16(-1.26),
+ F16(-1.27),
+ F16(-0.59),
+ F16(-1.02),
+ F16(-1.37),
+ F16(-0.9),
+ F16(-0.7),
+ F16(-1.4),
+ F16(-1.09),
+ F16(-0.74),
+ F16(-0.93),
+ F16(-1.07),
+ F16(-1.15),
+ F16(-0.82),
+ F16(-0.67),
+ F16(-0.64),
+ F16(-0.95),
+ F16(-1.23),
+ F16(-0.98),
+ F16(-0.95),
+ F16(-1.06),
+ F16(-0.67),
+ F16(-1.01),
+ F16(-1.06),
+ F16(-0.78),
+ F16(-0.66),
+ F16(-0.79),
+ F16(-0.82),
+ F16(-0.7),
+ F16(-0.72),
+ F16(-0.97),
+ F16(-0.87),
+ F16(-0.94),
+ F16(-0.92),
+ F16(-0.78),
+ F16(-0.57),
+ F16(-0.66),
+ F16(-0.86),
+ F16(-0.94),
+ F16(-0.86),
+ F16(-1.05),
+ F16(-0.88),
+ F16(-1.08),
+ F16(-0.82),
+ F16(-0.88),
+ F16(-0.86),
+ F16(-0.7),
+ F16(-0.95),
+ F16(-0.81),
+ F16(-0.65),
+ F16(-0.78),
+ F16(-0.68),
+ F16(-0.8),
+ F16(-0.7),
+ F16(-0.86),
+ F16(-0.73),
+ F16(-0.89),
+ F16(-0.77),
+ F16(-0.73),
+ F16(-0.78),
+ F16(-0.76),
+ F16(-0.9),
+ F16(-0.7),
+ F16(-0.77),
+ F16(-0.74),
+ F16(-0.69),
+ F16(-0.8),
+ F16(-0.75),
+ F16(-0.83),
+ F16(-0.75),
+ F16(-0.68),
+ F16(-0.8),
+ F16(-0.8),
+ F16(-0.81),
+ F16(-0.73),
+ F16(-0.74),
+ F16(-0.67),
+ F16(-0.76),
+ F16(-0.71),
+ F16(-0.76),
+ F16(-0.67),
+ F16(-0.79),
+ F16(-0.61),
+ F16(-0.69),
+ F16(-0.71),
+ F16(-0.82),
+ F16(-0.61),
+ F16(-0.65),
+ F16(-0.76),
+ F16(-0.74),
+ F16(-0.73),
+ F16(-0.72),
+ F16(-0.67),
+ F16(-0.63),
+ F16(-0.7),
+ F16(-0.68),
+ F16(-0.7),
+ F16(-0.71),
+ F16(-0.63),
+ F16(-0.64),
+ F16(-0.71),
+ F16(-0.7),
+ F16(-0.66),
+ F16(-0.65),
+ F16(-0.64),
+ F16(-0.62),
+ F16(-0.75),
+ F16(-0.7),
+ F16(-0.75),
+ F16(-0.72),
+ F16(-0.6),
+ F16(-0.62),
+ F16(-0.66),
+ F16(-0.65),
+ F16(-0.55),
+ F16(-0.7),
+ F16(-0.64),
+ F16(-0.58),
+ F16(-0.57),
+ F16(-0.64),
+ F16(-0.59),
+ F16(-0.62),
+ F16(-0.63),
+ F16(-0.66),
+ F16(-0.56),
+ F16(-0.64),
+ F16(-0.61),
+ F16(-0.55),
+ F16(-0.64),
+ F16(-0.57),
+ F16(-0.54),
+ F16(-0.62),
+ F16(-0.58),
+ F16(-0.6),
+ F16(-0.54),
+ F16(-0.51),
+ F16(-0.6),
+ F16(-0.54),
+ F16(-0.68),
+ F16(-0.65),
+ F16(-0.58),
+ F16(-0.58),
+ F16(-0.57),
+ F16(-0.54),
+ F16(-0.58),
+ F16(-0.58),
+ F16(-0.56),
+ F16(-0.53),
+ F16(-0.47),
+ F16(-0.52),
+ F16(-0.52),
+ F16(-0.53),
+ F16(-0.6),
+ F16(-0.55),
+ F16(-0.59),
+ F16(-0.52),
+ F16(-0.58),
+ F16(-0.5),
+ F16(-0.51),
+ F16(-0.57),
+ F16(-0.5),
+ F16(-0.54),
+ F16(-0.52),
+ F16(-0.57),
+ F16(-0.49),
+ F16(-0.52),
+ F16(-0.49),
+ F16(-0.51),
+ F16(-0.57),
+ F16(-0.55),
+ F16(-0.58),
+ F16(-0.53),
+ F16(-0.59),
+ F16(-0.51),
+ F16(-0.48),
+ F16(-0.45),
+ F16(-0.46),
+ F16(-0.45),
+ F16(-0.45),
+ F16(-0.48),
+ F16(-0.51),
+ F16(-0.5),
+ F16(-0.47),
+ F16(-0.44),
+ F16(-0.5),
+ F16(-0.45),
+ F16(-0.49),
+ F16(-0.48),
+ F16(-0.47),
+ F16(-0.44),
+ F16(-0.45),
+ F16(-0.52),
+ F16(-0.53),
+ F16(-0.56),
+ F16(-0.49),
+ F16(-0.41),
+ F16(-0.46),
+ F16(-0.5),
+ F16(-0.47),
+ F16(-0.49),
+ F16(-0.45),
+ F16(-0.43),
+ F16(-0.46),
+ F16(-0.41),
+ F16(-0.41),
+ F16(-0.44),
+ F16(-0.47),
+ F16(-0.51),
+ F16(-0.49),
+ F16(-0.44),
+ F16(-0.46),
+ F16(-0.42),
+ F16(-0.44),
+ F16(-0.47),
+ F16(-0.44),
+ F16(-0.46),
+ F16(-0.42),
+ F16(-0.44),
+ F16(-0.42),
+ F16(-0.45),
+ F16(-0.46),
+ F16(-0.45),
+ F16(-0.42),
+ F16(-0.41),
+ F16(-0.42),
+ F16(-0.46),
+ F16(-0.42),
+ F16(-0.41),
+ F16(-0.44),
+ F16(-0.41),
+ F16(-0.41),
+ F16(-0.42),
+ F16(-0.41),
+ F16(-0.39),
+ F16(-0.37),
+ F16(-0.43),
+ F16(-0.42),
+ F16(-0.43),
+ F16(-0.38),
+ F16(-0.41),
+ F16(-0.41),
+ F16(-0.39),
+ F16(-0.37),
+ F16(-0.38),
+ F16(-0.4),
+ F16(-0.37),
+ F16(-0.4),
+ F16(-0.36),
+ F16(-0.37),
+ F16(-0.36),
+ F16(-0.37),
+ F16(-0.41),
+ F16(-0.43),
+ F16(-0.35),
+ F16(-0.39),
+ F16(-0.32),
+ F16(-0.4),
+ F16(-0.35),
+ F16(-0.39),
+ F16(-0.38),
+ F16(-0.37),
+ F16(-0.36),
+ F16(-0.34),
+ F16(-0.42),
+ F16(-0.34),
+ F16(-0.36),
+ F16(-0.37),
+ F16(-0.36),
+ F16(-0.41),
+ F16(-0.34),
+ F16(-0.37),
+ F16(-0.38),
+ F16(-0.37),
+ F16(-0.31),
+ F16(-0.33),
+ F16(-0.35),
+ F16(-0.35),
+ F16(-0.38),
+ F16(-0.33),
+ F16(-0.31),
+ F16(-0.33),
+ F16(-0.36),
+ F16(-0.33),
+ F16(-0.39),
+ F16(-0.32),
+ F16(-0.34),
+ F16(-0.32),
+ F16(-0.31),
+ F16(-0.34),
+ F16(-0.33),
+ F16(-0.32),
+ F16(-0.35),
+ F16(-0.32),
+ F16(-0.34),
+ F16(-0.34),
+ F16(-0.29),
+ F16(-0.29),
+ F16(-0.35),
+ F16(-0.33),
+ F16(-0.39),
+ F16(-0.34),
+ F16(-0.31),
+ F16(-0.32),
+ F16(-0.29),
+ F16(-0.31),
+ F16(-0.33),
+ F16(-0.31),
+ F16(-0.31),
+ F16(-0.31),
+ F16(-0.31),
+ F16(-0.29),
+ F16(-0.29),
+ F16(-0.27),
+ F16(-0.31),
+ F16(-0.29),
+ F16(-0.3),
+ F16(-0.28),
+ F16(-0.27),
+ F16(-0.31),
+ F16(-0.32),
+ F16(-0.3),
+ F16(-0.31),
+ F16(-0.28),
+ F16(-0.29),
+ F16(-0.28),
+ F16(-0.27),
+ F16(-0.27),
+ F16(-0.28),
+ F16(-0.32),
+ F16(-0.3),
+ F16(-0.29),
+ F16(-0.31),
+ F16(-0.29),
+ F16(-0.27),
+ F16(-0.26),
+ F16(-0.27),
+ F16(-0.27),
+ F16(-0.28),
+ F16(-0.29),
+ F16(-0.29),
+ F16(-0.27),
+ F16(-0.28),
+ F16(-0.28),
+ F16(-0.26),
+ F16(-0.28),
+ F16(-0.26),
+ F16(-0.27),
+ F16(-0.3),
+ F16(-0.28),
+ F16(-0.3),
+ F16(-0.21),
+ F16(-0.21),
+ F16(-0.22),
+ F16(-0.27),
+ F16(-0.29),
+ F16(-0.26),
+ F16(-0.26),
+ F16(-0.25),
+ F16(-0.26),
+ F16(-0.23),
+ F16(-0.29),
+ F16(-0.28),
+ F16(-0.26),
+ F16(-0.29),
+ F16(-0.25),
+ F16(-0.21),
+ F16(-0.25),
+ F16(-0.23),
+ F16(-0.26),
+ F16(-0.23),
+ F16(-0.24),
+ F16(-0.25),
+ F16(-0.26),
+ F16(-0.24),
+ F16(-0.26),
+ F16(-0.24),
+ F16(-0.25),
+ F16(-0.2),
+ F16(-0.24),
+ F16(-0.23),
+ F16(-0.23),
+ F16(-0.24),
+ F16(-0.23),
+ F16(-0.25),
+ F16(-0.27),
+ F16(-0.23),
+ F16(-0.24),
+ F16(-0.21),
+ F16(-0.28),
+ F16(-0.22),
+ F16(-0.23),
+ F16(-0.24),
+ F16(-0.25),
+ F16(-0.2),
+ F16(-0.22),
+ F16(-0.21),
+ F16(-0.21),
+ F16(-0.23),
+ F16(-0.19),
+ F16(-0.22),
+ F16(-0.27),
+ F16(-0.21),
+ F16(-0.17),
+ F16(-0.21),
+ F16(-0.23),
+ F16(-0.18),
+ F16(-0.24),
+ F16(-0.22),
+ F16(-0.22),
+ F16(-0.25),
+ F16(-0.16),
+ F16(-0.18),
+ F16(-0.17),
+ F16(-0.23),
+ F16(-0.2),
+ F16(-0.18),
+ F16(-0.2),
+ F16(-0.2),
+ F16(-0.21),
+ F16(-0.19),
+ F16(-0.25),
+ F16(-0.21),
+ F16(-0.18),
+ F16(-0.22),
+ F16(-0.19),
+ F16(-0.23),
+ F16(-0.18),
+ F16(-0.19),
+ F16(-0.15),
+ F16(-0.16),
+ F16(-0.18),
+ F16(-0.21),
+ F16(-0.2),
+ F16(-0.18),
+ F16(-0.21),
+ F16(-0.19),
+ F16(-0.22),
+ F16(-0.16),
+ F16(-0.19),
+ F16(-0.16),
+ F16(-0.2),
+ F16(-0.18),
+ F16(-0.15),
+ F16(-0.19),
+ F16(-0.17),
+ F16(-0.18),
+ F16(-0.18),
+ F16(-0.18),
+ F16(-0.2),
+ F16(-0.14),
+ F16(-0.17),
+ F16(-0.17),
+ F16(-0.17),
+ F16(-0.14),
+ F16(-0.13),
+ F16(-0.2),
+ F16(-0.17),
+ F16(-0.16),
+ F16(-0.17),
+ F16(-0.18),
+ F16(-0.16),
+ F16(-0.17),
+ F16(-0.16),
+ F16(-0.16),
+ F16(-0.19),
+ F16(-0.16),
+ F16(-0.15),
+ F16(-0.17),
+ F16(-0.23),
+ F16(-0.18),
+ F16(-0.1),
+ F16(-0.21),
+ F16(-0.15),
+ F16(-0.14),
+ F16(-0.14),
+ F16(-0.17),
+ F16(-0.18),
+ F16(-0.14),
+ F16(-0.21),
+ F16(-0.16),
+ F16(-0.18),
+ F16(-0.16),
+ F16(-0.13),
+ F16(-0.18),
+ F16(-0.13),
+ F16(-0.14),
+ F16(-0.14),
+ F16(-0.13),
+ F16(-0.16),
+ F16(-0.14),
+ F16(-0.16),
+ F16(-0.15),
+ F16(-0.16),
+ F16(-0.17),
+ F16(-0.15),
+ F16(-0.16),
+ F16(-0.18),
+ F16(-0.15),
+ F16(-0.16),
+ F16(-0.09),
+ F16(-0.14),
+ F16(-0.09),
+ F16(-0.12),
+ F16(-0.13),
+ F16(-0.16),
+ F16(-0.13),
+ F16(-0.14),
+ F16(-0.13),
+ F16(-0.14),
+ F16(-0.12),
+ F16(-0.16),
+ F16(-0.14),
+ F16(-0.17),
+ F16(-0.13),
+ F16(-0.14),
+ F16(-0.14),
+ F16(-0.12),
+ F16(-0.12),
+ F16(-0.1),
+ F16(-0.12),
+ F16(-0.16),
+ F16(-0.11),
+ F16(-0.13),
+ F16(-0.16),
+ F16(-0.14),
+ F16(-0.12),
+ F16(-0.15),
+ F16(-0.13),
+ F16(-0.12),
+ F16(-0.12),
+ F16(-0.15),
+ F16(-0.14),
+ F16(-0.14),
+ F16(-0.12),
+ F16(-0.12),
+ F16(-0.13),
+ F16(-0.14),
+ F16(-0.14),
+ F16(-0.12),
+ F16(-0.13),
+ F16(-0.11),
+ F16(-0.11),
+ F16(-0.15),
+ F16(-0.13),
+ F16(-0.13),
+ F16(-0.15),
+ F16(-0.16),
+ F16(-0.14),
+ F16(-0.13),
+ F16(-0.12),
+ F16(-0.12),
+ F16(-0.13),
+ F16(-0.08),
+ F16(-0.11),
+ F16(-0.12),
+ F16(-0.13),
+ F16(-0.11),
+ F16(-0.12),
+ F16(-0.11),
+ F16(-0.09),
+ F16(-0.09),
+ F16(-0.09),
+ F16(-0.13),
+ F16(-0.1),
+ F16(-0.12),
+ F16(-0.08),
+ F16(-0.08),
+ F16(-0.12),
+ F16(-0.11),
+ F16(-0.1),
+ F16(-0.09),
+ F16(-0.11),
+ F16(-0.09),
+ F16(-0.09),
+ F16(-0.1),
+ F16(-0.12),
+ F16(-0.14),
+ F16(-0.1),
+ F16(-0.1),
+ F16(-0.08),
+ F16(-0.12),
+ F16(-0.11),
+ F16(-0.12),
+ F16(-0.1),
+ F16(-0.1),
+ F16(-0.11),
+ F16(-0.1),
+ F16(-0.08),
+ F16(-0.1),
+ F16(-0.12),
+ F16(-0.08),
+ F16(-0.07),
+ F16(-0.1),
+ F16(-0.11),
+ F16(-0.08),
+ F16(-0.05),
+ F16(-0.07),
+ F16(-0.06),
+ F16(-0.1),
+ F16(-0.13),
+ F16(-0.1),
+ F16(-0.09),
+ F16(-0.09),
+ F16(-0.08),
+ F16(-0.09),
+ F16(-0.08),
+ F16(-0.11),
+ F16(-0.09),
+ F16(-0.11),
+ F16(-0.08),
+ F16(-0.06),
+ F16(-0.1),
+ F16(-0.12),
+ F16(-0.08),
+ F16(-0.1),
+ F16(-0.08),
+ F16(-0.08),
+ F16(-0.06),
+ F16(-0.08),
+ F16(-0.05),
+ F16(-0.09),
+ F16(-0.06),
+ F16(-0.08),
+ F16(-0.07),
+ F16(-0.1),
+ F16(-0.07),
+ F16(-0.09),
+ F16(-0.08),
+ F16(-0.06),
+ F16(-0.09),
+ F16(-0.08),
+ F16(-0.07),
+ F16(-0.09),
+ F16(-0.09),
+ F16(-0.08),
+ F16(-0.06),
+ F16(-0.07),
+ F16(-0.08),
+ F16(-0.09),
+ F16(-0.06),
+ F16(-0.1),
+ F16(-0.09),
+ F16(-0.07),
+ F16(-0.08),
+ F16(-0.07),
+ F16(-0.07),
+ F16(-0.05),
+ F16(-0.05),
+ F16(-0.09),
+ F16(-0.06),
+ F16(-0.07),
+ F16(-0.05),
+ F16(-0.08),
+ F16(-0.06),
+ F16(-0.06),
+ F16(-0.08),
+ F16(-0.08),
+ F16(-0.09),
+ F16(-0.07),
+ F16(-0.05),
+ F16(-0.05),
+ F16(-0.06),
+ F16(-0.03),
+ F16(-0.06),
+ F16(-0.05),
+ F16(-0.06),
+ F16(-0.07),
+ F16(-0.07),
+ F16(-0.09),
+ F16(-0.07),
+ F16(-0.08),
+ F16(-0.06),
+ F16(-0.07),
+ F16(-0.07),
+ F16(-0.05),
+ F16(-0.08),
+ F16(-0.08),
+ F16(-0.04),
+ F16(-0.09),
+ F16(-0.05),
+ F16(-0.06),
+ F16(-0.06),
+ F16(-0.08),
+ F16(-0.05),
+ F16(-0.04),
+ F16(-0.07),
+ F16(-0.05),
+ F16(-0.07),
+ F16(-0.06),
+ F16(-0.06),
+ F16(-0.05),
+ F16(-0.07),
+ F16(-0.07),
+ F16(-0.05),
+ F16(-0.05),
+ F16(-0.05),
+ F16(-0.05),
+ F16(-0.04),
+ F16(-0.06),
+ F16(-0.05),
+ F16(-0.04),
+ F16(-0.05),
+ F16(-0.04),
+ F16(-0.06),
+ F16(-0.05),
+ F16(-0.06),
+ F16(-0.05),
+ F16(-0.04),
+ F16(-0.06),
+ F16(-0.05),
+ F16(-0.05),
+ F16(-0.05),
+ F16(-0.06),
+ F16(-0.05),
+ F16(-0.06),
+ F16(-0.03),
+ F16(-0.06),
+ F16(-0.05),
+ F16(-0.05),
+ F16(-0.05),
+ F16(-0.05),
+ F16(-0.06),
+ F16(-0.05),
+ F16(-0.06),
+ F16(-0.03),
+ F16(-0.04),
+ F16(-0.04),
+ F16(-0.05),
+ F16(-0.06),
+ F16(-0.04),
+ F16(-0.05),
+ F16(-0.05),
+ F16(-0.05),
+ F16(-0.02),
+ F16(-0.04),
+ F16(-0.05),
+ F16(-0.05),
+ F16(-0.04),
+ F16(-0.04),
+ F16(-0.04),
+ F16(-0.05),
+ F16(-0.04),
+ F16(-0.04),
+ F16(-0.04),
+ F16(-0.05),
+ F16(-0.04),
+ F16(-0.04),
+ F16(-0.04),
+ F16(-0.04),
+ F16(-0.05),
+ F16(-0.04),
+ F16(-0.03),
+ F16(-0.05),
+ F16(-0.05),
+ F16(-0.05),
+ F16(-0.04),
+ F16(-0.06),
+ F16(-0.02),
+ F16(-0.05),
+ F16(-0.05),
+ F16(-0.04),
+ F16(-0.03),
+ F16(-0.03),
+ F16(-0.04),
+ F16(-0.07),
+ F16(-0.04),
+ F16(-0.03),
+ F16(-0.03),
+ F16(-0.03),
+ F16(-0.03),
+ F16(-0.04),
+ F16(-0.05),
+ F16(-0.05),
+ F16(-0.02),
+ F16(-0.03),
+ F16(-0.04),
+ F16(-0.03),
+ F16(-0.04),
+ F16(-0.03),
+ F16(-0.03),
+ F16(-0.05),
+ F16(-0.05),
+ F16(-0.03),
+ F16(-0.03),
+ F16(-0.03),
+ F16(-0.03),
+ F16(-0.05),
+ F16(-0.02),
+ F16(-0.03),
+ F16(-0.03),
+ F16(-0.04),
+ F16(-0.03),
+ F16(-0.03),
+ F16(-0.03),
+ F16(-0.05),
+ F16(-0.02),
+ F16(-0.03),
+ F16(-0.04),
+ F16(-0.02),
+ F16(-0.03),
+ F16(-0.03),
+ F16(-0.04),
+ F16(-0.02),
+ F16(-0.03),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.03),
+ F16(-0.02),
+ F16(-0.03),
+ F16(-0.03),
+ F16(-0.03),
+ F16(-0.03),
+ F16(-0.03),
+ F16(-0.04),
+ F16(-0.02),
+ F16(-0.03),
+ F16(-0.03),
+ F16(-0.02),
+ F16(-0.04),
+ F16(-0.02),
+ F16(-0.03),
+ F16(-0.03),
+ F16(-0.03),
+ F16(-0.02),
+ F16(-0.04),
+ F16(-0.03),
+ F16(-0.02),
+ F16(-0.03),
+ F16(-0.03),
+ F16(-0.03),
+ F16(-0.02),
+ F16(-0.03),
+ F16(-0.03),
+ F16(-0.03),
+ F16(-0.03),
+ F16(-0.03),
+ F16(-0.04),
+ F16(-0.03),
+ F16(-0.03),
+ F16(-0.03),
+ F16(-0.03),
+ F16(-0.03),
+ F16(-0.03),
+ F16(-0.03),
+ F16(-0.03),
+ F16(-0.03),
+ F16(-0.03),
+ F16(-0.02),
+ F16(-0.03),
+ F16(-0.03),
+ F16(-0.03),
+ F16(-0.02),
+ F16(-0.03),
+ F16(-0.03),
+ F16(-0.03),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.03),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.03),
+ F16(-0.05),
+ F16(-0.03),
+ F16(-0.03),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.03),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.03),
+ F16(-0.03),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.03),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.03),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.03),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.03),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.03),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(0.9),
+ F16(-22.92),
+ F16(-0.03),
+ F16(0.05),
+ F16(-0.03),
+ F16(0.2),
+ F16(-14.86),
+ F16(0.05),
+ F16(0.08),
+ F16(0.06),
+ F16(0.09),
+ F16(-0.09),
+ F16(-0.1),
+ F16(-0.12),
+ F16(0.03),
+ F16(-0.17),
+ F16(-0.15),
+ F16(-0.11),
+ F16(-0.19),
+ F16(0.19),
+ F16(-0.02),
+ F16(0.02),
+ F16(0.16),
+ F16(-0.12),
+ F16(-0.13),
+ F16(-0.04),
+ F16(-0.08),
+ F16(-0.06),
+ F16(-0.12),
+ F16(-0.11),
+ F16(-0.13),
+ F16(-0.11),
+ F16(-0.09),
+ F16(-0.08),
+ F16(-0.09),
+ F16(-0.09),
+ F16(-0.09),
+ F16(-0.09),
+ F16(-0.08),
+ F16(-0.14),
+ F16(-0.13),
+ F16(-0.04),
+ F16(-0.07),
+ F16(-0.08),
+ F16(-0.13),
+ F16(-0.14),
+ F16(-0.1),
+ F16(-0.16),
+ F16(-0.17),
+ F16(-0.13),
+ F16(-0.14),
+ F16(-0.15),
+ F16(-0.2),
+ F16(-0.14),
+ F16(-0.17),
+ F16(-0.15),
+ F16(-0.15),
+ F16(-0.15),
+ F16(-0.14),
+ F16(-0.2),
+ F16(-0.16),
+ F16(-0.16),
+ F16(-0.16),
+ F16(-0.15),
+ F16(-0.16),
+ F16(-0.16),
+ F16(-0.14),
+ F16(-0.22),
+ F16(-0.17),
+ F16(-0.15),
+ F16(-0.17),
+ F16(-0.17),
+ F16(-0.2),
+ F16(-0.17),
+ F16(-0.17),
+ F16(-0.17),
+ F16(-0.16),
+ F16(-0.16),
+ F16(-0.18),
+ F16(-0.16),
+ F16(-0.98),
+ F16(-0.34),
+ F16(-0.18),
+ F16(-0.2),
+ F16(-0.2),
+ F16(-0.18),
+ F16(-0.31),
+ F16(-0.26),
+ F16(-0.32),
+ F16(-0.24),
+ F16(-0.24),
+ F16(-0.28),
+ F16(-0.38),
+ F16(-0.24),
+ F16(-0.25),
+ F16(-0.23),
+ F16(-0.23),
+ F16(-0.2),
+ F16(-0.24),
+ F16(-0.2),
+ F16(-0.27),
+ F16(-0.3),
+ F16(-0.2),
+ F16(-0.24),
+ F16(-0.24),
+ F16(-0.25),
+ F16(-0.25),
+ F16(-0.33),
+ F16(-0.24),
+ F16(-0.24),
+ F16(-0.32),
+ F16(-0.37),
+ F16(-0.3),
+ F16(-0.3),
+ F16(-0.24),
+ F16(-0.34),
+ F16(-0.38),
+ F16(-0.42),
+ F16(-0.36),
+ F16(-0.6),
+ F16(-0.7),
+ F16(-1.11),
+ F16(-0.54),
+ F16(-2.24),
+ F16(-3.03),
+ F16(-4.34),
+ F16(-1.96),
+ F16(-6.25),
+ F16(-6.78),
+ F16(-8.19),
+ F16(-5.72),
+ F16(-10.61),
+ F16(-11.77),
+ F16(-10.25),
+ F16(-9.6),
+ F16(-5.92),
+ F16(-1.7),
+ F16(0.76),
+ F16(-9.05),
+ F16(1.29),
+ F16(0.82),
+ F16(0.41),
+ F16(1.37),
+ F16(0.22),
+ F16(-0.12),
+ F16(-0.82),
+ F16(0.36),
+ F16(-1.28),
+ F16(-1.69),
+ F16(-1.49),
+ F16(-1.04),
+ F16(0.63),
+ F16(0.78),
+ F16(0.91),
+ F16(0.51),
+ F16(0.46),
+ F16(0.24),
+ F16(-0.12),
+ F16(0.87),
+ F16(-0.7),
+ F16(-0.7),
+ F16(-0.86),
+ F16(-0.34),
+ F16(-1.06),
+ F16(-0.69),
+ F16(-0.24),
+ F16(-1.02),
+ F16(0.35),
+ F16(0.62),
+ F16(0.83),
+ F16(0.08),
+ F16(0.73),
+ F16(0.56),
+ F16(0.54),
+ F16(0.66),
+ F16(0.42),
+ F16(0.5),
+ F16(0.41),
+ F16(0.48),
+ F16(-0.11),
+ F16(-0.16),
+ F16(-0.2),
+ F16(-0.02),
+ F16(0.31),
+ F16(0.34),
+ F16(0.76),
+ F16(-0.05),
+ F16(0.77),
+ F16(1.12),
+ F16(1.14),
+ F16(0.93),
+ F16(1.07),
+ F16(0.9),
+ F16(0.75),
+ F16(0.83),
+ F16(0.61),
+ F16(0.44),
+ F16(0.32),
+ F16(0.7),
+ F16(0.08),
+ F16(-0.01),
+ F16(-0.09),
+ F16(0.2),
+ F16(-0.21),
+ F16(-0.22),
+ F16(-0.12),
+ F16(-0.14),
+ F16(-0.03),
+ F16(0.04),
+ F16(0.08),
+ F16(-0.01),
+ F16(0.07),
+ F16(-0.03),
+ F16(-0.1),
+ F16(0.12),
+ F16(-0.2),
+ F16(-0.26),
+ F16(-0.3),
+ F16(-0.15),
+ F16(-0.29),
+ F16(-0.27),
+ F16(-0.27),
+ F16(-0.29),
+ F16(-0.17),
+ F16(0.03),
+ F16(0.2),
+ F16(-0.25),
+ F16(0.23),
+ F16(0.33),
+ F16(0.34),
+ F16(0.3),
+ F16(0.24),
+ F16(0.33),
+ F16(0.21),
+ F16(0.28),
+ F16(0.01),
+ F16(-0.05),
+ F16(-0.11),
+ F16(0.06),
+ F16(-0.15),
+ F16(-0.15),
+ F16(-0.15),
+ F16(-0.13),
+ F16(-0.03),
+ F16(-0.04),
+ F16(0.03),
+ F16(-0.08),
+ F16(-0.01),
+ F16(0.09),
+ F16(0.12),
+ F16(0.01),
+ F16(0.16),
+ F16(0.22),
+ F16(0.13),
+ F16(0.05),
+ F16(0.05),
+ F16(0.02),
+ F16(-0.01),
+ F16(0.08),
+ F16(-0.05),
+ F16(-0.05),
+ F16(-0.04),
+ F16(-0.03),
+ F16(-0),
+ F16(0.04),
+ F16(0.08),
+ F16(-0.04),
+ F16(0.06),
+ F16(0.09),
+ F16(0.09),
+ F16(0.06),
+ F16(0.11),
+ F16(0.09),
+ F16(0),
+ F16(0.11),
+ F16(-0.06),
+ F16(-0.03),
+ F16(-0.2),
+ F16(0),
+ F16(-0.1),
+ F16(-0.15),
+ F16(-0.12),
+ F16(-0.11),
+ F16(-0.14),
+ F16(-0.14),
+ F16(-0.14),
+ F16(-0.17),
+ F16(-0.04),
+ F16(-0.01),
+ F16(0.04),
+ F16(-0.12),
+ F16(0.11),
+ F16(0.2),
+ F16(0.19),
+ F16(0.1),
+ F16(0.24),
+ F16(0.3),
+ F16(0.22),
+ F16(0.25),
+ F16(0.22),
+ F16(0.16),
+ F16(0.2),
+ F16(0.19),
+ F16(0.24),
+ F16(0.25),
+ F16(0.32),
+ F16(0.17),
+ F16(0.36),
+ F16(0.36),
+ F16(0.39),
+ F16(0.34),
+ F16(0.56),
+ F16(0.59),
+ F16(0.78),
+ F16(0.46),
+ F16(0.87),
+ F16(0.81),
+ F16(0.94),
+ F16(0.8),
+ F16(0.91),
+ F16(0.86),
+ F16(0.88),
+ F16(0.95),
+ F16(1.09),
+ F16(0.9),
+ F16(0.93),
+ F16(0.93),
+ F16(0.6),
+ F16(0.49),
+ F16(0.41),
+ F16(0.8),
+ F16(0.21),
+ F16(0.2),
+ F16(0.23),
+ F16(0.26),
+ F16(0.31),
+ F16(0.33),
+ F16(0.43),
+ F16(0.29),
+ F16(0.61),
+ F16(0.62),
+ F16(0.74),
+ F16(0.52),
+ F16(1),
+ F16(1.06),
+ F16(0.94),
+ F16(0.85),
+ F16(0.95),
+ F16(0.98),
+ F16(0.98),
+ F16(0.99),
+ F16(0.88),
+ F16(0.77),
+ F16(0.72),
+ F16(0.94),
+ F16(0.46),
+ F16(0.31),
+ F16(0.18),
+ F16(0.64),
+ F16(0.25),
+ F16(0.31),
+ F16(0.31),
+ F16(0.17),
+ F16(0.53),
+ F16(0.55),
+ F16(0.62),
+ F16(0.31),
+ F16(0.67),
+ F16(0.76),
+ F16(0.83),
+ F16(0.61),
+ F16(1),
+ F16(0.96),
+ F16(0.82),
+ F16(0.94),
+ F16(0.69),
+ F16(0.73),
+ F16(0.57),
+ F16(0.76),
+ F16(0.2),
+ F16(0.1),
+ F16(0.07),
+ F16(0.39),
+ F16(0.04),
+ F16(0.04),
+ F16(0.05),
+ F16(0.04),
+ F16(0.45),
+ F16(0.95),
+ F16(0.95),
+ F16(0.13),
+ F16(0.76),
+ F16(0.39),
+ F16(0.8),
+ F16(0.84),
+ F16(0.72),
+ F16(0.46),
+ F16(0.29),
+ F16(0.99),
+ F16(0.32),
+ F16(0.23),
+ F16(0.1),
+ F16(0.51),
+ F16(-0.01),
+ F16(-0.01),
+ F16(-0.01),
+ F16(-0.01),
+ F16(0.11),
+ F16(0.21),
+ F16(0.21),
+ F16(0),
+ F16(0.31),
+ F16(0.45),
+ F16(0.37),
+ F16(0.23),
+ F16(0.32),
+ F16(0.18),
+ F16(0.11),
+ F16(0.29),
+ F16(0.03),
+ F16(0.02),
+ F16(0.14),
+ F16(0.03),
+ F16(0.31),
+ F16(0.36),
+ F16(0.3),
+ F16(0.22),
+ F16(0.31),
+ F16(0.34),
+ F16(0.32),
+ F16(0.27),
+ F16(0.25),
+ F16(0.22),
+ F16(0.21),
+ F16(0.33),
+ F16(0.13),
+ F16(0.12),
+ F16(0.15),
+ F16(0.17),
+ F16(0.33),
+ F16(0.59),
+ F16(0.89),
+ F16(0.21),
+ F16(0.62),
+ F16(0.54),
+ F16(0.65),
+ F16(0.92),
+ F16(0.68),
+ F16(0.5),
+ F16(0.38),
+ F16(0.83),
+ F16(0.33),
+ F16(0.24),
+ F16(0.08),
+ F16(0.51),
+ F16(-0.04),
+ F16(0.01),
+ F16(-0.08),
+ F16(0.02),
+ F16(-0.08),
+ F16(0.02),
+ F16(0.24),
+ F16(-0.12),
+ F16(0.41),
+ F16(0.35),
+ F16(0.41),
+ F16(0.21),
+ F16(0.26),
+ F16(0.06),
+ F16(0.07),
+ F16(0.28),
+ F16(0.05),
+ F16(0.15),
+ F16(0.15),
+ F16(0.01),
+ F16(0.05),
+ F16(0.19),
+ F16(0.18),
+ F16(0.16),
+ F16(0.41),
+ F16(0.29),
+ F16(0.23),
+ F16(0.34),
+ F16(0.13),
+ F16(0.14),
+ F16(0.19),
+ F16(0.15),
+ F16(0.38),
+ F16(0.49),
+ F16(0.59),
+ F16(0.28),
+ F16(0.62),
+ F16(0.57),
+ F16(0.54),
+ F16(0.61),
+ F16(0.43),
+ F16(0.31),
+ F16(0.04),
+ F16(0.55),
+ F16(-0.26),
+ F16(-0.4),
+ F16(-0.61),
+ F16(-0.1),
+ F16(-0.79),
+ F16(-0.81),
+ F16(-0.8),
+ F16(-0.73),
+ F16(-0.65),
+ F16(-0.52),
+ F16(-0.22),
+ F16(-0.74),
+ F16(0.08),
+ F16(0.08),
+ F16(0.14),
+ F16(0.01),
+ F16(-0.04),
+ F16(-0.26),
+ F16(-0.49),
+ F16(0.09),
+ F16(-0.66),
+ F16(-0.75),
+ F16(-0.78),
+ F16(-0.61),
+ F16(-0.69),
+ F16(-0.59),
+ F16(-0.52),
+ F16(-0.76),
+ F16(-0.41),
+ F16(-0.46),
+ F16(-0.43),
+ F16(-0.5),
+ F16(-0.43),
+ F16(-0.42),
+ F16(-0.43),
+ F16(-0.44),
+ F16(-0.21),
+ F16(0.02),
+ F16(0.15),
+ F16(-0.37),
+ F16(0.58),
+ F16(0.32),
+ F16(0.51),
+ F16(0.19),
+ F16(0.61),
+ F16(0.4),
+ F16(0.14),
+ F16(0.86),
+ F16(0.03),
+ F16(-0.03),
+ F16(-0.11),
+ F16(0.16),
+ F16(-0.17),
+ F16(-0.16),
+ F16(-0.08),
+ F16(-0.16),
+ F16(0.45),
+ F16(0.6),
+ F16(0.33),
+ F16(0.03),
+ F16(0.86),
+ F16(0.89),
+ F16(0.63),
+ F16(0.43),
+ F16(0.78),
+ F16(1.03),
+ F16(0.59),
+ F16(0.78),
+ F16(0.49),
+ F16(0.33),
+ F16(0.38),
+ F16(0.48),
+ F16(0.4),
+ F16(0.43),
+ F16(0.94),
+ F16(0.4),
+ F16(0.75),
+ F16(0.32),
+ F16(0.19),
+ F16(1.11),
+ F16(0.19),
+ F16(0.27),
+ F16(0.29),
+ F16(0.19),
+ F16(0.29),
+ F16(0.29),
+ F16(0.28),
+ F16(0.24),
+ F16(0.51),
+ F16(0.35),
+ F16(0.24),
+ F16(0.44),
+ F16(0.23),
+ F16(0.28),
+ F16(0.28),
+ F16(0.22),
+ F16(0.27),
+ F16(0.24),
+ F16(0.2),
+ F16(0.26),
+ F16(0.25),
+ F16(0.2),
+ F16(0.21),
+ F16(0.21),
+ F16(0.33),
+ F16(0.41),
+ F16(0.5),
+ F16(0.27),
+ F16(0.78),
+ F16(1.1),
+ F16(1.4),
+ F16(0.6),
+ F16(1.34),
+ F16(1.39),
+ F16(1.44),
+ F16(1.62),
+ F16(1.21),
+ F16(1.09),
+ F16(1.29),
+ F16(1.55),
+ F16(0.48),
+ F16(0.29),
+ F16(0.04),
+ F16(0.84),
+ F16(0.4),
+ F16(0.58),
+ F16(0.54),
+ F16(0.09),
+ F16(0.42),
+ F16(0.29),
+ F16(0.17),
+ F16(0.58),
+ F16(-0),
+ F16(-0.03),
+ F16(-0.04),
+ F16(0.05),
+ F16(0.12),
+ F16(0.2),
+ F16(0.36),
+ F16(0.03),
+ F16(0.67),
+ F16(0.56),
+ F16(0.67),
+ F16(0.53),
+ F16(0.54),
+ F16(0.36),
+ F16(0.32),
+ F16(0.65),
+ F16(0.53),
+ F16(0.59),
+ F16(0.78),
+ F16(0.39),
+ F16(0.83),
+ F16(0.95),
+ F16(1.03),
+ F16(0.86),
+ F16(0.33),
+ F16(0.15),
+ F16(0.1),
+ F16(0.52),
+ F16(0.51),
+ F16(0.36),
+ F16(0.37),
+ F16(0.29),
+ F16(0.49),
+ F16(0.44),
+ F16(0.36),
+ F16(0.51),
+ F16(0.24),
+ F16(0.42),
+ F16(0.58),
+ F16(0.27),
+ F16(0.16),
+ F16(0.08),
+ F16(0.05),
+ F16(0.38),
+ F16(0.12),
+ F16(0.21),
+ F16(0.3),
+ F16(0.06),
+ F16(0.33),
+ F16(0.44),
+ F16(0.41),
+ F16(0.36),
+ F16(0.28),
+ F16(0.4),
+ F16(0.49),
+ F16(0.32),
+ F16(0.22),
+ F16(0.12),
+ F16(0.05),
+ F16(0.23),
+ F16(0.12),
+ F16(0.13),
+ F16(0.2),
+ F16(0.06),
+ F16(0.27),
+ F16(0.2),
+ F16(0.17),
+ F16(0.19),
+ F16(0.1),
+ F16(0.03),
+ F16(0.17),
+ F16(0.13),
+ F16(0.38),
+ F16(0.65),
+ F16(0.86),
+ F16(0.15),
+ F16(0.93),
+ F16(0.83),
+ F16(0.91),
+ F16(1.09),
+ F16(0.61),
+ F16(0.71),
+ F16(0.71),
+ F16(0.46),
+ F16(0.75),
+ F16(0.86),
+ F16(0.75),
+ F16(0.72),
+ F16(0.31),
+ F16(0.2),
+ F16(0.16),
+ F16(0.56),
+ F16(0.14),
+ F16(0.11),
+ F16(0.12),
+ F16(0.13),
+ F16(0.11),
+ F16(0.13),
+ F16(0.16),
+ F16(0.11),
+ F16(0.24),
+ F16(0.15),
+ F16(0.08),
+ F16(0.18),
+ F16(0),
+ F16(-0.02),
+ F16(-0.05),
+ F16(0.04),
+ F16(-0.07),
+ F16(-0.07),
+ F16(-0.1),
+ F16(-0.06),
+ F16(-0.07),
+ F16(-0.04),
+ F16(0.01),
+ F16(-0.08),
+ F16(0.2),
+ F16(0.25),
+ F16(0.16),
+ F16(0.11),
+ F16(0.09),
+ F16(0.13),
+ F16(0.11),
+ F16(0.19),
+ F16(0.15),
+ F16(0.14),
+ F16(0.2),
+ F16(0.02),
+ F16(0.14),
+ F16(0.21),
+ F16(0.25),
+ F16(0.32),
+ F16(0.49),
+ F16(0.72),
+ F16(1.16),
+ F16(0.35),
+ F16(1.15),
+ F16(1.33),
+ F16(1.22),
+ F16(1.2),
+ F16(0.7),
+ F16(0.87),
+ F16(0.81),
+ F16(1.07),
+ F16(0.54),
+ F16(0.9),
+ F16(0.6),
+ F16(0.63),
+ F16(0.39),
+ F16(0.31),
+ F16(0.2),
+ F16(0.53),
+ F16(0.2),
+ F16(0.13),
+ F16(0.11),
+ F16(0.12),
+ F16(0.3),
+ F16(0.42),
+ F16(0.34),
+ F16(0.21),
+ F16(0.33),
+ F16(0.19),
+ F16(0.22),
+ F16(0.28),
+ F16(0.2),
+ F16(0.14),
+ F16(0.15),
+ F16(0.3),
+ F16(-0.05),
+ F16(-0.02),
+ F16(-0),
+ F16(-0.03),
+ F16(-0.1),
+ F16(0.01),
+ F16(0.05),
+ F16(0.07),
+ F16(-0.04),
+ F16(0.27),
+ F16(0.37),
+ F16(0.03),
+ F16(0.84),
+ F16(0.67),
+ F16(0.45),
+ F16(0.59),
+ F16(0.15),
+ F16(0.25),
+ F16(0.33),
+ F16(0.22),
+ F16(0.68),
+ F16(0.63),
+ F16(0.65),
+ F16(0.57),
+ F16(0.65),
+ F16(0.63),
+ F16(0.52),
+ F16(0.75),
+ F16(0.86),
+ F16(0.8),
+ F16(0.8),
+ F16(0.68),
+ F16(0.88),
+ F16(0.81),
+ F16(1.06),
+ F16(0.99),
+ F16(0.8),
+ F16(0.76),
+ F16(0.65),
+ F16(0.95),
+ F16(0.23),
+ F16(0.17),
+ F16(0.08),
+ F16(0.46),
+ F16(-0.06),
+ F16(-0.07),
+ F16(-0.06),
+ F16(-0.01),
+ F16(-0.03),
+ F16(0.06),
+ F16(0.17),
+ F16(-0.07),
+ F16(0.35),
+ F16(0.24),
+ F16(0.21),
+ F16(0.32),
+ F16(-0.12),
+ F16(-0.18),
+ F16(-0.21),
+ F16(0.01),
+ F16(-0.16),
+ F16(-0.09),
+ F16(-0.08),
+ F16(-0.18),
+ F16(-0.07),
+ F16(-0.05),
+ F16(0),
+ F16(-0.07),
+ F16(0.12),
+ F16(0.25),
+ F16(0.42),
+ F16(0.04),
+ F16(0.24),
+ F16(0.18),
+ F16(0.14),
+ F16(0.39),
+ F16(-0.01),
+ F16(0.11),
+ F16(0.21),
+ F16(0.06),
+ F16(0.21),
+ F16(0.34),
+ F16(0.46),
+ F16(0.25),
+ F16(0.64),
+ F16(0.79),
+ F16(0.64),
+ F16(0.5),
+ F16(0.61),
+ F16(0.53),
+ F16(0.52),
+ F16(0.53),
+ F16(0.71),
+ F16(0.78),
+ F16(0.72),
+ F16(0.58),
+ F16(0.61),
+ F16(0.43),
+ F16(0.14),
+ F16(0.81),
+ F16(-0.1),
+ F16(-0.12),
+ F16(-0.15),
+ F16(-0.01),
+ F16(-0.1),
+ F16(-0.04),
+ F16(0.01),
+ F16(-0.08),
+ F16(0.11),
+ F16(0.15),
+ F16(0.16),
+ F16(0.13),
+ F16(0.13),
+ F16(0.09),
+ F16(0.07),
+ F16(0.19),
+ F16(0.08),
+ F16(0.06),
+ F16(0.05),
+ F16(0.09),
+ F16(0.04),
+ F16(0.02),
+ F16(0.05),
+ F16(0.05),
+ F16(0.03),
+ F16(0.03),
+ F16(0.01),
+ F16(0.05),
+ F16(0.11),
+ F16(0.13),
+ F16(0.2),
+ F16(0.04),
+ F16(0.31),
+ F16(0.35),
+ F16(0.38),
+ F16(0.3),
+ F16(0.34),
+ F16(0.41),
+ F16(0.49),
+ F16(0.38),
+ F16(0.6),
+ F16(0.75),
+ F16(0.8),
+ F16(0.55),
+ F16(1.15),
+ F16(1.16),
+ F16(1.12),
+ F16(0.87),
+ F16(0.86),
+ F16(0.8),
+ F16(0.75),
+ F16(1.02),
+ F16(0.65),
+ F16(0.59),
+ F16(0.59),
+ F16(0.78),
+ F16(0.44),
+ F16(0.29),
+ F16(0.24),
+ F16(0.5),
+ F16(0.16),
+ F16(0.15),
+ F16(0.17),
+ F16(0.24),
+ F16(0.41),
+ F16(0.46),
+ F16(0.65),
+ F16(0.23),
+ F16(0.94),
+ F16(0.89),
+ F16(0.79),
+ F16(0.78),
+ F16(0.79),
+ F16(0.65),
+ F16(0.48),
+ F16(0.83),
+ F16(0.26),
+ F16(0.16),
+ F16(0.12),
+ F16(0.38),
+ F16(0.31),
+ F16(0.42),
+ F16(0.53),
+ F16(0.17),
+ F16(0.73),
+ F16(0.65),
+ F16(0.56),
+ F16(0.64),
+ F16(0.59),
+ F16(0.52),
+ F16(0.47),
+ F16(0.53),
+ F16(0.51),
+ F16(0.35),
+ F16(0.37),
+ F16(0.36),
+ F16(0.34),
+ F16(0.45),
+ F16(0.41),
+ F16(0.36),
+ F16(0.46),
+ F16(0.57),
+ F16(0.44),
+ F16(0.49),
+ F16(0.68),
+ F16(0.63),
+ F16(0.72),
+ F16(0.61),
+ F16(0.71),
+ F16(0.77),
+ F16(0.83),
+ F16(0.9),
+ F16(0.89),
+ F16(0.8),
+ F16(0.71),
+ F16(0.94),
+ F16(0.3),
+ F16(0.23),
+ F16(0.14),
+ F16(0.44),
+ F16(0.26),
+ F16(0.35),
+ F16(0.51),
+ F16(0.19),
+ F16(0.77),
+ F16(0.93),
+ F16(0.85),
+ F16(0.66),
+ F16(0.93),
+ F16(1.07),
+ F16(0.78),
+ F16(0.95),
+ F16(0.87),
+ F16(0.8),
+ F16(0.68),
+ F16(0.87),
+ F16(0.81),
+ F16(0.58),
+ F16(0.49),
+ F16(0.8),
+ F16(0.36),
+ F16(0.23),
+ F16(0.19),
+ F16(0.44),
+ F16(0.21),
+ F16(0.16),
+ F16(0.18),
+ F16(0.2),
+ F16(0.14),
+ F16(0.13),
+ F16(0.09),
+ F16(0.28),
+ F16(0.08),
+ F16(0.06),
+ F16(0.09),
+ F16(0.09),
+ F16(0.11),
+ F16(0.12),
+ F16(0.12),
+ F16(0.1),
+ F16(0.15),
+ F16(0.22),
+ F16(0.23),
+ F16(0.09),
+ F16(0.2),
+ F16(0.16),
+ F16(0.13),
+ F16(0.26),
+ F16(0.05),
+ F16(0.08),
+ F16(0.14),
+ F16(0.08),
+ F16(0.14),
+ F16(0.2),
+ F16(0.26),
+ F16(0.12),
+ F16(0.21),
+ F16(0.29),
+ F16(0.36),
+ F16(0.22),
+ F16(0.45),
+ F16(0.47),
+ F16(0.39),
+ F16(0.3),
+ F16(0.45),
+ F16(0.37),
+ F16(0.38),
+ F16(0.51),
+ F16(0.49),
+ F16(0.45),
+ F16(0.6),
+ F16(0.4),
+ F16(0.6),
+ F16(0.59),
+ F16(0.58),
+ F16(0.62),
+ F16(0.68),
+ F16(0.86),
+ F16(0.94),
+ F16(0.74),
+ F16(0.85),
+ F16(0.85),
+ F16(0.86),
+ F16(1.09),
+ F16(0.65),
+ F16(0.65),
+ F16(0.56),
+ F16(0.74),
+ F16(0.58),
+ F16(0.63),
+ F16(0.72),
+ F16(0.7),
+ F16(0.79),
+ F16(0.69),
+ F16(0.93),
+ F16(0.68),
+ F16(0.75),
+ F16(0.72),
+ F16(0.75),
+ F16(0.7),
+ F16(0.76),
+ F16(0.63),
+ F16(0.76),
+ F16(0.67),
+ F16(0.6),
+ F16(0.46),
+ F16(0.5),
+ F16(0.63),
+ F16(0.4),
+ F16(0.35),
+ F16(0.45),
+ F16(0.46),
+ F16(0.33),
+ F16(0.35),
+ F16(0.31),
+ F16(0.33),
+ F16(0.31),
+ F16(0.29),
+ F16(0.35),
+ F16(0.33),
+ F16(0.43),
+ F16(0.31),
+ F16(0.26),
+ F16(0.38),
+ F16(0.16),
+ F16(0.15),
+ F16(0.13),
+ F16(0.2),
+ F16(0.22),
+ F16(0.27),
+ F16(0.29),
+ F16(0.14),
+ F16(0.34),
+ F16(0.29),
+ F16(0.22),
+ F16(0.32),
+ F16(0.1),
+ F16(0.12),
+ F16(0.26),
+ F16(0.13),
+ F16(0.4),
+ F16(0.47),
+ F16(0.46),
+ F16(0.26),
+ F16(0.37),
+ F16(0.33),
+ F16(0.3),
+ F16(0.33),
+ F16(0.33),
+ F16(0.45),
+ F16(0.37),
+ F16(0.33),
+ F16(0.5),
+ F16(0.47),
+ F16(0.41),
+ F16(0.49),
+ F16(0.4),
+ F16(0.32),
+ F16(0.41),
+ F16(0.43),
+ F16(0.37),
+ F16(0.27),
+ F16(0.35),
+ F16(0.35),
+ F16(0.39),
+ F16(0.46),
+ F16(0.45),
+ F16(0.32),
+ F16(0.52),
+ F16(0.57),
+ F16(0.55),
+ F16(0.59),
+ F16(0.41),
+ F16(0.38),
+ F16(0.45),
+ F16(0.52),
+ F16(0.47),
+ F16(0.48),
+ F16(0.44),
+ F16(0.54),
+ F16(0.44),
+ F16(0.57),
+ F16(0.64),
+ F16(0.55),
+ F16(0.88),
+ F16(0.98),
+ F16(1.03),
+ F16(0.93),
+ F16(0.95),
+ F16(1.01),
+ F16(1.05),
+ F16(0.93),
+ F16(0.93),
+ F16(0.78),
+ F16(0.65),
+ F16(0.73),
+ F16(0.54),
+ F16(0.49),
+ F16(0.37),
+ F16(0.61),
+ F16(0.44),
+ F16(0.45),
+ F16(0.55),
+ F16(0.41),
+ F16(0.59),
+ F16(0.48),
+ F16(0.44),
+ F16(0.55),
+ F16(0.23),
+ F16(0.17),
+ F16(0.16),
+ F16(0.38),
+ F16(0.13),
+ F16(0.14),
+ F16(0.14),
+ F16(0.15),
+ F16(0.26),
+ F16(0.3),
+ F16(0.38),
+ F16(0.21),
+ F16(0.25),
+ F16(0.2),
+ F16(0.08),
+ F16(0.28),
+ F16(0.04),
+ F16(0.14),
+ F16(0.21),
+ F16(0.02),
+ F16(0.49),
+ F16(0.59),
+ F16(0.42),
+ F16(0.29),
+ F16(0.49),
+ F16(0.47),
+ F16(0.57),
+ F16(0.46),
+ F16(0.74),
+ F16(0.59),
+ F16(0.6),
+ F16(0.46),
+ F16(0.31),
+ F16(0.23),
+ F16(0.16),
+ F16(0.51),
+ F16(0.16),
+ F16(0.26),
+ F16(0.37),
+ F16(0.2),
+ F16(0.63),
+ F16(0.5),
+ F16(0.59),
+ F16(0.53),
+ F16(0.42),
+ F16(0.5),
+ F16(0.38),
+ F16(0.57),
+ F16(0.46),
+ F16(0.74),
+ F16(0.92),
+ F16(0.38),
+ F16(0.66),
+ F16(0.68),
+ F16(0.6),
+ F16(0.92),
+ F16(0.39),
+ F16(0.39),
+ F16(0.31),
+ F16(0.45),
+ F16(0.18),
+ F16(0.26),
+ F16(0.27),
+ F16(0.25),
+ F16(0.47),
+ F16(0.51),
+ F16(0.53),
+ F16(0.33),
+ F16(0.36),
+ F16(0.41),
+ F16(0.42),
+ F16(0.38),
+ F16(0.36),
+ F16(0.49),
+ F16(0.48),
+ F16(0.29),
+ F16(0.68),
+ F16(0.74),
+ F16(0.86),
+ F16(0.57),
+ F16(0.57),
+ F16(0.6),
+ F16(0.48),
+ F16(0.68),
+ F16(0.46),
+ F16(0.55),
+ F16(0.48),
+ F16(0.47),
+ F16(0.51),
+ F16(0.57),
+ F16(0.61),
+ F16(0.43),
+ F16(0.76),
+ F16(0.68),
+ F16(0.76),
+ F16(0.64),
+ F16(0.77),
+ F16(0.74),
+ F16(0.72),
+ F16(0.7),
+ F16(0.71),
+ F16(0.82),
+ F16(0.53),
+ F16(0.77),
+ F16(0.26),
+ F16(0.31),
+ F16(0.25),
+ F16(0.42),
+ F16(0.36),
+ F16(0.58),
+ F16(0.75),
+ F16(0.3),
+ F16(0.67),
+ F16(0.66),
+ F16(0.79),
+ F16(0.71),
+ F16(0.61),
+ F16(0.66),
+ F16(0.67),
+ F16(0.6),
+ F16(0.71),
+ F16(0.77),
+ F16(0.75),
+ F16(0.61),
+ F16(0.61),
+ F16(0.63),
+ F16(0.52),
+ F16(0.71),
+ F16(0.37),
+ F16(0.34),
+ F16(0.3),
+ F16(0.42),
+ F16(0.25),
+ F16(0.27),
+ F16(0.38),
+ F16(0.28),
+ F16(0.42),
+ F16(0.39),
+ F16(0.41),
+ F16(0.38),
+ F16(0.36),
+ F16(0.39),
+ F16(0.46),
+ F16(0.3),
+ F16(0.55),
+ F16(0.61),
+ F16(0.58),
+ F16(0.46),
+ F16(0.39),
+ F16(0.33),
+ F16(0.28),
+ F16(0.47),
+ F16(0.28),
+ F16(0.33),
+ F16(0.38),
+ F16(0.25),
+ F16(0.46),
+ F16(0.4),
+ F16(0.44),
+ F16(0.41),
+ F16(0.56),
+ F16(0.6),
+ F16(0.66),
+ F16(0.39),
+ F16(0.67),
+ F16(0.56),
+ F16(0.55),
+ F16(0.64),
+ F16(0.53),
+ F16(0.58),
+ F16(0.68),
+ F16(0.55),
+ F16(0.84),
+ F16(0.83),
+ F16(0.93),
+ F16(0.75),
+ F16(0.69),
+ F16(0.64),
+ F16(0.39),
+ F16(0.6),
+ F16(0.25),
+ F16(0.38),
+ F16(0.19),
+ F16(0.35),
+ F16(0.36),
+ F16(0.56),
+ F16(0.42),
+ F16(0.23),
+ F16(0.71),
+ F16(0.51),
+ F16(0.42),
+ F16(0.51),
+ F16(0.35),
+ F16(0.44),
+ F16(0.39),
+ F16(0.35),
+ F16(0.43),
+ F16(0.38),
+ F16(0.31),
+ F16(0.37),
+ F16(0.18),
+ F16(0.22),
+ F16(0.23),
+ F16(0.22),
+ F16(0.29),
+ F16(0.48),
+ F16(0.58),
+ F16(0.23),
+ F16(0.5),
+ F16(0.59),
+ F16(0.66),
+ F16(0.5),
+ F16(0.45),
+ F16(0.55),
+ F16(0.54),
+ F16(0.54),
+ F16(0.63),
+ F16(0.7),
+ F16(0.73),
+ F16(0.57),
+ F16(0.52),
+ F16(0.45),
+ F16(0.46),
+ F16(0.63),
+ F16(0.39),
+ F16(0.34),
+ F16(0.42),
+ F16(0.45),
+ F16(0.68),
+ F16(0.63),
+ F16(0.57),
+ F16(0.6),
+ F16(0.45),
+ F16(0.41),
+ F16(0.42),
+ F16(0.5),
+ F16(0.48),
+ F16(0.5),
+ F16(0.47),
+ F16(0.43),
+ F16(0.49),
+ F16(0.57),
+ F16(0.62),
+ F16(0.45),
+ F16(0.58),
+ F16(0.57),
+ F16(0.54),
+ F16(0.58),
+ F16(0.52),
+ F16(0.56),
+ F16(0.58),
+ F16(0.52),
+ F16(0.52),
+ F16(0.53),
+ F16(0.49),
+ F16(0.51),
+ F16(0.42),
+ F16(0.38),
+ F16(0.37),
+ F16(0.44),
+ F16(0.31),
+ F16(0.32),
+ F16(0.27),
+ F16(0.32),
+ F16(0.23),
+ F16(0.21),
+ F16(0.16),
+ F16(0.26),
+ F16(0.13),
+ F16(0.1),
+ F16(0.11),
+ F16(0.13),
+ F16(0.03),
+ F16(0.06),
+ F16(0.06),
+ F16(0.09),
+ F16(0.09),
+ F16(0.11),
+ F16(0.21),
+ F16(0.08),
+ F16(0.23),
+ F16(0.21),
+ F16(0.24),
+ F16(0.2),
+ F16(0.28),
+ F16(0.21),
+ F16(0.19),
+ F16(0.28),
+ F16(0.14),
+ F16(0.12),
+ F16(0.17),
+ F16(0.16),
+ F16(0.21),
+ F16(0.28),
+ F16(0.33),
+ F16(0.19),
+ F16(0.71),
+ F16(0.72),
+ F16(0.74),
+ F16(0.47),
+ F16(0.91),
+ F16(0.8),
+ F16(0.93),
+ F16(0.87),
+ F16(0.69),
+ F16(0.65),
+ F16(0.45),
+ F16(0.74),
+ F16(0.45),
+ F16(0.54),
+ F16(0.55),
+ F16(0.4),
+ F16(0.67),
+ F16(0.51),
+ F16(0.36),
+ F16(0.58),
+ F16(0.14),
+ F16(0.1),
+ F16(0.01),
+ F16(0.24),
+ F16(-0.05),
+ F16(-0.08),
+ F16(-0.01),
+ F16(-0.02),
+ F16(-0.01),
+ F16(0),
+ F16(0.01),
+ F16(-0),
+ F16(0.03),
+ F16(0.05),
+ F16(0.07),
+ F16(0.02),
+ F16(0.08),
+ F16(0.1),
+ F16(0.1),
+ F16(0.07),
+ F16(0.09),
+ F16(0.09),
+ F16(0.08),
+ F16(0.11),
+ F16(0.08),
+ F16(0.02),
+ F16(0.04),
+ F16(0.04),
+ F16(0.01),
+ F16(0),
+ F16(-0.05),
+ F16(0.03),
+ F16(-0.02),
+ F16(0.01),
+ F16(0),
+ F16(-0.01),
+ F16(0),
+ F16(0.01),
+ F16(0.02),
+ F16(0.02),
+ F16(0.07),
+ F16(0.08),
+ F16(0.07),
+ F16(0.04),
+ F16(0.1),
+ F16(0.1),
+ F16(0.16),
+ F16(0.05),
+ F16(0.25),
+ F16(0.31),
+ F16(0.34),
+ F16(0.19),
+ F16(0.46),
+ F16(0.53),
+ F16(0.55),
+ F16(0.39),
+ F16(0.72),
+ F16(0.82),
+ F16(0.89),
+ F16(0.61),
+ F16(1.13),
+ F16(1.15),
+ F16(1.24),
+ F16(1),
+ F16(1.2),
+ F16(1.13),
+ F16(1.12),
+ F16(1.27),
+ F16(0.73),
+ F16(0.66),
+ F16(0.61),
+ F16(0.89),
+ F16(0.56),
+ F16(0.53),
+ F16(0.56),
+ F16(0.52),
+ F16(0.62),
+ F16(0.48),
+ F16(0.5),
+ F16(0.54),
+ F16(0.5),
+ F16(0.41),
+ F16(0.49),
+ F16(0.51),
+ F16(0.51),
+ F16(0.42),
+ F16(0.43),
+ F16(0.46),
+ F16(0.48),
+ F16(0.63),
+ F16(0.67),
+ F16(0.39),
+ F16(0.47),
+ F16(0.36),
+ F16(0.37),
+ F16(0.58),
+ F16(0.45),
+ F16(0.4),
+ F16(0.54),
+ F16(0.4),
+ F16(0.57),
+ F16(0.55),
+ F16(0.54),
+ F16(0.55),
+ F16(0.38),
+ F16(0.33),
+ F16(0.26),
+ F16(0.47),
+ F16(0.21),
+ F16(0.22),
+ F16(0.28),
+ F16(0.27),
+ F16(0.33),
+ F16(0.31),
+ F16(0.29),
+ F16(0.28),
+ F16(0.25),
+ F16(0.21),
+ F16(0.2),
+ F16(0.26),
+ F16(0.15),
+ F16(0.11),
+ F16(0.12),
+ F16(0.17),
+ F16(0.04),
+ F16(0.03),
+ F16(0.03),
+ F16(0.07),
+ F16(0.02),
+ F16(0.02),
+ F16(0.01),
+ F16(0.01),
+ F16(0.02),
+ F16(0.01),
+ F16(0.09),
+ F16(0.01),
+ F16(0.05),
+ F16(0.1),
+ F16(0.09),
+ F16(0.04),
+ F16(0.11),
+ F16(0.13),
+ F16(0.13),
+ F16(0.11),
+ F16(0.17),
+ F16(0.21),
+ F16(0.25),
+ F16(0.15),
+ F16(0.38),
+ F16(0.44),
+ F16(0.5),
+ F16(0.3),
+ F16(0.66),
+ F16(0.73),
+ F16(0.73),
+ F16(0.57),
+ F16(0.46),
+ F16(0.38),
+ F16(0.2),
+ F16(0.6),
+ F16(0.1),
+ F16(0.19),
+ F16(0.08),
+ F16(0.14),
+ F16(0.15),
+ F16(0.13),
+ F16(0.05),
+ F16(0.08),
+ F16(0.11),
+ F16(0.05),
+ F16(0.08),
+ F16(0.05),
+ F16(0.13),
+ F16(0.13),
+ F16(0.15),
+ F16(0.09),
+ F16(0.15),
+ F16(0.16),
+ F16(0.18),
+ F16(0.13),
+ F16(0.16),
+ F16(0.14),
+ F16(0.1),
+ F16(0.14),
+ F16(0.08),
+ F16(0.04),
+ F16(0.03),
+ F16(0.1),
+ F16(0.08),
+ F16(0.09),
+ F16(0.17),
+ F16(0.07),
+ F16(0.2),
+ F16(0.24),
+ F16(0.24),
+ F16(0.18),
+ F16(0.28),
+ F16(0.3),
+ F16(0.34),
+ F16(0.29),
+ F16(0.25),
+ F16(0.16),
+ F16(0.2),
+ F16(0.27),
+ F16(0.28),
+ F16(0.35),
+ F16(0.42),
+ F16(0.22),
+ F16(0.35),
+ F16(0.34),
+ F16(0.34),
+ F16(0.35),
+ F16(0.37),
+ F16(0.38),
+ F16(0.36),
+ F16(0.35),
+ F16(0.31),
+ F16(0.3),
+ F16(0.25),
+ F16(0.35),
+ F16(0.21),
+ F16(0.21),
+ F16(0.21),
+ F16(0.22),
+ F16(0.16),
+ F16(0.16),
+ F16(0.15),
+ F16(0.2),
+ F16(0.12),
+ F16(0.02),
+ F16(-0.01),
+ F16(0.16),
+ F16(0.13),
+ F16(0.15),
+ F16(0.15),
+ F16(0.04),
+ F16(0.14),
+ F16(0.16),
+ F16(0.14),
+ F16(0.2),
+ F16(0.12),
+ F16(0.08),
+ F16(0.13),
+ F16(0.13),
+ F16(0.2),
+ F16(0.25),
+ F16(0.19),
+ F16(0.15),
+ F16(0.15),
+ F16(0.14),
+ F16(0.16),
+ F16(0.18),
+ F16(0.18),
+ F16(0.14),
+ F16(0.14),
+ F16(0.17),
+ F16(0.14),
+ F16(0.17),
+ F16(0.14),
+ F16(0.15),
+ F16(0.17),
+ F16(0.16),
+ F16(0.15),
+ F16(0.16),
+ F16(0.18),
+ F16(0.2),
+ F16(0.24),
+ F16(0.15),
+ F16(0.33),
+ F16(0.43),
+ F16(0.56),
+ F16(0.27),
+ F16(0.75),
+ F16(0.82),
+ F16(1),
+ F16(0.78),
+ F16(0.92),
+ F16(0.83),
+ F16(0.66),
+ F16(1.16),
+ F16(0.33),
+ F16(0.25),
+ F16(0.16),
+ F16(0.53),
+ F16(0.11),
+ F16(0.12),
+ F16(0.09),
+ F16(0.13),
+ F16(0.18),
+ F16(0.2),
+ F16(0.18),
+ F16(0.13),
+ F16(0.16),
+ F16(0.18),
+ F16(0.15),
+ F16(0.18),
+ F16(0.21),
+ F16(0.23),
+ F16(0.26),
+ F16(0.16),
+ F16(0.24),
+ F16(0.26),
+ F16(0.31),
+ F16(0.24),
+ F16(0.36),
+ F16(0.41),
+ F16(0.48),
+ F16(0.34),
+ F16(0.59),
+ F16(0.49),
+ F16(0.71),
+ F16(0.54),
+ F16(0.65),
+ F16(0.54),
+ F16(0.36),
+ F16(0.66),
+ F16(0.5),
+ F16(0.55),
+ F16(0.49),
+ F16(0.39),
+ F16(0.41),
+ F16(0.36),
+ F16(0.28),
+ F16(0.5),
+ F16(0.25),
+ F16(0.28),
+ F16(0.31),
+ F16(0.26),
+ F16(0.24),
+ F16(0.19),
+ F16(0.16),
+ F16(0.28),
+ F16(0.09),
+ F16(0.06),
+ F16(0.01),
+ F16(0.11),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.01),
+ F16(-0),
+ F16(0.13),
+ F16(0.18),
+ F16(0.19),
+ F16(0.03),
+ F16(0.24),
+ F16(0.24),
+ F16(0.25),
+ F16(0.22),
+ F16(0.39),
+ F16(0.43),
+ F16(0.38),
+ F16(0.32),
+ F16(0.35),
+ F16(0.37),
+ F16(0.33),
+ F16(0.35),
+ F16(0.4),
+ F16(0.38),
+ F16(0.43),
+ F16(0.33),
+ F16(0.36),
+ F16(0.32),
+ F16(0.3),
+ F16(0.31),
+ F16(0.29),
+ F16(0.4),
+ F16(0.41),
+ F16(0.3),
+ F16(0.37),
+ F16(0.42),
+ F16(0.47),
+ F16(0.4),
+ F16(0.53),
+ F16(0.55),
+ F16(0.65),
+ F16(0.47),
+ F16(0.82),
+ F16(0.86),
+ F16(1.02),
+ F16(0.73),
+ F16(0.89),
+ F16(0.86),
+ F16(0.67),
+ F16(1.07),
+ F16(0.32),
+ F16(0.27),
+ F16(0.26),
+ F16(0.38),
+ F16(0.35),
+ F16(0.39),
+ F16(0.42),
+ F16(0.24),
+ F16(0.36),
+ F16(0.26),
+ F16(0.24),
+ F16(0.43),
+ F16(0.25),
+ F16(0.34),
+ F16(0.32),
+ F16(0.23),
+ F16(0.4),
+ F16(0.47),
+ F16(0.49),
+ F16(0.37),
+ F16(0.49),
+ F16(0.55),
+ F16(0.53),
+ F16(0.47),
+ F16(0.52),
+ F16(0.48),
+ F16(0.49),
+ F16(0.48),
+ F16(0.41),
+ F16(0.46),
+ F16(0.39),
+ F16(0.45),
+ F16(0.33),
+ F16(0.38),
+ F16(0.36),
+ F16(0.35),
+ F16(0.19),
+ F16(0.21),
+ F16(0.26),
+ F16(0.25),
+ F16(0.28),
+ F16(0.3),
+ F16(0.36),
+ F16(0.27),
+ F16(0.34),
+ F16(0.36),
+ F16(0.39),
+ F16(0.34),
+ F16(0.44),
+ F16(0.42),
+ F16(0.45),
+ F16(0.46),
+ F16(0.39),
+ F16(0.38),
+ F16(0.42),
+ F16(0.45),
+ F16(0.39),
+ F16(0.56),
+ F16(0.52),
+ F16(0.36),
+ F16(0.59),
+ F16(0.49),
+ F16(0.42),
+ F16(0.49),
+ F16(0.4),
+ F16(0.39),
+ F16(0.33),
+ F16(0.45),
+ F16(0.34),
+ F16(0.32),
+ F16(0.3),
+ F16(0.31),
+ F16(0.28),
+ F16(0.2),
+ F16(0.32),
+ F16(0.24),
+ F16(0.37),
+ F16(0.39),
+ F16(0.4),
+ F16(0.33),
+ F16(0.34),
+ F16(0.36),
+ F16(0.33),
+ F16(0.35),
+ F16(0.27),
+ F16(0.34),
+ F16(0.33),
+ F16(0.3),
+ F16(0.23),
+ F16(0.18),
+ F16(0.14),
+ F16(0.31),
+ F16(0.15),
+ F16(0.15),
+ F16(0.16),
+ F16(0.12),
+ F16(0.18),
+ F16(0.17),
+ F16(0.18),
+ F16(0.14),
+ F16(0.17),
+ F16(0.16),
+ F16(0.16),
+ F16(0.17),
+ F16(0.11),
+ F16(0.15),
+ F16(0.13),
+ F16(0.15),
+ F16(0.11),
+ F16(0.12),
+ F16(0.13),
+ F16(0.13),
+ F16(0.11),
+ F16(0.16),
+ F16(0.15),
+ F16(0.14),
+ F16(0.13),
+ F16(0.19),
+ F16(0.18),
+ F16(0.15),
+ F16(0.18),
+ F16(0.21),
+ F16(0.25),
+ F16(0.19),
+ F16(0.22),
+ F16(0.25),
+ F16(0.25),
+ F16(0.24),
+ F16(0.25),
+ F16(0.26),
+ F16(0.28),
+ F16(0.22),
+ F16(0.31),
+ F16(0.31),
+ F16(0.36),
+ F16(0.29),
+ F16(0.4),
+ F16(0.38),
+ F16(0.44),
+ F16(0.35),
+ F16(0.53),
+ F16(0.54),
+ F16(0.64),
+ F16(0.5),
+ F16(0.74),
+ F16(0.74),
+ F16(0.83),
+ F16(0.7),
+ F16(0.83),
+ F16(0.85),
+ F16(0.76),
+ F16(0.84),
+ F16(0.73),
+ F16(0.65),
+ F16(0.62),
+ F16(0.74),
+ F16(0.55),
+ F16(0.64),
+ F16(0.61),
+ F16(0.69),
+ F16(0.56),
+ F16(0.5),
+ F16(0.47),
+ F16(0.62),
+ F16(0.5),
+ F16(0.47),
+ F16(0.51),
+ F16(0.45),
+ F16(0.59),
+ F16(0.49),
+ F16(0.5),
+ F16(0.5),
+ F16(0.47),
+ F16(0.57),
+ F16(0.59),
+ F16(0.45),
+ F16(0.53),
+ F16(0.57),
+ F16(0.51),
+ F16(0.59),
+ F16(0.43),
+ F16(0.36),
+ F16(0.35),
+ F16(0.42),
+ F16(0.25),
+ F16(0.25),
+ F16(0.23),
+ F16(0.3),
+ F16(0.17),
+ F16(0.18),
+ F16(0.16),
+ F16(0.2),
+ F16(0.19),
+ F16(0.15),
+ F16(0.15),
+ F16(0.17),
+ F16(0.19),
+ F16(0.17),
+ F16(0.18),
+ F16(0.18),
+ F16(0.23),
+ F16(0.22),
+ F16(0.21),
+ F16(0.19),
+ F16(0.25),
+ F16(0.23),
+ F16(0.26),
+ F16(0.21),
+ F16(0.23),
+ F16(0.25),
+ F16(0.26),
+ F16(0.22),
+ F16(0.23),
+ F16(0.22),
+ F16(0.23),
+ F16(0.26),
+ F16(0.2),
+ F16(0.19),
+ F16(0.17),
+ F16(0.25),
+ F16(0.17),
+ F16(0.12),
+ F16(0.11),
+ F16(0.2),
+ F16(0.04),
+ F16(0.02),
+ F16(0.02),
+ F16(0.07),
+ F16(-0.02),
+ F16(-0.08),
+ F16(-0.06),
+ F16(0.03),
+ F16(-0.02),
+ F16(-0.02),
+ F16(0.01),
+ F16(-0.01),
+ F16(0.07),
+ F16(0.15),
+ F16(0.16),
+ F16(0.01),
+ F16(0.19),
+ F16(0.29),
+ F16(0.24),
+ F16(0.18),
+ F16(0.28),
+ F16(0.26),
+ F16(0.2),
+ F16(0.25),
+ F16(0.19),
+ F16(0.16),
+ F16(0.16),
+ F16(0.21),
+ F16(0.18),
+ F16(0.21),
+ F16(0.21),
+ F16(0.16),
+ F16(0.34),
+ F16(0.33),
+ F16(0.29),
+ F16(0.27),
+ F16(0.51),
+ F16(0.54),
+ F16(0.62),
+ F16(0.36),
+ F16(0.78),
+ F16(0.64),
+ F16(0.64),
+ F16(0.6),
+ F16(0.7),
+ F16(0.7),
+ F16(0.76),
+ F16(0.71),
+ F16(0.63),
+ F16(0.64),
+ F16(0.52),
+ F16(0.66),
+ F16(0.49),
+ F16(0.37),
+ F16(0.48),
+ F16(0.71),
+ F16(0.4),
+ F16(0.42),
+ F16(0.3),
+ F16(0.54),
+ F16(0.22),
+ F16(0.17),
+ F16(0.16),
+ F16(0.37),
+ F16(0.22),
+ F16(0.15),
+ F16(0.17),
+ F16(0.19),
+ F16(0.2),
+ F16(0.21),
+ F16(0.17),
+ F16(0.18),
+ F16(0.45),
+ F16(0.12),
+ F16(0.19),
+ F16(0.16),
+ F16(0.15),
+ F16(0.18),
+ F16(0.19),
+ F16(0.16),
+ F16(0.17),
+ F16(0.19),
+ F16(0.21),
+ F16(0.18),
+ F16(0.2),
+ F16(0.21),
+ F16(0.22),
+ F16(0.19),
+ F16(0.2),
+ F16(0.2),
+ F16(0.23),
+ F16(0.2),
+ F16(0.19),
+ F16(0.19),
+ F16(0.22),
+ F16(0.23),
+ F16(0.2),
+ F16(0.19),
+ F16(0.19),
+ F16(0.2),
+ F16(0.17),
+ F16(0.12),
+ F16(0.13),
+ F16(0.16),
+ F16(0.13),
+ F16(0.16),
+ F16(0.16),
+ F16(0.09),
+ F16(0.19),
+ F16(0.21),
+ F16(0.28),
+ F16(0.15),
+ F16(0.31),
+ F16(0.31),
+ F16(0.32),
+ F16(0.29),
+ F16(0.36),
+ F16(0.38),
+ F16(0.43),
+ F16(0.35),
+ F16(0.44),
+ F16(0.47),
+ F16(0.51),
+ F16(0.44),
+ F16(0.48),
+ F16(0.38),
+ F16(0.32),
+ F16(0.47),
+ F16(0.37),
+ F16(0.43),
+ F16(0.43),
+ F16(0.39),
+ F16(0.51),
+ F16(0.48),
+ F16(0.46),
+ F16(0.5),
+ F16(0.44),
+ F16(0.41),
+ F16(0.38),
+ F16(0.43),
+ F16(0.38),
+ F16(0.39),
+ F16(0.35),
+ F16(0.39),
+ F16(0.3),
+ F16(0.29),
+ F16(0.3),
+ F16(0.3),
+ F16(0.23),
+ F16(0.32),
+ F16(0.43),
+ F16(0.25),
+ F16(0.56),
+ F16(0.69),
+ F16(0.66),
+ F16(0.48),
+ F16(0.55),
+ F16(0.43),
+ F16(0.39),
+ F16(0.62),
+ F16(0.32),
+ F16(0.31),
+ F16(0.34),
+ F16(0.32),
+ F16(0.45),
+ F16(0.35),
+ F16(0.25),
+ F16(0.45),
+ F16(0.19),
+ F16(0.17),
+ F16(0.14),
+ F16(0.24),
+ F16(0.16),
+ F16(0.21),
+ F16(0.24),
+ F16(0.16),
+ F16(0.23),
+ F16(0.25),
+ F16(0.25),
+ F16(0.22),
+ F16(0.28),
+ F16(0.3),
+ F16(0.36),
+ F16(0.3),
+ F16(0.34),
+ F16(0.32),
+ F16(0.36),
+ F16(0.36),
+ F16(0.33),
+ F16(0.29),
+ F16(0.29),
+ F16(0.38),
+ F16(0.28),
+ F16(0.26),
+ F16(0.23),
+ F16(0.32),
+ F16(0.25),
+ F16(0.21),
+ F16(0.21),
+ F16(0.25),
+ F16(0.18),
+ F16(0.2),
+ F16(0.18),
+ F16(0.17),
+ F16(0.16),
+ F16(0.19),
+ F16(0.19),
+ F16(0.15),
+ F16(0.16),
+ F16(0.15),
+ F16(0.14),
+ F16(0.2),
+ F16(0.09),
+ F16(0.08),
+ F16(0.03),
+ F16(0.14),
+ F16(0.03),
+ F16(0.1),
+ F16(0.15),
+ F16(0.07),
+ F16(0.29),
+ F16(0.21),
+ F16(0.22),
+ F16(0.23),
+ F16(0.33),
+ F16(0.35),
+ F16(0.26),
+ F16(0.27),
+ F16(0.35),
+ F16(0.39),
+ F16(0.45),
+ F16(0.31),
+ F16(0.42),
+ F16(0.44),
+ F16(0.44),
+ F16(0.41),
+ F16(0.41),
+ F16(0.38),
+ F16(0.45),
+ F16(0.41),
+ F16(0.4),
+ F16(0.39),
+ F16(0.39),
+ F16(0.43),
+ F16(0.38),
+ F16(0.39),
+ F16(0.42),
+ F16(0.42),
+ F16(0.36),
+ F16(0.29),
+ F16(0.25),
+ F16(0.4),
+ F16(0.21),
+ F16(0.2),
+ F16(0.17),
+ F16(0.22),
+ F16(0.11),
+ F16(0.07),
+ F16(0.05),
+ F16(0.13),
+ F16(0.04),
+ F16(0.07),
+ F16(0.02),
+ F16(0.04),
+ F16(0.1),
+ F16(0.1),
+ F16(0.08),
+ F16(0.07),
+ F16(0.06),
+ F16(0.05),
+ F16(0.04),
+ F16(0.05),
+ F16(0.05),
+ F16(0.03),
+ F16(0.02),
+ F16(0.04),
+ F16(0.05),
+ F16(0.1),
+ F16(0.12),
+ F16(0.03),
+ F16(0.13),
+ F16(0.15),
+ F16(0.21),
+ F16(0.11),
+ F16(0.19),
+ F16(0.24),
+ F16(0.29),
+ F16(0.21),
+ F16(0.33),
+ F16(0.35),
+ F16(0.4),
+ F16(0.33),
+ F16(0.43),
+ F16(0.49),
+ F16(0.49),
+ F16(0.38),
+ F16(0.51),
+ F16(0.57),
+ F16(0.61),
+ F16(0.44),
+ F16(0.69),
+ F16(0.62),
+ F16(0.54),
+ F16(0.67),
+ F16(0.42),
+ F16(0.32),
+ F16(0.33),
+ F16(0.47),
+ F16(0.6),
+ F16(0.72),
+ F16(0.69),
+ F16(0.44),
+ F16(0.61),
+ F16(0.48),
+ F16(0.5),
+ F16(0.71),
+ F16(0.55),
+ F16(0.66),
+ F16(0.68),
+ F16(0.48),
+ F16(0.75),
+ F16(0.81),
+ F16(0.82),
+ F16(0.86),
+ F16(1),
+ F16(1.01),
+ F16(1.06),
+ F16(0.9),
+ F16(0.96),
+ F16(0.87),
+ F16(0.81),
+ F16(1.04),
+ F16(0.8),
+ F16(0.72),
+ F16(0.75),
+ F16(0.86),
+ F16(0.75),
+ F16(0.68),
+ F16(0.58),
+ F16(0.72),
+ F16(0.43),
+ F16(0.39),
+ F16(0.34),
+ F16(0.5),
+ F16(0.31),
+ F16(0.29),
+ F16(0.29),
+ F16(0.33),
+ F16(0.23),
+ F16(0.26),
+ F16(0.23),
+ F16(0.24),
+ F16(0.24),
+ F16(0.22),
+ F16(0.2),
+ F16(0.23),
+ F16(0.23),
+ F16(0.18),
+ F16(0.15),
+ F16(0.2),
+ F16(0.13),
+ F16(0.1),
+ F16(0.08),
+ F16(0.12),
+ F16(0.06),
+ F16(0.08),
+ F16(0.07),
+ F16(0.07),
+ F16(0.06),
+ F16(0.06),
+ F16(0.07),
+ F16(0.06),
+ F16(0.08),
+ F16(0.08),
+ F16(0.09),
+ F16(0.06),
+ F16(0.11),
+ F16(0.12),
+ F16(0.15),
+ F16(0.11),
+ F16(0.13),
+ F16(0.15),
+ F16(0.18),
+ F16(0.14),
+ F16(0.18),
+ F16(0.17),
+ F16(0.2),
+ F16(0.16),
+ F16(0.22),
+ F16(0.21),
+ F16(0.21),
+ F16(0.2),
+ F16(0.25),
+ F16(0.25),
+ F16(0.27),
+ F16(0.21),
+ F16(0.29),
+ F16(0.33),
+ F16(0.39),
+ F16(0.27),
+ F16(0.4),
+ F16(0.44),
+ F16(0.46),
+ F16(0.41),
+ F16(0.47),
+ F16(0.46),
+ F16(0.5),
+ F16(0.47),
+ F16(0.5),
+ F16(0.46),
+ F16(0.47),
+ F16(0.41),
+ F16(0.46),
+ F16(0.46),
+ F16(0.42),
+ F16(0.48),
+ F16(0.46),
+ F16(0.47),
+ F16(0.46),
+ F16(0.43),
+ F16(0.47),
+ F16(0.37),
+ F16(0.39),
+ F16(0.4),
+ F16(0.35),
+ F16(0.31),
+ F16(0.3),
+ F16(0.37),
+ F16(0.33),
+ F16(0.37),
+ F16(0.37),
+ F16(0.32),
+ F16(0.4),
+ F16(0.41),
+ F16(0.42),
+ F16(0.35),
+ F16(0.39),
+ F16(0.41),
+ F16(0.42),
+ F16(0.4),
+ F16(0.42),
+ F16(0.44),
+ F16(0.5),
+ F16(0.4),
+ F16(0.56),
+ F16(0.6),
+ F16(0.65),
+ F16(0.54),
+ F16(0.63),
+ F16(0.55),
+ F16(0.54),
+ F16(0.68),
+ F16(0.57),
+ F16(0.49),
+ F16(0.46),
+ F16(0.54),
+ F16(0.53),
+ F16(0.5),
+ F16(0.47),
+ F16(0.55),
+ F16(0.4),
+ F16(0.42),
+ F16(0.39),
+ F16(0.51),
+ F16(0.46),
+ F16(0.44),
+ F16(0.56),
+ F16(0.39),
+ F16(0.53),
+ F16(0.72),
+ F16(0.73),
+ F16(0.56),
+ F16(0.6),
+ F16(0.69),
+ F16(0.75),
+ F16(0.62),
+ F16(0.8),
+ F16(0.71),
+ F16(0.7),
+ F16(0.77),
+ F16(0.55),
+ F16(0.55),
+ F16(0.46),
+ F16(0.64),
+ F16(0.34),
+ F16(0.29),
+ F16(0.26),
+ F16(0.42),
+ F16(0.2),
+ F16(0.2),
+ F16(0.2),
+ F16(0.22),
+ F16(0.12),
+ F16(0.11),
+ F16(0.12),
+ F16(0.16),
+ F16(0.13),
+ F16(0.1),
+ F16(0.08),
+ F16(0.1),
+ F16(0.07),
+ F16(0.06),
+ F16(0.06),
+ F16(0.07),
+ F16(0.08),
+ F16(0.08),
+ F16(0.06),
+ F16(0.08),
+ F16(0.06),
+ F16(0.07),
+ F16(0.06),
+ F16(0.08),
+ F16(0.07),
+ F16(0.04),
+ F16(0.04),
+ F16(0.05),
+ F16(0.02),
+ F16(0.02),
+ F16(0.02),
+ F16(0.01),
+ F16(0),
+ F16(-0),
+ F16(0.01),
+ F16(-0.02),
+ F16(0.04),
+ F16(0.02),
+ F16(0.04),
+ F16(0.03),
+ F16(0.05),
+ F16(0.12),
+ F16(0.14),
+ F16(0.08),
+ F16(0.2),
+ F16(0.21),
+ F16(0.24),
+ F16(0.18),
+ F16(0.29),
+ F16(0.3),
+ F16(0.3),
+ F16(0.27),
+ F16(0.34),
+ F16(0.32),
+ F16(0.33),
+ F16(0.33),
+ F16(0.36),
+ F16(0.37),
+ F16(0.41),
+ F16(0.34),
+ F16(0.47),
+ F16(0.6),
+ F16(0.78),
+ F16(0.46),
+ F16(0.72),
+ F16(0.57),
+ F16(0.41),
+ F16(0.74),
+ F16(0.2),
+ F16(0.16),
+ F16(0.12),
+ F16(0.26),
+ F16(0.24),
+ F16(0.34),
+ F16(0.33),
+ F16(0.12),
+ F16(0.39),
+ F16(0.32),
+ F16(0.23),
+ F16(0.42),
+ F16(0.26),
+ F16(0.29),
+ F16(0.28),
+ F16(0.23),
+ F16(0.34),
+ F16(0.51),
+ F16(0.57),
+ F16(0.23),
+ F16(0.82),
+ F16(0.85),
+ F16(0.89),
+ F16(0.67),
+ F16(0.86),
+ F16(0.86),
+ F16(0.88),
+ F16(0.85),
+ F16(0.75),
+ F16(0.74),
+ F16(0.81),
+ F16(0.81),
+ F16(0.75),
+ F16(0.65),
+ F16(0.59),
+ F16(0.81),
+ F16(0.52),
+ F16(0.51),
+ F16(0.53),
+ F16(0.59),
+ F16(0.43),
+ F16(0.31),
+ F16(0.24),
+ F16(0.44),
+ F16(0.24),
+ F16(0.27),
+ F16(0.24),
+ F16(0.21),
+ F16(0.28),
+ F16(0.29),
+ F16(0.3),
+ F16(0.25),
+ F16(0.31),
+ F16(0.47),
+ F16(0.28),
+ F16(0.32),
+ F16(0.31),
+ F16(0.3),
+ F16(0.21),
+ F16(0.24),
+ F16(0.22),
+ F16(0.23),
+ F16(0.24),
+ F16(0.17),
+ F16(0.28),
+ F16(0.28),
+ F16(0.31),
+ F16(0.28),
+ F16(0.35),
+ F16(0.29),
+ F16(0.31),
+ F16(0.32),
+ F16(0.29),
+ F16(0.25),
+ F16(0.26),
+ F16(0.33),
+ F16(0.21),
+ F16(0.2),
+ F16(0.21),
+ F16(0.25),
+ F16(0.16),
+ F16(0.18),
+ F16(0.21),
+ F16(0.18),
+ F16(0.22),
+ F16(0.25),
+ F16(0.29),
+ F16(0.17),
+ F16(0.33),
+ F16(0.34),
+ F16(0.35),
+ F16(0.37),
+ F16(0.39),
+ F16(0.42),
+ F16(0.44),
+ F16(0.39),
+ F16(0.55),
+ F16(0.57),
+ F16(0.64),
+ F16(0.53),
+ F16(0.69),
+ F16(0.62),
+ F16(0.53),
+ F16(0.69),
+ F16(0.44),
+ F16(0.48),
+ F16(0.42),
+ F16(0.46),
+ F16(0.49),
+ F16(0.49),
+ F16(0.47),
+ F16(0.48),
+ F16(0.4),
+ F16(0.37),
+ F16(0.32),
+ F16(0.4),
+ F16(0.32),
+ F16(0.36),
+ F16(0.35),
+ F16(0.34),
+ F16(0.3),
+ F16(0.31),
+ F16(0.28),
+ F16(0.27),
+ F16(0.23),
+ F16(0.23),
+ F16(0.27),
+ F16(0.29),
+ F16(0.31),
+ F16(0.3),
+ F16(0.3),
+ F16(0.3),
+ F16(0.34),
+ F16(0.3),
+ F16(0.3),
+ F16(0.34),
+ F16(0.33),
+ F16(0.33),
+ F16(0.2),
+ F16(0.29),
+ F16(0.23),
+ F16(0.27),
+ F16(0.28),
+ F16(0.23),
+ F16(0.18),
+ F16(0.18),
+ F16(0.2),
+ F16(0.22),
+ F16(0.18),
+ F16(0.17),
+ F16(0.18),
+ F16(0.21),
+ F16(0.24),
+ F16(0.22),
+ F16(0.24),
+ F16(0.23),
+ F16(0.28),
+ F16(0.35),
+ F16(0.35),
+ F16(0.28),
+ F16(0.41),
+ F16(0.4),
+ F16(0.42),
+ F16(0.38),
+ F16(0.34),
+ F16(0.44),
+ F16(0.39),
+ F16(0.47),
+ F16(0.33),
+ F16(0.26),
+ F16(0.39),
+ F16(0.37),
+ F16(0.35),
+ F16(0.23),
+ F16(0.21),
+ F16(0.24),
+ F16(0.19),
+ F16(0.13),
+ F16(0.09),
+ F16(0.23),
+ F16(0.16),
+ F16(0.13),
+ F16(0.16),
+ F16(0.14),
+ F16(0.23),
+ F16(0.31),
+ F16(0.4),
+ F16(0.22),
+ F16(0.33),
+ F16(0.34),
+ F16(0.28),
+ F16(0.22),
+ F16(0.32),
+ F16(0.3),
+ F16(0.31),
+ F16(0.31),
+ F16(0.28),
+ F16(0.31),
+ F16(0.26),
+ F16(0.28),
+ F16(0.27),
+ F16(0.28),
+ F16(0.32),
+ F16(0.32),
+ F16(0.32),
+ F16(0.29),
+ F16(0.37),
+ F16(0.38),
+ F16(0.39),
+ F16(0.37),
+ F16(0.41),
+ F16(0.39),
+ F16(0.44),
+ F16(0.49),
+ F16(0.48),
+ F16(0.46),
+ F16(0.5),
+ F16(0.44),
+ F16(0.44),
+ F16(0.47),
+ F16(0.36),
+ F16(0.27),
+ F16(0.21),
+ F16(0.4),
+ F16(0.13),
+ F16(0.18),
+ F16(0.09),
+ F16(0.19),
+ F16(0.18),
+ F16(0.14),
+ F16(0.13),
+ F16(0.12),
+ F16(0.23),
+ F16(0.18),
+ F16(0.18),
+ F16(0.18),
+ F16(0.21),
+ F16(0.18),
+ F16(0.16),
+ F16(0.19),
+ F16(0.13),
+ F16(0.15),
+ F16(0.15),
+ F16(0.16),
+ F16(0.04),
+ F16(0.06),
+ F16(0.13),
+ F16(0.15),
+ F16(0.03),
+ F16(0.11),
+ F16(0.16),
+ F16(0.08),
+ F16(0.2),
+ F16(0.28),
+ F16(0.31),
+ F16(0.18),
+ F16(0.38),
+ F16(0.36),
+ F16(0.38),
+ F16(0.38),
+ F16(0.43),
+ F16(0.38),
+ F16(0.33),
+ F16(0.43),
+ F16(0.28),
+ F16(0.27),
+ F16(0.23),
+ F16(0.3),
+ F16(0.21),
+ F16(0.19),
+ F16(0.17),
+ F16(0.18),
+ F16(0.14),
+ F16(0.24),
+ F16(0.22),
+ F16(0.09),
+ F16(0.22),
+ F16(0.16),
+ F16(0.22),
+ F16(0.17),
+ F16(0.17),
+ F16(0.21),
+ F16(0.2),
+ F16(0.17),
+ F16(0.17),
+ F16(0.17),
+ F16(0.17),
+ F16(0.18),
+ F16(0.18),
+ F16(0.17),
+ F16(0.12),
+ F16(0.19),
+ F16(0.23),
+ F16(0.11),
+ F16(0.15),
+ F16(0.18),
+ F16(0.1),
+ F16(0.06),
+ F16(0.08),
+ F16(0.13),
+ F16(0.12),
+ F16(0.11),
+ F16(0.07),
+ F16(0.08),
+ F16(0.14),
+ F16(0.1),
+ F16(0.25),
+ F16(0.11),
+ F16(0.35),
+ F16(0.26),
+ F16(0.3),
+ F16(0.21),
+ F16(0.34),
+ F16(0.27),
+ F16(0.32),
+ F16(0.33),
+ F16(0.21),
+ F16(0.13),
+ F16(0.08),
+ F16(0.21),
+ F16(-0.02),
+ F16(-0.08),
+ F16(-0.08),
+ F16(0.03),
+ F16(-0.03),
+ F16(-0.01),
+ F16(0.09),
+ F16(-0.07),
+ F16(0.18),
+ F16(0.21),
+ F16(0.25),
+ F16(0.16),
+ F16(0.2),
+ F16(0.18),
+ F16(0.19),
+ F16(0.23),
+ F16(0.15),
+ F16(0.11),
+ F16(0.16),
+ F16(0.15),
+ F16(0.1),
+ F16(0.11),
+ F16(0.14),
+ F16(0.08),
+ F16(0.24),
+ F16(0.26),
+ F16(0.28),
+ F16(0.18),
+ F16(0.43),
+ F16(0.38),
+ F16(0.33),
+ F16(0.35),
+ F16(0.35),
+ F16(0.36),
+ F16(0.39),
+ F16(0.3),
+ F16(0.26),
+ F16(0.3),
+ F16(0.3),
+ F16(0.29),
+ F16(0.33),
+ F16(0.38),
+ F16(0.4),
+ F16(0.3),
+ F16(0.39),
+ F16(0.41),
+ F16(0.34),
+ F16(0.41),
+ F16(0.19),
+ F16(0.14),
+ F16(0.11),
+ F16(0.31),
+ F16(-0.04),
+ F16(-0.01),
+ F16(0.07),
+ F16(0.05),
+ F16(-0.01),
+ F16(-0),
+ F16(0.07),
+ F16(-0.05),
+ F16(0.17),
+ F16(0.18),
+ F16(0.17),
+ F16(0.08),
+ F16(0.27),
+ F16(0.25),
+ F16(0.18),
+ F16(0.21),
+ F16(0.12),
+ F16(0.07),
+ F16(0.05),
+ F16(0.13),
+ F16(0),
+ F16(0.04),
+ F16(0.09),
+ F16(-0),
+ F16(0.14),
+ F16(0.21),
+ F16(0.23),
+ F16(0.05),
+ F16(0.39),
+ F16(0.42),
+ F16(0.39),
+ F16(0.31),
+ F16(0.46),
+ F16(0.38),
+ F16(0.46),
+ F16(0.44),
+ F16(0.5),
+ F16(0.45),
+ F16(0.4),
+ F16(0.41),
+ F16(0.39),
+ F16(0.39),
+ F16(0.39),
+ F16(0.41),
+ F16(0.28),
+ F16(0.2),
+ F16(0.16),
+ F16(0.37),
+ F16(0.06),
+ F16(0.06),
+ F16(0.07),
+ F16(0.18),
+ F16(-0.05),
+ F16(-0.02),
+ F16(0.06),
+ F16(0.07),
+ F16(0.01),
+ F16(0.1),
+ F16(0.12),
+ F16(0.02),
+ F16(0.15),
+ F16(0.19),
+ F16(0.18),
+ F16(0.13),
+ F16(0.15),
+ F16(0.16),
+ F16(0.14),
+ F16(0.15),
+ F16(0.19),
+ F16(0.24),
+ F16(0.21),
+ F16(0.14),
+ F16(0.35),
+ F16(0.36),
+ F16(0.41),
+ F16(0.33),
+ F16(0.39),
+ F16(0.35),
+ F16(0.29),
+ F16(0.38),
+ F16(0.24),
+ F16(0.28),
+ F16(0.31),
+ F16(0.26),
+ F16(0.32),
+ F16(0.33),
+ F16(0.36),
+ F16(0.32),
+ F16(0.31),
+ F16(0.26),
+ F16(0.21),
+ F16(0.34),
+ F16(0.07),
+ F16(0.06),
+ F16(0.09),
+ F16(0.17),
+ F16(0.06),
+ F16(0.09),
+ F16(0.21),
+ F16(0.07),
+ F16(0.35),
+ F16(0.39),
+ F16(0.36),
+ F16(0.26),
+ F16(0.37),
+ F16(0.36),
+ F16(0.32),
+ F16(0.33),
+ F16(0.34),
+ F16(0.42),
+ F16(0.4),
+ F16(0.35),
+ F16(0.46),
+ F16(0.33),
+ F16(0.35),
+ F16(0.39),
+ F16(0.24),
+ F16(0.16),
+ F16(0.12),
+ F16(0.31),
+ F16(0.22),
+ F16(0.22),
+ F16(0.24),
+ F16(0.08),
+ F16(0.38),
+ F16(0.34),
+ F16(0.38),
+ F16(0.26),
+ F16(0.43),
+ F16(0.45),
+ F16(0.42),
+ F16(0.41),
+ F16(0.41),
+ F16(0.45),
+ F16(0.45),
+ F16(0.4),
+ F16(0.47),
+ F16(0.48),
+ F16(0.46),
+ F16(0.48),
+ F16(0.41),
+ F16(0.3),
+ F16(0.27),
+ F16(0.41),
+ F16(0.19),
+ F16(0.2),
+ F16(0.17),
+ F16(0.23),
+ F16(0.23),
+ F16(0.28),
+ F16(0.32),
+ F16(0.19),
+ F16(0.27),
+ F16(0.21),
+ F16(0.19),
+ F16(0.3),
+ F16(0.22),
+ F16(0.24),
+ F16(0.25),
+ F16(0.2),
+ F16(0.3),
+ F16(0.26),
+ F16(0.27),
+ F16(0.32),
+ F16(0.2),
+ F16(0.14),
+ F16(0.15),
+ F16(0.24),
+ F16(0.09),
+ F16(0.18),
+ F16(0.21),
+ F16(0.07),
+ F16(0.31),
+ F16(0.37),
+ F16(0.42),
+ F16(0.29),
+ F16(0.33),
+ F16(0.38),
+ F16(0.4),
+ F16(0.41),
+ F16(0.45),
+ F16(0.45),
+ F16(0.47),
+ F16(0.44),
+ F16(0.29),
+ F16(0.34),
+ F16(0.27),
+ F16(0.43),
+ F16(0.16),
+ F16(0.23),
+ F16(0.26),
+ F16(0.28),
+ F16(0.38),
+ F16(0.44),
+ F16(0.42),
+ F16(0.33),
+ F16(0.32),
+ F16(0.36),
+ F16(0.32),
+ F16(0.34),
+ F16(0.25),
+ F16(0.23),
+ F16(0.2),
+ F16(0.29),
+ F16(0.18),
+ F16(0.14),
+ F16(0.14),
+ F16(0.21),
+ F16(0.18),
+ F16(0.23),
+ F16(0.27),
+ F16(0.15),
+ F16(0.39),
+ F16(0.36),
+ F16(0.36),
+ F16(0.37),
+ F16(0.27),
+ F16(0.24),
+ F16(0.21),
+ F16(0.36),
+ F16(0.25),
+ F16(0.3),
+ F16(0.3),
+ F16(0.3),
+ F16(0.32),
+ F16(0.38),
+ F16(0.4),
+ F16(0.35),
+ F16(0.43),
+ F16(0.51),
+ F16(0.51),
+ F16(0.42),
+ F16(0.36),
+ F16(0.28),
+ F16(0.18),
+ F16(0.43),
+ F16(0.17),
+ F16(0.13),
+ F16(0.23),
+ F16(0.22),
+ F16(0.37),
+ F16(0.4),
+ F16(0.33),
+ F16(0.29),
+ F16(0.36),
+ F16(0.39),
+ F16(0.37),
+ F16(0.36),
+ F16(0.33),
+ F16(0.28),
+ F16(0.25),
+ F16(0.33),
+ F16(0.14),
+ F16(0.17),
+ F16(0.24),
+ F16(0.19),
+ F16(0.36),
+ F16(0.4),
+ F16(0.4),
+ F16(0.28),
+ F16(0.47),
+ F16(0.4),
+ F16(0.42),
+ F16(0.45),
+ F16(0.37),
+ F16(0.38),
+ F16(0.35),
+ F16(0.4),
+ F16(0.37),
+ F16(0.43),
+ F16(0.46),
+ F16(0.38),
+ F16(0.56),
+ F16(0.57),
+ F16(0.57),
+ F16(0.5),
+ F16(0.32),
+ F16(0.26),
+ F16(0.31),
+ F16(0.43),
+ F16(0.26),
+ F16(0.37),
+ F16(0.37),
+ F16(0.24),
+ F16(0.32),
+ F16(0.33),
+ F16(0.3),
+ F16(0.37),
+ F16(0.33),
+ F16(0.35),
+ F16(0.32),
+ F16(0.32),
+ F16(0.23),
+ F16(0.16),
+ F16(0.1),
+ F16(0.28),
+ F16(0.17),
+ F16(0.26),
+ F16(0.3),
+ F16(0.1),
+ F16(0.31),
+ F16(0.24),
+ F16(0.17),
+ F16(0.33),
+ F16(0.04),
+ F16(0.09),
+ F16(0.21),
+ F16(0.12),
+ F16(0.34),
+ F16(0.34),
+ F16(0.37),
+ F16(0.26),
+ F16(0.29),
+ F16(0.23),
+ F16(0.22),
+ F16(0.32),
+ F16(0.23),
+ F16(0.3),
+ F16(0.38),
+ F16(0.23),
+ F16(0.39),
+ F16(0.42),
+ F16(0.41),
+ F16(0.33),
+ F16(0.39),
+ F16(0.31),
+ F16(0.29),
+ F16(0.41),
+ F16(0.24),
+ F16(0.26),
+ F16(0.29),
+ F16(0.25),
+ F16(0.36),
+ F16(0.34),
+ F16(0.31),
+ F16(0.36),
+ F16(0.25),
+ F16(0.21),
+ F16(0.2),
+ F16(0.27),
+ F16(0.24),
+ F16(0.23),
+ F16(0.21),
+ F16(0.2),
+ F16(0.22),
+ F16(0.29),
+ F16(0.28),
+ F16(0.21),
+ F16(0.22),
+ F16(0.23),
+ F16(0.21),
+ F16(0.21),
+ F16(0.18),
+ F16(0.18),
+ F16(0.28),
+ F16(0.16),
+ F16(0.35),
+ F16(0.34),
+ F16(0.28),
+ F16(0.35),
+ F16(0.16),
+ F16(0.15),
+ F16(0.24),
+ F16(0.22),
+ F16(0.36),
+ F16(0.42),
+ F16(0.42),
+ F16(0.25),
+ F16(0.39),
+ F16(0.33),
+ F16(0.26),
+ F16(0.46),
+ F16(0.27),
+ F16(0.34),
+ F16(0.41),
+ F16(0.23),
+ F16(0.45),
+ F16(0.47),
+ F16(0.39),
+ F16(0.45),
+ F16(0.37),
+ F16(0.35),
+ F16(0.27),
+ F16(0.35),
+ F16(0.3),
+ F16(0.33),
+ F16(0.27),
+ F16(0.26),
+ F16(0.31),
+ F16(0.3),
+ F16(0.3),
+ F16(0.31),
+ F16(0.17),
+ F16(0.17),
+ F16(0.19),
+ F16(0.23),
+ F16(0.19),
+ F16(0.21),
+ F16(0.23),
+ F16(0.19),
+ F16(0.27),
+ F16(0.24),
+ F16(0.22),
+ F16(0.29),
+ F16(0.12),
+ F16(0.17),
+ F16(0.16),
+ F16(0.2),
+ F16(0.3),
+ F16(0.29),
+ F16(0.26),
+ F16(0.24),
+ F16(0.22),
+ F16(0.17),
+ F16(0.17),
+ F16(0.27),
+ F16(0.28),
+ F16(0.28),
+ F16(0.31),
+ F16(0.22),
+ F16(0.33),
+ F16(0.29),
+ F16(0.25),
+ F16(0.32),
+ F16(0.23),
+ F16(0.26),
+ F16(0.28),
+ F16(0.23),
+ F16(0.37),
+ F16(0.35),
+ F16(0.31),
+ F16(0.32),
+ F16(0.24),
+ F16(0.24),
+ F16(0.21),
+ F16(0.22),
+ F16(0.32),
+ F16(0.28),
+ F16(0.26),
+ F16(0.28),
+ F16(0.19),
+ F16(0.2),
+ F16(0.26),
+ F16(0.22),
+ F16(0.24),
+ F16(0.19),
+ F16(0.15),
+ F16(0.28),
+ F16(0.16),
+ F16(0.26),
+ F16(0.27),
+ F16(0.15),
+ F16(0.26),
+ F16(0.15),
+ F16(0.07),
+ F16(0.3),
+ F16(0.08),
+ F16(0.2),
+ F16(0.3),
+ F16(0.02),
+ F16(0.26),
+ F16(0.16),
+ F16(0.11),
+ F16(0.33),
+ F16(0.13),
+ F16(0.28),
+ F16(0.27),
+ F16(0.09),
+ F16(0.3),
+ F16(0.21),
+ F16(0.19),
+ F16(0.32),
+ F16(0.26),
+ F16(0.28),
+ F16(0.3),
+ F16(0.27),
+ F16(0.22),
+ F16(0.31),
+ F16(0.31),
+ F16(0.27),
+ F16(0.24),
+ F16(0.24),
+ F16(0.19),
+ F16(0.33),
+ F16(0.25),
+ F16(0.32),
+ F16(0.31),
+ F16(0.24),
+ F16(0.19),
+ F16(0.22),
+ F16(0.15),
+ F16(0.25),
+ F16(0.21),
+ F16(0.22),
+ F16(0.26),
+ F16(0.13),
+ F16(0.17),
+ F16(0.17),
+ F16(0.18),
+ F16(0.21),
+ F16(0.19),
+ F16(0.12),
+ F16(0.11),
+ F16(0.18),
+ F16(0.16),
+ F16(0.25),
+ F16(0.27),
+ F16(0.13),
+ F16(0.23),
+ F16(0.13),
+ F16(0.12),
+ F16(0.3),
+ F16(0.26),
+ F16(0.34),
+ F16(0.42),
+ F16(0.14),
+ F16(0.34),
+ F16(0.31),
+ F16(0.34),
+ F16(0.39),
+ F16(0.35),
+ F16(0.38),
+ F16(0.42),
+ F16(0.38),
+ F16(0.46),
+ F16(0.37),
+ F16(0.29),
+ F16(0.45),
+ F16(0.16),
+ F16(0.14),
+ F16(0.25),
+ F16(0.17),
+ F16(0.41),
+ F16(0.34),
+ F16(0.22),
+ F16(0.36),
+ F16(0.14),
+ F16(0.16),
+ F16(0.26),
+ F16(0.17),
+ F16(0.24),
+ F16(0.12),
+ F16(0.12),
+ F16(0.27),
+ F16(0.2),
+ F16(0.26),
+ F16(0.32),
+ F16(0.19),
+ F16(0.12),
+ F16(0.01),
+ F16(0.06),
+ F16(0.29),
+ F16(0.32),
+ F16(0.4),
+ F16(0.37),
+ F16(0.21),
+ F16(0.13),
+ F16(0.1),
+ F16(0.18),
+ F16(0.2),
+ F16(0.45),
+ F16(0.42),
+ F16(0.38),
+ F16(0.35),
+ F16(0.3),
+ F16(0.33),
+ F16(0.35),
+ F16(0.31),
+ F16(0.28),
+ F16(0.29),
+ F16(0.34),
+ F16(0.33),
+ F16(0.33),
+ F16(0.29),
+ F16(0.2),
+ F16(0.37),
+ F16(0.15),
+ F16(0.14),
+ F16(0.23),
+ F16(0.17),
+ F16(0.3),
+ F16(0.21),
+ F16(0.12),
+ F16(0.29),
+ F16(0.11),
+ F16(0.17),
+ F16(0.24),
+ F16(0.11),
+ F16(0.16),
+ F16(0.15),
+ F16(0.2),
+ F16(0.22),
+ F16(0.23),
+ F16(0.28),
+ F16(0.2),
+ F16(0.24),
+ F16(0.17),
+ F16(0.21),
+ F16(0.31),
+ F16(0.14),
+ F16(0.49),
+ F16(0.46),
+ F16(0.31),
+ F16(0.42),
+ F16(0.32),
+ F16(0.37),
+ F16(0.47),
+ F16(0.27),
+ F16(0.59),
+ F16(0.52),
+ F16(0.4),
+ F16(0.55),
+ F16(0.11),
+ F16(0.15),
+ F16(0.31),
+ F16(0.22),
+ F16(0.46),
+ F16(0.39),
+ F16(0.3),
+ F16(0.4),
+ F16(0.12),
+ F16(0.16),
+ F16(0.28),
+ F16(0.16),
+ F16(0.28),
+ F16(0.14),
+ F16(0.1),
+ F16(0.34),
+ F16(0.28),
+ F16(0.3),
+ F16(0.26),
+ F16(0.13),
+ F16(0.11),
+ F16(0.07),
+ F16(0.15),
+ F16(0.14),
+ F16(0.36),
+ F16(0.24),
+ F16(0.14),
+ F16(0.28),
+ F16(0.09),
+ F16(0.21),
+ F16(0.28),
+ F16(0.07),
+ F16(0.23),
+ F16(0.15),
+ F16(0.15),
+ F16(0.28),
+ F16(0.19),
+ F16(0.22),
+ F16(0.21),
+ F16(0.16),
+ F16(0.15),
+ F16(0.19),
+ F16(0.19),
+ F16(0.16),
+ F16(0.2),
+ F16(0.12),
+ F16(0.1),
+ F16(0.26),
+ F16(0.17),
+ F16(0.23),
+ F16(0.22),
+ F16(0.11),
+ F16(0.12),
+ F16(0.04),
+ F16(0.12),
+ F16(0.17),
+ F16(0.24),
+ F16(0.2),
+ F16(0.08),
+ F16(0.2),
+ F16(0.16),
+ F16(0.23),
+ F16(0.28),
+ F16(0.09),
+ F16(0.23),
+ F16(0.1),
+ F16(0.12),
+ F16(0.27),
+ F16(0.38),
+ F16(0.4),
+ F16(0.4),
+ F16(0.23),
+ F16(0.14),
+ F16(0.07),
+ F16(0.13),
+ F16(0.26),
+ F16(0.3),
+ F16(0.39),
+ F16(0.28),
+ F16(0.22),
+ F16(-0.02),
+ F16(-0.04),
+ F16(0.09),
+ F16(0.1),
+ F16(0.32),
+ F16(0.26),
+ F16(0.13),
+ F16(0.3),
+ F16(-0.01),
+ F16(0.08),
+ F16(0.21),
+ F16(0.03),
+ F16(0.23),
+ F16(0.12),
+ F16(0.05),
+ F16(0.26),
+ F16(0.16),
+ F16(0.25),
+ F16(0.27),
+ F16(0.1),
+ F16(0.1),
+ F16(0.09),
+ F16(0.14),
+ F16(0.19),
+ F16(0.28),
+ F16(0.26),
+ F16(0.18),
+ F16(0.24),
+ F16(0.14),
+ F16(0.23),
+ F16(0.27),
+ F16(0.11),
+ F16(0.23),
+ F16(0.16),
+ F16(0.14),
+ F16(0.29),
+ F16(0.28),
+ F16(0.3),
+ F16(0.23),
+ F16(0.21),
+ F16(0.1),
+ F16(0.1),
+ F16(0.25),
+ F16(0.14),
+ F16(0.25),
+ F16(0.19),
+ F16(0.07),
+ F16(0.33),
+ F16(0.14),
+ F16(0.19),
+ F16(0.28),
+ F16(0.09),
+ F16(0.2),
+ F16(0.12),
+ F16(0.05),
+ F16(0.27),
+ F16(0.16),
+ F16(0.2),
+ F16(0.24),
+ F16(0.03),
+ F16(0.13),
+ F16(0.13),
+ F16(0.12),
+ F16(0.17),
+ F16(0.14),
+ F16(0.05),
+ F16(0.02),
+ F16(0.17),
+ F16(0.15),
+ F16(0.29),
+ F16(0.25),
+ F16(0.04),
+ F16(-0.04),
+ F16(-0.17),
+ F16(-0.05),
+ F16(0.14),
+ F16(0.31),
+ F16(0.35),
+ F16(0.18),
+ F16(0.14),
+ F16(-0.2),
+ F16(-0.15),
+ F16(0.08),
+ F16(-0.04),
+ F16(0.38),
+ F16(0.23),
+ F16(0.04),
+ F16(0.29),
+ F16(-0.12),
+ F16(0.04),
+ F16(0.24),
+ F16(-0.12),
+ F16(0.26),
+ F16(0.1),
+ F16(0.04),
+ F16(0.27),
+ F16(0.14),
+ F16(0.19),
+ F16(0.23),
+ F16(0.05),
+ F16(0.08),
+ F16(0.13),
+ F16(0.15),
+ F16(0.16),
+ F16(0.21),
+ F16(0.15),
+ F16(0.08),
+ F16(0.23),
+ F16(0.12),
+ F16(0.19),
+ F16(0.2),
+ F16(0.12),
+ F16(0.13),
+ F16(0.09),
+ F16(0.09),
+ F16(0.21),
+ F16(0.17),
+ F16(0.24),
+ F16(0.21),
+ F16(0.1),
+ F16(0.06),
+ F16(0.07),
+ F16(0.16),
+ F16(0.13),
+ F16(0.27),
+ F16(0.23),
+ F16(0.19),
+ F16(0.2),
+ F16(0.09),
+ F16(0.17),
+ F16(0.22),
+ F16(0.08),
+ F16(0.3),
+ F16(0.21),
+ F16(0.11),
+ F16(0.27),
+ F16(0.16),
+ F16(0.29),
+ F16(0.29),
+ F16(0.12),
+ F16(0.23),
+ F16(0.17),
+ F16(0.21),
+ F16(0.29),
+ F16(0.33),
+ F16(0.35),
+ F16(0.28),
+ F16(0.24),
+ F16(0.12),
+ F16(0.19),
+ F16(0.28),
+ F16(0.23),
+ F16(0.4),
+ F16(0.33),
+ F16(0.22),
+ F16(0.37),
+ F16(0.09),
+ F16(0.23),
+ F16(0.38),
+ F16(0.08),
+ F16(0.31),
+ F16(0.15),
+ F16(0.05),
+ F16(0.43),
+ F16(0.23),
+ F16(0.38),
+ F16(0.45),
+ F16(0.03),
+ F16(0.12),
+ F16(-0.02),
+ F16(0.09),
+ F16(0.3),
+ F16(0.38),
+ F16(0.51),
+ F16(0.4),
+ F16(0.19),
+ F16(0.1),
+ F16(0.14),
+ F16(0.29),
+ F16(0.17),
+ F16(0.46),
+ F16(0.38),
+ F16(0.25),
+ F16(0.46),
+ F16(0.22),
+ F16(0.31),
+ F16(0.33),
+ F16(0.19),
+ F16(0.29),
+ F16(0.26),
+ F16(0.25),
+ F16(0.3),
+ F16(0.39),
+ F16(0.4),
+ F16(0.26),
+ F16(0.33),
+ F16(0.18),
+ F16(0.31),
+ F16(0.41),
+ F16(0.25),
+ F16(0.5),
+ F16(0.33),
+ F16(0.25),
+ F16(0.47),
+ F16(0.21),
+ F16(0.31),
+ F16(0.41),
+ F16(0.16),
+ F16(0.32),
+ F16(0.2),
+ F16(0.06),
+ F16(0.46),
+ F16(0.22),
+ F16(0.34),
+ F16(0.32),
+ F16(0.09),
+ F16(0.18),
+ F16(0.16),
+ F16(0.22),
+ F16(0.24),
+ F16(0.21),
+ F16(0.12),
+ F16(0.03),
+ F16(0.27),
+ F16(0.08),
+ F16(0.24),
+ F16(0.34),
+ F16(0),
+ F16(0.08),
+ F16(-0.12),
+ F16(-0.22),
+ F16(0.27),
+ F16(0.17),
+ F16(0.38),
+ F16(0.36),
+ F16(-0.05),
+ F16(-0.17),
+ F16(-0.29),
+ F16(-0.16),
+ F16(0.13),
+ F16(0.4),
+ F16(0.45),
+ F16(0.24),
+ F16(0.14),
+ F16(-0.19),
+ F16(-0.15),
+ F16(0.12),
+ F16(-0.03),
+ F16(0.39),
+ F16(0.29),
+ F16(0.11),
+ F16(0.34),
+ F16(0.05),
+ F16(0.08),
+ F16(0.2),
+ F16(0.03),
+ F16(0.22),
+ F16(0.15),
+ F16(0.08),
+ F16(0.23),
+ F16(0.14),
+ F16(0.19),
+ F16(0.16),
+ F16(0.1),
+ F16(0.07),
+ F16(0.12),
+ F16(0.15),
+ F16(0.1),
+ F16(0.17),
+ F16(0.08),
+ F16(0.03),
+ F16(0.17),
+ F16(0.03),
+ F16(0.16),
+ F16(0.25),
+ F16(-0.01),
+ F16(0.11),
+ F16(-0.01),
+ F16(-0.04),
+ F16(0.26),
+ F16(0.14),
+ F16(0.25),
+ F16(0.25),
+ F16(0.04),
+ F16(0.05),
+ F16(-0),
+ F16(0.07),
+ F16(0.19),
+ F16(0.32),
+ F16(0.29),
+ F16(0.21),
+ F16(0.2),
+ F16(0.04),
+ F16(0.14),
+ F16(0.26),
+ F16(0.13),
+ F16(0.29),
+ F16(0.19),
+ F16(0.16),
+ F16(0.31),
+ F16(0.19),
+ F16(0.3),
+ F16(0.32),
+ F16(0.13),
+ F16(0.1),
+ F16(0.07),
+ F16(0.18),
+ F16(0.24),
+ F16(0.4),
+ F16(0.27),
+ F16(0.07),
+ F16(0.33),
+ F16(-0),
+ F16(0.22),
+ F16(0.42),
+ F16(-0.08),
+ F16(0.26),
+ F16(-0.03),
+ F16(-0.19),
+ F16(0.48),
+ F16(0.25),
+ F16(0.52),
+ F16(0.51),
+ F16(-0.06),
+ F16(-0.01),
+ F16(-0.11),
+ F16(0.04),
+ F16(0.25),
+ F16(0.45),
+ F16(0.5),
+ F16(0.27),
+ F16(0.31),
+ F16(0.11),
+ F16(0.21),
+ F16(0.34),
+ F16(0.17),
+ F16(0.38),
+ F16(0.18),
+ F16(0.16),
+ F16(0.45),
+ F16(0.36),
+ F16(0.35),
+ F16(0.29),
+ F16(0.28),
+ F16(0.2),
+ F16(0.28),
+ F16(0.33),
+ F16(0.18),
+ F16(0.22),
+ F16(0.11),
+ F16(0.12),
+ F16(0.36),
+ F16(0.35),
+ F16(0.34),
+ F16(0.25),
+ F16(0.21),
+ F16(0.11),
+ F16(0.15),
+ F16(0.25),
+ F16(0.16),
+ F16(0.28),
+ F16(0.22),
+ F16(0.14),
+ F16(0.31),
+ F16(0.21),
+ F16(0.28),
+ F16(0.33),
+ F16(0.15),
+ F16(0.13),
+ F16(0.13),
+ F16(0.21),
+ F16(0.24),
+ F16(0.25),
+ F16(0.13),
+ F16(0.03),
+ F16(0.26),
+ F16(0.09),
+ F16(0.2),
+ F16(0.23),
+ F16(0.01),
+ F16(-0.01),
+ F16(-0.11),
+ F16(-0.04),
+ F16(0.16),
+ F16(0.25),
+ F16(0.23),
+ F16(0),
+ F16(0.15),
+ F16(-0.17),
+ F16(0.06),
+ F16(0.28),
+ F16(-0.17),
+ F16(0.09),
+ F16(-0.17),
+ F16(-0.28),
+ F16(0.3),
+ F16(0.13),
+ F16(0.32),
+ F16(0.21),
+ F16(-0.15),
+ F16(-0.23),
+ F16(-0.2),
+ F16(0.02),
+ F16(-0.02),
+ F16(0.35),
+ F16(0.18),
+ F16(-0.05),
+ F16(0.27),
+ F16(-0.08),
+ F16(0.12),
+ F16(0.25),
+ F16(-0.16),
+ F16(0.17),
+ F16(0.06),
+ F16(0.02),
+ F16(0.3),
+ F16(0.16),
+ F16(0.19),
+ F16(0.16),
+ F16(0.07),
+ F16(0.19),
+ F16(0.23),
+ F16(0.19),
+ F16(0.17),
+ F16(-0.03),
+ F16(0),
+ F16(0.14),
+ F16(0.09),
+ F16(0.3),
+ F16(0.2),
+ F16(0.05),
+ F16(0.25),
+ F16(-0.04),
+ F16(0.09),
+ F16(0.26),
+ F16(-0.04),
+ F16(0.25),
+ F16(0.1),
+ F16(-0.02),
+ F16(0.33),
+ F16(0.09),
+ F16(0.21),
+ F16(0.3),
+ F16(-0.01),
+ F16(0.21),
+ F16(0.2),
+ F16(0.17),
+ F16(0.29),
+ F16(0.18),
+ F16(0.27),
+ F16(0.35),
+ F16(0.17),
+ F16(0.41),
+ F16(0.38),
+ F16(0.37),
+ F16(0.41),
+ F16(0.38),
+ F16(0.38),
+ F16(0.5),
+ F16(0.36),
+ F16(0.66),
+ F16(0.63),
+ F16(0.5),
+ F16(0.6),
+ F16(0.31),
+ F16(0.36),
+ F16(0.44),
+ F16(0.34),
+ F16(0.58),
+ F16(0.47),
+ F16(0.29),
+ F16(0.54),
+ F16(0.25),
+ F16(0.42),
+ F16(0.49),
+ F16(0.21),
+ F16(0.26),
+ F16(0.27),
+ F16(0.42),
+ F16(0.42),
+ F16(0.41),
+ F16(0.26),
+ F16(0.16),
+ F16(0.48),
+ F16(0.19),
+ F16(0.36),
+ F16(0.41),
+ F16(0.17),
+ F16(0.21),
+ F16(0.08),
+ F16(0.11),
+ F16(0.35),
+ F16(0.39),
+ F16(0.4),
+ F16(0.34),
+ F16(0.15),
+ F16(0.11),
+ F16(0.13),
+ F16(0.21),
+ F16(0.2),
+ F16(0.36),
+ F16(0.33),
+ F16(0.28),
+ F16(0.28),
+ F16(0.15),
+ F16(0.16),
+ F16(0.2),
+ F16(0.2),
+ F16(0.24),
+ F16(0.25),
+ F16(0.28),
+ F16(0.28),
+ F16(0.14),
+ F16(0.13),
+ F16(0.15),
+ F16(0.23),
+ F16(0.23),
+ F16(0.25),
+ F16(0.27),
+ F16(0.18),
+ F16(0.1),
+ F16(0.07),
+ F16(0.14),
+ F16(0.15),
+ F16(0.2),
+ F16(0.17),
+ F16(0.07),
+ F16(0.21),
+ F16(0.09),
+ F16(0.17),
+ F16(0.18),
+ F16(0.04),
+ F16(0.05),
+ F16(0),
+ F16(0.06),
+ F16(0.12),
+ F16(0.22),
+ F16(0.19),
+ F16(0.05),
+ F16(0.16),
+ F16(-0.09),
+ F16(0.05),
+ F16(0.24),
+ F16(-0.11),
+ F16(0.19),
+ F16(-0.05),
+ F16(-0.24),
+ F16(0.35),
+ F16(0.1),
+ F16(0.3),
+ F16(0.36),
+ F16(-0.12),
+ F16(-0.06),
+ F16(-0.12),
+ F16(-0.12),
+ F16(0.2),
+ F16(0.29),
+ F16(0.33),
+ F16(0.22),
+ F16(0.13),
+ F16(-0),
+ F16(0.01),
+ F16(0.16),
+ F16(0.03),
+ F16(0.2),
+ F16(0.18),
+ F16(0.11),
+ F16(0.25),
+ F16(0.14),
+ F16(0.12),
+ F16(0.09),
+ F16(0.1),
+ F16(0.13),
+ F16(0.13),
+ F16(0.19),
+ F16(0.12),
+ F16(0.18),
+ F16(0.1),
+ F16(0.06),
+ F16(0.18),
+ F16(0.13),
+ F16(0.25),
+ F16(0.3),
+ F16(0.02),
+ F16(0.18),
+ F16(0.1),
+ F16(0.14),
+ F16(0.26),
+ F16(0.29),
+ F16(0.34),
+ F16(0.35),
+ F16(0.2),
+ F16(0.17),
+ F16(0.17),
+ F16(0.21),
+ F16(0.24),
+ F16(0.34),
+ F16(0.3),
+ F16(0.2),
+ F16(0.33),
+ F16(0.13),
+ F16(0.24),
+ F16(0.33),
+ F16(0.1),
+ F16(0.26),
+ F16(0.2),
+ F16(0.16),
+ F16(0.35),
+ F16(0.28),
+ F16(0.35),
+ F16(0.28),
+ F16(0.2),
+ F16(0.17),
+ F16(0.22),
+ F16(0.39),
+ F16(0.19),
+ F16(0.36),
+ F16(0.22),
+ F16(0.15),
+ F16(0.41),
+ F16(0.28),
+ F16(0.41),
+ F16(0.51),
+ F16(0.12),
+ F16(0.26),
+ F16(0.16),
+ F16(0.12),
+ F16(0.46),
+ F16(0.43),
+ F16(0.53),
+ F16(0.46),
+ F16(0.25),
+ F16(0.19),
+ F16(0.23),
+ F16(0.31),
+ F16(0.35),
+ F16(0.49),
+ F16(0.41),
+ F16(0.35),
+ F16(0.47),
+ F16(0.3),
+ F16(0.45),
+ F16(0.46),
+ F16(0.33),
+ F16(0.41),
+ F16(0.39),
+ F16(0.36),
+ F16(0.45),
+ F16(0.42),
+ F16(0.37),
+ F16(0.33),
+ F16(0.38),
+ F16(0.29),
+ F16(0.26),
+ F16(0.31),
+ F16(0.27),
+ F16(0.22),
+ F16(0.19),
+ F16(0.21),
+ F16(0.28),
+ F16(0.27),
+ F16(0.26),
+ F16(0.21),
+ F16(0.25),
+ F16(0.16),
+ F16(0.21),
+ F16(0.23),
+ F16(0.15),
+ F16(0.15),
+ F16(0.06),
+ F16(0.06),
+ F16(0.22),
+ F16(0.25),
+ F16(0.36),
+ F16(0.25),
+ F16(0.12),
+ F16(-0.01),
+ F16(0.01),
+ F16(0.12),
+ F16(0.14),
+ F16(0.38),
+ F16(0.32),
+ F16(0.13),
+ F16(0.28),
+ F16(0.03),
+ F16(0.11),
+ F16(0.23),
+ F16(0.03),
+ F16(0.36),
+ F16(0.25),
+ F16(0.1),
+ F16(0.34),
+ F16(0.17),
+ F16(0.28),
+ F16(0.34),
+ F16(0.06),
+ F16(0.27),
+ F16(0.19),
+ F16(0.13),
+ F16(0.35),
+ F16(0.25),
+ F16(0.23),
+ F16(0.26),
+ F16(0.17),
+ F16(0.24),
+ F16(0.23),
+ F16(0.24),
+ F16(0.24),
+ F16(0.21),
+ F16(0.14),
+ F16(0.16),
+ F16(0.29),
+ F16(0.27),
+ F16(0.28),
+ F16(0.29),
+ F16(0.26),
+ F16(0.19),
+ F16(0.16),
+ F16(0.18),
+ F16(0.24),
+ F16(0.25),
+ F16(0.26),
+ F16(0.21),
+ F16(0.19),
+ F16(0.1),
+ F16(0.16),
+ F16(0.21),
+ F16(0.16),
+ F16(0.16),
+ F16(0.11),
+ F16(0.1),
+ F16(0.19),
+ F16(0.19),
+ F16(0.22),
+ F16(0.17),
+ F16(0.16),
+ F16(0.03),
+ F16(0.06),
+ F16(0.18),
+ F16(0.1),
+ F16(0.27),
+ F16(0.24),
+ F16(0.15),
+ F16(0.26),
+ F16(0.09),
+ F16(0.22),
+ F16(0.34),
+ F16(0.08),
+ F16(0.34),
+ F16(0.26),
+ F16(0.18),
+ F16(0.35),
+ F16(0.21),
+ F16(0.36),
+ F16(0.49),
+ F16(0.17),
+ F16(0.33),
+ F16(0.21),
+ F16(0.13),
+ F16(0.46),
+ F16(0.27),
+ F16(0.36),
+ F16(0.41),
+ F16(0.16),
+ F16(0.24),
+ F16(0.2),
+ F16(0.16),
+ F16(0.38),
+ F16(0.26),
+ F16(0.32),
+ F16(0.31),
+ F16(0.19),
+ F16(0.18),
+ F16(0.21),
+ F16(0.23),
+ F16(0.26),
+ F16(0.25),
+ F16(0.23),
+ F16(0.2),
+ F16(0.25),
+ F16(0.22),
+ F16(0.24),
+ F16(0.24),
+ F16(0.21),
+ F16(0.18),
+ F16(0.22),
+ F16(0.18),
+ F16(0.21),
+ F16(0.18),
+ F16(0.19),
+ F16(0.19),
+ F16(0.17),
+ F16(0.18),
+ F16(0.19),
+ F16(0.2),
+ F16(0.19),
+ F16(0.15),
+ F16(0.16),
+ F16(0.2),
+ F16(0.16),
+ F16(0.19),
+ F16(0.16),
+ F16(0.13),
+ F16(0.22),
+ F16(0.16),
+ F16(0.2),
+ F16(0.21),
+ F16(0.14),
+ F16(0.14),
+ F16(0.13),
+ F16(0.13),
+ F16(0.16),
+ F16(0.25),
+ F16(0.3),
+ F16(0.22),
+ F16(0.19),
+ F16(0.08),
+ F16(0.09),
+ F16(0.19),
+ F16(0.15),
+ F16(0.3),
+ F16(0.29),
+ F16(0.18),
+ F16(0.28),
+ F16(0.06),
+ F16(0.11),
+ F16(0.25),
+ F16(0.06),
+ F16(0.29),
+ F16(0.21),
+ F16(0.11),
+ F16(0.28),
+ F16(0.06),
+ F16(0.13),
+ F16(0.29),
+ F16(0.05),
+ F16(0.2),
+ F16(0.1),
+ F16(0.02),
+ F16(0.32),
+ F16(0.14),
+ F16(0.2),
+ F16(0.27),
+ F16(0.05),
+ F16(0.13),
+ F16(0.09),
+ F16(0.1),
+ F16(0.2),
+ F16(0.2),
+ F16(0.26),
+ F16(0.19),
+ F16(0.15),
+ F16(0.1),
+ F16(0.1),
+ F16(0.13),
+ F16(0.14),
+ F16(0.22),
+ F16(0.19),
+ F16(0.15),
+ F16(0.17),
+ F16(0.15),
+ F16(0.16),
+ F16(0.17),
+ F16(0.16),
+ F16(0.15),
+ F16(0.15),
+ F16(0.18),
+ F16(0.17),
+ F16(0.21),
+ F16(0.19),
+ F16(0.16),
+ F16(0.22),
+ F16(0.17),
+ F16(0.21),
+ F16(0.25),
+ F16(0.14),
+ F16(0.24),
+ F16(0.18),
+ F16(0.15),
+ F16(0.26),
+ F16(0.22),
+ F16(0.24),
+ F16(0.24),
+ F16(0.15),
+ F16(0.17),
+ F16(0.17),
+ F16(0.2),
+ F16(0.22),
+ F16(0.19),
+ F16(0.14),
+ F16(0.14),
+ F16(0.21),
+ F16(0.23),
+ F16(0.24),
+ F16(0.2),
+ F16(0.16),
+ F16(0.08),
+ F16(0.11),
+ F16(0.13),
+ F16(0.15),
+ F16(0.25),
+ F16(0.23),
+ F16(0.11),
+ F16(0.22),
+ F16(0.06),
+ F16(0.16),
+ F16(0.27),
+ F16(0.02),
+ F16(0.16),
+ F16(0.08),
+ F16(0.04),
+ F16(0.27),
+ F16(0.2),
+ F16(0.27),
+ F16(0.34),
+ F16(0.06),
+ F16(0.1),
+ F16(0.06),
+ F16(0.11),
+ F16(0.21),
+ F16(0.32),
+ F16(0.37),
+ F16(0.23),
+ F16(0.27),
+ F16(0.08),
+ F16(0.15),
+ F16(0.27),
+ F16(0.12),
+ F16(0.34),
+ F16(0.24),
+ F16(0.17),
+ F16(0.29),
+ F16(0.11),
+ F16(0.18),
+ F16(0.2),
+ F16(0.1),
+ F16(0.21),
+ F16(0.17),
+ F16(0.09),
+ F16(0.2),
+ F16(0.1),
+ F16(0.1),
+ F16(0.14),
+ F16(0.08),
+ F16(0.15),
+ F16(0.15),
+ F16(0.09),
+ F16(0.16),
+ F16(0.12),
+ F16(0.13),
+ F16(0.14),
+ F16(0.09),
+ F16(0.08),
+ F16(0.12),
+ F16(0.15),
+ F16(0.11),
+ F16(0.16),
+ F16(0.12),
+ F16(0.12),
+ F16(0.19),
+ F16(0.16),
+ F16(0.2),
+ F16(0.23),
+ F16(0.12),
+ F16(0.2),
+ F16(0.19),
+ F16(0.19),
+ F16(0.21),
+ F16(0.15),
+ F16(0.18),
+ F16(0.24),
+ F16(0.16),
+ F16(0.2),
+ F16(0.16),
+ F16(0.17),
+ F16(0.21),
+ F16(0.15),
+ F16(0.14),
+ F16(0.2),
+ F16(0.21),
+ F16(0.23),
+ F16(0.21),
+ F16(0.17),
+ F16(0.26),
+ F16(0.18),
+ F16(0.21),
+ F16(0.27),
+ F16(0.19),
+ F16(0.21),
+ F16(0.24),
+ F16(0.21),
+ F16(0.26),
+ F16(0.26),
+ F16(0.28),
+ F16(0.28),
+ F16(0.27),
+ F16(0.23),
+ F16(0.2),
+ F16(0.24),
+ F16(0.24),
+ F16(0.32),
+ F16(0.31),
+ F16(0.2),
+ F16(0.29),
+ F16(0.11),
+ F16(0.17),
+ F16(0.25),
+ F16(0.13),
+ F16(0.3),
+ F16(0.22),
+ F16(0.15),
+ F16(0.3),
+ F16(0.11),
+ F16(0.23),
+ F16(0.3),
+ F16(0.07),
+ F16(0.23),
+ F16(0.16),
+ F16(0.16),
+ F16(0.27),
+ F16(0.25),
+ F16(0.31),
+ F16(0.31),
+ F16(0.17),
+ F16(0.2),
+ F16(0.22),
+ F16(0.22),
+ F16(0.23),
+ F16(0.29),
+ F16(0.29),
+ F16(0.29),
+ F16(0.26),
+ F16(0.24),
+ F16(0.26),
+ F16(0.23),
+ F16(0.24),
+ F16(0.27),
+ F16(0.25),
+ F16(0.34),
+ F16(0.28),
+ F16(0.29),
+ F16(0.24),
+ F16(0.23),
+ F16(0.32),
+ F16(0.28),
+ F16(0.29),
+ F16(0.3),
+ F16(0.25),
+ F16(0.27),
+ F16(0.22),
+ F16(0.19),
+ F16(0.3),
+ F16(0.26),
+ F16(0.19),
+ F16(0.24),
+ F16(0.2),
+ F16(0.19),
+ F16(0.18),
+ F16(0.16),
+ F16(0.22),
+ F16(0.22),
+ F16(0.14),
+ F16(0.15),
+ F16(0.19),
+ F16(0.16),
+ F16(0.22),
+ F16(0.23),
+ F16(0.12),
+ F16(0.17),
+ F16(0.09),
+ F16(0.08),
+ F16(0.23),
+ F16(0.23),
+ F16(0.29),
+ F16(0.26),
+ F16(0.19),
+ F16(0.14),
+ F16(0.08),
+ F16(0.1),
+ F16(0.24),
+ F16(0.35),
+ F16(0.41),
+ F16(0.3),
+ F16(0.26),
+ F16(0.15),
+ F16(0.13),
+ F16(0.19),
+ F16(0.2),
+ F16(0.35),
+ F16(0.34),
+ F16(0.3),
+ F16(0.27),
+ F16(0.17),
+ F16(0.12),
+ F16(0.18),
+ F16(0.23),
+ F16(0.28),
+ F16(0.27),
+ F16(0.17),
+ F16(0.21),
+ F16(0.11),
+ F16(0.13),
+ F16(0.15),
+ F16(0.13),
+ F16(0.16),
+ F16(0.16),
+ F16(0.12),
+ F16(0.2),
+ F16(0.16),
+ F16(0.19),
+ F16(0.19),
+ F16(0.11),
+ F16(0.13),
+ F16(0.08),
+ F16(0.06),
+ F16(0.23),
+ F16(0.23),
+ F16(0.29),
+ F16(0.27),
+ F16(0.09),
+ F16(0.07),
+ F16(0.06),
+ F16(0.07),
+ F16(0.22),
+ F16(0.27),
+ F16(0.31),
+ F16(0.27),
+ F16(0.15),
+ F16(0.13),
+ F16(0.09),
+ F16(0.13),
+ F16(0.16),
+ F16(0.24),
+ F16(0.25),
+ F16(0.29),
+ F16(0.17),
+ F16(0.17),
+ F16(0.14),
+ F16(0.17),
+ F16(0.21),
+ F16(0.22),
+ F16(0.23),
+ F16(0.25),
+ F16(0.22),
+ F16(0.28),
+ F16(0.3),
+ F16(0.2),
+ F16(0.28),
+ F16(0.21),
+ F16(0.24),
+ F16(0.3),
+ F16(0.2),
+ F16(0.32),
+ F16(0.24),
+ F16(0.23),
+ F16(0.34),
+ F16(0.2),
+ F16(0.26),
+ F16(0.27),
+ F16(0.14),
+ F16(0.22),
+ F16(0.21),
+ F16(0.25),
+ F16(0.24),
+ F16(0.24),
+ F16(0.2),
+ F16(0.17),
+ F16(0.23),
+ F16(0.17),
+ F16(0.24),
+ F16(0.3),
+ F16(0.15),
+ F16(0.2),
+ F16(0.09),
+ F16(0.05),
+ F16(0.34),
+ F16(0.24),
+ F16(0.36),
+ F16(0.36),
+ F16(0.09),
+ F16(0.11),
+ F16(0.02),
+ F16(0.07),
+ F16(0.23),
+ F16(0.32),
+ F16(0.33),
+ F16(0.31),
+ F16(0.18),
+ F16(0.09),
+ F16(0.1),
+ F16(0.15),
+ F16(0.16),
+ F16(0.31),
+ F16(0.28),
+ F16(0.16),
+ F16(0.24),
+ F16(0.07),
+ F16(0.16),
+ F16(0.25),
+ F16(0.1),
+ F16(0.21),
+ F16(0.13),
+ F16(0.14),
+ F16(0.25),
+ F16(0.2),
+ F16(0.25),
+ F16(0.24),
+ F16(0.14),
+ F16(0.16),
+ F16(0.13),
+ F16(0.12),
+ F16(0.22),
+ F16(0.23),
+ F16(0.23),
+ F16(0.21),
+ F16(0.16),
+ F16(0.17),
+ F16(0.15),
+ F16(0.18),
+ F16(0.19),
+ F16(0.17),
+ F16(0.2),
+ F16(0.19),
+ F16(0.21),
+ F16(0.17),
+ F16(0.13),
+ F16(0.15),
+ F16(0.17),
+ F16(0.17),
+ F16(0.19),
+ F16(0.16),
+ F16(0.13),
+ F16(0.09),
+ F16(0.07),
+ F16(0.11),
+ F16(0.14),
+ F16(0.19),
+ F16(0.18),
+ F16(0.13),
+ F16(0.13),
+ F16(0.08),
+ F16(0.09),
+ F16(0.2),
+ F16(0.09),
+ F16(0.18),
+ F16(0.09),
+ F16(0.02),
+ F16(0.22),
+ F16(0.13),
+ F16(0.22),
+ F16(0.21),
+ F16(0.09),
+ F16(0.04),
+ F16(-0.02),
+ F16(0.03),
+ F16(0.13),
+ F16(0.25),
+ F16(0.21),
+ F16(0.08),
+ F16(0.14),
+ F16(-0.08),
+ F16(0.03),
+ F16(0.18),
+ F16(-0.07),
+ F16(0.21),
+ F16(0.01),
+ F16(-0.09),
+ F16(0.29),
+ F16(0.06),
+ F16(0.2),
+ F16(0.27),
+ F16(-0.07),
+ F16(0.02),
+ F16(-0.1),
+ F16(-0.04),
+ F16(0.15),
+ F16(0.22),
+ F16(0.21),
+ F16(0.12),
+ F16(0.1),
+ F16(-0.01),
+ F16(0.04),
+ F16(0.15),
+ F16(0.03),
+ F16(0.15),
+ F16(0.12),
+ F16(0.07),
+ F16(0.18),
+ F16(0.07),
+ F16(0.13),
+ F16(0.14),
+ F16(0.12),
+ F16(0.14),
+ F16(0.13),
+ F16(0.14),
+ F16(0.14),
+ F16(0.08),
+ F16(0.11),
+ F16(0.07),
+ F16(0.11),
+ F16(0.14),
+ F16(0.18),
+ F16(0.15),
+ F16(0.08),
+ F16(-0.01),
+ F16(0.03),
+ F16(0.09),
+ F16(0.08),
+ F16(0.18),
+ F16(0.16),
+ F16(0.1),
+ F16(0.18),
+ F16(0.07),
+ F16(0.12),
+ F16(0.11),
+ F16(0.09),
+ F16(0.2),
+ F16(0.13),
+ F16(0.14),
+ F16(0.14),
+ F16(0.13),
+ F16(0.12),
+ F16(0.1),
+ F16(0.17),
+ F16(0.12),
+ F16(0.15),
+ F16(0.21),
+ F16(0.11),
+ F16(0.11),
+ F16(0.12),
+ F16(0.06),
+ F16(0.18),
+ F16(0.17),
+ F16(0.23),
+ F16(0.25),
+ F16(0.1),
+ F16(0.03),
+ F16(-0.02),
+ F16(0.05),
+ F16(0.11),
+ F16(0.27),
+ F16(0.22),
+ F16(0.14),
+ F16(0.19),
+ F16(0.04),
+ F16(0.07),
+ F16(0.16),
+ F16(0.06),
+ F16(0.2),
+ F16(0.1),
+ F16(0.02),
+ F16(0.26),
+ F16(0.09),
+ F16(0.19),
+ F16(0.24),
+ F16(0.04),
+ F16(0.01),
+ F16(0.01),
+ F16(0.08),
+ F16(0.15),
+ F16(0.21),
+ F16(0.16),
+ F16(0.09),
+ F16(0.19),
+ F16(0.04),
+ F16(0.15),
+ F16(0.18),
+ F16(0.04),
+ F16(0.15),
+ F16(0.07),
+ F16(0.03),
+ F16(0.25),
+ F16(0.2),
+ F16(0.23),
+ F16(0.19),
+ F16(0.13),
+ F16(0.1),
+ F16(0.14),
+ F16(0.19),
+ F16(0.12),
+ F16(0.17),
+ F16(0.16),
+ F16(0.17),
+ F16(0.18),
+ F16(0.19),
+ F16(0.19),
+ F16(0.17),
+ F16(0.18),
+ F16(0.16),
+ F16(0.19),
+ F16(0.2),
+ F16(0.12),
+ F16(0.09),
+ F16(0.06),
+ F16(0.13),
+ F16(0.15),
+ F16(0.19),
+ F16(0.12),
+ F16(0.09),
+ F16(0.2),
+ F16(0.12),
+ F16(0.15),
+ F16(0.18),
+ F16(0.07),
+ F16(0.1),
+ F16(0.1),
+ F16(0.13),
+ F16(0.15),
+ F16(0.18),
+ F16(0.14),
+ F16(0.07),
+ F16(0.17),
+ F16(0.13),
+ F16(0.17),
+ F16(0.15),
+ F16(0.08),
+ F16(0.09),
+ F16(0.1),
+ F16(0.13),
+ F16(0.12),
+ F16(0.16),
+ F16(0.18),
+ F16(0.14),
+ F16(0.18),
+ F16(0.08),
+ F16(0.1),
+ F16(0.18),
+ F16(0.08),
+ F16(0.25),
+ F16(0.17),
+ F16(0.11),
+ F16(0.22),
+ F16(0.08),
+ F16(0.17),
+ F16(0.28),
+ F16(0.06),
+ F16(0.21),
+ F16(0.11),
+ F16(0.05),
+ F16(0.26),
+ F16(0.13),
+ F16(0.24),
+ F16(0.26),
+ F16(0.02),
+ F16(0.09),
+ F16(0.02),
+ F16(0.03),
+ F16(0.24),
+ F16(0.21),
+ F16(0.24),
+ F16(0.2),
+ F16(0.13),
+ F16(0),
+ F16(0.07),
+ F16(0.18),
+ F16(0.13),
+ F16(0.21),
+ F16(0.14),
+ F16(0.08),
+ F16(0.22),
+ F16(0.19),
+ F16(0.23),
+ F16(0.24),
+ F16(0.14),
+ F16(0.09),
+ F16(0.06),
+ F16(0.19),
+ F16(0.19),
+ F16(0.28),
+ F16(0.23),
+ F16(0.14),
+ F16(0.32),
+ F16(0.14),
+ F16(0.22),
+ F16(0.25),
+ F16(0.06),
+ F16(0.19),
+ F16(0.1),
+ F16(0.08),
+ F16(0.27),
+ F16(0.17),
+ F16(0.19),
+ F16(0.17),
+ F16(0.13),
+ F16(0.17),
+ F16(0.18),
+ F16(0.13),
+ F16(0.19),
+ F16(0.12),
+ F16(0.16),
+ F16(0.2),
+ F16(0.12),
+ F16(0.16),
+ F16(0.12),
+ F16(0.1),
+ F16(0.21),
+ F16(0.21),
+ F16(0.2),
+ F16(0.21),
+ F16(0.15),
+ F16(0.13),
+ F16(0.14),
+ F16(0.16),
+ F16(0.2),
+ F16(0.24),
+ F16(0.24),
+ F16(0.18),
+ F16(0.22),
+ F16(0.1),
+ F16(0.15),
+ F16(0.27),
+ F16(0.13),
+ F16(0.25),
+ F16(0.16),
+ F16(0.09),
+ F16(0.3),
+ F16(0.18),
+ F16(0.24),
+ F16(0.28),
+ F16(0.09),
+ F16(0.12),
+ F16(0.05),
+ F16(0.06),
+ F16(0.22),
+ F16(0.25),
+ F16(0.27),
+ F16(0.17),
+ F16(0.19),
+ F16(0.06),
+ F16(0.1),
+ F16(0.19),
+ F16(0.08),
+ F16(0.24),
+ F16(0.13),
+ F16(0.03),
+ F16(0.27),
+ F16(0.13),
+ F16(0.23),
+ F16(0.3),
+ F16(0.04),
+ F16(0.08),
+ F16(0.02),
+ F16(0.03),
+ F16(0.23),
+ F16(0.24),
+ F16(0.27),
+ F16(0.22),
+ F16(0.12),
+ F16(0.12),
+ F16(0.13),
+ F16(0.19),
+ F16(0.14),
+ F16(0.23),
+ F16(0.24),
+ F16(0.21),
+ F16(0.23),
+ F16(0.27),
+ F16(0.27),
+ F16(0.29),
+ F16(0.23),
+ F16(0.23),
+ F16(0.24),
+ F16(0.33),
+ F16(0.27),
+ F16(0.27),
+ F16(0.2),
+ F16(0.16),
+ F16(0.31),
+ F16(0.27),
+ F16(0.34),
+ F16(0.29),
+ F16(0.18),
+ F16(0.11),
+ F16(0.08),
+ F16(0.12),
+ F16(0.19),
+ F16(0.24),
+ F16(0.23),
+ F16(0.18),
+ F16(0.2),
+ F16(0.15),
+ F16(0.18),
+ F16(0.22),
+ F16(0.14),
+ F16(0.14),
+ F16(0.17),
+ F16(0.23),
+ F16(0.16),
+ F16(0.32),
+ F16(0.27),
+ F16(0.18),
+ F16(0.31),
+ F16(0.18),
+ F16(0.28),
+ F16(0.42),
+ F16(0.16),
+ F16(0.39),
+ F16(0.26),
+ F16(0.17),
+ F16(0.48),
+ F16(0.19),
+ F16(0.33),
+ F16(0.43),
+ F16(0.16),
+ F16(0.32),
+ F16(0.24),
+ F16(0.13),
+ F16(0.37),
+ F16(0.24),
+ F16(0.3),
+ F16(0.34),
+ F16(0.18),
+ F16(0.25),
+ F16(0.18),
+ F16(0.16),
+ F16(0.31),
+ F16(0.22),
+ F16(0.27),
+ F16(0.24),
+ F16(0.16),
+ F16(0.19),
+ F16(0.19),
+ F16(0.19),
+ F16(0.19),
+ F16(0.2),
+ F16(0.15),
+ F16(0.15),
+ F16(0.19),
+ F16(0.23),
+ F16(0.18),
+ F16(0.17),
+ F16(0.21),
+ F16(0.13),
+ F16(0.11),
+ F16(0.13),
+ F16(0.17),
+ F16(0.18),
+ F16(0.2),
+ F16(0.22),
+ F16(0.16),
+ F16(0.06),
+ F16(0.05),
+ F16(0.12),
+ F16(0.14),
+ F16(0.25),
+ F16(0.22),
+ F16(0.15),
+ F16(0.16),
+ F16(0.01),
+ F16(0.02),
+ F16(0.12),
+ F16(0.09),
+ F16(0.25),
+ F16(0.15),
+ F16(0.04),
+ F16(0.2),
+ F16(0.04),
+ F16(0.14),
+ F16(0.22),
+ F16(0.01),
+ F16(0.11),
+ F16(0.05),
+ F16(0.02),
+ F16(0.21),
+ F16(0.23),
+ F16(0.19),
+ F16(0.17),
+ F16(0.12),
+ F16(0.08),
+ F16(0.14),
+ F16(0.13),
+ F16(0.11),
+ F16(0.21),
+ F16(0.19),
+ F16(0.15),
+ F16(0.2),
+ F16(0.13),
+ F16(0.17),
+ F16(0.21),
+ F16(0.14),
+ F16(0.16),
+ F16(0.14),
+ F16(0.17),
+ F16(0.19),
+ F16(0.15),
+ F16(0.16),
+ F16(0.13),
+ F16(0.15),
+ F16(0.15),
+ F16(0.16),
+ F16(0.13),
+ F16(0.12),
+ F16(0.12),
+ F16(0.16),
+ F16(0.19),
+ F16(0.09),
+ F16(0.11),
+ F16(0.04),
+ F16(0.06),
+ F16(0.17),
+ F16(0.18),
+ F16(0.16),
+ F16(0.11),
+ F16(0.14),
+ F16(0.03),
+ F16(0.09),
+ F16(0.17),
+ F16(0.05),
+ F16(0.14),
+ F16(0.07),
+ F16(0.02),
+ F16(0.21),
+ F16(0.23),
+ F16(0.28),
+ F16(0.24),
+ F16(0.11),
+ F16(0.09),
+ F16(0.12),
+ F16(0.18),
+ F16(0.15),
+ F16(0.32),
+ F16(0.26),
+ F16(0.15),
+ F16(0.3),
+ F16(0.14),
+ F16(0.17),
+ F16(0.21),
+ F16(0.1),
+ F16(0.21),
+ F16(0.15),
+ F16(0.11),
+ F16(0.24),
+ F16(0.1),
+ F16(0.14),
+ F16(0.22),
+ F16(0.04),
+ F16(0.11),
+ F16(0.05),
+ F16(0.04),
+ F16(0.18),
+ F16(0.12),
+ F16(0.16),
+ F16(0.12),
+ F16(0.08),
+ F16(0.04),
+ F16(0.08),
+ F16(0.14),
+ F16(0.06),
+ F16(0.1),
+ F16(0.04),
+ F16(0.06),
+ F16(0.14),
+ F16(0.15),
+ F16(0.21),
+ F16(0.17),
+ F16(0.07),
+ F16(-0.01),
+ F16(0.05),
+ F16(0.17),
+ F16(0.08),
+ F16(0.26),
+ F16(0.15),
+ F16(0.06),
+ F16(0.24),
+ F16(0.11),
+ F16(0.22),
+ F16(0.28),
+ F16(0.03),
+ F16(0.15),
+ F16(0.09),
+ F16(0.12),
+ F16(0.21),
+ F16(0.16),
+ F16(0.25),
+ F16(0.19),
+ F16(0.14),
+ F16(0.18),
+ F16(0.15),
+ F16(0.08),
+ F16(0.19),
+ F16(0.19),
+ F16(0.21),
+ F16(0.26),
+ F16(0.08),
+ F16(0.09),
+ F16(0.04),
+ F16(0.06),
+ F16(0.2),
+ F16(0.23),
+ F16(0.2),
+ F16(0.16),
+ F16(0.16),
+ F16(0.06),
+ F16(0.12),
+ F16(0.13),
+ F16(0.11),
+ F16(0.12),
+ F16(0.12),
+ F16(0.17),
+ F16(0.12),
+ F16(0.19),
+ F16(0.08),
+ F16(-0.01),
+ F16(0.24),
+ F16(0.21),
+ F16(0.31),
+ F16(0.36),
+ F16(0.01),
+ F16(0.05),
+ F16(-0),
+ F16(0.1),
+ F16(0.21),
+ F16(0.37),
+ F16(0.31),
+ F16(0.14),
+ F16(0.29),
+ F16(0.06),
+ F16(0.11),
+ F16(0.23),
+ F16(0.08),
+ F16(0.27),
+ F16(0.21),
+ F16(0.08),
+ F16(0.29),
+ F16(0.12),
+ F16(0.23),
+ F16(0.27),
+ F16(0.04),
+ F16(0.1),
+ F16(0.06),
+ F16(0.15),
+ F16(0.21),
+ F16(0.22),
+ F16(0.16),
+ F16(0.1),
+ F16(0.2),
+ F16(0.15),
+ F16(0.26),
+ F16(0.27),
+ F16(0.07),
+ F16(0.09),
+ F16(0.09),
+ F16(0.21),
+ F16(0.2),
+ F16(0.29),
+ F16(0.2),
+ F16(0.07),
+ F16(0.33),
+ F16(0.2),
+ F16(0.31),
+ F16(0.31),
+ F16(0.09),
+ F16(0.12),
+ F16(0.13),
+ F16(0.18),
+ F16(0.2),
+ F16(0.17),
+ F16(0.14),
+ F16(0.16),
+ F16(0.2),
+ F16(0.16),
+ F16(0.13),
+ F16(0.13),
+ F16(0.14),
+ F16(0.09),
+ F16(0.13),
+ F16(0.14),
+ F16(0.11),
+ F16(0.06),
+ F16(0.05),
+ F16(0.08),
+ F16(0.13),
+ F16(0.18),
+ F16(0.13),
+ F16(0.09),
+ F16(0.1),
+ F16(0.06),
+ F16(0.09),
+ F16(0.12),
+ F16(0.06),
+ F16(0.12),
+ F16(0.12),
+ F16(0.12),
+ F16(0.14),
+ F16(0.14),
+ F16(0.14),
+ F16(0.13),
+ F16(0.13),
+ F16(0.27),
+ F16(0.26),
+ F16(0.12),
+ F16(0.18),
+ F16(0.08),
+ F16(0.16),
+ F16(0.23),
+ F16(0.09),
+ F16(0.18),
+ F16(0.15),
+ F16(0.04),
+ F16(0.28),
+ F16(0.12),
+ F16(0.29),
+ F16(0.25),
+ F16(0.06),
+ F16(0.04),
+ F16(-0),
+ F16(0.12),
+ F16(0.12),
+ F16(0.25),
+ F16(0.16),
+ F16(-0),
+ F16(0.25),
+ F16(0.12),
+ F16(0.22),
+ F16(0.22),
+ F16(0.02),
+ F16(0.02),
+ F16(-0.01),
+ F16(0.11),
+ F16(0.12),
+ F16(0.18),
+ F16(0.09),
+ F16(0.01),
+ F16(0.22),
+ F16(0.16),
+ F16(0.21),
+ F16(0.21),
+ F16(0.05),
+ F16(0.04),
+ F16(0.05),
+ F16(0.16),
+ F16(0.1),
+ F16(0.22),
+ F16(0.13),
+ F16(0.02),
+ F16(0.27),
+ F16(0.16),
+ F16(0.24),
+ F16(0.19),
+ F16(0.05),
+ F16(0.05),
+ F16(0.06),
+ F16(0.1),
+ F16(0.09),
+ F16(0.15),
+ F16(0.16),
+ F16(0.1),
+ F16(0.13),
+ F16(0.08),
+ F16(0.1),
+ F16(0.11),
+ F16(0.12),
+ F16(0.14),
+ F16(0.09),
+ F16(0.08),
+ F16(0.13),
+ F16(0.11),
+ F16(0.11),
+ F16(0.1),
+ F16(0.07),
+ F16(0.09),
+ F16(0.1),
+ F16(0.13),
+ F16(0.11),
+ F16(0.16),
+ F16(0.13),
+ F16(0.12),
+ F16(0.14),
+ F16(0.16),
+ F16(0.16),
+ F16(0.17),
+ F16(0.14),
+ F16(0.14),
+ F16(0.13),
+ F16(0.18),
+ F16(0.12),
+ F16(0.23),
+ F16(0.15),
+ F16(0.14),
+ F16(0.23),
+ F16(0.12),
+ F16(0.18),
+ F16(0.27),
+ F16(0.06),
+ F16(0.16),
+ F16(0.07),
+ F16(0.06),
+ F16(0.22),
+ F16(0.24),
+ F16(0.23),
+ F16(0.2),
+ F16(0.12),
+ F16(0.02),
+ F16(0.06),
+ F16(0.16),
+ F16(0.09),
+ F16(0.22),
+ F16(0.19),
+ F16(0.1),
+ F16(0.25),
+ F16(0.18),
+ F16(0.2),
+ F16(0.2),
+ F16(0.11),
+ F16(0.19),
+ F16(0.2),
+ F16(0.21),
+ F16(0.17),
+ F16(0.2),
+ F16(0.21),
+ F16(0.2),
+ F16(0.22),
+ F16(0.3),
+ F16(0.31),
+ F16(0.3),
+ F16(0.25),
+ F16(0.22),
+ F16(0.18),
+ F16(0.3),
+ F16(0.2),
+ F16(0.3),
+ F16(0.25),
+ F16(0.28),
+ F16(0.27),
+ F16(0.29),
+ F16(0.26),
+ F16(0.25),
+ F16(0.26),
+ F16(0.27),
+ F16(0.25),
+ F16(0.18),
+ F16(0.27),
+ F16(0.26),
+ F16(0.24),
+ F16(0.23),
+ F16(0.21),
+ F16(0.14),
+ F16(0.15),
+ F16(0.19),
+ F16(0.2),
+ F16(0.26),
+ F16(0.18),
+ F16(0.07),
+ F16(0.26),
+ F16(0.21),
+ F16(0.28),
+ F16(0.3),
+ F16(0.09),
+ F16(0.06),
+ F16(0.01),
+ F16(0.15),
+ F16(0.2),
+ F16(0.39),
+ F16(0.25),
+ F16(0.08),
+ F16(0.33),
+ F16(0.09),
+ F16(0.25),
+ F16(0.38),
+ F16(-0.01),
+ F16(0.17),
+ F16(0.07),
+ F16(0.05),
+ F16(0.31),
+ F16(0.14),
+ F16(0.25),
+ F16(0.27),
+ F16(0.08),
+ F16(0.1),
+ F16(0.07),
+ F16(0.09),
+ F16(0.18),
+ F16(0.2),
+ F16(0.17),
+ F16(0.14),
+ F16(0.15),
+ F16(0.11),
+ F16(0.16),
+ F16(0.12),
+ F16(0.09),
+ F16(0.09),
+ F16(0.11),
+ F16(0.14),
+ F16(0.1),
+ F16(0.12),
+ F16(0.08),
+ F16(0.05),
+ F16(0.14),
+ F16(0.08),
+ F16(0.11),
+ F16(0.11),
+ F16(0.05),
+ F16(0.07),
+ F16(0.01),
+ F16(0.02),
+ F16(0.11),
+ F16(0.11),
+ F16(0.13),
+ F16(0.14),
+ F16(0.06),
+ F16(0.03),
+ F16(0.05),
+ F16(0.1),
+ F16(0.06),
+ F16(0.15),
+ F16(0.13),
+ F16(0.08),
+ F16(0.14),
+ F16(0.11),
+ F16(0.15),
+ F16(0.21),
+ F16(0.04),
+ F16(0.2),
+ F16(0.12),
+ F16(0.08),
+ F16(0.22),
+ F16(0.1),
+ F16(0.19),
+ F16(0.26),
+ F16(0.06),
+ F16(0.18),
+ F16(0.1),
+ F16(0.02),
+ F16(0.25),
+ F16(0.09),
+ F16(0.19),
+ F16(0.27),
+ F16(0.03),
+ F16(0.12),
+ F16(0.02),
+ F16(0.01),
+ F16(0.24),
+ F16(0.19),
+ F16(0.23),
+ F16(0.15),
+ F16(0.14),
+ F16(0.09),
+ F16(0.15),
+ F16(0.21),
+ F16(0.08),
+ F16(0.13),
+ F16(0.08),
+ F16(0.1),
+ F16(0.19),
+ F16(0.1),
+ F16(0.11),
+ F16(0.15),
+ F16(0.17),
+ F16(0.05),
+ F16(0.11),
+ F16(0.23),
+ F16(0.07),
+ F16(0.48),
+ F16(0.29),
+ F16(0.12),
+ F16(0.39),
+ F16(0.24),
+ F16(0.43),
+ F16(0.57),
+ F16(0.07),
+ F16(0.33),
+ F16(0.26),
+ F16(0.32),
+ F16(0.53),
+ F16(0.71),
+ F16(0.76),
+ F16(0.72),
+ F16(0.49),
+ F16(0.51),
+ F16(0.61),
+ F16(0.81),
+ F16(0.58),
+ F16(1.9),
+ F16(2.75),
+ F16(3.2),
+ F16(1.09),
+ F16(0.42),
+ F16(0.33),
+ F16(0.08),
+ F16(1.67),
+ F16(0.16),
+ F16(0.05),
+ F16(-0.06),
+ F16(0.2),
+ F16(-0),
+ F16(0.08),
+ F16(0.12),
+ F16(-0.09),
+ F16(-0.04),
+ F16(-0.02),
+ F16(0.06),
+ F16(0.04),
+ F16(0.32),
+ F16(0.23),
+ F16(0.12),
+ F16(0.21),
+ F16(-0.23),
+ F16(-0.28),
+ F16(-0.19),
+ F16(-0.06),
+ F16(0.07),
+ F16(0.21),
+ F16(0.23),
+ F16(-0.12),
+ F16(-0.04),
+ F16(-0.17),
+ F16(-0.2),
+ F16(0.11),
+ F16(0.11),
+ F16(0.24),
+ F16(0.22),
+ F16(-0.05),
+ F16(0.02),
+ F16(0.07),
+ F16(0.28),
+ F16(0.13),
+ F16(0.67),
+ F16(0.58),
+ F16(0.3),
+ F16(0.56),
+ F16(-0.12),
+ F16(0.04),
+ F16(0.31),
+ F16(0.01),
+ F16(0.8),
+ F16(0.77),
+ F16(0.56),
+ F16(0.65),
+ F16(0.2),
+ F16(0.31),
+ F16(0.48),
+ F16(0.33),
+ F16(0.85),
+ F16(0.95),
+ F16(0.88),
+ F16(0.66),
+ F16(0.79),
+ F16(0.79),
+ F16(0.87),
+ F16(0.83),
+ F16(1.02),
+ F16(1.13),
+ F16(1.11),
+ F16(0.93),
+ F16(0.94),
+ F16(0.84),
+ F16(0.78),
+ F16(1.04),
+ F16(0.8),
+ F16(0.93),
+ F16(0.99),
+ F16(0.74),
+ F16(0.8),
+ F16(0.77),
+ F16(0.73),
+ F16(0.94),
+ F16(0.49),
+ F16(0.43),
+ F16(0.4),
+ F16(0.59),
+ F16(0.54),
+ F16(0.71),
+ F16(0.84),
+ F16(0.43),
+ F16(0.49),
+ F16(0.44),
+ F16(0.48),
+ F16(0.65),
+ F16(0.87),
+ F16(1.16),
+ F16(1.75),
+ F16(0.73),
+ F16(4.65),
+ F16(6.1),
+ F16(7.12),
+ F16(3.1),
+ F16(7.72),
+ F16(6.12),
+ F16(4.51),
+ F16(7.91),
+ F16(2.55),
+ F16(2.03),
+ F16(1.77),
+ F16(3.42),
+ F16(1.51),
+ F16(1.53),
+ F16(1.73),
+ F16(1.61),
+ F16(2.12),
+ F16(2.27),
+ F16(2.36),
+ F16(1.92),
+ F16(2.43),
+ F16(2.29),
+ F16(2.1),
+ F16(2.44),
+ F16(1.55),
+ F16(1.41),
+ F16(1.31),
+ F16(1.86),
+ F16(1.37),
+ F16(1.56),
+ F16(1.8),
+ F16(1.28),
+ F16(1.34),
+ F16(1.2),
+ F16(1.09),
+ F16(1.7),
+ F16(0.98),
+ F16(0.95),
+ F16(0.91),
+ F16(1.02),
+ F16(0.89),
+ F16(0.9),
+ F16(0.93),
+ F16(0.9),
+ F16(1.16),
+ F16(1.29),
+ F16(1.4),
+ F16(1.04),
+ F16(1.73),
+ F16(1.81),
+ F16(1.71),
+ F16(1.56),
+ F16(1.26),
+ F16(1.36),
+ F16(1.65),
+ F16(1.46),
+ F16(1.56),
+ F16(1.09),
+ F16(0.79),
+ F16(1.79),
+ F16(0.52),
+ F16(0.41),
+ F16(0.33),
+ F16(0.64),
+ F16(0.21),
+ F16(0.17),
+ F16(0.15),
+ F16(0.26),
+ F16(0.12),
+ F16(0.14),
+ F16(0.2),
+ F16(0.13),
+ F16(0.44),
+ F16(0.62),
+ F16(0.86),
+ F16(0.3),
+ F16(1.62),
+ F16(2.02),
+ F16(2.3),
+ F16(1.22),
+ F16(2.23),
+ F16(1.92),
+ F16(1.75),
+ F16(2.4),
+ F16(1.72),
+ F16(1.51),
+ F16(1.28),
+ F16(1.76),
+ F16(1.02),
+ F16(0.98),
+ F16(0.92),
+ F16(1.11),
+ F16(0.75),
+ F16(0.63),
+ F16(0.53),
+ F16(0.85),
+ F16(0.39),
+ F16(0.36),
+ F16(0.34),
+ F16(0.45),
+ F16(0.37),
+ F16(0.45),
+ F16(0.58),
+ F16(0.35),
+ F16(0.82),
+ F16(0.96),
+ F16(1.13),
+ F16(0.7),
+ F16(1.49),
+ F16(1.59),
+ F16(1.61),
+ F16(1.33),
+ F16(1.55),
+ F16(1.51),
+ F16(1.43),
+ F16(1.57),
+ F16(1.09),
+ F16(0.98),
+ F16(0.93),
+ F16(1.26),
+ F16(1.04),
+ F16(1.13),
+ F16(1.17),
+ F16(0.96),
+ F16(0.98),
+ F16(0.87),
+ F16(0.83),
+ F16(1.13),
+ F16(0.77),
+ F16(0.76),
+ F16(0.82),
+ F16(0.8),
+ F16(1.08),
+ F16(1.15),
+ F16(1.21),
+ F16(0.96),
+ F16(1.27),
+ F16(1.25),
+ F16(1.21),
+ F16(1.26),
+ F16(1.17),
+ F16(1.24),
+ F16(1.33),
+ F16(1.17),
+ F16(1.35),
+ F16(1.31),
+ F16(1.25),
+ F16(1.35),
+ F16(1.1),
+ F16(1.02),
+ F16(0.96),
+ F16(1.17),
+ F16(0.92),
+ F16(0.94),
+ F16(0.96),
+ F16(0.92),
+ F16(0.96),
+ F16(0.94),
+ F16(0.93),
+ F16(0.96),
+ F16(0.88),
+ F16(0.87),
+ F16(0.87),
+ F16(0.91),
+ F16(0.91),
+ F16(0.96),
+ F16(1.01),
+ F16(0.88),
+ F16(1.07),
+ F16(1.06),
+ F16(1.04),
+ F16(1.05),
+ F16(1),
+ F16(1.03),
+ F16(1.07),
+ F16(1),
+ F16(1.14),
+ F16(1.17),
+ F16(1.17),
+ F16(1.12),
+ F16(1.07),
+ F16(1.01),
+ F16(0.93),
+ F16(1.13),
+ F16(0.84),
+ F16(0.84),
+ F16(0.87),
+ F16(0.89),
+ F16(1.01),
+ F16(1.07),
+ F16(1.11),
+ F16(0.94),
+ F16(1.16),
+ F16(1.14),
+ F16(1.11),
+ F16(1.14),
+ F16(1.11),
+ F16(1.15),
+ F16(1.19),
+ F16(1.1),
+ F16(1.25),
+ F16(1.26),
+ F16(1.24),
+ F16(1.23),
+ F16(1.14),
+ F16(1.09),
+ F16(1.03),
+ F16(1.2),
+ F16(0.92),
+ F16(0.88),
+ F16(0.86),
+ F16(0.97),
+ F16(0.88),
+ F16(0.91),
+ F16(0.94),
+ F16(0.86),
+ F16(0.95),
+ F16(0.95),
+ F16(0.96),
+ F16(0.95),
+ F16(0.96),
+ F16(0.96),
+ F16(0.97),
+ F16(0.96),
+ F16(0.98),
+ F16(0.99),
+ F16(1),
+ F16(0.97),
+ F16(0.95),
+ F16(0.91),
+ F16(0.87),
+ F16(0.98),
+ F16(0.81),
+ F16(0.8),
+ F16(0.81),
+ F16(0.83),
+ F16(0.83),
+ F16(0.84),
+ F16(0.84),
+ F16(0.82),
+ F16(0.8),
+ F16(0.78),
+ F16(0.78),
+ F16(0.83),
+ F16(0.83),
+ F16(0.87),
+ F16(0.92),
+ F16(0.8),
+ F16(0.99),
+ F16(1.02),
+ F16(1.04),
+ F16(0.96),
+ F16(1.06),
+ F16(1.06),
+ F16(1.06),
+ F16(1.06),
+ F16(1.03),
+ F16(1.02),
+ F16(1.01),
+ F16(1.05),
+ F16(0.98),
+ F16(0.98),
+ F16(0.99),
+ F16(0.99),
+ F16(1),
+ F16(1.02),
+ F16(1.04),
+ F16(1),
+ F16(1.09),
+ F16(1.11),
+ F16(1.13),
+ F16(1.06),
+ F16(1.18),
+ F16(1.21),
+ F16(1.23),
+ F16(1.15),
+ F16(1.23),
+ F16(1.2),
+ F16(1.15),
+ F16(1.24),
+ F16(1.07),
+ F16(1.05),
+ F16(1.05),
+ F16(1.11),
+ F16(1.1),
+ F16(1.12),
+ F16(1.12),
+ F16(1.07),
+ F16(1.13),
+ F16(1.11),
+ F16(1.09),
+ F16(1.12),
+ F16(1.06),
+ F16(1.07),
+ F16(1.07),
+ F16(1.07),
+ F16(1.04),
+ F16(1.02),
+ F16(1.01),
+ F16(1.05),
+ F16(1.04),
+ F16(1.04),
+ F16(1.04),
+ F16(1.03),
+ F16(1.04),
+ F16(1.03),
+ F16(1.02),
+ F16(1.04),
+ F16(1.01),
+ F16(1.01),
+ F16(1),
+ F16(1.01),
+ F16(0.99),
+ F16(1),
+ F16(1.01),
+ F16(0.99),
+ F16(1.04),
+ F16(1.04),
+ F16(1.04),
+ F16(1.03),
+ F16(1.05),
+ F16(1.04),
+ F16(1.01),
+ F16(1.05),
+ F16(0.92),
+ F16(0.91),
+ F16(0.93),
+ F16(0.96),
+ F16(0.98),
+ F16(1),
+ F16(1.03),
+ F16(0.96),
+ F16(1.07),
+ F16(1.08),
+ F16(1.07),
+ F16(1.06),
+ F16(1.05),
+ F16(1.03),
+ F16(1.02),
+ F16(1.06),
+ F16(1.01),
+ F16(0.99),
+ F16(0.98),
+ F16(1.02),
+ F16(1.02),
+ F16(1.05),
+ F16(1.06),
+ F16(0.99),
+ F16(0.99),
+ F16(0.93),
+ F16(0.89),
+ F16(1.04),
+ F16(0.84),
+ F16(0.84),
+ F16(0.85),
+ F16(0.86),
+ F16(0.89),
+ F16(0.93),
+ F16(0.92),
+ F16(0.86),
+ F16(0.88),
+ F16(0.88),
+ F16(0.87),
+ F16(0.9),
+ F16(0.89),
+ F16(0.91),
+ F16(0.92),
+ F16(0.88),
+ F16(0.96),
+ F16(0.97),
+ F16(0.97),
+ F16(0.94),
+ F16(0.95),
+ F16(0.94),
+ F16(0.94),
+ F16(0.97),
+ F16(0.99),
+ F16(1.02),
+ F16(1.04),
+ F16(0.96),
+ F16(1.07),
+ F16(1.07),
+ F16(1.06),
+ F16(1.06),
+ F16(1.05),
+ F16(1.06),
+ F16(1.08),
+ F16(1.05),
+ F16(1.12),
+ F16(1.13),
+ F16(1.14),
+ F16(1.1),
+ F16(1.13),
+ F16(1.11),
+ F16(1.08),
+ F16(1.14),
+ F16(1.04),
+ F16(1.02),
+ F16(1.02),
+ F16(1.06),
+ F16(1.01),
+ F16(0.99),
+ F16(0.98),
+ F16(1.02),
+ F16(0.99),
+ F16(0.98),
+ F16(0.97),
+ F16(0.98),
+ F16(0.92),
+ F16(0.9),
+ F16(0.88),
+ F16(0.95),
+ F16(0.85),
+ F16(0.86),
+ F16(0.88),
+ F16(0.86),
+ F16(0.94),
+ F16(0.96),
+ F16(0.97),
+ F16(0.91),
+ F16(0.96),
+ F16(0.94),
+ F16(0.91),
+ F16(0.98),
+ F16(0.92),
+ F16(0.95),
+ F16(0.98),
+ F16(0.91),
+ F16(0.99),
+ F16(0.98),
+ F16(1.07),
+ F16(0.99),
+ F16(1.03),
+ F16(1.01),
+ F16(1.01),
+ F16(1.06),
+ F16(0.97),
+ F16(0.95),
+ F16(0.93),
+ F16(1),
+ F16(0.94),
+ F16(0.98),
+ F16(1.02),
+ F16(0.93),
+ F16(1.05),
+ F16(1.04),
+ F16(1.02),
+ F16(1.04),
+ F16(1.01),
+ F16(1.04),
+ F16(1.06),
+ F16(1.01),
+ F16(1.08),
+ F16(1.08),
+ F16(1.08),
+ F16(1.08),
+ F16(1.04),
+ F16(0.99),
+ F16(0.97),
+ F16(1.07),
+ F16(0.96),
+ F16(0.97),
+ F16(1.01),
+ F16(0.96),
+ F16(1.03),
+ F16(1.03),
+ F16(1.03),
+ F16(1.03),
+ F16(1.04),
+ F16(1.05),
+ F16(1.06),
+ F16(1.04),
+ F16(1.06),
+ F16(1.05),
+ F16(1.04),
+ F16(1.06),
+ F16(1.02),
+ F16(1.02),
+ F16(1.03),
+ F16(1.02),
+ F16(1),
+ F16(0.99),
+ F16(0.98),
+ F16(1.02),
+ F16(0.98),
+ F16(1),
+ F16(1.01),
+ F16(0.98),
+ F16(1.06),
+ F16(1.08),
+ F16(1.1),
+ F16(1.03),
+ F16(1.1),
+ F16(1.09),
+ F16(1.08),
+ F16(1.1),
+ F16(1.06),
+ F16(1.05),
+ F16(1.04),
+ F16(1.07),
+ F16(1.06),
+ F16(1.08),
+ F16(1.11),
+ F16(1.04),
+ F16(1.12),
+ F16(1.13),
+ F16(1.12),
+ F16(1.12),
+ F16(1.12),
+ F16(1.15),
+ F16(1.19),
+ F16(1.11),
+ F16(1.22),
+ F16(1.23),
+ F16(1.24),
+ F16(1.21),
+ F16(1.23),
+ F16(1.21),
+ F16(1.18),
+ F16(1.24),
+ F16(1.12),
+ F16(1.12),
+ F16(1.12),
+ F16(1.14),
+ F16(1.15),
+ F16(1.16),
+ F16(1.16),
+ F16(1.14),
+ F16(1.16),
+ F16(1.17),
+ F16(1.17),
+ F16(1.16),
+ F16(1.15),
+ F16(1.14),
+ F16(1.14),
+ F16(1.16),
+ F16(1.13),
+ F16(1.12),
+ F16(1.11),
+ F16(1.13),
+ F16(1.07),
+ F16(1.06),
+ F16(1.05),
+ F16(1.09),
+ F16(1.02),
+ F16(1),
+ F16(0.96),
+ F16(1.04),
+ F16(0.9),
+ F16(0.87),
+ F16(0.85),
+ F16(0.93),
+ F16(0.89),
+ F16(0.94),
+ F16(0.98),
+ F16(0.86),
+ F16(0.98),
+ F16(0.93),
+ F16(0.88),
+ F16(0.99),
+ F16(0.83),
+ F16(0.84),
+ F16(0.88),
+ F16(0.84),
+ F16(0.95),
+ F16(0.98),
+ F16(0.99),
+ F16(0.91),
+ F16(0.99),
+ F16(0.98),
+ F16(0.97),
+ F16(0.99),
+ F16(0.97),
+ F16(0.98),
+ F16(0.99),
+ F16(0.97),
+ F16(0.99),
+ F16(0.99),
+ F16(0.99),
+ F16(0.99),
+ F16(0.97),
+ F16(0.94),
+ F16(0.93),
+ F16(0.98),
+ F16(0.96),
+ F16(0.98),
+ F16(0.99),
+ F16(0.94),
+ F16(1.02),
+ F16(1.03),
+ F16(1.03),
+ F16(1),
+ F16(1.01),
+ F16(1),
+ F16(0.99),
+ F16(1.03),
+ F16(1),
+ F16(1),
+ F16(1.01),
+ F16(0.99),
+ F16(1.02),
+ F16(1.04),
+ F16(1.05),
+ F16(1.02),
+ F16(1.02),
+ F16(0.98),
+ F16(0.95),
+ F16(1.05),
+ F16(0.98),
+ F16(1.01),
+ F16(1.01),
+ F16(0.95),
+ F16(0.95),
+ F16(0.9),
+ F16(0.87),
+ F16(0.99),
+ F16(0.86),
+ F16(0.87),
+ F16(0.89),
+ F16(0.85),
+ F16(0.96),
+ F16(0.99),
+ F16(1.02),
+ F16(0.92),
+ F16(1.03),
+ F16(1.02),
+ F16(1),
+ F16(1.03),
+ F16(0.95),
+ F16(0.93),
+ F16(0.92),
+ F16(0.97),
+ F16(0.94),
+ F16(0.95),
+ F16(0.97),
+ F16(0.92),
+ F16(1.04),
+ F16(1.06),
+ F16(1.07),
+ F16(1.01),
+ F16(1.07),
+ F16(1.05),
+ F16(1.03),
+ F16(1.08),
+ F16(0.96),
+ F16(0.92),
+ F16(0.87),
+ F16(1),
+ F16(0.83),
+ F16(0.85),
+ F16(0.89),
+ F16(0.84),
+ F16(0.98),
+ F16(1.02),
+ F16(1.04),
+ F16(0.94),
+ F16(1.06),
+ F16(1.06),
+ F16(1.05),
+ F16(1.06),
+ F16(1.04),
+ F16(1.04),
+ F16(1.05),
+ F16(1.05),
+ F16(1.09),
+ F16(1.11),
+ F16(1.14),
+ F16(1.07),
+ F16(1.2),
+ F16(1.23),
+ F16(1.25),
+ F16(1.17),
+ F16(1.21),
+ F16(1.17),
+ F16(1.14),
+ F16(1.24),
+ F16(1.12),
+ F16(1.12),
+ F16(1.14),
+ F16(1.13),
+ F16(1.18),
+ F16(1.19),
+ F16(1.21),
+ F16(1.16),
+ F16(1.22),
+ F16(1.21),
+ F16(1.19),
+ F16(1.22),
+ F16(1.12),
+ F16(1.07),
+ F16(1.05),
+ F16(1.16),
+ F16(1.04),
+ F16(1.04),
+ F16(1.03),
+ F16(1.05),
+ F16(1.01),
+ F16(0.99),
+ F16(0.98),
+ F16(1.02),
+ F16(0.99),
+ F16(1.01),
+ F16(1.04),
+ F16(0.98),
+ F16(1.11),
+ F16(1.12),
+ F16(1.11),
+ F16(1.08),
+ F16(1.06),
+ F16(1.04),
+ F16(1.02),
+ F16(1.08),
+ F16(1),
+ F16(1),
+ F16(1.01),
+ F16(1),
+ F16(1.04),
+ F16(1.04),
+ F16(1.03),
+ F16(1.02),
+ F16(0.98),
+ F16(0.95),
+ F16(0.93),
+ F16(1.01),
+ F16(0.93),
+ F16(0.95),
+ F16(0.98),
+ F16(0.92),
+ F16(1.04),
+ F16(1.08),
+ F16(1.1),
+ F16(1.01),
+ F16(1.11),
+ F16(1.1),
+ F16(1.09),
+ F16(1.12),
+ F16(1.05),
+ F16(1.04),
+ F16(1.05),
+ F16(1.07),
+ F16(1.07),
+ F16(1.09),
+ F16(1.11),
+ F16(1.06),
+ F16(1.16),
+ F16(1.18),
+ F16(1.21),
+ F16(1.13),
+ F16(1.27),
+ F16(1.29),
+ F16(1.3),
+ F16(1.24),
+ F16(1.28),
+ F16(1.26),
+ F16(1.24),
+ F16(1.29),
+ F16(1.23),
+ F16(1.23),
+ F16(1.24),
+ F16(1.24),
+ F16(1.25),
+ F16(1.26),
+ F16(1.25),
+ F16(1.25),
+ F16(1.22),
+ F16(1.19),
+ F16(1.17),
+ F16(1.24),
+ F16(1.11),
+ F16(1.07),
+ F16(1.04),
+ F16(1.14),
+ F16(0.98),
+ F16(0.96),
+ F16(0.95),
+ F16(1.01),
+ F16(0.95),
+ F16(0.95),
+ F16(0.95),
+ F16(0.95),
+ F16(0.94),
+ F16(0.93),
+ F16(0.91),
+ F16(0.95),
+ F16(0.85),
+ F16(0.82),
+ F16(0.79),
+ F16(0.88),
+ F16(0.83),
+ F16(0.88),
+ F16(0.94),
+ F16(0.8),
+ F16(1.02),
+ F16(1.05),
+ F16(1.07),
+ F16(0.98),
+ F16(1.11),
+ F16(1.12),
+ F16(1.13),
+ F16(1.08),
+ F16(1.12),
+ F16(1.12),
+ F16(1.11),
+ F16(1.12),
+ F16(1.1),
+ F16(1.1),
+ F16(1.11),
+ F16(1.1),
+ F16(1.14),
+ F16(1.16),
+ F16(1.17),
+ F16(1.12),
+ F16(1.19),
+ F16(1.19),
+ F16(1.18),
+ F16(1.18),
+ F16(1.11),
+ F16(1.09),
+ F16(1.09),
+ F16(1.15),
+ F16(1.12),
+ F16(1.12),
+ F16(1.12),
+ F16(1.1),
+ F16(1.13),
+ F16(1.13),
+ F16(1.12),
+ F16(1.13),
+ F16(1.12),
+ F16(1.12),
+ F16(1.1),
+ F16(1.12),
+ F16(1.08),
+ F16(1.07),
+ F16(1.06),
+ F16(1.09),
+ F16(1.02),
+ F16(1),
+ F16(1),
+ F16(1.04),
+ F16(1.02),
+ F16(1.05),
+ F16(1.08),
+ F16(1.01),
+ F16(1.14),
+ F16(1.13),
+ F16(1.09),
+ F16(1.12),
+ F16(0.96),
+ F16(0.91),
+ F16(0.87),
+ F16(1.03),
+ F16(0.88),
+ F16(0.9),
+ F16(0.91),
+ F16(0.86),
+ F16(0.92),
+ F16(0.91),
+ F16(0.89),
+ F16(0.91),
+ F16(0.87),
+ F16(0.87),
+ F16(0.87),
+ F16(0.88),
+ F16(0.87),
+ F16(0.87),
+ F16(0.87),
+ F16(0.87),
+ F16(0.89),
+ F16(0.9),
+ F16(0.91),
+ F16(0.87),
+ F16(0.95),
+ F16(0.98),
+ F16(1),
+ F16(0.93),
+ F16(1.04),
+ F16(1.05),
+ F16(1.05),
+ F16(1.02),
+ F16(1.04),
+ F16(1.04),
+ F16(1.03),
+ F16(1.05),
+ F16(1.04),
+ F16(1.05),
+ F16(1.06),
+ F16(1.03),
+ F16(1.08),
+ F16(1.09),
+ F16(1.1),
+ F16(1.07),
+ F16(1.11),
+ F16(1.08),
+ F16(1.04),
+ F16(1.12),
+ F16(0.99),
+ F16(1),
+ F16(1),
+ F16(1.01),
+ F16(1.03),
+ F16(1.03),
+ F16(1.03),
+ F16(1.01),
+ F16(1.03),
+ F16(1.05),
+ F16(1.07),
+ F16(1.03),
+ F16(1.08),
+ F16(1.07),
+ F16(1.08),
+ F16(1.08),
+ F16(1.08),
+ F16(1.09),
+ F16(1.1),
+ F16(1.08),
+ F16(1.11),
+ F16(1.1),
+ F16(1.08),
+ F16(1.11),
+ F16(1.05),
+ F16(1.05),
+ F16(1.05),
+ F16(1.06),
+ F16(1.03),
+ F16(1.02),
+ F16(1.02),
+ F16(1.04),
+ F16(1.02),
+ F16(1.03),
+ F16(1.05),
+ F16(1.02),
+ F16(1.07),
+ F16(1.08),
+ F16(1.08),
+ F16(1.07),
+ F16(1.11),
+ F16(1.12),
+ F16(1.11),
+ F16(1.09),
+ F16(1.06),
+ F16(1.04),
+ F16(1.01),
+ F16(1.09),
+ F16(0.97),
+ F16(0.95),
+ F16(0.96),
+ F16(0.99),
+ F16(1.05),
+ F16(1.1),
+ F16(1.15),
+ F16(1),
+ F16(1.2),
+ F16(1.2),
+ F16(1.19),
+ F16(1.19),
+ F16(1.12),
+ F16(1.07),
+ F16(1.06),
+ F16(1.16),
+ F16(1.09),
+ F16(1.1),
+ F16(1.11),
+ F16(1.07),
+ F16(1.13),
+ F16(1.14),
+ F16(1.14),
+ F16(1.12),
+ F16(1.08),
+ F16(1.02),
+ F16(0.97),
+ F16(1.12),
+ F16(0.98),
+ F16(1.05),
+ F16(1.14),
+ F16(0.96),
+ F16(1.26),
+ F16(1.29),
+ F16(1.29),
+ F16(1.21),
+ F16(1.25),
+ F16(1.22),
+ F16(1.2),
+ F16(1.27),
+ F16(1.17),
+ F16(1.15),
+ F16(1.12),
+ F16(1.19),
+ F16(1.1),
+ F16(1.1),
+ F16(1.13),
+ F16(1.1),
+ F16(1.19),
+ F16(1.21),
+ F16(1.25),
+ F16(1.16),
+ F16(1.26),
+ F16(1.24),
+ F16(1.21),
+ F16(1.27),
+ F16(1.12),
+ F16(1.08),
+ F16(1.06),
+ F16(1.17),
+ F16(1.13),
+ F16(1.18),
+ F16(1.2),
+ F16(1.09),
+ F16(1.23),
+ F16(1.23),
+ F16(1.21),
+ F16(1.22),
+ F16(1.16),
+ F16(1.13),
+ F16(1.11),
+ F16(1.18),
+ F16(1.1),
+ F16(1.11),
+ F16(1.11),
+ F16(1.1),
+ F16(1.1),
+ F16(1.1),
+ F16(1.09),
+ F16(1.11),
+ F16(1.07),
+ F16(1.04),
+ F16(1.01),
+ F16(1.08),
+ F16(0.9),
+ F16(0.85),
+ F16(0.84),
+ F16(0.95),
+ F16(0.89),
+ F16(0.94),
+ F16(0.97),
+ F16(0.86),
+ F16(0.98),
+ F16(0.95),
+ F16(0.92),
+ F16(0.99),
+ F16(0.86),
+ F16(0.85),
+ F16(0.84),
+ F16(0.89),
+ F16(0.85),
+ F16(0.87),
+ F16(0.89),
+ F16(0.84),
+ F16(0.95),
+ F16(0.99),
+ F16(1.01),
+ F16(0.92),
+ F16(1.03),
+ F16(1.02),
+ F16(1),
+ F16(1.02),
+ F16(0.95),
+ F16(0.95),
+ F16(0.95),
+ F16(0.97),
+ F16(1),
+ F16(1.05),
+ F16(1.09),
+ F16(0.97),
+ F16(1.17),
+ F16(1.19),
+ F16(1.2),
+ F16(1.13),
+ F16(1.2),
+ F16(1.19),
+ F16(1.17),
+ F16(1.21),
+ F16(1.12),
+ F16(1.11),
+ F16(1.1),
+ F16(1.15),
+ F16(1.14),
+ F16(1.14),
+ F16(1.11),
+ F16(1.12),
+ F16(1.02),
+ F16(0.96),
+ F16(0.9),
+ F16(1.08),
+ F16(0.91),
+ F16(0.96),
+ F16(1.02),
+ F16(0.88),
+ F16(1.12),
+ F16(1.15),
+ F16(1.19),
+ F16(1.07),
+ F16(1.19),
+ F16(1.17),
+ F16(1.14),
+ F16(1.2),
+ F16(1.1),
+ F16(1.12),
+ F16(1.15),
+ F16(1.12),
+ F16(1.2),
+ F16(1.22),
+ F16(1.23),
+ F16(1.18),
+ F16(1.23),
+ F16(1.22),
+ F16(1.21),
+ F16(1.23),
+ F16(1.21),
+ F16(1.21),
+ F16(1.21),
+ F16(1.21),
+ F16(1.21),
+ F16(1.22),
+ F16(1.23),
+ F16(1.21),
+ F16(1.24),
+ F16(1.22),
+ F16(1.17),
+ F16(1.24),
+ F16(1.06),
+ F16(1.02),
+ F16(1.02),
+ F16(1.11),
+ F16(1.08),
+ F16(1.12),
+ F16(1.12),
+ F16(1.04),
+ F16(1.06),
+ F16(1.02),
+ F16(0.98),
+ F16(1.1),
+ F16(0.97),
+ F16(0.99),
+ F16(1.02),
+ F16(0.96),
+ F16(1.05),
+ F16(1.06),
+ F16(1.08),
+ F16(1.04),
+ F16(1.1),
+ F16(1.12),
+ F16(1.14),
+ F16(1.08),
+ F16(1.16),
+ F16(1.17),
+ F16(1.18),
+ F16(1.15),
+ F16(1.17),
+ F16(1.17),
+ F16(1.18),
+ F16(1.18),
+ F16(1.13),
+ F16(1.09),
+ F16(1.04),
+ F16(1.17),
+ F16(0.99),
+ F16(0.97),
+ F16(0.96),
+ F16(1.01),
+ F16(0.97),
+ F16(0.99),
+ F16(1.03),
+ F16(0.96),
+ F16(1.11),
+ F16(1.13),
+ F16(1.14),
+ F16(1.07),
+ F16(1.1),
+ F16(1.06),
+ F16(1.03),
+ F16(1.12),
+ F16(1.04),
+ F16(1.08),
+ F16(1.12),
+ F16(1.03),
+ F16(1.2),
+ F16(1.21),
+ F16(1.22),
+ F16(1.16),
+ F16(1.19),
+ F16(1.16),
+ F16(1.13),
+ F16(1.21),
+ F16(1.11),
+ F16(1.11),
+ F16(1.12),
+ F16(1.12),
+ F16(1.13),
+ F16(1.14),
+ F16(1.16),
+ F16(1.12),
+ F16(1.18),
+ F16(1.19),
+ F16(1.19),
+ F16(1.16),
+ F16(1.16),
+ F16(1.14),
+ F16(1.11),
+ F16(1.17),
+ F16(1.09),
+ F16(1.09),
+ F16(1.09),
+ F16(1.09),
+ F16(1.08),
+ F16(1.08),
+ F16(1.07),
+ F16(1.09),
+ F16(1.05),
+ F16(1.02),
+ F16(0.99),
+ F16(1.07),
+ F16(0.98),
+ F16(1),
+ F16(1.02),
+ F16(0.98),
+ F16(1.07),
+ F16(1.09),
+ F16(1.1),
+ F16(1.04),
+ F16(1.09),
+ F16(1.05),
+ F16(1),
+ F16(1.1),
+ F16(0.91),
+ F16(0.89),
+ F16(0.89),
+ F16(0.95),
+ F16(0.97),
+ F16(1.03),
+ F16(1.08),
+ F16(0.92),
+ F16(1.11),
+ F16(1.09),
+ F16(1.05),
+ F16(1.11),
+ F16(0.95),
+ F16(0.93),
+ F16(0.95),
+ F16(0.99),
+ F16(1.05),
+ F16(1.09),
+ F16(1.13),
+ F16(0.99),
+ F16(1.17),
+ F16(1.17),
+ F16(1.16),
+ F16(1.15),
+ F16(1.13),
+ F16(1.11),
+ F16(1.11),
+ F16(1.14),
+ F16(1.1),
+ F16(1.09),
+ F16(1.09),
+ F16(1.11),
+ F16(-4.67),
+ F16(-4.42),
+ F16(-3.4),
+ F16(19.46),
+ F16(-0.64),
+ F16(-0.26),
+ F16(-5.3),
+ F16(-1.81),
+ F16(-2.01),
+ F16(-3.17),
+ F16(-3.75),
+ F16(-1.95),
+ F16(-2.97),
+ F16(-2.85),
+ F16(-0.8),
+ F16(-1.56),
+ F16(-0.46),
+ F16(-0.22),
+ F16(-0.21),
+ F16(-0.53),
+ F16(-0.54),
+ F16(-1),
+ F16(-1.01),
+ F16(-0.36),
+ F16(-0.54),
+ F16(-0.32),
+ F16(-0.01),
+ F16(-0.84),
+ F16(-0),
+ F16(-0.02),
+ F16(-0.06),
+ F16(0.07),
+ F16(-0.04),
+ F16(-0.04),
+ F16(-0.05),
+ F16(-0.04),
+ F16(-0.05),
+ F16(-0.04),
+ F16(-0.04),
+ F16(-0.05),
+ F16(-0.03),
+ F16(-0.04),
+ F16(-0.05),
+ F16(-0.06),
+ F16(-0.04),
+ F16(-0.04),
+ F16(-0.04),
+ F16(-0.05),
+ F16(-0.05),
+ F16(-0.05),
+ F16(-0.04),
+ F16(-0.05),
+ F16(-0.04),
+ F16(-0.05),
+ F16(-0.04),
+ F16(-0.04),
+ F16(-0.04),
+ F16(-0.02),
+ F16(-0.01),
+ F16(-0.04),
+ F16(0.14),
+ F16(0.18),
+ F16(0.25),
+ F16(0.04),
+ F16(-0.08),
+ F16(-0.04),
+ F16(-0.06),
+ F16(0.03),
+ F16(-0.21),
+ F16(-0.21),
+ F16(-0.35),
+ F16(-0.14),
+ F16(-0.32),
+ F16(-0.13),
+ F16(-0.07),
+ F16(-0.42),
+ F16(0.27),
+ F16(-0.1),
+ F16(-0.11),
+ F16(0.3),
+ F16(0.22),
+ F16(0.1),
+ F16(-0.07),
+ F16(-0.08),
+ F16(-0.35),
+ F16(-0.39),
+ F16(-0.49),
+ F16(-0.35),
+ F16(-0.71),
+ F16(-0.54),
+ F16(-0.49),
+ F16(-0.64),
+ F16(-0.5),
+ F16(-0.45),
+ F16(-0.14),
+ F16(-0.54),
+ F16(0.05),
+ F16(0.08),
+ F16(0.04),
+ F16(0),
+ F16(-0.03),
+ F16(0),
+ F16(-0.04),
+ F16(-0.07),
+ F16(-0.03),
+ F16(-0.02),
+ F16(-0.03),
+ F16(-0),
+ F16(-0.02),
+ F16(-0.03),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.03),
+ F16(-0.01),
+ F16(-0.03),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.03),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.03),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.03),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.03),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02),
+ F16(-0.02) };
diff --git a/include/pico-logger b/include/pico-logger
new file mode 160000
+Subproject ff9037af927b8984db6e2a8287d3961b0c751e1
diff --git a/include/pico-sdk b/include/pico-sdk
-Subproject 6a7db34ff63345a7badec79ebea3aaef1712f37
+Subproject bddd20f928ce76142793bef434d4f75f4af6e43
diff --git a/include/pwm.hpp b/include/pwm.hpp
index 90e31cc..45c8b3b 100644
--- a/include/pwm.hpp
+++ b/include/pwm.hpp
@@ -7,7 +7,6 @@
#include "pico/types.h"
#include "pico/divider.h"
-#define SERVO_PIN 27 // Servo motor connected to GPIO PIN 32 (GP27)
#define WRAP_VALUE 65535
#define CLOCK_DIV_RATE 38.15
#define SERVO_MIN 13
diff --git a/include/rp2040_micro.h b/include/rp2040_micro.h
new file mode 100644
index 0000000..1ac6382
--- /dev/null
+++ b/include/rp2040_micro.h
@@ -0,0 +1,111 @@
+// -----------------------------------------------------
+// NOTE: THIS HEADER IS ALSO INCLUDED BY ASSEMBLER SO
+// SHOULD ONLY CONSIST OF PREPROCESSOR DIRECTIVES
+// -----------------------------------------------------
+
+
+#ifndef _BOARDS_RP2040_MICRO_H
+#define _BOARDS_RP2040_MICRO_H
+
+// For board detection
+#define RP2040_MICRO_H
+
+// --- UART ---
+#ifndef PICO_DEFAULT_UART
+#define PICO_DEFAULT_UART 0
+#endif
+#ifndef PICO_DEFAULT_UART_TX_PIN
+#define PICO_DEFAULT_UART_TX_PIN 12
+#endif
+#ifndef PICO_DEFAULT_UART_RX_PIN
+#define PICO_DEFAULT_UART_RX_PIN 13
+#endif
+
+// --- LED ---
+#ifndef PICO_DEFAULT_LED_PIN
+#define PICO_DEFAULT_LED_PIN 25
+#endif
+// no PICO_DEFAULT_WS2812_PIN
+
+// --- I2C ---
+#ifndef PICO_DEFAULT_I2C
+#define PICO_DEFAULT_I2C 0
+#endif
+#ifndef PICO_DEFAULT_I2C_SDA_PIN
+#define PICO_DEFAULT_I2C_SDA_PIN 20
+#endif
+#ifndef PICO_DEFAULT_I2C_SCL_PIN
+#define PICO_DEFAULT_I2C_SCL_PIN 21
+#endif
+
+// --- SPI ---
+#ifndef PICO_DEFAULT_SPI
+#define PICO_DEFAULT_SPI 0
+#endif
+#ifndef PICO_DEFAULT_SPI_SCK_PIN
+#define PICO_DEFAULT_SPI_SCK_PIN 18
+#endif
+#ifndef PICO_DEFAULT_SPI_TX_PIN
+#define PICO_DEFAULT_SPI_TX_PIN 19
+#endif
+#ifndef PICO_DEFAULT_SPI_RX_PIN
+#define PICO_DEFAULT_SPI_RX_PIN 16
+#endif
+#ifndef PICO_DEFAULT_SPI_CSN_PIN
+#define PICO_DEFAULT_SPI_CSN_PIN 17
+#endif
+
+// --- MISC ---
+#ifndef MICRO_DEFAULT_PWM
+#define MICRO_DEFAULT_PWM 7
+#endif
+
+#ifndef MICRO_DEFAULT_SERVO_ENABLE
+#define MICRO_DEFAULT_SERVO_ENABLE 4
+#endif
+
+#ifndef MICRO_DEFAULT_CLK_OUTPUT
+#define MICRO_DEFAULT_CLK_OUTPUT 23
+#endif
+
+#ifndef MICRO_IMU_INTTERUPT
+#define MICRO_IMU_INTERRUPT 22
+#endif
+
+#ifndef MICRO_ACCEL_INTERRUPT_0
+#define MICRO_ACCEL_INTERRUPT_0 19
+#endif
+
+#ifndef MICRO_ACCEL_INTERRUPT_1
+#define MICRO_ACCEL_INTERRUPT_1 18
+#endif
+
+#ifndef MICRO_MAG_INTERRUPT
+#define MICRO_MAG_INTERRUPT 17
+#endif
+
+#ifndef MICRO_BUZZER
+#define MICRO_BUZZER 0
+#endif
+
+// --- FLASH ---
+
+#define PICO_BOOT_STAGE2_CHOOSE_W25Q080 1
+
+#ifndef PICO_FLASH_SPI_CLKDIV
+#define PICO_FLASH_SPI_CLKDIV 2
+#endif
+
+#ifndef PICO_FLASH_SIZE_BYTES
+#define PICO_FLASH_SIZE_BYTES (16 * 1024 * 1024)
+#endif
+
+// Drive high to force power supply into PWM mode (lower ripple on 3V3 at light loads)
+#define PICO_SMPS_MODE_PIN 23
+
+// All boards have B1 RP2040
+#ifndef PICO_RP2040_B0_SUPPORTED
+#define PICO_RP2040_B0_SUPPORTED 0
+#endif
+
+#endif
diff --git a/include/serial.hpp b/include/serial.hpp
new file mode 100644
index 0000000..68ca54a
--- /dev/null
+++ b/include/serial.hpp
@@ -0,0 +1,86 @@
+#pragma once
+
+#include <stdlib.h>
+#include <stdio.h>
+#include <string.h>
+
+#include "pico/stdlib.h"
+#include "pico/stdio.h"
+
+/* Kernel includes. */
+#include "FreeRTOS.h"
+#include "FreeRTOSConfig.h"
+#include "portmacro.h"
+#include "projdefs.h"
+#include "task.h"
+#include "semphr.h"
+
+typedef struct {
+ const char* name;
+ const size_t len;
+ void (*function)();
+} command_t;
+
+
+void serial_task( void *pvParameters );
+int input_line(char *buffer, size_t len);
+
+void info_cmd_func();
+void help_cmd_func();
+void top_cmd_func();
+void clear_cmd_func();
+void reset_cmd_func();
+
+static const char* logo = \
+"\n\e[0;37m#####################################################################################\n\
+# \e[0;33m= \e[0;37m#\n\
+# \e[0;33m= \e[0;37m#\n\
+# \e[0;33m= \e[0;37m#\n\
+# #\n\
+# \e[0;31m# \e[0;37m#\n\
+# \e[0;31m# \e[0;37m#\n\
+# \e[0;33m========== \e[0;31m## \e[0;37m#\n\
+# \e[0;33m========== ===\e[0;31m### \e[0;37m#\n\
+# \e[0;33m======= \e[0;31m### \e[0;33m===== \e[0;37m#\n\
+# \e[0;33m====== \e[0;31m### \e[0;33m===== \e[0;37m#\n\
+# \e[0;33m====== \e[0;31m### \e[0;33m===== \e[0;37m#\n\
+# \e[0;33m====== \e[0;31m### \e[0;33m===== \e[0;37m#\n\
+# \e[0;33m====== \e[0;31m### \e[0;33m===== \e[0;37m#\n\
+# \e[0;31m######### \e[0;33m===== \e[0;31m#### \e[0;33m==== \e[0;31m######## \e[0;37m #\n\
+# \e[0;31m########## ##### ######### \e[0;37m#\n\
+# \e[0;31m##################################### ##### ################################ \e[0;37m#\n\
+# \e[0;31m#################################### ##### ################################ \e[0;37m#\n\
+# \e[0;31m############# ## ## ## ## ###### ## ## ### ## ############## \e[0;37m#\n\
+# \e[0;31m############# ## ## ## ## ###### ## ## ### ## ############## \e[0;37m#\n\
+# \e[0;31m############# ## ## ## ## ##### ## ## ### ## ############## \e[0;37m#\n\
+# \e[0;31m############################### ###### #################################### \e[0;37m#\n\
+# \e[0;31m############################## ####### ################################ \e[0;37m#\n\
+# \e[0;31m################### ####### #################### \e[0;37m#\n\
+# \e[0;31m############# ######## ############## \e[0;37m#\n\
+# \e[0;31m############ ######### ############## \e[0;37m#\n\
+# \e[0;31m############ ########### ############## \e[0;37m#\n\
+# \e[0;31m############ ############# ############## \e[0;37m#\n\
+# \e[0;31m############ ################## ############## \e[0;37m#\n\
+# \e[0;31m############ ######################### ############## \e[0;37m#\n\
+# \e[0;37m#\n\
+#####################################################################################\n";
+
+#define NUM_BASE_CMDS 5
+const command_t base_commands[] = { {.name = "help",
+ .len = 4,
+ .function = &help_cmd_func},
+ {.name = "info",
+ .len = 4,
+ .function = &info_cmd_func},
+ {.name = "clear",
+ .len = 5,
+ .function = &clear_cmd_func},
+ {.name = "top",
+ .len = 3,
+ .function = &top_cmd_func},
+ {.name = "reset",
+ .len = 5,
+ .function = &reset_cmd_func}};
+
+extern const size_t num_user_cmds;
+extern const command_t user_commands[];
diff --git a/include/spi_flash.h b/include/spi_flash.h
deleted file mode 100644
index d3c0247..0000000
--- a/include/spi_flash.h
+++ /dev/null
@@ -1,55 +0,0 @@
-#ifndef SPI_FLASH
-#define SPI_FLASH
-
-#include <stdint.h>
-#include "hardware/spi.h"
-#include "boards/pico_w.h"
-#include "pico/stdlib.h"
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-#define FLASH_PAGE_SIZE 256
-#define FLASH_NUM_PAGES 32768
-#define FLASH_SECTOR_SIZE 4096
-#define FLASH_BLOCK_SIZE 65536
-#define FLASH_PHYS_SIZE (FLASH_PAGE_SIZE * FLASH_NUM_PAGES)
-
-#define FLASH_CMD_PAGE_PROGRAM 0x02
-#define FLASH_CMD_READ 0x03
-#define FLASH_CMD_STATUS 0x05
-#define FLASH_CMD_WRITE_EN 0x06
-#define FLASH_CMD_SECTOR_ERASE 0x20
-#define FLASH_CMD_BLOCK_ERASE 0xD8
-#define FLASH_CMD_CHIP_ERASE 0xC7
-
-#define FLASH_STATUS_BUSY_MASK 0x01
-
-// #define FLASH_TEST
-
-#define PACKET_SIZE 32
-
-
-static uint8_t page_buffer[FLASH_PAGE_SIZE];
-static uint32_t base_addr = 0;
-
-void write_entry(uint8_t* data_entry);
-
-void __not_in_flash_func(flash_read)(spi_inst_t *spi, uint cs_pin, uint32_t addr, uint8_t *dest, size_t len);
-
-
-void __not_in_flash_func(flash_write_enable)(spi_inst_t *spi, uint cs_pin);
-void __not_in_flash_func(flash_page_program)(spi_inst_t *spi, uint cs_pin, uint32_t addr, uint8_t* src);
-void __not_in_flash_func(flash_write)(spi_inst_t *spi, uint cs_pin, uint32_t addr, uint8_t* src, size_t size);
-
-void __not_in_flash_func(flash_wait_done)(spi_inst_t *spi, uint cs_pin);
-
-void __not_in_flash_func(flash_sector_erase)(spi_inst_t *spi, uint cs_pin, uint32_t addr);
-void __not_in_flash_func(flash_block_erase)(spi_inst_t *spi, uint cs_pin, uint32_t addr);
-void __not_in_flash_func(flash_erase)(spi_inst_t *spi, uint cs_pin);
-
-#ifdef __cplusplus
-}
-#endif
-#endif
diff --git a/notes.txt b/notes.txt
new file mode 100644
index 0000000..c1e7604
--- /dev/null
+++ b/notes.txt
@@ -0,0 +1,15 @@
++ADXL375_AXIS_ALONG = +X
++ADXL375_AXIS_ACROSS = +Y
++ADXL375_AXIS_THROUGH = -Z
+
++MMC5983MA_AXIS_ALONG = -Y
++MMC5983MA_AXIS_ACROSS = +X
++MMC5983MA_AXIS_THROUGH = +Z
+
++IIM42653_AXIS_ALONG = +Y
++IIM42653_AXIS_ACROSS = -X
++IIM42653_AXIS_THROUGH = -Z
+
++IIM42653_AXIS_ROLL = +Y
++IIM42653_AXIS_PITCH = -X
++IIM42653_AXIS_YAW = -Z
diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt
index e372541..9aedf74 100644
--- a/src/CMakeLists.txt
+++ b/src/CMakeLists.txt
@@ -1,17 +1,27 @@
-add_executable(ads
- active_drag_system.cpp
- spi_flash.c
- imu.cpp
- pwm.cpp
- altimeter.cpp
- kalman_filter.cpp
+add_executable(active_drag_system
+ ${PROJECT_SOURCE_DIR}/src/active_drag_system.cpp
+ ${PROJECT_SOURCE_DIR}/src/ms5607.cpp
+ ${PROJECT_SOURCE_DIR}/src/adxl375.cpp
+ ${PROJECT_SOURCE_DIR}/src/iim42653.cpp
+ ${PROJECT_SOURCE_DIR}/src/mmc5983ma.cpp
+ ${PROJECT_SOURCE_DIR}/src/pwm.cpp
+ ${PROJECT_SOURCE_DIR}/src/log_format.cpp
+ ${PROJECT_SOURCE_DIR}/src/heartbeat.cpp
+ ${PROJECT_SOURCE_DIR}/src/serial.cpp
)
-target_link_libraries(ads pico_stdlib pico_multicore pico_sync hardware_i2c hardware_spi hardware_pwm hardware_adc pico_cyw43_arch_none ${Eigen_LIBRARIES})
-target_include_directories(ads PUBLIC ../include)
+pico_set_binary_type(active_drag_system copy_to_ram)
-pico_enable_stdio_usb(ads 0)
-pico_enable_stdio_uart(ads 0)
+target_link_libraries(active_drag_system pico_stdlib pico_logger pico_flash pico_rand pico_multicore pico_sync hardware_i2c hardware_adc hardware_timer hardware_pwm FreeRTOS-Kernel FreeRTOS-Kernel-Heap4 libfixmath libfixmatrix libfixkalman)
+target_include_directories(active_drag_system PUBLIC ${PROJECT_SOURCE_DIR}/include)
+target_compile_definitions(active_drag_system PRIVATE
+ USE_FREERTOS=1
+ # DEBUG=1
+ PICO_STDIO_STACK_BUFFER_SIZE=64 # use a small printf on stack buffer
+)
+
+pico_enable_stdio_usb(active_drag_system 1)
+pico_enable_stdio_uart(active_drag_system 0)
-pico_add_extra_outputs(ads)
+pico_add_extra_outputs(active_drag_system)
diff --git a/src/active_drag_system.cpp b/src/active_drag_system.cpp
index 6f5d57e..ce898bb 100644
--- a/src/active_drag_system.cpp
+++ b/src/active_drag_system.cpp
@@ -1,436 +1,845 @@
-#include "cyw43_configport.h"
-#include "pico/multicore.h"
-#include "pico/platform.h"
-#include "pico/sem.h"
-#include "boards/pico_w.h"
+#include <pico.h>
+#include <stdlib.h>
+#include <stdio.h>
+#include <string.h>
+#include <inttypes.h>
+
#include "hardware/gpio.h"
#include "hardware/i2c.h"
#include "hardware/adc.h"
+#include <hardware/timer.h>
+#include "pico/rand.h"
#include "pico/stdlib.h"
+#include "pico/stdio.h"
+#include "pico/multicore.h"
#include "pico/time.h"
-#include "pico/types.h"
-#include "pico/cyw43_arch.h"
-#include <inttypes.h>
-#include <math.h>
+#include <pico/error.h>
+#include <pico/types.h>
+#include "math.h"
+
+#include "FreeRTOS.h"
+#include "FreeRTOSConfig.h"
+#include "portmacro.h"
+#include "projdefs.h"
+#include "serial.hpp"
+#include "task.h"
+#include "semphr.h"
+
+extern "C" {
+#include <fix16.h>
+#include <fixmatrix.h>
+#include <fixkalman.h>
+}
+#include "adxl375.hpp"
+#include "ms5607.hpp"
+#include "iim42653.hpp"
+#include "mmc5983ma.hpp"
#include "pwm.hpp"
-#include "imu.hpp"
-#include "altimeter.hpp"
-#include "kalman_filter.hpp"
-#include "spi_flash.h"
-
-#define MPL3115A2_ADDR 0x60
-
-#define BNO055_ADDR 0x28
-#define BNO055_ID 0xA0
-
-#define MAX_SCL 400000
-#define DATA_RATE_HZ 100
-#define LOOP_PERIOD (1.0f / DATA_RATE_HZ)
-#define INT1_PIN 6 // INT1 PIN on MPL3115A2 connected to GPIO PIN 9 (GP6)
-#define MOSFET_PIN 26 // MOSFET PIN connected to GPIO PIN 31 (GP26)
-
-#define LOG_RATE_HZ 8
-#define HEART_RATE_HZ 5
-
-#define MOTOR_BURN_TIME 3900 // Burn time in milliseconds for M2500T
-
-#define PAD_SECONDS 8
-#define PAD_BUFFER_SIZE (PACKET_SIZE * LOG_RATE_HZ * PAD_SECONDS)
-
-typedef enum {
- PAD = 0,
- BOOST,
- COAST,
- APOGEE,
- RECOVERY,
- END
-} state_t;
+#include "pico_logger.h"
+#include "log_format.hpp"
+#include "serial.hpp"
+#include "heartbeat.hpp"
+
+/****************************** FREERTOS **************************************/
+#define SENSOR_EVENT_HANDLER_PRIORITY ( tskIDLE_PRIORITY + 7 )
+#define SENSOR_SAMPLE_PRIORITY ( tskIDLE_PRIORITY + 6 )
+#define KALMAN_TASK_PRIORITY ( tskIDLE_PRIORITY + 6 )
+#define ROCKET_TASK_PRIORITY ( tskIDLE_PRIORITY + 4 )
+#define ROCKET_EVENT_HANDLER_PRIORITY ( tskIDLE_PRIORITY + 3 )
+#define HEARTBEAT_TASK_PRIORITY ( tskIDLE_PRIORITY + 2 )
+#define LOGGING_PRIORITY ( tskIDLE_PRIORITY + 2 )
+#define SERIAL_TASK_PRIORITY ( tskIDLE_PRIORITY + 1 )
+
+void vApplicationTickHook(void) { /* optional */ }
+void vApplicationMallocFailedHook(void) { /* optional */ }
+void vApplicationStackOverflowHook(TaskHandle_t xTask, char *pcTaskName) { for( ;; ); }
+
+static void logging_task(void* pvParameters);
+
+#define ROCKET_TASK_RATE_HZ 50
+volatile TaskHandle_t rocket_task_handle = NULL;
+static void rocket_task(void* pvParameters);
+
+#define KALMAN_TASK_RATE_HZ 50
+volatile TaskHandle_t kalman_task_handle = NULL;
+static void kalman_task(void* pvParameters);
+
+int64_t launch_event_callback(alarm_id_t id, void* user_data);
+int64_t coast_event_callback(alarm_id_t id, void* user_data);
+int64_t end_event_callback(alarm_id_t id, void* user_data);
+
+volatile TaskHandle_t launch_event_handler_task_handle = NULL;
+volatile TaskHandle_t coast_event_handler_task_handle = NULL;
+volatile TaskHandle_t end_event_handler_task_handle = NULL;
+static void launch_event_handler_task(void* pvParameters);
+static void coast_event_handler_task(void* pvParameters);
+static void end_event_handler_task(void* pvParameters);
+
+/****************************** FREERTOS **************************************/
+
+/****************************** SERIAL CONSOLE ********************************/
+static void read_cmd_func();
+static void write_cmd_func();
+static void erase_cmd_func();
+static void show_cmd_func();
+static void deploy_cmd_func();
+static void kalman_cmd_func();
+
+const char* executeable_name = "active-drag-system.uf2";
+const size_t num_user_cmds = 6;
+const command_t user_commands[] = { {.name = "read",
+ .len = 4,
+ .function = &read_cmd_func},
+ {.name = "write",
+ .len = 5,
+ .function = &write_cmd_func},
+ {.name = "erase",
+ .len = 5,
+ .function = &erase_cmd_func},
+ {.name = "show",
+ .len = 4,
+ .function = &show_cmd_func},
+ {.name = "deploy",
+ .len = 6,
+ .function = &deploy_cmd_func},
+ {.name = "kalman",
+ .len = 6,
+ .function = &kalman_cmd_func} };
+/****************************** SERIAL CONSOLE ********************************/
+
+/****************************** LOGGING ***************************************/
+volatile bool use_circular_buffer = true;
+volatile TaskHandle_t logging_handle = NULL;
+volatile log_entry_t log_entry;
+
+Logger logger(PACKET_SIZE, LOG_BASE_ADDR, print_log_entry);
+
+static void populate_log_entry(log_entry_t* log_entry);
+/****************************** LOGGING ***************************************/
+
+volatile bool serial_data_output = false;
+
+MS5607 alt(i2c_default);
+ADXL375 adxl375(i2c_default);
+IIM42653 iim42653(i2c_default);
+MMC5983MA mmc5983ma(i2c_default);
PWM pwm;
-kalman_filter *kf;
-VectorXf control(1);
-VectorXf measurement(1);
-VectorXf res(2);
-
-void pad_callback(uint gpio, uint32_t event_mask);
-int64_t boost_callback(alarm_id_t id, void* user_data);
-int64_t apogee_callback(alarm_id_t id, void* user_data);
-int64_t coast_callback(alarm_id_t id, void* user_data);
-void recovery_callback(uint gpio, uint32_t event_mask);
-float get_deploy_percent(float velocity, float altitude);
-
-bool timer_callback(repeating_timer_t *rt);
-
-void populate_entry();
-bool logging_buffer_callback(repeating_timer_t *rt);
-bool logging_flash_callback(repeating_timer_t *rt);
-bool heartbeat_callback(repeating_timer_t *rt);
-void logging_core();
-
-semaphore_t sem;
-
-volatile float altitude = 0.0f;
-volatile float velocity = 0.0f;
-volatile state_t state = PAD;
-volatile float threshold_altitude = 30.0f;
-volatile float threshold_velocity = 30.0f;
-volatile uint8_t deployment_percent = 0;
-volatile uint8_t led_counter;
-volatile uint32_t pad_buffer_offset = 0;
-Eigen::Vector3f linear_acceleration;
-Eigen::Vector4f quaternion;
-Eigen::Vector3f euler_angles;
-
-volatile calibration_status_t calib_status;
-
-repeating_timer_t data_timer;
-repeating_timer_t log_timer;
-repeating_timer_t heartbeat_timer;
-
-float ground_altitude = 0.0f;
+#define MOTOR_BURN_TIME 6200
+volatile state_t rocket_state = PAD;
+volatile uint8_t deployment_percent = 0;
-altimeter altimeter(i2c_default, MPL3115A2_ADDR);
-imu imu(i2c_default, BNO055_ADDR, BNO055_ID, NDOF);
+volatile int32_t ground_altitude = 0;
+volatile int32_t threshold_altitude = 30;
+
+/****************************** KALMAN ****************************************/
+#define KALMAN_NAME verticality
+#define KALMAN_NUM_STATES 2
+#define KALMAN_NUM_INPUTS 1
+kalman16_t kf;
+
+#define KALMAN_MEASUREMENT_NAME altitude
+#define KALMAN_NUM_MEASUREMENTS 1
+kalman16_observation_t kfm;
+
+#define matrix_set(matrix, row, column, value) \
+ matrix->data[row][column] = value
+
+#define matrix_set_symmetric(matrix, row, column, value) \
+ matrix->data[row][column] = value; \
+ matrix->data[column][row] = value
+
+#ifndef FIXMATRIX_MAX_SIZE
+#error FIXMATRIX_MAX_SIZE must be defined and greater or equal to the number of states, inputs and measurements.
+#endif
+
+#if (FIXMATRIX_MAX_SIZE < KALMAN_NUM_STATES) || (FIXMATRIX_MAX_SIZE < KALMAN_NUM_INPUTS) || (FIXMATRIX_MAX_SIZE < KALMAN_NUM_MEASUREMENTS)
+#error FIXMATRIX_MAX_SIZE must be greater or equal to the number of states, inputs and measurements.
+#endif
+
+static void kalman_verticality_init() {
+ /************************************************************************/
+ /* initialize the filter structures */
+ /************************************************************************/
+ kalman_filter_initialize(&kf, KALMAN_NUM_STATES, KALMAN_NUM_INPUTS);
+ kalman_observation_initialize(&kfm, KALMAN_NUM_STATES, KALMAN_NUM_MEASUREMENTS);
+
+ /************************************************************************/
+ /* set initial state */
+ /************************************************************************/
+ mf16 *x = kalman_get_state_vector(&kf);
+ x->data[0][0] = 0; // s_i
+ x->data[1][0] = 0; // v_i
+
+ /************************************************************************/
+ /* set state transition */
+ /************************************************************************/
+ mf16 *A = kalman_get_state_transition(&kf);
+
+ // set time constant
+#if (DEBUG == 1)
+ const fix16_t T = fix16_from_float(0.02f);
+#else
+ const fix16_t T = fix16_from_float(0.02f);
+#endif
+ const fix16_t Tsquare = fix16_sq(T);
+
+ // helper
+ const fix16_t fix16_half = fix16_from_float(0.5);
+
+ // transition of x to s
+ matrix_set(A, 0, 0, fix16_one); // 1
+ matrix_set(A, 0, 1, T); // T
+
+ // transition of x to v
+ matrix_set(A, 1, 0, 0); // 0
+ matrix_set(A, 1, 1, fix16_one); // 1
+
+
+ /************************************************************************/
+ /* set covariance */
+ /************************************************************************/
+ mf16 *P = kalman_get_system_covariance(&kf);
+
+// matrix_set_symmetric(P, 0, 0, fix16_half); // var(s)
+// matrix_set_symmetric(P, 0, 1, 0); // cov(s,v)
+// matrix_set_symmetric(P, 0, 2, 0); // cov(s,g)
+//
+// matrix_set_symmetric(P, 1, 1, fix16_one); // var(v)
+// matrix_set_symmetric(P, 1, 2, 0); // cov(v,g)
+//
+// matrix_set_symmetric(P, 2, 2, fix16_one); // var(g)
+
+ /************************************************************************/
+ /* set input covariance */
+ /************************************************************************/
+ mf16 *Q = kalman_get_input_covariance(&kf);
+// mf16_fill_diagonal(Q, fix16_one);
+ mf16_mul_bt(Q, A, A);
+ mf16_mul_s(Q, Q, fix16_from_int(10*10));
+
+ /************************************************************************/
+ /* set control input transformation */
+ /************************************************************************/
+ mf16 *B = kalman_get_input_transition(&kf);
+ matrix_set(B, 0, 0, fix16_mul(fix16_half, Tsquare)); // u = 0*s
+ matrix_set(B, 1, 0, T); // + 0*v
+
+ /************************************************************************/
+ /* set measurement transformation */
+ /************************************************************************/
+ mf16 *H = kalman_get_observation_transformation(&kfm);
+ matrix_set(H, 0, 0, fix16_one); // z = 1*s
+ matrix_set(H, 0, 1, 0); // + 0*v
+
+ /************************************************************************/
+ /* set process noise */
+ /************************************************************************/
+ mf16 *R = kalman_get_observation_process_noise(&kfm);
+
+ matrix_set(R, 0, 0, fix16_from_int(36)); // var(s)
+}
-uint8_t *altimeter_buffer;
-uint8_t *acceleration_buffer;
-uint8_t *quaternion_buffer;
+volatile bool derate_baro_sensor = false;
+const fix16_t baro_velocity_derate = F16(160.f);
+
+volatile fix16_t altitude_filt = 0;
+volatile fix16_t velocity_filt = 0;
+
+volatile fix16_t drag_force = 0;
+volatile fix16_t apogee_prediction = 0;
+volatile fix16_t desired_drag_force = 0;
+volatile fix16_t desired_deployment = 0;
+
+void kalman_update(fix16_t altitude, fix16_t vertical_acceleration) {
+ static mf16* control = kalman_get_input_vector(&kf);
+ static mf16* measurement = kalman_get_observation_vector(&kfm);
+ static mf16* Q = kalman_get_input_covariance(&kf);
+ static mf16 *R = kalman_get_observation_process_noise(&kfm);
+ static mf16* state_vector = kalman_get_state_vector(&kf);
+
+ if (state_vector->data[1][0] >= baro_velocity_derate && !derate_baro_sensor) {
+ mf16_div_s(Q, Q, fix16_from_int(3));
+ mf16_mul_s(R, R, fix16_from_int(4));
+ derate_baro_sensor = true;
+ } else if (state_vector->data[1][0] < baro_velocity_derate && derate_baro_sensor) {
+ mf16_mul_s(Q, Q, fix16_from_int(3));
+ mf16_div_s(R, R, fix16_from_int(4));
+ derate_baro_sensor = false;
+ }
+ matrix_set(control, 0, 0, vertical_acceleration);
+ kalman_predict(&kf);
+ matrix_set(measurement, 0, 0, altitude);
+ kalman_correct(&kf, &kfm);
+}
-uint8_t entry_buffer[PACKET_SIZE];
+fix16_t calculate_drag_force(fix16_t deployment_percentage, fix16_t vertical_velocity);
+fix16_t predict_apogee(fix16_t altitude, fix16_t vertical_velocity, fix16_t drag_force);
+fix16_t calculate_deployment_percentage(fix16_t drag_force, fix16_t vertical_velocity);
+fix16_t calculate_desired_drag_force(fix16_t altitude, fix16_t vertical_velocity);
-uint8_t *pad_buffer;
+/****************************** KALMAN ****************************************/
int main() {
+ stdio_init_all();
+
adc_init();
adc_set_temp_sensor_enabled(true);
- cyw43_arch_init();
+ heartbeat_initialize(PICO_DEFAULT_LED_PIN);
- i2c_init(i2c_default, MAX_SCL);
+ i2c_init(i2c_default, 400000);
gpio_set_function(PICO_DEFAULT_I2C_SDA_PIN, GPIO_FUNC_I2C);
gpio_set_function(PICO_DEFAULT_I2C_SCL_PIN, GPIO_FUNC_I2C);
- gpio_pull_up(PICO_DEFAULT_I2C_SDA_PIN);
- gpio_pull_up(PICO_DEFAULT_I2C_SCL_PIN);
-
- // Enable SPI 0 at 60 MHz and connect to GPIOs
- spi_init(spi_default, 1000 * 1000 * 60);
- gpio_set_function(PICO_DEFAULT_SPI_RX_PIN, GPIO_FUNC_SPI);
- gpio_set_function(PICO_DEFAULT_SPI_TX_PIN, GPIO_FUNC_SPI);
- gpio_set_function(PICO_DEFAULT_SPI_SCK_PIN, GPIO_FUNC_SPI);
-
- // Chip select is active-low, so we'll initialise it to a driven-high state
- gpio_init(PICO_DEFAULT_SPI_CSN_PIN);
- gpio_set_dir(PICO_DEFAULT_SPI_CSN_PIN, GPIO_OUT);
- gpio_put(PICO_DEFAULT_SPI_CSN_PIN, 1);
-
- gpio_init(INT1_PIN);
- gpio_pull_up(INT1_PIN);
-
- alarm_pool_init_default();
- altimeter.initialize(30.0f, INT1_PIN, &pad_callback);
+ gpio_init(MICRO_DEFAULT_SERVO_ENABLE);
+ gpio_set_dir(MICRO_DEFAULT_SERVO_ENABLE, GPIO_OUT);
+ gpio_put(MICRO_DEFAULT_SERVO_ENABLE, 0);
+
+ sleep_ms(2500);
+
+ info_cmd_func();
+ stdio_flush();
- imu.initialize();
- imu.linear_acceleration(linear_acceleration);
- imu.quaternion(quaternion);
- imu.quaternion_euler(euler_angles, quaternion);
+ logger.initialize(true);
+ logger.initialize_circular_buffer(PAD_BUFFER_SIZE);
+ alt.initialize();
+ sleep_ms(500);
+ adxl375.initialize();
+ sleep_ms(500);
+ iim42653.initialize();
+ sleep_ms(500);
+ mmc5983ma.initialize();
+ sleep_ms(500);
pwm.init();
- // Initialize MOSFET
- gpio_init(MOSFET_PIN);
- gpio_set_dir(MOSFET_PIN, GPIO_OUT);
+ kalman_verticality_init();
- cyw43_arch_gpio_put(CYW43_WL_GPIO_LED_PIN, 1);
+ xTaskCreate(heartbeat_task, "heartbeat", 256, NULL, HEARTBEAT_TASK_PRIORITY, NULL);
+ xTaskCreate(serial_task, "serial", 8192, NULL, SERIAL_TASK_PRIORITY, NULL);
- pad_buffer = (uint8_t*)malloc(PAD_BUFFER_SIZE);
+ xTaskCreate(MS5607::update_ms5607_task, "update_ms5607", 256, &alt, SENSOR_SAMPLE_PRIORITY, &(alt.update_task_handle));
+ xTaskCreate(ADXL375::update_adxl375_task, "update_adxl375", 256, &adxl375, SENSOR_SAMPLE_PRIORITY, &(adxl375.update_task_handle));
+ xTaskCreate(IIM42653::update_iim42653_task, "update_iim42653", 256, &iim42653, SENSOR_SAMPLE_PRIORITY, &(iim42653.update_task_handle));
+ xTaskCreate(MMC5983MA::update_mmc5983ma_task, "update_mmc5983ma", 256, &mmc5983ma, SENSOR_SAMPLE_PRIORITY, &(mmc5983ma.update_task_handle));
- // Initialize Kalman Filter
- kf = new kalman_filter(2, 1, 1, 0.01);
- VectorXf state_vec(2);
- MatrixXf state_cov(2, 2);
- state_vec << altimeter.get_altitude_converted(), linear_acceleration.z();
- state_cov << 0.018, 0.0, 0.0, 0.0005;
- kf->state_initialize(state_vec, state_cov);
- ground_altitude = altimeter.get_altitude_converted();
+ xTaskCreate(MS5607::ms5607_sample_handler, "ms5607_sample_handler", 256, &alt, SENSOR_EVENT_HANDLER_PRIORITY, &(alt.sample_handler_task_handle));
- altimeter.expose_buffer(&altimeter_buffer);
- imu.expose_acceleration_buffer(&acceleration_buffer);
- imu.expose_quaternion_buffer(&quaternion_buffer);
+ xTaskCreate(rocket_task, "rocket_task", 512, NULL, SENSOR_SAMPLE_PRIORITY, const_cast<TaskHandle_t *>(&rocket_task_handle));
+#if (DEBUG != 1)
+ xTaskCreate(kalman_task, "kalman_task", 512, NULL, KALMAN_TASK_PRIORITY, const_cast<TaskHandle_t *>(&kalman_task_handle));
+ vTaskCoreAffinitySet(kalman_task_handle, 0x01);
+#endif
+ vTaskCoreAffinitySet( alt.update_task_handle, 0x01 );
+ vTaskCoreAffinitySet( adxl375.update_task_handle, 0x01 );
+ vTaskCoreAffinitySet( iim42653.update_task_handle, 0x01 );
+ vTaskCoreAffinitySet( mmc5983ma.update_task_handle, 0x01 );
- sem_init(&sem, 1, 1);
+ vTaskCoreAffinitySet(rocket_task_handle, 0x01);
- add_repeating_timer_us(-1000000 / DATA_RATE_HZ, &timer_callback, NULL, &data_timer);
+ vTaskCoreAffinitySet( alt.sample_handler_task_handle, 0x01 );
- multicore_launch_core1(logging_core);
+ xTaskCreate(logging_task, "logging", 256, NULL, LOGGING_PRIORITY, const_cast<TaskHandle_t *>(&logging_handle));
+ vTaskCoreAffinitySet(logging_handle, 0x02);
+
+ vTaskStartScheduler();
while (1) {
tight_loop_contents();
}
}
-// PRIMARY THREAD RELATED FUNCTIONS AND CALLBACKS
-//===============================================================================
-
-bool timer_callback(repeating_timer_t *rt) {
- sem_acquire_blocking(&sem);
- imu.linear_acceleration(linear_acceleration);
- imu.quaternion(quaternion);
-
- control(0) = linear_acceleration.z();
- measurement(0) = altimeter.get_altitude_converted();
- res = kf->run(control, measurement, 0.01f);
- altitude = res(0);
- velocity = res(1);
-
-
- deployment_percent = (uint8_t)(std::min(std::max(30.0f, get_deploy_percent(velocity, (altitude - ground_altitude))), 100.0f));
-
- switch(state) {
- case PAD:
- gpio_put(MOSFET_PIN, 0);
- pwm.set_servo_percent(0);
- deployment_percent = 0;
- break;
- case BOOST:
- gpio_put(MOSFET_PIN, 1);
- pwm.set_servo_percent(0);
- deployment_percent = 0;
- break;
- case COAST:
- gpio_put(MOSFET_PIN, 1);
- pwm.set_servo_percent(deployment_percent);
- break;
- case APOGEE:
- gpio_put(MOSFET_PIN, 1);
- pwm.set_servo_percent(0);
- deployment_percent = 0;
- break;
- case RECOVERY:
- gpio_put(MOSFET_PIN, 1);
- pwm.set_servo_percent(0);
- deployment_percent = 0;
- break;
- case END:
- gpio_put(MOSFET_PIN, 1);
- pwm.set_servo_percent(0);
- deployment_percent = 0;
- break;
- }
- sem_release(&sem);
- return true;
+/****************************** LOGGING ***************************************/
+static void populate_log_entry(log_entry_t* log_entry) {
+ log_entry->time_us = time_us_64();
+
+ adc_select_input(4);
+ log_entry->temperature_chip = adc_read();
+ log_entry->state = rocket_state;
+ log_entry->deploy_percent = deployment_percent;
+ log_entry->pressure = alt.get_pressure();
+ log_entry->altitude = alt.get_altitude();
+ log_entry->altitude_filt = altitude_filt;
+ log_entry->velocity_filt = velocity_filt;
+ log_entry->temperature_alt = alt.get_temperature();
+
+ log_entry->ax = iim42653.get_ax();
+ log_entry->ay = iim42653.get_ay();
+ log_entry->az = iim42653.get_az();
+ log_entry->gx = iim42653.get_gx();
+ log_entry->gy = iim42653.get_gy();
+ log_entry->gz = iim42653.get_gz();
+
+ log_entry->mag_x = mmc5983ma.get_ax();
+ log_entry->mag_y = mmc5983ma.get_ay();
+ log_entry->mag_z = mmc5983ma.get_az();
+
+ log_entry->high_g_x = adxl375.get_ax();
+ log_entry->high_g_y = adxl375.get_ay();
+ log_entry->high_g_z = adxl375.get_az();
+
+ log_entry->drag_force = drag_force;
+ log_entry->apogee_prediction = apogee_prediction;
+ log_entry->desired_drag_force = desired_drag_force;
+
+ log_entry->data0 = get_rand_32();
}
-/**
- * @brief Call back function for when rocket is on the pad
- *
- * @param gpio pin number of interrupt
- * @param event_mask interrupt condition, value is set by PICO_SDK
- * GPIO_IRQ_LEVEL_LOW = 0x1u,
- * GPIO_IRQ_LEVEL_HIGH = 0x2u,
- * GPIO_IRQ_EDGE_FALL = 0x4u,
- * GPIO_IRQ_EDGE_RISE = 0x8u,
- * @link https://www.raspberrypi.com/documentation/pico-sdk/hardware/gpio.html#ga6347e27da3ab34f1ea65b5ae16ab724f
- */
-void pad_callback(uint gpio, uint32_t event_mask) {
- sem_acquire_blocking(&sem);
- altimeter.unset_threshold_altitude(INT1_PIN);
- state = BOOST;
- sem_release(&sem);
- // start motor burn timer with boost transition function as callback
- add_alarm_in_ms(MOTOR_BURN_TIME, &boost_callback, NULL, false);
+static void logging_task(void* pvParameters) {
+ TickType_t xLastWakeTime;
+ const TickType_t xFrequency = pdMS_TO_TICKS(1000 / LOG_RATE_HZ);
+
+ xLastWakeTime = xTaskGetTickCount();
+ while (1) {
+ vTaskDelayUntil(&xLastWakeTime, xFrequency);
+ populate_log_entry(const_cast<log_entry_t *>(&log_entry));
+ if (serial_data_output) {
+ print_log_entry(reinterpret_cast<const uint8_t *>(const_cast<log_entry_t *>(&log_entry)));
+ stdio_flush();
+ }
+
+ if (use_circular_buffer) {
+ logger.write_circular_buffer(reinterpret_cast<const uint8_t *>(const_cast<log_entry_t *>(&log_entry)));
+ if (rocket_state != PAD) {
+ logger.flush_circular_buffer(true);
+ use_circular_buffer = false;
+ }
+ } else {
+ logger.write_memory(reinterpret_cast<const uint8_t *>(const_cast<log_entry_t *>(&log_entry)), false);
+ }
+ if ((xLastWakeTime + xFrequency) < xTaskGetTickCount()) {
+ xLastWakeTime = xTaskGetTickCount();
+ }
+ }
}
+/****************************** LOGGING ***************************************/
-int64_t boost_callback(alarm_id_t id, void* user_data) {
- // Configure accelerometer and/or altimeter to generate interrupt
- // for when velocity is negative with this function as callback to
- // transition to APOGEE
- sem_acquire_blocking(&sem);
- state = COAST;
- populate_entry();
- write_entry(entry_buffer);
- sem_release(&sem);
- add_alarm_in_ms(1000, &coast_callback, NULL, false);
- return 0;
+/****************************** SERIAL CONSOLE ********************************/
+static void read_cmd_func() {
+ if (logging_handle != NULL) {
+ vTaskSuspend(logging_handle);
+ }
+ logger.read_memory();
+ if (logging_handle != NULL) {
+ vTaskResume(logging_handle);
+ }
}
-int64_t coast_callback(alarm_id_t id, void* user_data) {
- // Want to somehow immediately transition to RECOVERY from APOGEE (extremely short timer?)
- if (velocity <= 0.0f) {
- sem_acquire_blocking(&sem);
- state = APOGEE;
- populate_entry();
- write_entry(entry_buffer);
- sem_release(&sem);
- add_alarm_in_ms(1, &apogee_callback, NULL, false);
+static void write_cmd_func() {
+ if (logging_handle != NULL) {
+ vTaskSuspend(logging_handle);
+ }
+ uint64_t start = time_us_64();
+ log_entry_t log_entry;
+ populate_log_entry(&log_entry);
+ printf("\nWriting the following entry!\n");
+ print_log_entry(reinterpret_cast<const uint8_t *>(&log_entry));
+ if (use_circular_buffer) {
+ logger.write_circular_buffer(reinterpret_cast<const uint8_t *>(&log_entry));
} else {
- add_alarm_in_ms(250, &coast_callback, NULL, false);
+ logger.write_memory(reinterpret_cast<const uint8_t *>(&log_entry), true);
+ }
+ uint64_t end = time_us_64();
+ printf("\nTook %" PRIu64 " us to write that entry!\n", (end - start));
+ if (logging_handle != NULL) {
+ vTaskResume(logging_handle);
}
- return 0;
}
-int64_t apogee_callback(alarm_id_t id, void* user_data) {
- state = RECOVERY;
- // Set altimeter interrupt to occur for when rocket touches back to the ground
- altimeter.set_threshold_altitude((ground_altitude + 10.0f), INT1_PIN, &recovery_callback);
+static void erase_cmd_func() {
+ if (logging_handle != NULL) {
+ vTaskSuspend(logging_handle);
+ }
+ logger.erase_memory();
+ if (logging_handle != NULL) {
+ vTaskResume(logging_handle);
+ }
+}
- sem_acquire_blocking(&sem);
- populate_entry();
- write_entry(entry_buffer);
- sem_release(&sem);
- return 0;
+static void show_cmd_func() {
+ serial_data_output = !serial_data_output;
+}
+
+static void deploy_cmd_func() {
+ vTaskSuspend(rocket_task_handle);
+ printf("Enabling servo!\n");
+ gpio_put(MICRO_DEFAULT_SERVO_ENABLE, 1);
+ vTaskDelay(pdMS_TO_TICKS(1000));
+ printf("Setting servo to 80%\n");
+ pwm.set_servo_percent(80);
+ vTaskDelay(pdMS_TO_TICKS(5000));
+ printf("Setting servo to 0%\n");
+ pwm.set_servo_percent(0);
+ vTaskDelay(pdMS_TO_TICKS(5000));
+ printf("Setting servo to 80%\n");
+ pwm.set_servo_percent(80);
+ vTaskDelay(pdMS_TO_TICKS(5000));
+ printf("Setting servo to 0%\n");
+ pwm.set_servo_percent(0);
+ vTaskDelay(pdMS_TO_TICKS(5000));
+ printf("Disabling servo!\n");
+ gpio_put(MICRO_DEFAULT_SERVO_ENABLE, 0);
+ vTaskResume(rocket_task_handle);
}
-void recovery_callback(uint gpio, uint32_t event_mask) {
- // Essentially just a signal to stop logging data
- sem_acquire_blocking(&sem);
- state = END;
- populate_entry();
- write_entry(entry_buffer);
- sem_acquire_blocking(&sem);
+#if (DEBUG == 1)
+#include "ohio_test_data.h"
+#endif
+
+static void kalman_cmd_func() {
+ static mf16* state_vector = kalman_get_state_vector(&kf);
+ printf("Perfoming Kalman Filter Test! Stand back!\n");
+ printf("*******************************************\n");
+ printf("\naltitude,velocity,acceleration,drag_force,apogee_prediction,desired_drag_force,desired_deployment\n");
+
+ fix16_t drag_force_l = 0;
+ fix16_t apogee_prediction_l = 0;
+ fix16_t desired_drag_force_l = 0;
+ fix16_t desired_deployment_l = 0;
+#if (DEBUG == 1)
+ for (uint32_t i = 0; i < 7500; i++) {
+ kalman_update(altitude_test_data[i], fix16_mul(fix16_sub(acceleration_data[i], fix16_one), F16(9.81f)));
+
+ if (i >= 693 && i <= 1632) {
+ drag_force_l = calculate_drag_force(fix16_from_int(80), state_vector->data[1][0]);
+ } else {
+ drag_force_l = calculate_drag_force(0, state_vector->data[1][0]);
+ }
+ apogee_prediction_l = predict_apogee(state_vector->data[0][0], state_vector->data[1][0], drag_force_l);
+ desired_drag_force_l = calculate_desired_drag_force(state_vector->data[0][0], state_vector->data[1][0]);
+ desired_deployment_l = calculate_deployment_percentage(desired_drag_force_l, state_vector->data[1][0]);
+ desired_deployment_l = fix16_clamp(desired_deployment_l, 0, fix16_from_int(100));
+ printf("%4.2f,%4.2f,%4.2f,%4.2f,%4.2f,%4.2f,%4.2f\n", fix16_to_float(state_vector->data[0][0]), fix16_to_float(state_vector->data[1][0]), fix16_to_float(fix16_mul(acceleration_data[i], F16(9.81f))), fix16_to_float(drag_force_l), fix16_to_float(apogee_prediction_l), fix16_to_float(desired_drag_force_l), fix16_to_float(desired_deployment_l));
+ stdio_flush();
+ }
+#else
+ kalman_update(0, 0);
+#endif
+}
+/****************************** SERIAL CONSOLE ********************************/
+
+
+static void rocket_task(void* pvParameters) {
+ TickType_t xLastWakeTime;
+ const TickType_t xFrequency = pdMS_TO_TICKS(1000 / ROCKET_TASK_RATE_HZ);
+
+ vTaskDelay(pdMS_TO_TICKS(1000));
+ ground_altitude = alt.get_altitude();
+
+ // Sign of life
+ gpio_put(MICRO_DEFAULT_SERVO_ENABLE, 1);
+ pwm.set_servo_percent(0);
+ vTaskDelay(pdMS_TO_TICKS(1000));
+ pwm.set_servo_percent(20);
+ vTaskDelay(pdMS_TO_TICKS(3000));
+ pwm.set_servo_percent(0);
+ vTaskDelay(pdMS_TO_TICKS(3000));
+ pwm.set_servo_percent(20);
+ vTaskDelay(pdMS_TO_TICKS(3000));
+ pwm.set_servo_percent(0);
+ vTaskDelay(pdMS_TO_TICKS(3000));
+ gpio_put(MICRO_DEFAULT_SERVO_ENABLE, 0);
+
+ xTaskCreate(launch_event_handler_task, "launch_event_handler", 512, NULL, ROCKET_EVENT_HANDLER_PRIORITY, const_cast<TaskHandle_t *>(&launch_event_handler_task_handle));
+ vTaskCoreAffinitySet(launch_event_handler_task_handle, 0x01);
+ alt.set_threshold_altitude(ground_altitude + (threshold_altitude * ALTITUDE_SCALE), &launch_event_callback);
+
+ xLastWakeTime = xTaskGetTickCount();
+ while (1) {
+ vTaskDelayUntil(&xLastWakeTime, xFrequency);
+
+ drag_force = calculate_drag_force(fix16_from_int(deployment_percent), velocity_filt);
+ apogee_prediction = predict_apogee(altitude_filt, velocity_filt, drag_force);
+ desired_drag_force = calculate_desired_drag_force(altitude_filt, velocity_filt);
+ desired_deployment = calculate_deployment_percentage(desired_drag_force, velocity_filt);
+ desired_deployment = fix16_clamp(desired_deployment, 0, fix16_from_int(100));
+
+ switch(rocket_state) {
+ case PAD:
+ deployment_percent = 0;
+ pwm.set_servo_percent(deployment_percent);
+ gpio_put(MICRO_DEFAULT_SERVO_ENABLE, 0);
+ break;
+ case BOOST:
+ gpio_put(MICRO_DEFAULT_SERVO_ENABLE, 1);
+ deployment_percent = 0;
+ pwm.set_servo_percent(deployment_percent);
+ break;
+ case COAST:
+ gpio_put(MICRO_DEFAULT_SERVO_ENABLE, 1);
+ if (velocity_filt <= 0) {
+ rocket_state = APOGEE;
+ populate_log_entry(const_cast<log_entry_t *>(&log_entry));
+ logger.write_memory(reinterpret_cast<const uint8_t *>(const_cast<log_entry_t *>(&log_entry)), false);
+ deployment_percent = 0;
+ pwm.set_servo_percent(deployment_percent);
+ rocket_state = RECOVERY;
+ xTaskCreate(end_event_handler_task, "end_event_handler", 1024, NULL, ROCKET_EVENT_HANDLER_PRIORITY, const_cast<TaskHandle_t *>(&end_event_handler_task_handle));
+ vTaskCoreAffinitySet(end_event_handler_task_handle, 0x01);
+ add_alarm_in_ms(450000, end_event_callback, NULL, false);
+ }
+ deployment_percent = desired_deployment;
+ if ((alt.get_altitude() - ground_altitude)> (2895 * ALTITUDE_SCALE)) {
+ deployment_percent = 100;
+ }
+ pwm.set_servo_percent(deployment_percent);
+ break;
+ case APOGEE:
+ gpio_put(MICRO_DEFAULT_SERVO_ENABLE, 1);
+ deployment_percent = 0;
+ pwm.set_servo_percent(deployment_percent);
+ break;
+ case RECOVERY:
+ gpio_put(MICRO_DEFAULT_SERVO_ENABLE, 1);
+ deployment_percent = 0;
+ pwm.set_servo_percent(deployment_percent);
+ break;
+ case END:
+ deployment_percent = 0;
+ pwm.set_servo_percent(deployment_percent);
+ vTaskDelay(pdMS_TO_TICKS(1000));
+ gpio_put(MICRO_DEFAULT_SERVO_ENABLE, 0);
+ vTaskDelete(logging_handle);
+ vTaskDelete(end_event_handler_task_handle);
+ vTaskDelete(rocket_task_handle);
+ break;
+ }
+
+ if ((xLastWakeTime + xFrequency) < xTaskGetTickCount()) {
+ xLastWakeTime = xTaskGetTickCount();
+ }
+ }
}
-/**
- * @brief Calculates the fitted Coeficient of Drag using the Surface Fit Model for the current rocket design.
- * @param velocity Velocity
- * @param altitude Altitude
- *
- * @return: Drag Coefficient (CD)
- */
-float get_deploy_percent(float velocity, float altitude) {
- // Lookup table (Data from 'dragSurfFit.m' for Surface Fit Model Formula)
- float p00 = -8.498e+04;
- float p10 = 924.4;
- float p01 = 69.98;
- float p20 = -3.62;
- float p11 = -0.6196;
- float p02 = -0.01897;
- float p30 = 0.005983;
- float p21 = 0.001756;
- float p12 = 0.0001271;
- float p03 = 1.693e-06;
- float p40 = -3.451e-06;
- float p31 = -1.582e-06;
- float p22 = -2.004e-07;
- float p13 = -7.476e-09;
-
-
- /* MATLAB Code:
- * return p00 + p10 * V + p01 * H + p20 * V ** 2 + \
- * p11 * V * H + p02 * H ** 2 + p30 * V ** 3 + \
- * p21 * V ** 2 * H + p12 * V * H ** 2 + p03 * H ** 3 + \
- * p40 * V ** 4 + p31 * V ** 3 * H + p22 * V ** 2 * H ** 2 + \
- * p13 * V * H ** 3
- */
-
- return (p00 + p10 * velocity + p01 * altitude + p20 * std::pow(velocity, 2) + p11 * velocity * altitude + p02 * std::pow(altitude, 2)
- + p30 * std::pow(velocity, 3) + p21 * std::pow(velocity, 2) * altitude + p12 * velocity * std::pow(altitude, 2) + p03 * std::pow(altitude, 3)
- + p40 * std::pow(velocity, 4) + p31 * std::pow(velocity, 3) * altitude + p22 * std::pow(velocity, 2) * std::pow(altitude, 2) + p13 * velocity * std::pow(altitude, 3));
+static void kalman_task(void* pvParameters) {
+ TickType_t xLastWakeTime;
+ const TickType_t xFrequency = pdMS_TO_TICKS(1000 / KALMAN_TASK_RATE_HZ);
+ const fix16_t accel_scale = fix16_div(F16(9.81f), F16(S_IIM42653_ACCEL_SENSITIVITY_FACTOR));
+
+ mf16* state_vector = kalman_get_state_vector(&kf);
+ fix16_t altitude_agl = 0;
+ fix16_t vertical_accel = 1;
+
+ xLastWakeTime = xTaskGetTickCount();
+ while (1) {
+ vTaskDelayUntil(&xLastWakeTime, xFrequency);
+ taskENTER_CRITICAL();
+ altitude_agl = fix16_div(fix16_from_int(alt.get_altitude() - ground_altitude), fix16_from_int(ALTITUDE_SCALE));
+ vertical_accel = fix16_mul(fix16_sub(fix16_from_int(iim42653.get_az()), fix16_one), accel_scale);
+ kalman_update(altitude_agl, vertical_accel);
+ altitude_filt = state_vector->data[0][0];
+ velocity_filt = state_vector->data[1][0];
+ taskEXIT_CRITICAL();
+ if ((xLastWakeTime + xFrequency) < xTaskGetTickCount()) {
+ xLastWakeTime = xTaskGetTickCount();
+ }
+ }
+}
+static void launch_event_handler_task(void* pvParameters) {
+ const TickType_t xInterruptFrequency = pdMS_TO_TICKS( 1000 );
+ const TickType_t xMaxExpectedBlockTime = xInterruptFrequency + pdMS_TO_TICKS( 500 );
+ uint32_t ulEventsToProcess;
+ while (1) {
+ /* Wait to receive a notification sent directly to this task from the
+ interrupt service routine. */
+ ulEventsToProcess = ulTaskNotifyTake( pdTRUE, xMaxExpectedBlockTime );
+ if( ulEventsToProcess != 0 ) {
+ /* To get here at least one event must have occurred. Loop here
+ until all the pending events have been processed */
+ while( ulEventsToProcess > 0 ) {
+ vTaskSuspendAll();
+ rocket_state = BOOST;
+ xTaskCreate(coast_event_handler_task, "coast_event_handler", 512, NULL, ROCKET_EVENT_HANDLER_PRIORITY, const_cast<TaskHandle_t *>(&coast_event_handler_task_handle));
+ vTaskCoreAffinitySet(coast_event_handler_task_handle, 0x01);
+ add_alarm_in_ms(MOTOR_BURN_TIME, coast_event_callback, NULL, false);
+ vTaskDelete(launch_event_handler_task_handle);
+ launch_event_handler_task_handle = NULL;
+ xTaskResumeAll();
+ }
+ }
+ }
}
-// LOGGING THREAD RELATED FUNCTIONS AND CALLBACKS
-//===============================================================================
+static void coast_event_handler_task(void* pvParameters) {
+ const TickType_t xInterruptFrequency = pdMS_TO_TICKS( MOTOR_BURN_TIME );
+ const TickType_t xMaxExpectedBlockTime = xInterruptFrequency + pdMS_TO_TICKS( 500 );
+ uint32_t ulEventsToProcess;
+ while (1) {
+ /* Wait to receive a notification sent directly to this task from the
+ interrupt service routine. */
+ ulEventsToProcess = ulTaskNotifyTake( pdTRUE, xMaxExpectedBlockTime );
+ if( ulEventsToProcess != 0 ) {
+ /* To get here at least one event must have occurred. Loop here
+ until all the pending events have been processed */
+ while( ulEventsToProcess > 0 ) {
+ vTaskSuspendAll();
+ rocket_state = COAST;
+ vTaskDelete(coast_event_handler_task_handle);
+ coast_event_handler_task_handle = NULL;
+ xTaskResumeAll();
+ }
+ }
+ }
+}
-void logging_core() {
- add_repeating_timer_us(-1000000 / LOG_RATE_HZ, &logging_buffer_callback, NULL, &log_timer);
- add_repeating_timer_us(-1000000 / HEART_RATE_HZ, &heartbeat_callback, NULL, &heartbeat_timer);
+static void end_event_handler_task(void* pvParameters) {
+ const TickType_t xInterruptFrequency = pdMS_TO_TICKS( 30000 );
+ const TickType_t xMaxExpectedBlockTime = xInterruptFrequency + pdMS_TO_TICKS( 500 );
+ uint32_t ulEventsToProcess;
while (1) {
- tight_loop_contents();
+ /* Wait to receive a notification sent directly to this task from the
+ interrupt service routine. */
+ ulEventsToProcess = ulTaskNotifyTake( pdTRUE, xMaxExpectedBlockTime );
+ if( ulEventsToProcess != 0 ) {
+ /* To get here at least one event must have occurred. Loop here
+ until all the pending events have been processed */
+ while( ulEventsToProcess > 0 ) {
+ rocket_state = END;
+ vTaskDelete(end_event_handler_task_handle);
+ end_event_handler_task_handle = NULL;
+ }
+ }
}
}
-void populate_entry() {
- absolute_time_t now = get_absolute_time();
- uint64_t now_us = to_us_since_boot(now);
- uint32_t vel_bits = *((uint32_t *)&velocity);
- entry_buffer[0] = now_us >> 56;
- entry_buffer[1] = now_us >> 48;
- entry_buffer[2] = now_us >> 40;
- entry_buffer[3] = now_us >> 32;
- entry_buffer[4] = now_us >> 24;
- entry_buffer[5] = now_us >> 16;
- entry_buffer[6] = now_us >> 8;
- entry_buffer[7] = now_us;
+int64_t launch_event_callback(alarm_id_t id, void* user_data) {
+ BaseType_t xHigherPriorityTaskWoken;
+ xHigherPriorityTaskWoken = pdFALSE;
+ // Defer ISR handling to separate handler within FreeRTOS context
+ vTaskNotifyGiveFromISR(launch_event_handler_task_handle, &xHigherPriorityTaskWoken );
+ portYIELD_FROM_ISR( xHigherPriorityTaskWoken );
+ return 0;
+}
- adc_select_input(4);
- uint16_t temperature = adc_read();
- entry_buffer[8] = ((*(uint8_t *)(&state)) << 4) | (temperature >> 8);
- entry_buffer[9] = temperature;
-
- entry_buffer[10] = deployment_percent;
- entry_buffer[11] = altimeter_buffer[0];
- entry_buffer[12] = altimeter_buffer[1];
- entry_buffer[13] = altimeter_buffer[2];
- entry_buffer[14] = vel_bits >> 24;
- entry_buffer[15] = vel_bits >> 16;
- entry_buffer[16] = vel_bits >> 8;
- entry_buffer[17] = vel_bits;
- entry_buffer[18] = acceleration_buffer[0];
- entry_buffer[19] = acceleration_buffer[1];
- entry_buffer[20] = acceleration_buffer[2];
- entry_buffer[21] = acceleration_buffer[3];
- entry_buffer[22] = acceleration_buffer[4];
- entry_buffer[23] = acceleration_buffer[5];
- entry_buffer[24] = quaternion_buffer[0];
- entry_buffer[25] = quaternion_buffer[1];
- entry_buffer[26] = quaternion_buffer[2];
- entry_buffer[27] = quaternion_buffer[3];
- entry_buffer[28] = quaternion_buffer[4];
- entry_buffer[29] = quaternion_buffer[5];
- entry_buffer[30] = quaternion_buffer[6];
- entry_buffer[31] = quaternion_buffer[7];
+int64_t coast_event_callback(alarm_id_t id, void* user_data) {
+ BaseType_t xHigherPriorityTaskWoken;
+ xHigherPriorityTaskWoken = pdFALSE;
+ // Defer ISR handling to separate handler within FreeRTOS context
+ vTaskNotifyGiveFromISR(coast_event_handler_task_handle, &xHigherPriorityTaskWoken );
+ portYIELD_FROM_ISR( xHigherPriorityTaskWoken );
+ return 0;
}
-bool logging_buffer_callback(repeating_timer_t *rt) {
- sem_acquire_blocking(&sem);
- populate_entry();
- sem_release(&sem);
- for (uint32_t i = 0; i < PACKET_SIZE; i++) {
- pad_buffer[i + pad_buffer_offset] = entry_buffer[i];
- }
- pad_buffer_offset += PACKET_SIZE;
- pad_buffer_offset %= PAD_BUFFER_SIZE;
-
- if (state != PAD) {
- uint32_t idx = ((pad_buffer_offset + PACKET_SIZE) % PAD_BUFFER_SIZE);
- sem_acquire_blocking(&sem);
- do {
- write_entry(pad_buffer + idx);
- idx += PACKET_SIZE;
- idx %= PAD_BUFFER_SIZE;
- } while (idx != pad_buffer_offset);
- sem_release(&sem);
- cancel_repeating_timer(&log_timer);
- free(pad_buffer);
- add_repeating_timer_us(-1000000 / LOG_RATE_HZ, &logging_flash_callback, NULL, &log_timer);
- }
- return true;
+int64_t end_event_callback(alarm_id_t id, void* user_data) {
+ BaseType_t xHigherPriorityTaskWoken;
+ xHigherPriorityTaskWoken = pdFALSE;
+ // Defer ISR handling to separate handler within FreeRTOS context
+ vTaskNotifyGiveFromISR(end_event_handler_task_handle, &xHigherPriorityTaskWoken );
+ portYIELD_FROM_ISR( xHigherPriorityTaskWoken );
+ return 0;
}
-bool logging_flash_callback(repeating_timer_t *rt) {
- sem_acquire_blocking(&sem);
- populate_entry();
- write_entry(entry_buffer);
- sem_release(&sem);
- if (state == END) {
- cancel_repeating_timer(&log_timer);
- }
- return true;
+fix16_t calculate_drag_force(fix16_t deployment_percentage, fix16_t vertical_velocity) {
+ static const fix16_t p00 = F16(125.f);
+ static const fix16_t p10 = F16(-3.286f);
+ static const fix16_t p01 = F16(-1.803f);
+ static const fix16_t p20 = F16(0.01675f);
+ static const fix16_t p11 = F16(0.02687f);
+ static const fix16_t p02 = F16(0.008441f);
+
+ fix16_t term1 = fix16_mul(p10, deployment_percentage);
+ fix16_t term2 = fix16_mul(p01, vertical_velocity);
+ fix16_t term3 = fix16_mul(p20, fix16_sq(deployment_percentage));
+ fix16_t term4 = fix16_mul(fix16_mul(p11, vertical_velocity), deployment_percentage);
+ fix16_t term5 = fix16_mul(fix16_mul(p02, vertical_velocity), vertical_velocity);
+
+ fix16_t drag_force = fix16_add(p00, term1);
+ drag_force = fix16_add(drag_force, term2);
+ drag_force = fix16_add(drag_force, term3);
+ drag_force = fix16_add(drag_force, term4);
+ drag_force = fix16_add(drag_force, term5);
+
+ return drag_force;
}
-bool heartbeat_callback(repeating_timer_t *rt) {
- const bool sequence[] = {true, false, true, false, false};
- const uint8_t sequence_length = 5;
+fix16_t predict_apogee(fix16_t altitude, fix16_t vertical_velocity, fix16_t drag_force) {
+ static const fix16_t gravity = F16(9.81f);
+ static const fix16_t mass = F16(21.8f);
+
+ fix16_t nal_log_internal = fix16_div(gravity, fix16_add(gravity, fix16_div(drag_force, mass)));
+ fix16_t nal_log_scale = fix16_mul(fix16_mul(fix16_div(vertical_velocity, fix16_mul(F16(2), drag_force)), vertical_velocity), mass);
+ fix16_t apogee_prediction = fix16_sub(altitude, fix16_mul(nal_log_scale, fix16_log(nal_log_internal)));
+ return apogee_prediction;
+}
- bool led_status = sequence[led_counter];
- cyw43_arch_gpio_put(CYW43_WL_GPIO_LED_PIN, led_status);
- led_counter++;
- led_counter %= sequence_length;
- return true;
+fix16_t calculate_deployment_percentage(fix16_t drag_force, fix16_t vertical_velocity) {
+ static const fix16_t p00 = F16(79.05f);
+ static const fix16_t p10 = F16(1.057f);
+ static const fix16_t p01 = F16(-1.049f);
+ static const fix16_t p20 = F16(-7.296e-5f);
+ static const fix16_t p11 = F16(-0.003321f);
+ static const fix16_t p02 = F16(0.002322f);
+
+
+ fix16_t term1 = fix16_mul(p10, drag_force);
+ fix16_t term2 = fix16_mul(p01, vertical_velocity);
+ fix16_t term3 = fix16_mul(fix16_mul(p20, drag_force), drag_force);
+ fix16_t term4 = fix16_mul(fix16_mul(p11, drag_force), vertical_velocity);
+ fix16_t term5 = fix16_mul(fix16_mul(p02, vertical_velocity), vertical_velocity);
+
+ fix16_t deployment_percentage = fix16_add(p00, term1);
+ deployment_percentage = fix16_add(deployment_percentage, term2);
+ deployment_percentage = fix16_add(deployment_percentage, term3);
+ deployment_percentage = fix16_add(deployment_percentage, term4);
+ deployment_percentage = fix16_add(deployment_percentage, term5);
+ deployment_percentage = fix16_clamp(deployment_percentage, 0, fix16_from_int(100));
+ return deployment_percentage;
}
+fix16_t calculate_desired_drag_force(fix16_t altitude, fix16_t vertical_velocity) {
+ static const fix16_t p00 = F16(-2.042e+01);
+ static const fix16_t p10 = F16(2.879e+01);
+ static const fix16_t p01 = F16(2.391e+02);
+ static const fix16_t p20 = F16(-1.265e+01);
+ static const fix16_t p11 = F16(-2.499e+02);
+ static const fix16_t p02 = F16(-1.063e+03);
+ static const fix16_t p30 = F16(1.774);
+ static const fix16_t p21 = F16(7.604e+01);
+ static const fix16_t p12 = F16(7.028e+02);
+ static const fix16_t p03 = F16(2.135e+03);
+ static const fix16_t p31 = F16(-6.349);
+ static const fix16_t p22 = F16(-1.049e+02);
+ static const fix16_t p13 = F16(-6.41e+02);
+ static const fix16_t p04 = F16(-1.604e+03);
+
+ fix16_t altitude_km = fix16_div(altitude, fix16_from_int(1000));
+ fix16_t vertical_velocity_km = fix16_div(vertical_velocity_km, fix16_from_int(1000));
+
+ fix16_t term01 = fix16_mul(p10, altitude_km);
+ fix16_t term02 = fix16_mul(p01, vertical_velocity_km);
+ fix16_t term03 = fix16_mul(fix16_mul(p20, altitude_km), altitude_km);
+ fix16_t term04 = fix16_mul(fix16_mul(p11, altitude_km), vertical_velocity_km);
+ fix16_t term05 = fix16_mul(fix16_mul(p02, vertical_velocity_km), vertical_velocity_km);
+ fix16_t term06 = fix16_mul(fix16_mul(fix16_mul(p30, altitude_km), altitude_km), altitude_km);
+ fix16_t term07 = fix16_mul(fix16_mul(fix16_mul(p21, altitude_km), altitude_km), vertical_velocity_km);
+ fix16_t term08 = fix16_mul(fix16_mul(fix16_mul(p12, altitude_km), vertical_velocity_km), vertical_velocity_km);
+ fix16_t term09 = fix16_mul(fix16_mul(fix16_mul(p03, vertical_velocity_km), vertical_velocity_km), vertical_velocity_km);
+ fix16_t term10 = fix16_mul(fix16_mul(fix16_mul(fix16_mul(p31, altitude_km), altitude_km), altitude_km), vertical_velocity_km);
+ fix16_t term11 = fix16_mul(fix16_mul(fix16_mul(fix16_mul(p22, altitude_km), altitude_km), vertical_velocity_km), vertical_velocity_km);
+ fix16_t term12 = fix16_mul(fix16_mul(fix16_mul(fix16_mul(p13, altitude_km), vertical_velocity_km), vertical_velocity_km), vertical_velocity_km);
+ fix16_t term13 = fix16_mul(fix16_mul(fix16_mul(fix16_mul(p04, vertical_velocity_km), vertical_velocity_km), vertical_velocity_km), vertical_velocity_km);
+
+ fix16_t desired_drag_force = fix16_add(p00, term01);
+ desired_drag_force = fix16_add(desired_drag_force, term02);
+ desired_drag_force = fix16_add(desired_drag_force, term03);
+ desired_drag_force = fix16_add(desired_drag_force, term04);
+ desired_drag_force = fix16_add(desired_drag_force, term05);
+ desired_drag_force = fix16_add(desired_drag_force, term06);
+ desired_drag_force = fix16_add(desired_drag_force, term07);
+ desired_drag_force = fix16_add(desired_drag_force, term08);
+ desired_drag_force = fix16_add(desired_drag_force, term09);
+ desired_drag_force = fix16_add(desired_drag_force, term10);
+ desired_drag_force = fix16_add(desired_drag_force, term11);
+ desired_drag_force = fix16_add(desired_drag_force, term12);
+ desired_drag_force = fix16_add(desired_drag_force, term13);
+
+ desired_drag_force = fix16_mul(desired_drag_force, fix16_from_int(1000));
+
+ return desired_drag_force;
+}
diff --git a/src/adxl375.cpp b/src/adxl375.cpp
new file mode 100644
index 0000000..5b18c42
--- /dev/null
+++ b/src/adxl375.cpp
@@ -0,0 +1,60 @@
+#include "adxl375.hpp"
+
+void ADXL375::initialize() {
+ //Configure power mode and ODR
+ buffer[0] = R_ADXL375_BW_RATE;
+ bw_rate.fields.LOW_POWER = B_ADXL375_BW_RATE_NORMAL_POWER_MODE;
+ bw_rate.fields.RATE = B_ADXL375_ODR_800_HZ;
+ buffer[1] = bw_rate.data;
+ i2c_write_blocking(i2c, addr, buffer, 2, false);
+
+ //Configure data output format
+ buffer[0] = R_ADXL375_DATA_FORMAT;
+ i2c_write_blocking(i2c, addr, buffer, 1, true);
+ i2c_read_blocking(i2c, addr, buffer, 1, false);
+ //Some reserved fields are set to 1, read byte and *then* set desired bits
+ data_format.data = buffer[0];
+
+ buffer[0] = R_ADXL375_DATA_FORMAT;
+ data_format.fields.JUSTIFY = B_ADXL375_DATA_FORMAT_JUSTIFY_RIGHT;
+ data_format.fields.INT_INVERT = B_ADXL375_DATA_FORMAT_INTERRUPT_ACTIVE_HIGH;
+ buffer[1] = data_format.data;
+ i2c_write_blocking(i2c, addr, buffer, 2, false);
+
+ //Set to measurement mode
+ buffer[0] = R_ADXL375_POWER_CTL;
+ power_ctl.fields.MEASURE = true;
+ buffer[1] = power_ctl.data;
+ i2c_write_blocking(i2c, addr, buffer, 2, false);
+}
+
+void ADXL375::sample() {
+ //Read DATAX0 - DATAZ1 as a block
+ buffer[0] = R_ADXL375_DATAX0;
+ i2c_write_blocking(i2c, addr, buffer, 1, true);
+ i2c_read_blocking(i2c, addr, buffer, 6, false);
+
+ //Split buffer into individual fields
+ ax = ((int16_t) buffer[0]) | ((int16_t) buffer[1] << 8);
+ ay = ((int16_t) buffer[2]) | ((int16_t) buffer[3] << 8);
+ az = ((int16_t) buffer[4]) | ((int16_t) buffer[5] << 8);
+}
+
+#if (USE_FREERTOS == 1)
+void ADXL375::update_adxl375_task(void* pvParameters) {
+ TickType_t xLastWakeTime;
+ const TickType_t xFrequency = pdMS_TO_TICKS(1000 / ADXL375_SAMPLE_RATE_HZ);
+
+ xLastWakeTime = xTaskGetTickCount();
+ while (1) {
+ vTaskDelayUntil(&xLastWakeTime, xFrequency);
+ taskENTER_CRITICAL();
+ ADXL375* adxl375 = (ADXL375 *) pvParameters;
+ adxl375->sample();
+ taskEXIT_CRITICAL();
+ if ((xLastWakeTime + xFrequency) < xTaskGetTickCount()) {
+ xLastWakeTime = xTaskGetTickCount();
+ }
+ }
+}
+#endif
diff --git a/src/altimeter.cpp b/src/altimeter.cpp
deleted file mode 100644
index 9c47ceb..0000000
--- a/src/altimeter.cpp
+++ /dev/null
@@ -1,145 +0,0 @@
-#include "altimeter.hpp"
-#include "hardware/gpio.h"
-
-altimeter::altimeter(i2c_inst_t* inst, uint8_t addr) {
- this->inst = inst;
- this->addr = addr;
-}
-
-void altimeter::initialize() {
- // Select control register(0x26)
- // Active mode, OSR = 16, altimeter mode(0xB8)
- this->buffer[0] = 0x26;
- this->buffer[1] = 0x89;
- i2c_write_blocking(this->inst, this->addr, this->buffer, 2, true);
-}
-
-void altimeter::initialize(float threshold_altitude, uint8_t interrupt_pin, gpio_irq_callback_t callback) {
- this->initialize();
-
- // Below configures the interrupt for the first transition from PAD to BOOST
- // Initial Reading
-
- sleep_ms(1000);
-
- float altitude = 0.0f;
-
- while (altitude == 0.0f) {
- altitude = this->get_altitude_converted();
- }
-
- threshold_altitude += altitude; // 30 meters above ground
-
- // Select control register 3 (0x28)
- // Set bot interrupt pins to active low and enable internal pullups
- this->buffer[0] = 0x28;
- this->buffer[1] = 0x01;
- i2c_write_blocking(this->inst, this->addr, this->buffer, 2, true);
-
- // Select pressure target MSB register(0x16)
- // Set altitude target to 30 meters above ground altitude
- this->buffer[0] = 0x16;
- this->buffer[1] = (uint8_t) (((int16_t)(threshold_altitude)) >> 8);
- i2c_write_blocking(this->inst, this->addr, this->buffer, 2, true);
-
- // Select pressure target LSB register(0x17)
- // Set altitude target to 30 meters above ground altitude
- this->buffer[0] = 0x17;
- this->buffer[1] = (uint8_t) (((int16_t)(threshold_altitude)));
- i2c_write_blocking(this->inst, this->addr, this->buffer, 2, true);
-
- // Select interrupt enable register (0x29)
- // Set interrupt enabled for altitude threshold(0x08)
- this->buffer[0] = 0x29;
- this->buffer[1] = 0x08;
- i2c_write_blocking(this->inst, this->addr, this->buffer, 2, true);
-
- // Select interrupt this->bufferuration register (0x2A)
- // Set interrupt enabled for altitude threshold to route to INT1 pin(0x08)
- this->buffer[0] = 0x2A;
- this->buffer[1] = 0x08;
- i2c_write_blocking(this->inst, this->addr, this->buffer, 2, true);
-
- gpio_set_irq_enabled_with_callback(interrupt_pin, GPIO_IRQ_LEVEL_LOW, true, callback);
- // End of configuration of interrupt for first transition from PAD to BOOST
-}
-
-void altimeter::set_threshold_altitude(float threshold_altitude, uint8_t interrupt_pin, gpio_irq_callback_t callback) {
- float altitude = 0.0f;
-
- while (altitude == 0.0f) {
- altitude = get_altitude_converted();
- }
-
- threshold_altitude += altitude;
-
- // Select control register 3 (0x28)
- // Set bot interrupt pins to active low and enable internal pullups
- this->buffer[0] = 0x28;
- this->buffer[1] = 0x01;
- i2c_write_blocking(this->inst, this->addr, this->buffer, 2, true);
-
- // Select pressure target MSB register(0x16)
- // Set altitude target to 30 meters above ground altitude
- this->buffer[0] = 0x16;
- this->buffer[1] = (uint8_t) (((int16_t)(threshold_altitude)) >> 8);
- i2c_write_blocking(this->inst, this->addr, this->buffer, 2, true);
-
- // Select pressure target LSB register(0x17)
- // Set altitude target to provided threshold altitude
- this->buffer[0] = 0x17;
- this->buffer[1] = (uint8_t) (((int16_t)(threshold_altitude)));
- i2c_write_blocking(this->inst, this->addr, this->buffer, 2, true);
-
- // Select interrupt enable register (0x29)
- // Set interrupt enabled for altitude threshold(0x08)
- this->buffer[0] = 0x29;
- this->buffer[1] = 0x08;
- i2c_write_blocking(this->inst, this->addr, this->buffer, 2, true);
-
- // Select interrupt this->bufferuration register (0x2A)
- // Set interrupt enabled for altitude threshold to route to INT1 pin(0x08)
- this->buffer[0] = 0x2A;
- this->buffer[1] = 0x08;
- i2c_write_blocking(this->inst, this->addr, this->buffer, 2, true);
-
- gpio_set_irq_enabled_with_callback(interrupt_pin, GPIO_IRQ_LEVEL_LOW, true, callback);
- // End of configuration of interrupt for first transition from PAD to BOOST
-}
-
-void altimeter::unset_threshold_altitude(uint8_t interrupt_pin) {
- gpio_set_irq_enabled_with_callback(interrupt_pin, GPIO_IRQ_LEVEL_LOW, false, NULL);
-
- // Select interrupt enable register (0x29)
- // Set interrupt enabled for altitude threshold(0x08)
- this->buffer[0] = 0x29;
- this->buffer[1] = 0x00;
- i2c_write_blocking(this->inst, this->addr, this->buffer, 2, true);
-
- // Select interrupt configuration register (0x2A)
- // Set interrupt enabled for altitude threshold to route to INT1 pin(0x08)
- this->buffer[0] = 0x2A;
- this->buffer[1] = 0x00;
- i2c_write_blocking(this->inst, this->addr, this->buffer, 2, true);
-}
-
-float altimeter::get_altitude_converted() {
- uint8_t reg = 0x01;
- i2c_write_blocking(this->inst, this->addr, &reg, 1, true);
- i2c_read_blocking(this->inst, this->addr, this->altitude_buffer, 4, false);
- // Exactly how MPL3115A2 datasheet says to retrieve altitude
- float altitude = (float) ((int16_t) ((this->altitude_buffer[0] << 8) | this->altitude_buffer[1])) + (float) (this->altitude_buffer[2] >> 4) * 0.0625;
- return altitude;
-}
-
-void altimeter::get_altitude_raw(uint8_t* buffer) {
- uint8_t reg = 0x01;
- i2c_write_blocking(this->inst, this->addr, &reg, 1, true);
- i2c_read_blocking(this->inst, this->addr, buffer, 3, false);
-}
-
-uint32_t altimeter::expose_buffer(uint8_t** buffer) {
- *buffer = this->altitude_buffer;
- return sizeof(this->altitude_buffer);
-}
-
diff --git a/src/heartbeat.cpp b/src/heartbeat.cpp
new file mode 100644
index 0000000..e627935
--- /dev/null
+++ b/src/heartbeat.cpp
@@ -0,0 +1,48 @@
+#include "heartbeat.hpp"
+
+static int led_pin;
+
+#if (USE_FREERTOS != 1)
+static repeating_timer_t heartbeat_timer;
+
+static bool heartbeat_callback(repeating_timer_t *rt) {
+ static volatile uint8_t led_counter = 0;
+ const bool sequence[] = {true, false, true, false, false};
+ const uint8_t sequence_length = 5;
+ bool led_status = sequence[led_counter];
+ gpio_put(led_pin, led_status);
+ led_counter++;
+ led_counter %= sequence_length;
+ return true;
+}
+#endif
+
+void heartbeat_initialize(int gpio) {
+ led_pin = gpio;
+ gpio_init(led_pin);
+ gpio_set_dir(led_pin, GPIO_OUT);
+ gpio_put(led_pin, 0);
+#if (USE_FREERTOS != 1)
+ add_repeating_timer_us(-1000000 / HEART_RATE_HZ, &heartbeat_callback, NULL, &heartbeat_timer);
+#endif
+}
+
+
+#if (USE_FREERTOS == 1)
+void heartbeat_task( void *pvParameters ) {
+ TickType_t xLastWakeTime;
+ const TickType_t xFrequency = pdMS_TO_TICKS(1000 / HEART_RATE_HZ);
+ static volatile uint8_t led_counter = 0;
+ const bool sequence[] = {true, false, true, false, false};
+ const uint8_t sequence_length = 5;
+
+ xLastWakeTime = xTaskGetTickCount();
+ while (1) {
+ vTaskDelayUntil(&xLastWakeTime, xFrequency);
+ bool led_status = sequence[led_counter];
+ gpio_put(PICO_DEFAULT_LED_PIN, led_status);
+ led_counter++;
+ led_counter %= sequence_length;
+ }
+}
+#endif
diff --git a/src/iim42653.cpp b/src/iim42653.cpp
new file mode 100644
index 0000000..d9b96d4
--- /dev/null
+++ b/src/iim42653.cpp
@@ -0,0 +1,108 @@
+#include "iim42653.hpp"
+
+int16_t IIM42653::sat_sub(int16_t a, int16_t b) {
+ int32_t result = (int32_t) a - (int32_t) b;
+ if (result < INT16_MIN) {
+ result = INT16_MIN;
+ }
+ if (result > INT16_MAX) {
+ result = INT16_MAX;
+ }
+ return (int16_t) result;
+};
+
+//Startup routine, initialize GPIO clock output
+void IIM42653::initialize() {
+ //Enable 40kHz clock output on GPIO 23
+ clock_gpio_init(MICRO_DEFAULT_CLK_OUTPUT, IIM42653_CLOCK_SOURCE_SYSTEM, IIM42653_CLOCK_DIVISOR);
+ sleep_ms(50); //Allow time for clock output to stabilize
+
+ //Configure Gyroscope FSR and ODR
+ buffer[0] = R_IIM42653_GYRO_CONFIG0;
+ gyro_config0.fields.GYRO_ODR = B_IIM42653_GYRO_CONFIG0_ODR_500HZ;
+ gyro_config0.fields.GYRO_UI_FS_SEL = B_IIM42653_GYRO_CONFIG0_FSR_4000DPS;
+ buffer[1] = gyro_config0.data;
+ i2c_write_blocking(i2c, addr, buffer, 2, false);
+
+ //Configure Accelerometer FSR and ODR
+ buffer[0] = R_IIM42653_ACCEL_CONFIG0;
+ accel_config0.fields.ACCEL_ODR = B_IIM42653_ACCEL_CONFIG0_ODR_500HZ;
+ accel_config0.fields.ACCEL_UI_FS_SEL = B_IIM42653_ACCEL_CONFIG0_FSR_32G;
+ buffer[1] = accel_config0.data;
+ i2c_write_blocking(i2c, addr, buffer, 2, false);
+
+ //Enable Gyroscope, Accelerometer, and Thermocouple
+ buffer[0] = R_IIM42653_PWR_MGMT0;
+ pwr_mgmt0.fields.ACCEL_MODE = B_IIM42653_PWR_MGMT0_ACCEL_MODE_LOW_NOISE;
+ pwr_mgmt0.fields.GYRO_MODE = B_IIM42653_PWR_MGMT0_GYRO_MODE_LOW_NOISE;
+ pwr_mgmt0.fields.TEMP_DIS = B_IIM42653_PWR_MGMT0_TEMP_ENABLE;
+ buffer[1] = pwr_mgmt0.data;
+ i2c_write_blocking(i2c, addr, buffer, 2, false);
+ sleep_ms(10); //Datasheet instructs 200us wait after changing sensor power modes
+
+ //Calibrate gyro bias once all sensors are initialized
+ calibrate_gyro();
+}
+
+//Read all 12 data registers at once and format them into their internal fields
+void IIM42653::sample() {
+ //Read ACCEL_DATA_X1_UI - GYRO_DATA_Z0_UI as a block
+ buffer[0] = R_IIM42653_ACCEL_DATA_X1_UI;
+ i2c_write_blocking(i2c, addr, buffer, 1, true);
+ i2c_read_blocking(i2c, addr, buffer, 12, false);
+
+ //Split buffer into individial fields
+ ax = ((int16_t)buffer[1]) | (((int16_t)buffer[0]) << 8);
+ ay = ((int16_t)buffer[3]) | (((int16_t)buffer[2]) << 8);
+ az = ((int16_t)buffer[5]) | (((int16_t)buffer[4]) << 8);
+ raw_gx = ((int16_t)buffer[7]) | (((int16_t)buffer[6]) << 8);
+ raw_gy = ((int16_t)buffer[9]) | (((int16_t)buffer[8]) << 8);
+ raw_gz = ((int16_t)buffer[11]) | (((int16_t)buffer[10]) << 8);
+}
+void IIM42653::apply_gyro_offset() {
+ gx = sat_sub(raw_gx, bias_gx);
+ gy = sat_sub(raw_gy, bias_gy);
+ gz = sat_sub(raw_gz, bias_gz);
+}
+
+//Request certain number of gyroscope readings, and set the gyro bias values to the averages of the readings
+void IIM42653::calibrate_gyro() {
+ //Initialize buffers
+ int64_t g_x = 0;
+ int64_t g_y = 0;
+ int64_t g_z = 0;
+
+ //Request configured number of samples and l
+ for (int64_t i = 0; i < n_gyro_bias_readings; i++) {
+ sample();
+ g_x += raw_gx;
+ g_y += raw_gy;
+ g_z += raw_gz;
+ sleep_ms(5);
+ }
+
+ //Set bias values to the average readings during the calibration period
+ bias_gx = g_x/n_gyro_bias_readings;
+ bias_gy = g_y/n_gyro_bias_readings;
+ bias_gz = g_z/n_gyro_bias_readings;
+}
+
+#if ( USE_FREERTOS == 1 )
+void IIM42653::update_iim42653_task(void* pvParameters) {
+ TickType_t xLastWakeTime;
+ const TickType_t xFrequency = pdMS_TO_TICKS(1000 / IIM42653_SAMPLE_RATE_HZ);
+
+ xLastWakeTime = xTaskGetTickCount();
+ while (1) {
+ vTaskDelayUntil(&xLastWakeTime, xFrequency);
+ taskENTER_CRITICAL();
+ IIM42653* iim42653 = (IIM42653*) pvParameters;
+ iim42653->sample();
+ iim42653->apply_gyro_offset();
+ taskEXIT_CRITICAL();
+ if ((xLastWakeTime + xFrequency) < xTaskGetTickCount()) {
+ xLastWakeTime = xTaskGetTickCount();
+ }
+ }
+}
+#endif
diff --git a/src/imu.cpp b/src/imu.cpp
deleted file mode 100644
index 4a81042..0000000
--- a/src/imu.cpp
+++ /dev/null
@@ -1,160 +0,0 @@
-#include "imu.hpp"
-
-imu::imu(i2c_inst_t* inst, uint8_t addr, uint8_t id, imu_opmode_t mode) {
- this->inst = inst;
- this->addr = addr;
- this->id = id;
- this->mode = mode;
-}
-
-void imu::reset() {
- this->buffer[0] = SYS_TRIGGER;
- this->buffer[1] = 0x20; // Reset system
- i2c_write_blocking(this->inst, this->addr, buffer, 2, true);
- sleep_ms(1000); // Wait 650ms for the sensor to reset
-}
-
-void imu::initialize() {
- sleep_ms(1000); // Wait 650ms for the sensor to reset
-
- uint8_t chip_id_addr = CHIP_ID;
- uint8_t read_id = 0x00;
- while (read_id != this->id) {
- i2c_write_blocking(this->inst, this->addr, &chip_id_addr, 1, false);
- i2c_read_blocking(this->inst, this->addr, &read_id, 1, false);
- sleep_ms(100);
- }
-
- // Use internal oscillator
- this->buffer[0] = SYS_TRIGGER;
- this->buffer[1] = 0x40; // Set to use internal oscillator
- i2c_write_blocking(this->inst, this->addr, this->buffer, 2, true);
- sleep_ms(50);
-
- // Reset all interrupt status bits
- this->buffer[0] = SYS_TRIGGER;
- this->buffer[1] = 0x01; // Reset interrupt status
- i2c_write_blocking(this->inst, this->addr, this->buffer, 2, true);
- sleep_ms(50);
-
- // Set to normal power mode
- this->buffer[0] = POWER_MODE;
- this->buffer[1] = 0x00; // Normal power mode
- i2c_write_blocking(this->inst, this->addr, this->buffer, 2, true);
- sleep_ms(50);
-
- // Default Axis Config
- this->buffer[0] = AXIS_MAP_CONFIG;
- this->buffer[1] = 0x24; // P1=Z, P2=Y, P3=X
- i2c_write_blocking(this->inst, this->addr, this->buffer, 2, true);
- sleep_ms(50);
-
- // Default Axis Sign
- this->buffer[0] = AXIS_MAP_SIGN;
- this->buffer[1] = 0x00; // P1=Positive, P2=Positive, P3=Positive
- i2c_write_blocking(this->inst, this->addr, this->buffer, 2, true);
- sleep_ms(50);
-
- // Set units to m/s^2
- this->buffer[0] = UNIT_SELECTION;
- this->buffer[1] = 0x00; // Windows, Celsius, Degrees, DPS, m/s^2
- i2c_write_blocking(this->inst, this->addr, this->buffer, 2, true);
- sleep_ms(200);
-
- uint8_t sensor_offsets[19];
- sensor_offsets[0] = ACCELERATION_OFFSET_X_LSB;
- sensor_offsets[1] = 0x00;
- sensor_offsets[2] = 0x00;
- sensor_offsets[3] = 0x00;
- sensor_offsets[4] = 0x00;
- sensor_offsets[5] = 0x00;
- sensor_offsets[6] = 0x00;
- sensor_offsets[7] = 0x00;
- sensor_offsets[8] = 0x00;
- sensor_offsets[9] = 0x00;
- sensor_offsets[10] = 0x00;
- sensor_offsets[11] = 0x00;
- sensor_offsets[12] = 0x00;
- sensor_offsets[13] = 0x00;
- sensor_offsets[14] = 0x00;
- sensor_offsets[15] = 0x00;
- sensor_offsets[16] = 0x00;
- sensor_offsets[17] = 0x00;
- sensor_offsets[18] = 0x00;
- i2c_write_blocking(this->inst, this->addr, sensor_offsets, 19, true);
- sleep_ms(200);
-
- // The default operation mode after power-on is CONFIG
- // Set to desired mode
- this->buffer[0] = OPERATION_MODE;
- this->buffer[1] = this->mode; // NDOF
- i2c_write_blocking(this->inst, this->addr, this->buffer, 2, false);
- sleep_ms(100);
-}
-
-void imu::calibration_status(calibration_status_t* status) {
- read_register(CALIBRATION_STATUS, 1, this->buffer);
- status->mag = ((this->buffer[0] & 0b00000011) >> 0);
- status->accel = ((this->buffer[0] & 0b00001100) >> 2);
- status->gyro = ((this->buffer[0] & 0b00110000) >> 4);
- status->sys = ((this->buffer[0] & 0b11000000) >> 6);
-}
-
-void imu::linear_acceleration(Eigen::Vector3f& vec) {
- read_register(LINEAR_ACCELERATION_X_LSB, 6, this->accel_buffer);
- int16_t x, y, z;
- x = y = z = 0;
- x = ((int16_t)this->accel_buffer[0]) | (((int16_t)this->accel_buffer[1]) << 8);
- y = ((int16_t)this->accel_buffer[2]) | (((int16_t)this->accel_buffer[3]) << 8);
- z = ((int16_t)this->accel_buffer[4]) | (((int16_t)this->accel_buffer[5]) << 8);
- vec(0) = ((float)x) / 100.0;
- vec(1) = ((float)y) / 100.0;
- vec(2) = ((float)z) / 100.0;
-}
-
-void imu::quaternion(Eigen::Vector4f& vec) {
- read_register(QUATERNION_W_LSB, 8, this->quat_buffer);
- int16_t w, x, y, z;
- w = x = y = z = 0;
- w = ((int16_t)this->quat_buffer[0]) | (((int16_t)this->quat_buffer[1]) << 8);
- x = ((int16_t)this->quat_buffer[2]) | (((int16_t)this->quat_buffer[3]) << 8);
- y = ((int16_t)this->quat_buffer[4]) | (((int16_t)this->quat_buffer[5]) << 8);
- z = ((int16_t)this->quat_buffer[6]) | (((int16_t)this->quat_buffer[7]) << 8);
- vec(0) = ((float)w) / 16384.0;
- vec(1) = ((float)x) / 16384.0;
- vec(2) = ((float)y) / 16384.0;
- vec(3) = ((float)z) / 16384.0;
-}
-
-void imu::quaternion_euler(Eigen::Vector3f& angles, Eigen::Vector4f& quat) {
- // roll (x-axis rotation)
- float sinr_cosp = 2 * (quat(0) * quat(1) + quat(2) * quat(3));
- float cosr_cosp = 1 - 2 * (quat(1) * quat(1) + quat(2) * quat(2));
- angles(0) = Eigen::numext::atan2(sinr_cosp, cosr_cosp);
-
- // pitch (y-axis rotation)
- float sinp = Eigen::numext::sqrt(1 + 2 * (quat(0) * quat(2) - quat(1) * quat(3)));
- float cosp = Eigen::numext::sqrt(1 - 2 * (quat(0) * quat(2) - quat(1) * quat(3)));
- angles(1) = 2 * Eigen::numext::atan2(sinp, cosp) - M_PI / 2;
-
- // yaw (z-axis rotation)
- float siny_cosp = 2 * (quat(0) * quat(3) + quat(1) * quat(2));
- float cosy_cosp = 1 - 2 * (quat(2) * quat(2) + quat(3) * quat(3));
- angles(2) = Eigen::numext::atan2(siny_cosp, cosy_cosp);
-}
-
-uint32_t imu::expose_acceleration_buffer(uint8_t** buffer) {
- *buffer = this->accel_buffer;
- return sizeof(this->accel_buffer);
-}
-
-uint32_t imu::expose_quaternion_buffer(uint8_t** buffer) {
- *buffer = this->quat_buffer;
- return sizeof(this->quat_buffer);
-}
-
-void imu::read_register(uint8_t reg, size_t len, uint8_t* buffer) {
- i2c_write_blocking(this->inst, this->addr, &reg, 1, true);
- i2c_read_blocking(this->inst, this->addr, buffer, len, false);
-}
-
diff --git a/src/log_format.cpp b/src/log_format.cpp
new file mode 100644
index 0000000..5d9d275
--- /dev/null
+++ b/src/log_format.cpp
@@ -0,0 +1,66 @@
+#include "log_format.hpp"
+
+void print_log_entry(const uint8_t* entry) {
+ static bool first_call = true;
+
+ if (first_call) {
+ printf("time_us,state,temperature_chip_celsius,deployment_percent,pressure_mb,altitude,altitude_filt,velocity_filt,temperature_alt_celsius,mid_imu_ax,mid_imu_ay,mid_imu_az,mid_imu_gx,mid_imu_gy,mid_imu_gz,mag_x,mag_y,mag_z,high_g_x,high_g_y,high_g_z,drag_force,apogee_prediction,desired_drag_force\r\n");
+ first_call = false;
+ }
+
+ const log_entry_t* packet = reinterpret_cast<const log_entry_t *>(entry);
+ printf("%" PRIu64 ",", packet->time_us);
+ state_t state = (state_t) packet->state;
+ switch (state) {
+ case PAD:
+ printf("PAD");
+ break;
+ case BOOST:
+ printf("BOOST");
+ break;
+ case COAST:
+ printf("COAST");
+ break;
+ case APOGEE:
+ printf("APOGEE");
+ break;
+ case RECOVERY:
+ printf("RECOVERY");
+ break;
+ case END:
+ printf("END");
+ break;
+ }
+ printf(",");
+ const float conversionFactor = 3.3f / (1 << 12);
+ float tempC = 27.0f - (((float)(packet->temperature_chip) * conversionFactor) - 0.706f) / 0.001721f;
+ printf("%4.2f,", tempC);
+ printf("%d,", packet->deploy_percent);
+ printf("%4.2f,", ((float) packet->pressure) / PRESSURE_SCALE_F);
+ printf("%4.2f,", ((float) packet->altitude) / ALTITUDE_SCALE_F);
+ printf("%4.2f,", (fix16_to_float(packet->altitude_filt)));
+ printf("%4.2f,", (fix16_to_float(packet->velocity_filt)));
+ printf("%4.2f,", ((float) packet->temperature_alt) / TEMPERATURE_SCALE_F);
+
+ printf("%4.2f,", IIM42653::scale_accel(packet->ax));
+ printf("%4.2f,", IIM42653::scale_accel(packet->ay));
+ printf("%4.2f,", IIM42653::scale_accel(packet->az));
+
+ printf("%4.2f,", IIM42653::scale_gyro(packet->gx));
+ printf("%4.2f,", IIM42653::scale_gyro(packet->gy));
+ printf("%4.2f,", IIM42653::scale_gyro(packet->gz));
+
+ printf("%" PRIi16 ",", packet->mag_x);
+ printf("%" PRIi16 ",", packet->mag_y);
+ printf("%" PRIi16 ",", packet->mag_z);
+
+ printf("%4.2f,", ADXL375::scale(packet->high_g_x));
+ printf("%4.2f,", ADXL375::scale(packet->high_g_y));
+ printf("%4.2f,", ADXL375::scale(packet->high_g_z));
+ printf("%4.2f,", (fix16_to_float(packet->drag_force)));
+ printf("%4.2f,", (fix16_to_float(packet->apogee_prediction)));
+ printf("%4.2f,", (fix16_to_float(packet->desired_drag_force)));
+ printf("\r\n");
+ stdio_flush();
+}
+
diff --git a/src/mmc5983ma.cpp b/src/mmc5983ma.cpp
new file mode 100644
index 0000000..45ef94a
--- /dev/null
+++ b/src/mmc5983ma.cpp
@@ -0,0 +1,158 @@
+#include "mmc5983ma.hpp"
+
+int16_t MMC5983MA::sat_sub(int16_t a, int16_t b) {
+ int32_t result = (int32_t) a - (int32_t) b;
+ if (result < INT16_MIN) {
+ result = INT16_MIN;
+ }
+ if (result > INT16_MAX) {
+ result = INT16_MAX;
+ }
+ return (int16_t) result;
+};
+
+void MMC5983MA::initialize() {
+ // Restart device prior to configuration
+ buffer[0] = R_MMC5983MA_INTERNAL_CTL1;
+ internal_ctl1.fields.RESTART = true;
+ buffer[1] = internal_ctl1.data;
+ i2c_write_blocking(i2c, addr, buffer, 2, false);
+ internal_ctl1.data = 0;
+
+ sleep_ms(100);
+
+ calibrate();
+
+ //Configure decimation filter bandwidth for 200 Hz
+ buffer[0] = R_MMC5983MA_INTERNAL_CTL1;
+ internal_ctl1.fields.BANDWIDTH = B_MMC5983MA_BANDWIDTH_200HZ;
+ buffer[1] = internal_ctl1.data;
+ i2c_write_blocking(i2c, addr, buffer, 2, false);
+
+ //Configure and enable continuous measurement mode for 200 Hz
+ buffer[0] = R_MMC5983MA_INTERNAL_CTL2;
+ internal_ctl2.fields.CONTINUOUS_MODE_ENABLE = true;
+ internal_ctl2.fields.CONTINUOUS_MODE_FREQ = B_MMC5983_CONTINUOUS_MODE_FREQ_200HZ;
+ internal_ctl2.fields.PERIODIC_SET_ENABLE = false;
+ internal_ctl2.fields.PERIODIC_SET_RATE = B_MMC5983_PERIODIC_SET_RATE_MEAS_TIMES_1000;
+ buffer[1] = internal_ctl2.data;
+ i2c_write_blocking(i2c, addr, buffer, 2, false);
+ printf("MMC5983MA Initialized!\n");
+}
+
+void MMC5983MA::sample() {
+ buffer[0] = R_MMC5983MA_XOUT0;
+ i2c_write_blocking(i2c, addr, buffer, 1, true);
+ i2c_read_blocking(i2c, addr, buffer, 6, false);
+
+ raw_x = (int16_t) ((((uint16_t) buffer[0] << 8) | buffer[1]) - 32768);
+ raw_y = (int16_t) ((((uint16_t) buffer[2] << 8) | buffer[3]) - 32768);
+ raw_z = (int16_t) ((((uint16_t) buffer[4] << 8) | buffer[5]) - 32768);
+}
+
+void MMC5983MA::apply_offset() {
+ ax = sat_sub(raw_x, offset_x);
+ ay = sat_sub(raw_y, offset_y);
+ az = sat_sub(raw_z, offset_z);
+}
+
+void MMC5983MA::calibrate() {
+ sleep_ms(100);
+
+ printf("MMC5983MA Calibration | Set command");
+ // Take measurement after SET command completes
+ buffer[0] = R_MMC5983MA_INTERNAL_CTL0;
+ internal_ctl0.fields.SET_CMD = true;
+ buffer[1] = internal_ctl0.data;
+ i2c_write_blocking(i2c, addr, buffer, 2, false);
+ internal_ctl0.data = 0;
+
+ sleep_ms(100);
+ printf(" | Measurement Request");
+
+ buffer[0] = R_MMC5983MA_INTERNAL_CTL0;
+ internal_ctl0.fields.TAKE_MAG_MEAS = true;
+ buffer[1] = internal_ctl0.data;
+ i2c_write_blocking(i2c, addr, buffer, 2, false);
+ internal_ctl0.data = 0;
+ printf(" | Request sent, awaiting completion...\n");
+
+ size_t counter = 0;
+ while (!dev_status.fields.MEAS_M_DONE) {
+ sleep_ms(1);
+ buffer[0] = R_MMC5983MA_DEV_STATUS;
+ i2c_write_blocking(i2c, addr, buffer, 1, true);
+ i2c_read_blocking(i2c, addr, buffer, 1, false);
+ dev_status.data = buffer[0];
+ printf("W | ");
+ counter++;
+ if (counter == 20) {
+ printf("\n");
+ counter = 0;
+ }
+ }
+ printf("\n\nMeasurement taken!");
+
+ sample();
+ printf(" | Sample taken!");
+
+ int16_t set_ax = raw_x, set_ay = raw_y, set_az = raw_z;
+
+ // Take measurement after RESET command completes
+ buffer[0] = R_MMC5983MA_INTERNAL_CTL0;
+ internal_ctl0.fields.RESET_CMD = true;
+ buffer[1] = internal_ctl0.data;
+ i2c_write_blocking(i2c, addr, buffer, 2, false);
+ internal_ctl0.data = 0;
+
+ sleep_ms(100);
+
+ buffer[0] = R_MMC5983MA_INTERNAL_CTL0;
+ internal_ctl0.fields.TAKE_MAG_MEAS = true;
+ buffer[1] = internal_ctl0.data;
+ i2c_write_blocking(i2c, addr, buffer, 2, false);
+ internal_ctl0.data = 0;
+
+ while (!dev_status.fields.MEAS_M_DONE) {
+ sleep_ms(1);
+ buffer[0] = R_MMC5983MA_DEV_STATUS;
+ i2c_write_blocking(i2c, addr, buffer, 1, true);
+ i2c_read_blocking(i2c, addr, buffer, 1, false);
+ dev_status.data = buffer[0];
+ }
+
+ sample();
+
+ int16_t reset_ax = raw_x, reset_ay = raw_y, reset_az = raw_z;
+
+ sleep_ms(100);
+
+ // Average the two measurements taken and assign them as offsets
+ offset_x = (int16_t) (((int32_t) set_ax + (int32_t) reset_ax) / 2);
+ offset_y = (int16_t) (((int32_t) set_ay + (int32_t) reset_ay) / 2);
+ offset_z = (int16_t) (((int32_t) set_az + (int32_t) reset_az) / 2);
+
+#if ( DEBUG == 1 )
+ printf("MMC5983MA: Calibrated!\n\toffset_x: %" PRIi16 "\n\toffset_y: %" PRIi16 "\n\toffset_z: %" PRIi16 "\n", offset_x, offset_y, offset_z);
+#endif
+}
+
+#if (USE_FREERTOS == 1)
+void MMC5983MA::update_mmc5983ma_task(void* pvParameters) {
+ TickType_t xLastWakeTime;
+ const TickType_t xFrequency = pdMS_TO_TICKS(1000 / MMC5983_SAMPLE_RATE_HZ);
+
+ xLastWakeTime = xTaskGetTickCount();
+ while (1) {
+ vTaskDelayUntil(&xLastWakeTime, xFrequency);
+ taskENTER_CRITICAL();
+ MMC5983MA* mag = (MMC5983MA *) pvParameters;
+ mag->sample();
+ mag->apply_offset();
+ taskEXIT_CRITICAL();
+ if ((xLastWakeTime + xFrequency) < xTaskGetTickCount()) {
+ xLastWakeTime = xTaskGetTickCount();
+ }
+ }
+}
+#endif
diff --git a/src/ms5607.cpp b/src/ms5607.cpp
new file mode 100644
index 0000000..c093189
--- /dev/null
+++ b/src/ms5607.cpp
@@ -0,0 +1,208 @@
+#include "ms5607.hpp"
+
+static const int32_t altitude_table[] = {
+#include "altitude-pa.h"
+};
+
+#define ALT_SCALE (1 << ALT_SHIFT)
+#define ALT_MASK (ALT_SCALE - 1)
+
+void MS5607::initialize() {
+ sample_state = NOT_SAMPLING;
+
+ alarm_pool_init_default();
+
+ ms5607_cmd cmd;
+ cmd.data = RESET_COMMAND;
+
+ ms5607_write_cmd(&cmd);
+
+ sleep_ms(500);
+
+ cmd.data = 0;
+ cmd.fields.PROM = true;
+ cmd.fields.PROM2 = true;
+
+ cmd.fields.ADDR_OSR = PROM_CALIBRATION_COEFFICENT_1_ADDR;
+
+ for (uint8_t prom_addr = PROM_CALIBRATION_COEFFICENT_1_ADDR; prom_addr <= PROM_CALIBRATION_COEFFICENT_6_ADDR; prom_addr++) {
+ sleep_ms(100);
+ cmd.fields.ADDR_OSR = prom_addr;
+ ms5607_write_cmd(&cmd);
+ i2c_read_blocking(i2c, addr, buffer, 2, false);
+
+ prom[prom_addr - 1] = static_cast<uint16_t>((((uint16_t) buffer[0]) << 8) | ((uint16_t) buffer[1]));
+ }
+}
+
+void MS5607::ms5607_write_cmd(ms5607_cmd* cmd) {
+ i2c_write_blocking(i2c, addr, (uint8_t *) cmd, 1, false);
+}
+
+void MS5607::ms5607_start_sample() {
+ if (sample_state == NOT_SAMPLING) {
+ sample_state = PRESSURE_CONVERT;
+ ms5607_sample();
+ }
+}
+
+#if (USE_FREERTOS == 1)
+void MS5607::ms5607_sample_handler(void* pvParameters) {
+ /* xMaxExpectedBlockTime is set to be a little longer than the maximum
+ expected time between events. */
+ const TickType_t xInterruptFrequency = pdMS_TO_TICKS( 1000 / (MS5607_SAMPLE_RATE_HZ * 2) );
+ const TickType_t xMaxExpectedBlockTime = xInterruptFrequency + pdMS_TO_TICKS( 1 );
+ uint32_t ulEventsToProcess;
+ while (1) {
+ /* Wait to receive a notification sent directly to this task from the
+ interrupt service routine. */
+ ulEventsToProcess = ulTaskNotifyTake( pdTRUE, xMaxExpectedBlockTime );
+ if( ulEventsToProcess != 0 ) {
+ /* To get here at least one event must have occurred. Loop here
+ until all the pending events have been processed */
+ while( ulEventsToProcess > 0 ) {
+ MS5607* alt = (MS5607 *) pvParameters;
+ taskENTER_CRITICAL();
+ alt->ms5607_sample();
+ taskEXIT_CRITICAL();
+ ulEventsToProcess--;
+ }
+ }
+ }
+
+}
+
+void MS5607::update_ms5607_task(void* pvParameters) {
+ TickType_t xLastWakeTime;
+ const TickType_t xFrequency = pdMS_TO_TICKS(1000 / MS5607_SAMPLE_RATE_HZ);
+
+ xLastWakeTime = xTaskGetTickCount();
+ while (1) {
+ vTaskDelayUntil(&xLastWakeTime, xFrequency);
+ MS5607* alt = (MS5607 *) pvParameters;
+ taskENTER_CRITICAL();
+ alt->ms5607_start_sample();
+ taskEXIT_CRITICAL();
+ }
+}
+#endif
+
+int64_t MS5607::ms5607_sample_callback(alarm_id_t id, void* user_data) {
+#if ( USE_FREERTOS == 1 )
+ BaseType_t xHigherPriorityTaskWoken;
+ xHigherPriorityTaskWoken = pdFALSE;
+ MS5607* alt = (MS5607 *) user_data;
+ // Defer ISR handling to separate handler within FreeRTOS context
+ vTaskNotifyGiveFromISR(alt->sample_handler_task_handle, &xHigherPriorityTaskWoken );
+ portYIELD_FROM_ISR( xHigherPriorityTaskWoken );
+#else
+ MS5607* alt = (MS5607 *) user_data;
+ alt->ms5607_sample();
+#endif
+ return 0;
+}
+
+void MS5607::ms5607_sample() {
+ ms5607_cmd cmd = {.data = 0};
+
+ switch (sample_state) {
+ case NOT_SAMPLING:
+ break;
+ case PRESSURE_CONVERT: {
+ cmd.fields.CONVERT = 1;
+ cmd.fields.TYPE = TYPE_UNCOMPENSATED_PRESSURE;
+ cmd.fields.ADDR_OSR = OSR_CONVERT_256;
+
+ ms5607_write_cmd(&cmd);
+
+ add_alarm_in_us(OSR_256_CONVERSION_TIME_US, MS5607::ms5607_sample_callback, (void *) this, true);
+
+ sample_state = TEMPERATURE_CONVERT;
+ break;
+ };
+ case TEMPERATURE_CONVERT: {
+ cmd.data = ADC_READ_COMMAND;
+ ms5607_write_cmd(&cmd);
+ i2c_read_blocking(i2c, addr, buffer, 3, false);
+ uncompensated_pressure = (((uint32_t) buffer[0]) << 16) | (((uint32_t) buffer[1]) << 8) | ((uint32_t) buffer[2]);
+
+ cmd.fields.CONVERT = 1;
+ cmd.fields.TYPE = TYPE_UNCOMPENSATED_TEMPERATURE;
+ cmd.fields.ADDR_OSR = OSR_CONVERT_256;
+
+ ms5607_write_cmd(&cmd);
+
+ add_alarm_in_us(OSR_256_CONVERSION_TIME_US, MS5607::ms5607_sample_callback, (void *) this, true);
+
+ sample_state = COMPENSATE;
+ break;
+ };
+ case COMPENSATE: {
+ cmd.data = ADC_READ_COMMAND;
+ ms5607_write_cmd(&cmd);
+ i2c_read_blocking(i2c, addr, buffer, 3, false);
+ uncompensated_temperature = (((uint32_t) buffer[0]) << 16) | (((uint32_t) buffer[1]) << 8) | ((uint32_t) buffer[2]);
+ ms5607_compensate();
+ altitude = pressure_to_altitude(pressure);
+
+
+ sample_state = NOT_SAMPLING;
+ if (threshold_callback != NULL) {
+ if (positive_crossing) {
+ if (altitude >= threshold_altitude) {
+ add_alarm_in_ms(1, threshold_callback, NULL, true);
+ }
+ } else {
+ if (altitude <= threshold_altitude) {
+ add_alarm_in_ms(1, threshold_callback, NULL, true);
+ }
+ }
+ }
+ break;
+ };
+ };
+
+}
+
+void MS5607::ms5607_compensate() {
+ int32_t dT = uncompensated_temperature - (((uint32_t) prom[4]) << 8);
+ temperature = 2000 + ( ( ( (int64_t) dT) * ( (int64_t) prom[5]) ) >> 23);
+ int64_t OFF = ( ( (int64_t) prom[1]) << 17) + ( ( ((int64_t) prom[3]) * ( (int64_t) dT)) >> 6);
+ int64_t SENS = ( ( (int64_t) prom[0]) << 16) + (( ( (int64_t) prom[2]) * ((int64_t) dT)) >> 7);
+ pressure = (int32_t) ((((((int64_t) uncompensated_pressure) * SENS) >> 21) - OFF) >> 15);
+
+}
+
+int32_t MS5607::pressure_to_altitude(int32_t pressure) {
+ uint16_t o;
+ int16_t part;
+ int32_t low, high;
+
+ if (pressure < 0) {
+ pressure = 0;
+ }
+
+ if (pressure > 120000) {
+ pressure = 120000;
+ }
+
+ o = (uint16_t) (pressure >> ALT_SHIFT);
+ part = pressure & ALT_MASK;
+
+ low = (int32_t) altitude_table[o] * (ALT_SCALE - part);
+ high = (int32_t) altitude_table[o + 1] * part;
+ return ((low + high + (ALT_SCALE >> 1)) >> ALT_SHIFT);
+}
+
+
+void MS5607::set_threshold_altitude(int32_t threshold_altitude, alarm_callback_t callback) {
+ this->threshold_altitude = threshold_altitude;
+
+ positive_crossing = (threshold_altitude > altitude);
+
+ threshold_callback = callback;
+}
+
+void MS5607::clear_threshold_altitude() {
+ this->threshold_callback = NULL;
+}
diff --git a/src/pwm.cpp b/src/pwm.cpp
index 3a78d23..267765b 100644
--- a/src/pwm.cpp
+++ b/src/pwm.cpp
@@ -2,9 +2,9 @@
void PWM::init() {
// Tell GPIO 0 they are allocated to the PWM
- gpio_set_function(SERVO_PIN, GPIO_FUNC_PWM);
+ gpio_set_function(MICRO_DEFAULT_PWM, GPIO_FUNC_PWM);
// Find out which PWM slice is connected to GPIO 0 (it's slice 0)
- uint slice_num = pwm_gpio_to_slice_num(SERVO_PIN);
+ uint slice_num = pwm_gpio_to_slice_num(MICRO_DEFAULT_PWM);
// Configure PWM slice and set it running
pwm_config cfg = pwm_get_default_config();
@@ -24,7 +24,7 @@ void PWM::set_duty_cycle(int duty_cycle_percent) {
uint32_t raw_value = WRAP_VALUE * (duty_cycle_percent / 100.0);
// Set the duty cycle
- pwm_set_gpio_level(SERVO_PIN, raw_value);
+ pwm_set_gpio_level(MICRO_DEFAULT_PWM, raw_value);
}
void PWM::set_servo_percent(int percent) {
diff --git a/src/serial.cpp b/src/serial.cpp
new file mode 100644
index 0000000..9dfd5d9
--- /dev/null
+++ b/src/serial.cpp
@@ -0,0 +1,134 @@
+#include "serial.hpp"
+#include "portable.h"
+#include "portmacro.h"
+#include <pico/multicore.h>
+#include <pico/stdio.h>
+
+void serial_task( void *pvParameters ) {
+ char *str = (char *) malloc(1024);
+ size_t len = 1024;
+
+
+ printf("Welcome! :3\n");
+
+ while (1) {
+ printf("# ");
+ stdio_flush();
+
+ size_t n = input_line(str,len);
+ printf("\n");
+ if (n > 0) {
+ for (int i = 0; i < (NUM_BASE_CMDS + num_user_cmds); i++) {
+ if ((i < NUM_BASE_CMDS) && n >= base_commands[i].len && strncmp(str, base_commands[i].name, base_commands[i].len) == 0) {
+ base_commands[i].function();
+ break;
+ }
+
+ if ((i >= NUM_BASE_CMDS && ((i - NUM_BASE_CMDS) < num_user_cmds)) && n >= user_commands[i - NUM_BASE_CMDS].len && strncmp(str, user_commands[i - NUM_BASE_CMDS].name, user_commands[i - NUM_BASE_CMDS].len) == 0) {
+ user_commands[i - NUM_BASE_CMDS].function();
+ break;
+ }
+ if (i == (NUM_BASE_CMDS + num_user_cmds - 1)) {
+ printf("Invalid command! Please try again or use 'help' to see the available commands.\n");
+ }
+ }
+ }
+ }
+}
+
+int input_line(char *buffer, size_t len) {
+ size_t n = 0;
+ int c;
+ for (n = 0; n < len - 1; n++) {
+
+ c = getchar_timeout_us(0);
+ switch (c) {
+ case 127: /* fall through to below */
+ case '\b': /* backspace character received */
+ if (n > 0)
+ n--;
+ buffer[n] = 0;
+ stdio_putchar('\b'); /* output backspace character */
+ stdio_putchar(' ');
+ stdio_putchar('\b');
+ n--; /* set up next iteration to deal with preceding char location */
+ break;
+ case '\n': /* fall through to \r */
+ case '\r':
+ buffer[n] = 0;
+ return n;
+ default:
+ if (c != PICO_ERROR_TIMEOUT && c < 256) {
+ stdio_putchar(c);
+ buffer[n] = c;
+ } else {
+ n--;
+ }
+ break;
+ }
+ }
+ buffer[len - 1] = 0;
+ return 0; // Filled up buffer without reading a linebreak
+}
+
+void info_cmd_func() {
+ extern const char* executeable_name;
+ printf("%s", logo);
+ printf("#####################################################################################\n");
+ printf("# \e[0;31mRocketry \e[0;37mat \e[0;33mVirginia Tech\e[0;37m #\n");
+ printf("# Executeable: %s #\n", executeable_name);
+ printf("#####################################################################################\n\n");
+}
+
+void help_cmd_func() {
+ printf("Commands: \n");
+ for (int i = 0; i < NUM_BASE_CMDS; i++) {
+ printf("\t%s\n", base_commands[i].name);
+ }
+
+ for (int i = 0; i < num_user_cmds; i++) {
+ printf("\t%s\n", user_commands[i].name);
+ }
+}
+
+void clear_cmd_func() {
+ printf("%c%c%c%c",0x1B,0x5B,0x32,0x4A);
+}
+
+void top_cmd_func() {
+#if (configGENERATE_RUN_TIME_STATS == 1)
+ UBaseType_t num_tasks = uxTaskGetNumberOfTasks();
+ char* buffer = (char *) malloc( 40 * num_tasks );
+ vTaskGetRunTimeStats(buffer);
+ printf("%s", buffer);
+ free(buffer);
+#endif
+#if (configSUPPORT_DYNAMIC_ALLOCATION == 1)
+ HeapStats_t heap_stats;
+ vPortGetHeapStats(&heap_stats);
+ printf("\n\tAvailable Heap Space In Bytes:\t%d\nSize Of Largest Free Block In Bytes:\t%d\nNumber Of Successful Allocations:\t%d\n", heap_stats.xAvailableHeapSpaceInBytes, heap_stats.xSizeOfLargestFreeBlockInBytes, heap_stats.xNumberOfSuccessfulAllocations);
+#endif
+}
+
+static void reset_cmd_task(void * unused_arg) {
+ reset_cmd_func();
+}
+
+void reset_cmd_func() {
+#define AIRCR_Register (*((volatile uint32_t*)(PPB_BASE + 0x0ED0C)))
+ if (get_core_num() == 0) {
+ vTaskSuspendAll();
+ multicore_reset_core1();
+ printf("\nOn core zero! Going dark!\n");
+ stdio_flush();
+ AIRCR_Register = 0x5FA0004;
+ } else {
+ printf("\nOn core one! Tasking core zero with the reset!\n");
+ stdio_flush();
+ TaskHandle_t reset_task = NULL;
+ vTaskSuspendAll();
+ xTaskCreate(reset_cmd_task, "reset", 256, NULL, (configMAX_PRIORITIES - 1), &reset_task);
+ vTaskCoreAffinitySet( reset_task, 0x01 );
+ xTaskResumeAll();
+ }
+}
diff --git a/src/spi_flash.c b/src/spi_flash.c
deleted file mode 100644
index 32babc5..0000000
--- a/src/spi_flash.c
+++ /dev/null
@@ -1,267 +0,0 @@
-/**
- * Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
- *
- * SPDX-License-Identifier: BSD-3-Clause
- */
-
-// Example of reading/writing an external serial flash using the PL022 SPI interface
-
-#include "spi_flash.h"
-
-static inline void cs_select(uint cs_pin) {
- asm volatile("nop \n nop \n nop"); // FIXME
- gpio_put(cs_pin, 0);
- asm volatile("nop \n nop \n nop"); // FIXME
-}
-
-static inline void cs_deselect(uint cs_pin) {
- asm volatile("nop \n nop \n nop"); // FIXME
- gpio_put(cs_pin, 1);
- asm volatile("nop \n nop \n nop"); // FIXME
-}
-
-void __not_in_flash_func(flash_read)(spi_inst_t *spi, uint cs_pin, uint32_t addr, uint8_t* dest, size_t len) {
- cs_select(cs_pin);
- uint8_t cmdbuf[4] = {
- FLASH_CMD_READ,
- addr >> 16,
- addr >> 8,
- addr
- };
- spi_write_blocking(spi, cmdbuf, 4);
- spi_read_blocking(spi, 0, dest, len);
- cs_deselect(cs_pin);
-}
-
-void __not_in_flash_func(flash_write_enable)(spi_inst_t *spi, uint cs_pin) {
- cs_select(cs_pin);
- uint8_t cmd = FLASH_CMD_WRITE_EN;
- spi_write_blocking(spi, &cmd, 1);
- cs_deselect(cs_pin);
-}
-
-void __not_in_flash_func(flash_wait_done)(spi_inst_t *spi, uint cs_pin) {
- uint8_t status;
- do {
- cs_select(cs_pin);
- uint8_t buf[2] = {FLASH_CMD_STATUS, 0};
- spi_write_read_blocking(spi, buf, buf, 2);
- cs_deselect(cs_pin);
- status = buf[1];
- } while (status & FLASH_STATUS_BUSY_MASK);
-}
-
-void __not_in_flash_func(flash_sector_erase)(spi_inst_t *spi, uint cs_pin, uint32_t addr) {
- uint8_t cmdbuf[4] = {
- FLASH_CMD_SECTOR_ERASE,
- addr >> 16,
- addr >> 8,
- addr
- };
- flash_write_enable(spi, cs_pin);
- cs_select(cs_pin);
- spi_write_blocking(spi, cmdbuf, 4);
- cs_deselect(cs_pin);
- flash_wait_done(spi, cs_pin);
-}
-
-void __not_in_flash_func(flash_block_erase)(spi_inst_t *spi, uint cs_pin, uint32_t addr) {
- uint8_t cmdbuf[4] = {
- FLASH_CMD_BLOCK_ERASE,
- addr >> 16,
- addr >> 8,
- addr
- };
- flash_write_enable(spi, cs_pin);
- cs_select(cs_pin);
- spi_write_blocking(spi, cmdbuf, 4);
- cs_deselect(cs_pin);
- flash_wait_done(spi, cs_pin);
-}
-
-
-void __not_in_flash_func(flash_erase)(spi_inst_t *spi, uint cs_pin) {
- uint8_t cmdbuf[1] = {
- FLASH_CMD_CHIP_ERASE
- };
- flash_write_enable(spi, cs_pin);
- cs_select(cs_pin);
- spi_write_blocking(spi, cmdbuf, 1);
- cs_deselect(cs_pin);
- flash_wait_done(spi, cs_pin);
-}
-
-void __not_in_flash_func(flash_page_program)(spi_inst_t *spi, uint cs_pin, uint32_t addr, uint8_t* src) {
- uint8_t cmdbuf[4] = {
- FLASH_CMD_PAGE_PROGRAM,
- addr >> 16,
- addr >> 8,
- addr
- };
- flash_write_enable(spi, cs_pin);
- cs_select(cs_pin);
- spi_write_blocking(spi, cmdbuf, 4);
- spi_write_blocking(spi, src, FLASH_PAGE_SIZE);
- cs_deselect(cs_pin);
- flash_wait_done(spi, cs_pin);
-}
-
-void __not_in_flash_func(flash_write)(spi_inst_t *spi, uint cs_pin, uint32_t addr, uint8_t* src, size_t size) {
- uint8_t cmdbuf[4] = {
- FLASH_CMD_PAGE_PROGRAM,
- addr >> 16,
- addr >> 8,
- addr
- };
- flash_write_enable(spi, cs_pin);
- cs_select(cs_pin);
- spi_write_blocking(spi, cmdbuf, 4);
- spi_write_blocking(spi, src, size);
- cs_deselect(cs_pin);
- flash_wait_done(spi, cs_pin);
-}
-
-void write_entry(uint8_t* data_entry) {
- flash_read(spi_default, PICO_DEFAULT_SPI_CSN_PIN, base_addr, page_buffer, FLASH_PAGE_SIZE);
- for (uint16_t i = 0; i < FLASH_PAGE_SIZE; i += PACKET_SIZE) {
- if (page_buffer[i] == 0xFF) {
- base_addr += i;
- break;
- }
- if ((i + PACKET_SIZE) == FLASH_PAGE_SIZE) {
- base_addr += FLASH_PAGE_SIZE;
- flash_read(spi_default, PICO_DEFAULT_SPI_CSN_PIN, base_addr, page_buffer, FLASH_PAGE_SIZE);
- i = 0;
- }
- }
- flash_write(spi_default, PICO_DEFAULT_SPI_CSN_PIN, base_addr, data_entry, PACKET_SIZE);
- base_addr += PACKET_SIZE;
-}
-
-
-#ifdef FLASH_TEST
- #include "pico/multicore.h"
- #include <stdint.h>
- #include <inttypes.h>
- #include <stdio.h>
-
-
- void printbuf(uint8_t buf[FLASH_PAGE_SIZE]) {
- for (int i = 0; i < FLASH_PAGE_SIZE; ++i) {
- if (i % 16 == 15)
- printf("%02x\n", buf[i]);
- else
- printf("%02x ", buf[i]);
- }
- }
-
-
-
- void core1_entry() {
- printf("SPI flash example\n");
-
- // Enable SPI 0 at 1 MHz and connect to GPIOs
- spi_init(spi_default, 1000 * 1000 * 60);
- gpio_set_function(PICO_DEFAULT_SPI_RX_PIN, GPIO_FUNC_SPI);
- gpio_set_function(PICO_DEFAULT_SPI_TX_PIN, GPIO_FUNC_SPI);
- gpio_set_function(PICO_DEFAULT_SPI_SCK_PIN, GPIO_FUNC_SPI);
-
- // Chip select is active-low, so we'll initialise it to a driven-high state
- gpio_init(PICO_DEFAULT_SPI_CSN_PIN);
- gpio_set_dir(PICO_DEFAULT_SPI_CSN_PIN, GPIO_OUT);
- gpio_put(PICO_DEFAULT_SPI_CSN_PIN, 1);
-
- // flash_erase(spi_default, PICO_DEFAULT_SPI_CSN_PIN);
- // flash_sector_erase(spi_default, PICO_DEFAULT_SPI_CSN_PIN, 0);
- printf("Before program:\n");
- flash_read(spi_default, PICO_DEFAULT_SPI_CSN_PIN, 0, page_buffer, FLASH_PAGE_SIZE);
- printbuf(page_buffer);
-
- uint8_t entry[PACKET_SIZE];
-
- printf("Written Data:\n");
- printf("time (us)\t|\tstate\t|\tdep pcnt\t|\talt (m)\t|\tvel (m/s)\t|\tempty\n");
- for (uint16_t i = 0; i < 500; i++) {
- absolute_time_t now = get_absolute_time();
- uint64_t now_us= to_us_since_boot(now);
- float altitude = 10.0f * i;
- float velocity = 5.0f * i;
- uint8_t deploy_percent = (i*1000) / 200;
- printf("%"PRIu64"\t|\t%"PRIu8"\t|\t%"PRIu8"\t|\t%4.2f\t|\t%4.2f\t|\tDAWSYN_SCHRAIB\n", now_us, (uint8_t)(i), deploy_percent, altitude, velocity);
- uint32_t alt_bits = *((uint32_t *)&altitude);
- uint32_t vel_bits = *((uint32_t *)&velocity);
- entry[0] = now_us >> 56;
- entry[1] = now_us >> 48;
- entry[2] = now_us >> 40;
- entry[3] = now_us >> 32;
- entry[4] = now_us >> 24;
- entry[5] = now_us >> 16;
- entry[6] = now_us >> 8;
- entry[7] = now_us;
- entry[8] = i;
- entry[9] = deploy_percent;
- entry[10] = alt_bits >> 24;
- entry[11] = alt_bits >> 16;
- entry[12] = alt_bits >> 8;
- entry[13] = alt_bits;
- entry[14] = vel_bits >> 24;
- entry[15] = vel_bits >> 16;
- entry[16] = vel_bits >> 8;
- entry[17] = vel_bits;
- entry[18] = 'D';
- entry[19] = 'A';
- entry[20] = 'W';
- entry[21] = 'S';
- entry[22] = 'Y';
- entry[23] = 'N';
- entry[24] = '_';
- entry[25] = 'S';
- entry[26] = 'C';
- entry[27] = 'H';
- entry[28] = 'R';
- entry[29] = 'A';
- entry[30] = 'I';
- entry[31] = 'B';
- write_entry(entry);
- }
-
- printf("After program:\n");
- flash_read(spi_default, PICO_DEFAULT_SPI_CSN_PIN, 0, page_buffer, FLASH_PAGE_SIZE);
- printbuf(page_buffer);
-
- printf("\nRead Data:\n");
- printf("time (us)\t|\tstate\t|\tdep pcnt\t|\talt (m)\t|\tvel (m/s)\t|\tempty\n");
- for (uint32_t i = 0; i < base_addr; i += PACKET_SIZE) {
- flash_read(spi_default, PICO_DEFAULT_SPI_CSN_PIN, i, entry, PACKET_SIZE);
- uint64_t now_us = (((uint64_t)entry[0] << 56) | ((uint64_t)entry[1] << 48) | \
- ((uint64_t)entry[2] << 40) | ((uint64_t)entry[3] << 32) | \
- ((uint64_t)entry[4] << 24) | ((uint64_t)entry[5] << 16) | \
- ((uint64_t)entry[6] << 8) | ((uint64_t)entry[7]));
-
- uint8_t state = entry[8];
- uint8_t deploy_percent = entry[9];
-
- uint32_t alt_bits = (entry[10] << 24) | (entry[11] << 16) | (entry[12] << 8) | (entry[13]);
- uint32_t vel_bits = (entry[14] << 24) | (entry[15] << 16) | (entry[16] << 8) | (entry[17]);
- float altitude = *(float *)(&alt_bits);
- float velocity = *(float *)(&vel_bits);
- printf("%"PRIu64"\t|\t%"PRIu8"\t|\t%"PRIu8"\t|\t%4.2f\t|\t%4.2f\t|\t%c%c%c%c%c%c%c%c%c%c%c%c%c%c\n", \
- now_us, state, deploy_percent, altitude, velocity, \
- entry[18],entry[19],entry[20],entry[21],entry[22],entry[23],entry[24],entry[25],entry[26],entry[27],entry[28],entry[29],entry[30],entry[31]);
- }
-
- }
-
- int main() {
- // Enable UART so we can print status output
- stdio_init_all();
- getchar();
-
- multicore_launch_core1(core1_entry);
-
- while (1) {
- tight_loop_contents();
- }
-
- }
-#endif
diff --git a/tools/CMakeLists.txt b/tools/CMakeLists.txt
index 8806fb0..a5a7ba6 100644
--- a/tools/CMakeLists.txt
+++ b/tools/CMakeLists.txt
@@ -1,34 +1,42 @@
if (COMPILE_TOOLS)
add_executable(read_flash
- read_flash.c
- ../src/spi_flash.c
+ read_flash.cpp
+ ${PROJECT_SOURCE_DIR}/src/ms5607.cpp
+ ${PROJECT_SOURCE_DIR}/src/adxl375.cpp
+ ${PROJECT_SOURCE_DIR}/src/iim42653.cpp
+ ${PROJECT_SOURCE_DIR}/src/mmc5983ma.cpp
+ ${PROJECT_SOURCE_DIR}/src/log_format.cpp
+ ${PROJECT_SOURCE_DIR}/src/heartbeat.cpp
+ ${PROJECT_SOURCE_DIR}/src/serial.cpp
)
add_executable(servo_test
servo_test.cpp
- ../src/pwm.cpp
+ ${PROJECT_SOURCE_DIR}/src/pwm.cpp
)
add_executable(alt_test
alt_test.cpp
- )
-
- add_executable(imu_calib
- imu_calib.cpp
+ ${PROJECT_SOURCE_DIR}/src/ms5607.cpp
+ ${PROJECT_SOURCE_DIR}/src/heartbeat.cpp
)
# pull in common dependencies
- target_link_libraries(read_flash pico_stdlib hardware_spi)
- target_include_directories(read_flash PUBLIC ../include)
+ target_link_libraries(read_flash pico_stdlib pico_logger pico_flash pico_rand pico_multicore pico_sync hardware_i2c hardware_adc hardware_timer FreeRTOS-Kernel FreeRTOS-Kernel-Heap4)
+ target_include_directories(read_flash PUBLIC ${PROJECT_SOURCE_DIR}/include)
+ target_compile_definitions(read_flash PRIVATE
+ USE_FREERTOS=1
+ DEBUG=1
+ PICO_STDIO_STACK_BUFFER_SIZE=64 # use a small printf on stack buffer
+ )
+ pico_set_binary_type(read_flash copy_to_ram)
target_link_libraries(servo_test pico_stdlib hardware_pwm hardware_i2c)
- target_include_directories(servo_test PUBLIC ../include)
+ target_include_directories(servo_test PUBLIC ${PROJECT_SOURCE_DIR}/include)
target_link_libraries(alt_test pico_stdlib hardware_i2c hardware_gpio)
-
- target_link_libraries(imu_calib pico_stdlib hardware_i2c hardware_gpio)
- target_include_directories(imu_calib PUBLIC ../include)
-
+ target_include_directories(alt_test PUBLIC ${PROJECT_SOURCE_DIR}/include)
+
pico_enable_stdio_usb(read_flash 1)
pico_enable_stdio_uart(read_flash 0)
@@ -37,14 +45,10 @@ if (COMPILE_TOOLS)
pico_enable_stdio_usb(alt_test 1)
pico_enable_stdio_uart(alt_test 0)
-
- pico_enable_stdio_usb(imu_calib 1)
- pico_enable_stdio_uart(imu_calib 0)
-
+
# create map/bin/hex file etc.
pico_add_extra_outputs(read_flash)
pico_add_extra_outputs(servo_test)
pico_add_extra_outputs(alt_test)
- pico_add_extra_outputs(imu_calib)
endif()
diff --git a/tools/alt_test.cpp b/tools/alt_test.cpp
index a5c8849..9e92cdd 100644
--- a/tools/alt_test.cpp
+++ b/tools/alt_test.cpp
@@ -1,50 +1,47 @@
#include <stdio.h>
#include "hardware/gpio.h"
-#include "boards/pico_w.h"
#include "hardware/i2c.h"
#include "pico/stdio.h"
#include "pico/time.h"
-#define ALT_ADDR 0x60
+#include "ms5607.hpp"
+#include "heartbeat.hpp"
+#include "rp2040_micro.h"
+
+#define DATA_RATE_HZ 200
#define MAX_SCL 400000
-#define DATA_RATE_HZ 15
-float altitude = 0.0f;
-float get_altitude();
+bool data_callback(repeating_timer_t *rt);
+
+repeating_timer_t data_timer;
+
+MS5607 altimeter(i2c_default);
int main() {
stdio_init_all();
i2c_init(i2c_default, MAX_SCL);
- gpio_set_function(PICO_DEFAULT_I2C_SDA_PIN, GPIO_FUNC_I2C);
+ gpio_init(PICO_DEFAULT_I2C_SCL_PIN);
+ gpio_init(PICO_DEFAULT_I2C_SDA_PIN);
gpio_set_function(PICO_DEFAULT_I2C_SCL_PIN, GPIO_FUNC_I2C);
- gpio_pull_up(PICO_DEFAULT_I2C_SDA_PIN);
- gpio_pull_up(PICO_DEFAULT_I2C_SCL_PIN);
+ gpio_set_function(PICO_DEFAULT_I2C_SDA_PIN, GPIO_FUNC_I2C);
- uint8_t config[2] = {0};
+ altimeter.initialize();
+ heartbeat_initialize(PICO_DEFAULT_LED_PIN);
+ // gpio_init(PICO_DEFAULT_LED_PIN);
+ // gpio_set_dir(PICO_DEFAULT_LED_PIN, GPIO_OUT);
+ // gpio_put(PICO_DEFAULT_LED_PIN, 1);
- // Select control register(0x26)
- // Active mode, OSR = 16, altimeter mode(0xB8)
- config[0] = 0x26;
- config[1] = 0xB9;
- i2c_write_blocking(i2c_default, ALT_ADDR, config, 2, true);
- sleep_ms(1500);
+ add_repeating_timer_us(-1000000 / DATA_RATE_HZ, &data_callback, NULL, &data_timer);
while (1) {
- sleep_ms(1000);
- altitude = get_altitude();
- printf("Altitude: %4.2f\n", altitude);
+ sleep_ms(500);
+ printf("\n\nAltitude: %4.2f\nPressure: %4.2f\nTemperature: %4.2f\n", (float) altimeter.get_altitude() / ALTITUDE_SCALE_F, (float) altimeter.get_pressure() / PRESSURE_SCALE_F, (float) altimeter.get_temperature() / TEMPERATURE_SCALE_F);
}
}
-float get_altitude() {
- uint8_t reg = 0x01;
- uint8_t data[5];
- i2c_write_blocking(i2c_default, ALT_ADDR, &reg, 1, true);
- i2c_read_blocking(i2c_default, ALT_ADDR, data, 5, false);
- // Exactly how MPL3115A2 datasheet says to retrieve altitude
- float altitude = (float) ((int16_t) ((data[0] << 8) | data[1])) + (float) (data[2] >> 4) * 0.0625;
- return altitude;
+bool data_callback(repeating_timer_t *rt) {
+ altimeter.ms5607_start_sample();
+ return true;
}
-
diff --git a/tools/clock_gen_test.cpp b/tools/clock_gen_test.cpp
new file mode 100644
index 0000000..6cfdcdd
--- /dev/null
+++ b/tools/clock_gen_test.cpp
@@ -0,0 +1,22 @@
+#include <stdio.h>
+
+#include "boards/pico_w.h"
+#include "pico/stdio.h"
+#include "hardware/gpio.h"
+#include "hardware/clocks.h"
+#include "pico/time.h"
+
+//Generate a 40kHz square wave with duty 0.5 on pin 21
+int main() {
+ stdio_init_all();
+
+ //21 --> GPIO Selection, Pin 21 (Clock 0)
+ //0x6 --> Input selection, CLK_SYS as input (125MHz)
+ //3125 --> Clock Divider Int, 125MHz/40kHz = 3125
+ clock_gpio_init(21, 0x6, 3125);
+
+ while(1) {
+ printf("Clock may or may not be running?");
+ sleep_ms(1000);
+ }
+}
diff --git a/tools/imu_calib.cpp b/tools/imu_calib.cpp
deleted file mode 100644
index dc45f39..0000000
--- a/tools/imu_calib.cpp
+++ /dev/null
@@ -1,222 +0,0 @@
-#include <stdio.h>
-#include <stdint.h>
-#include <inttypes.h>
-#include <Eigen/Geometry>
-
-#include "pico/stdio.h"
-#include "hardware/gpio.h"
-#include "hardware/i2c.h"
-
-#define MAX_SCL 400000
-
-#define BNO055_OPR_MODE_ADDR 0x3D
-#define BNO055_OPR_MODE_CONFIG 0x00
-#define BNO055_SYS_TRIGGER_ADDR 0x3F
-#define BNO055_ADDRESS 0x28
-#define BNO055_CHIP_ID_ADDR 0x00
-#define BNO055_CHIP_ID 0xA0
-#define BNO055_OPR_MODE_NDOF 0x0C
-#define BNO055_CALIB_STAT_ADDR 0x35
-#define ACCEL_OFFSET_X_LSB_ADDR 0x55
-#define BNO055_LINEAR_ACCEL_DATA_X_LSB_ADDR 0x28
-#define BNO055_QUATERNION_DATA_W_LSB_ADDR 0x20
-#define UNIT_SELECTION 0x3B
-
-void get_calibration(uint8_t *sys, uint8_t *gyro, uint8_t *accel, uint8_t *mag);
-
-int main() {
- stdio_init_all();
-
- getchar();
-
- i2c_init(i2c_default, MAX_SCL);
- gpio_set_function(PICO_DEFAULT_I2C_SDA_PIN, GPIO_FUNC_I2C);
- gpio_set_function(PICO_DEFAULT_I2C_SCL_PIN, GPIO_FUNC_I2C);
- gpio_pull_up(PICO_DEFAULT_I2C_SDA_PIN);
- gpio_pull_up(PICO_DEFAULT_I2C_SCL_PIN);
-
- uint8_t buf[2] = {BNO055_CHIP_ID_ADDR};
-
- uint8_t id = 0x00;
- sleep_ms(1000);
- i2c_write_blocking(i2c_default, BNO055_ADDRESS, buf, 1, false);
- i2c_read_blocking(i2c_default, BNO055_ADDRESS, &id, 1, false);
- while (id != BNO055_CHIP_ID) {
- i2c_write_blocking(i2c_default, BNO055_ADDRESS, buf, 1, false);
- i2c_read_blocking(i2c_default, BNO055_ADDRESS, &id, 1, false);
- printf("Id not correct!, seeing: %" PRIu8 "\n", id);
- sleep_ms(10);
- }
-
- buf[0] = BNO055_OPR_MODE_ADDR;
- buf[1] = BNO055_OPR_MODE_CONFIG;
- i2c_write_blocking(i2c_default, BNO055_ADDRESS, buf, 2, false);
-
- buf[0] = BNO055_SYS_TRIGGER_ADDR;
- buf[1] = 0x20; // RESET
- i2c_write_blocking(i2c_default, BNO055_ADDRESS, buf, 2, false);
- sleep_ms(30);
-
- buf[0] = BNO055_CHIP_ID_ADDR;
- id = 0x00;
- while (id != BNO055_CHIP_ID) {
- i2c_write_blocking(i2c_default, BNO055_ADDRESS, buf, 1, false);
- i2c_read_blocking(i2c_default, BNO055_ADDRESS, &id, 1, false);
- printf("Id not correct!, seeing: %" PRIu8 "\n", id);
- sleep_ms(10);
- }
-
- buf[0] = BNO055_SYS_TRIGGER_ADDR;
- buf[1] = 0x00; // RESET
- i2c_write_blocking(i2c_default, BNO055_ADDRESS, buf, 2, false);
- sleep_ms(30);
-
- // Set units to m/s^2
- buf[0] = UNIT_SELECTION;
- buf[1] = 0x00; // Windows, Celsius, Degrees, DPS, m/s^2
- i2c_write_blocking(i2c_default, BNO055_ADDRESS, buf, 2, false);
- sleep_ms(50);
-
- buf[0] = BNO055_OPR_MODE_ADDR;
- buf[1] = BNO055_OPR_MODE_NDOF;
- i2c_write_blocking(i2c_default, BNO055_ADDRESS, buf, 2, false);
-
- uint8_t gyro = 0x00, accel = 0x00, mag = 0x00;
-
- printf("Magnetometer: Perform the figure-eight calibration dance.\n");
- while (mag != 3) {
- // Calibration Dance Step One: Magnetometer
- // Move sensor away from magnetic interference or shields
- // Perform the figure-eight until calibrated
- get_calibration(NULL, NULL, NULL, &mag);
- printf("Mag Calib Status: %3.0f\n", (100 / 3 * mag));
- sleep_ms(1000);
- }
- printf("... CALIBRATED\n");
- sleep_ms(1000);
-
- printf("Accelerometer: Perform the six-step calibration dance.\n");
- while (accel != 3) {
- // Calibration Dance Step Two: Accelerometer
- // Place sensor board into six stable positions for a few seconds each:
- // 1) x-axis right, y-axis up, z-axis away
- // 2) x-axis up, y-axis left, z-axis away
- // 3) x-axis left, y-axis down, z-axis away
- // 4) x-axis down, y-axis right, z-axis away
- // 5) x-axis left, y-axis right, z-axis up
- // 6) x-axis right, y-axis left, z-axis down
- // Repeat the steps until calibrated
- get_calibration(NULL, NULL, &accel, NULL);
- printf("Accel Calib Status: %3.0f\n", (100 / 3 * accel));
- sleep_ms(1000);
- }
- printf("... CALIBRATED\n");
- sleep_ms(1000);
-
- printf("Gyroscope: Perform the hold-in-place calibration dance.\n");
- while (gyro != 3) {
- // Calibration Dance Step Three: Gyroscope
- // Place sensor in any stable position for a few seconds
- // (Accelerometer calibration may also calibrate the gyro)
- get_calibration(NULL, &gyro, NULL, NULL);
- printf("Gyro Calib Status: %3.0f\n", (100 / 3 * gyro));
- sleep_ms(1000);
- }
- printf("... CALIBRATED\n");
- sleep_ms(1000);
- printf("CALIBRATION COMPLETED\n");
-
- // Get Sensor Offsets
- buf[0] = BNO055_OPR_MODE_ADDR;
- buf[1] = BNO055_OPR_MODE_CONFIG;
- uint8_t sensor_offsets[22];
- i2c_write_blocking(i2c_default, BNO055_ADDRESS, buf, 2, false);
- sleep_ms(30);
-
- buf[0] = ACCEL_OFFSET_X_LSB_ADDR;
- i2c_write_blocking(i2c_default, BNO055_ADDRESS, buf, 1, false);
- i2c_read_blocking(i2c_default, BNO055_ADDRESS, sensor_offsets, 18, false);
- for (uint8_t i = 0; i < 18; i++) {
- printf("sensor_offsets[%" PRIu8 "] = 0x%" PRIx8 ";\r\n", i + 1, sensor_offsets[i]);
- }
- sleep_ms(5000);
-
- buf[0] = BNO055_OPR_MODE_ADDR;
- buf[1] = BNO055_OPR_MODE_NDOF;
- i2c_write_blocking(i2c_default, BNO055_ADDRESS, buf, 2, false);
- sleep_ms(5000);
-
- getchar();
-
- uint8_t lin_accel[6];
- uint8_t quat[8];
- float accel_x, accel_y, accel_z;
- float abs_lin_accel_x, abs_lin_accel_y, abs_lin_accel_z;
- float abs_quaternion_w, abs_quaternion_x, abs_quaternion_y, abs_quaternion_z;
- while (1) {
- uint8_t lin_accel_reg = BNO055_LINEAR_ACCEL_DATA_X_LSB_ADDR;
- i2c_write_blocking(i2c_default, BNO055_ADDRESS, &lin_accel_reg, 1, true);
- i2c_read_blocking(i2c_default, BNO055_ADDRESS, lin_accel, 6, false);
- int16_t x, y, z;
- x = y = z = 0;
- x = ((int16_t)lin_accel[0]) | (((int16_t)lin_accel[1]) << 8);
- y = ((int16_t)lin_accel[2]) | (((int16_t)lin_accel[3]) << 8);
- z = ((int16_t)lin_accel[4]) | (((int16_t)lin_accel[5]) << 8);
- accel_x = ((float)x) / 100.0;
- accel_y = ((float)y) / 100.0;
- accel_z = ((float)z) / 100.0;
-
- uint8_t quat_reg = BNO055_QUATERNION_DATA_W_LSB_ADDR;
- i2c_write_blocking(i2c_default, BNO055_ADDRESS, &quat_reg, 1, true);
- i2c_read_blocking(i2c_default, BNO055_ADDRESS, quat, 8, false);
- int16_t w;
- w = x = y = z = 0;
- w = ((int16_t)quat[0]) | (((int16_t)quat[1]) << 8);
- x = ((int16_t)quat[2]) | (((int16_t)quat[3]) << 8);
- y = ((int16_t)quat[4]) | (((int16_t)quat[5]) << 8);
- z = ((int16_t)quat[6]) | (((int16_t)quat[7]) << 8);
- abs_quaternion_w = ((float)w) / 16384.0; // 2^14 LSB
- abs_quaternion_x = ((float)x) / 16384.0;
- abs_quaternion_y = ((float)y) / 16384.0;
- abs_quaternion_z = ((float)z) / 16384.0;
-
- Eigen::Quaternion<float> q;
- q.w() = abs_quaternion_w;
- q.x() = abs_quaternion_x;
- q.y() = abs_quaternion_y;
- q.z() = abs_quaternion_z;
- // q.normalize();
- Eigen::Matrix3f rotation_matrix = q.toRotationMatrix();
- Eigen::Vector3f lin_accel;
- abs_lin_accel_x = accel_x* rotation_matrix(0, 0) + accel_y * rotation_matrix(0, 1) + accel_z* rotation_matrix(0, 2);
- abs_lin_accel_y = accel_x * rotation_matrix(1, 0) + accel_y * rotation_matrix(1, 1) + accel_z * rotation_matrix(1, 2);
- abs_lin_accel_z = -1.0f * (accel_x * rotation_matrix(2, 0) + accel_y * rotation_matrix(2, 1) + accel_z * rotation_matrix(2, 2));
-
- printf("Acceleration Vector: %4.2f, %4.2f, %4.2f\n", accel_x, accel_y, accel_z);
- printf("Abs Acceleration Vector: %4.2f, %4.2f, %4.2f\n", abs_lin_accel_x, abs_lin_accel_y, abs_lin_accel_z);
- printf("Quaternion: %4.2f, %4.2f, %4.2f, %4.2f\n\n\n", abs_quaternion_w, abs_quaternion_x, abs_quaternion_y, abs_quaternion_z);
- sleep_ms(1000);
- }
-
- return 0;
-}
-
-void get_calibration(uint8_t *sys, uint8_t *gyro, uint8_t *accel, uint8_t *mag) {
- uint8_t buf[1] = {BNO055_CALIB_STAT_ADDR};
- uint8_t cal_data = 0x00;
- i2c_write_blocking(i2c_default, BNO055_ADDRESS, buf, 1, false);
- i2c_read_blocking(i2c_default, BNO055_ADDRESS, &cal_data, 1, false);
- if (sys != NULL) {
- *sys = (cal_data >> 6) & 0x03;
- }
- if (gyro != NULL) {
- *gyro = (cal_data >> 4) & 0x03;
- }
- if (accel != NULL) {
- *accel = (cal_data >> 2) & 0x03;
- }
- if (mag != NULL) {
- *mag = cal_data & 0x03;
- }
-}
-
diff --git a/tools/read_flash.c b/tools/read_flash.c
deleted file mode 100644
index 91c75fb..0000000
--- a/tools/read_flash.c
+++ /dev/null
@@ -1,78 +0,0 @@
-#include <stdio.h>
-#include <inttypes.h>
-#include "boards/pico_w.h"
-#include "hardware/spi.h"
-#include "spi_flash.h"
-
-int main() {
- stdio_init_all();
- getchar();
- // Enable SPI 0 at 1 MHz and connect to GPIOs
- spi_init(spi_default, 1000 * 1000 * 60);
- gpio_set_function(PICO_DEFAULT_SPI_RX_PIN, GPIO_FUNC_SPI);
- gpio_set_function(PICO_DEFAULT_SPI_TX_PIN, GPIO_FUNC_SPI);
- gpio_set_function(PICO_DEFAULT_SPI_SCK_PIN, GPIO_FUNC_SPI);
-
- // Chip select is active-low, so we'll initialise it to a driven-high state
- gpio_init(PICO_DEFAULT_SPI_CSN_PIN);
- gpio_set_dir(PICO_DEFAULT_SPI_CSN_PIN, GPIO_OUT);
- gpio_put(PICO_DEFAULT_SPI_CSN_PIN, 1);
-
- uint8_t entry[PACKET_SIZE];
-
- // flash_erase(spi_default, PICO_DEFAULT_SPI_CSN_PIN);
- flash_read(spi_default, PICO_DEFAULT_SPI_CSN_PIN, base_addr, page_buffer, FLASH_PAGE_SIZE);
- for (uint16_t i = 0; i < FLASH_PAGE_SIZE; i += PACKET_SIZE) {
- if (page_buffer[i] == 0xFF) {
- base_addr += i;
- break;
- }
- if ((i + PACKET_SIZE) == FLASH_PAGE_SIZE) {
- base_addr += FLASH_PAGE_SIZE;
- flash_read(spi_default, PICO_DEFAULT_SPI_CSN_PIN, base_addr, page_buffer, FLASH_PAGE_SIZE);
- i = 0;
- }
- }
-
- printf("\nRead Data:\n");
- printf("time,state,board_temp,deploy_percent,altitude,velocity,lin_ax,lin_ay,lin_az,quat_w,quat_x,quat_y,quat_z\n");
- for (uint32_t i = 0; i < base_addr; i += PACKET_SIZE) {
- flash_read(spi_default, PICO_DEFAULT_SPI_CSN_PIN, i, entry, PACKET_SIZE);
- uint64_t now_us = (((uint64_t)entry[0] << 56) | ((uint64_t)entry[1] << 48) | \
- ((uint64_t)entry[2] << 40) | ((uint64_t)entry[3] << 32) | \
- ((uint64_t)entry[4] << 24) | ((uint64_t)entry[5] << 16) | \
- ((uint64_t)entry[6] << 8) | ((uint64_t)entry[7]));
-
- uint8_t state = entry[8] >> 4;
- uint16_t temperature_data = ((uint16_t)(entry[8] & 0x0F) << 8) | ((uint16_t)entry[9]);
- const float conversionFactor = 3.3f / (1 << 12);
- float tempC = 27.0f - (((float)(temperature_data) * conversionFactor) - 0.706f) / 0.001721f;
-
- uint8_t deploy_percent = entry[10];
-
- float altitude = (float) ((int16_t) ((entry[11] << 8) | entry[12])) + (float) (entry[13] >> 4) * 0.0625;
- uint32_t vel_bits = (entry[14] << 24) | (entry[15] << 16) | (entry[16] << 8) | (entry[17]);
- float velocity = *(float *)(&vel_bits);
-
- int16_t ax = ((int16_t)entry[18]) | (((int16_t)entry[19]) << 8);
- int16_t ay = ((int16_t)entry[20]) | (((int16_t)entry[21]) << 8);
- int16_t az = ((int16_t)entry[22]) | (((int16_t)entry[23]) << 8);
- float lax = ((float)ax) / 100.0;
- float lay = ((float)ay) / 100.0;
- float laz = ((float)az) / 100.0;
-
- int16_t w, x, y, z;
- w = x = y = z = 0;
- w = ((int16_t)entry[24]) | (((int16_t)entry[25]) << 8);
- x = ((int16_t)entry[26]) | (((int16_t)entry[27]) << 8);
- y = ((int16_t)entry[28]) | (((int16_t)entry[29]) << 8);
- z = ((int16_t)entry[30]) | (((int16_t)entry[31]) << 8);
- float qw = ((float)w) / 16384.0;
- float qx = ((float)x) / 16384.0;
- float qy = ((float)y) / 16384.0;
- float qz = ((float)z) / 16384.0;
-
- printf("%"PRIu64",%"PRIu8",%04.2f,%"PRIu8",%04.2f,%04.2f,%04.2f,%04.2f,%04.2f,%04.2f,%04.2f,%04.2f,%04.2f\r\n", \
- now_us, state, tempC, deploy_percent, altitude, velocity, lax, lay, laz, qw, qx, qy, qz);
- }
-}
diff --git a/tools/read_flash.cpp b/tools/read_flash.cpp
new file mode 100644
index 0000000..b3305aa
--- /dev/null
+++ b/tools/read_flash.cpp
@@ -0,0 +1,538 @@
+#include <stdlib.h>
+#include <stdio.h>
+#include <string.h>
+#include <inttypes.h>
+
+#include <cmath> //TODO: Reimplement math properly using Eigen functions
+#include <sstream> //TODO: This is for debug purposes, remove when implemented
+#include <Eigen/Dense>
+using namespace Eigen; //TODO: Limit scope to necessary components once implemented
+
+#include "hardware/gpio.h"
+#include "hardware/i2c.h"
+#include "hardware/adc.h"
+#include <hardware/timer.h>
+#include "pico/rand.h"
+#include "pico/stdlib.h"
+#include "pico/stdio.h"
+#include "pico/multicore.h"
+#include "pico/time.h"
+#include <pico/error.h>
+#include <pico/types.h>
+
+/* Kernel includes. */
+#include "FreeRTOS.h"
+#include "FreeRTOSConfig.h"
+#include "portmacro.h"
+#include "projdefs.h"
+#include "serial.hpp"
+#include "task.h"
+#include "semphr.h"
+
+#include "heartbeat.hpp"
+#include "adxl375.hpp"
+#include "ms5607.hpp"
+#include "iim42653.hpp"
+#include "mmc5983ma.hpp"
+#include "serial.hpp"
+#include "pico_logger.h"
+#include "log_format.hpp"
+
+/* Priorities at which the tasks are created. */
+#define EVENT_HANDLER_PRIORITY ( tskIDLE_PRIORITY + 4 )
+#define SENSOR_SAMPLE_PRIORITY ( tskIDLE_PRIORITY + 3 )
+#define HEARTBEAT_TASK_PRIORITY ( tskIDLE_PRIORITY + 2 )
+#define LOGGING_PRIORITY ( tskIDLE_PRIORITY + 2 )
+#define SERIAL_TASK_PRIORITY ( tskIDLE_PRIORITY + 1 )
+
+#define SENSOR_SAMPLE_RATE_HZ 500
+#define ORIENTATION_ESTIMATION_RATE_HZ 5
+
+#define MAX_SCL 400000
+
+static void populate_log_entry(log_entry_t * log_entry);
+static void sample_cmd_func();
+static void debug_cmd_func();
+static void circular_cmd_func();
+static void read_cmd_func();
+static void write_cmd_func();
+static void erase_cmd_func();
+static void orient_cmd_func();
+static void logging_task(void * unused_arg);
+
+void vApplicationTickHook(void) { /* optional */ }
+void vApplicationMallocFailedHook(void) { /* optional */ }
+void vApplicationStackOverflowHook(TaskHandle_t xTask, char *pcTaskName) { for( ;; ); }
+
+const char* executeable_name = "read_flash.uf2";
+const size_t num_user_cmds = 7;
+const command_t user_commands[] = { {.name = "sample",
+ .len = 6,
+ .function = &sample_cmd_func},
+ {.name = "debug",
+ .len = 5,
+ .function = &debug_cmd_func},
+ {.name = "circular",
+ .len = 8,
+ .function = &circular_cmd_func},
+ {.name = "read",
+ .len = 4,
+ .function = &read_cmd_func},
+ {.name = "write",
+ .len = 5,
+ .function = &write_cmd_func},
+ {.name = "erase",
+ .len = 5,
+ .function = &erase_cmd_func},
+ {.name = "orient",
+ .len = 6,
+ .function = &orient_cmd_func} };
+
+volatile bool serial_data_output = false;
+volatile bool use_circular_buffer = false;
+
+MS5607 alt(i2c_default);
+ADXL375 adxl375(i2c_default);
+IIM42653 iim42653(i2c_default);
+MMC5983MA mmc5983ma(i2c_default);
+
+Logger logger(PACKET_SIZE, LOG_BASE_ADDR, print_log_entry);
+
+volatile TaskHandle_t logging_handle = NULL;
+
+int main() {
+ stdio_init_all();
+
+ adc_init();
+ adc_set_temp_sensor_enabled(true);
+
+ gpio_init(PICO_DEFAULT_LED_PIN);
+ gpio_set_dir(PICO_DEFAULT_LED_PIN, GPIO_OUT);
+ gpio_put(PICO_DEFAULT_LED_PIN, 0);
+
+ i2c_init(i2c_default, MAX_SCL);
+ gpio_set_function(PICO_DEFAULT_I2C_SDA_PIN, GPIO_FUNC_I2C);
+ gpio_set_function(PICO_DEFAULT_I2C_SCL_PIN, GPIO_FUNC_I2C);
+ gpio_pull_up(PICO_DEFAULT_I2C_SDA_PIN);
+ gpio_pull_up(PICO_DEFAULT_I2C_SCL_PIN);
+
+ sleep_ms(2500);
+
+ info_cmd_func();
+ stdio_flush();
+
+ logger.initialize(true);
+
+ alt.initialize();
+ sleep_ms(500);
+ adxl375.initialize();
+ sleep_ms(500);
+ iim42653.initialize();
+ sleep_ms(500);
+ mmc5983ma.initialize();
+ sleep_ms(500);
+
+ xTaskCreate(heartbeat_task, "heartbeat", 256, NULL, HEARTBEAT_TASK_PRIORITY, NULL);
+ xTaskCreate(serial_task, "serial", 8192, NULL, SERIAL_TASK_PRIORITY, NULL);
+
+ vTaskStartScheduler();
+
+ while (1) {
+ tight_loop_contents();
+ }
+}
+
+static void logging_task(void * unused_arg) {
+ TickType_t xLastWakeTime;
+ const TickType_t xFrequency = pdMS_TO_TICKS(1000 / 10);
+
+ xLastWakeTime = xTaskGetTickCount();
+ printf("Time,Pressure,Altitude,Temperature,ax,ay,az,ax,ay,az,gx,gy,gz,ax,ay,az\n");
+ while (1) {
+ vTaskDelayUntil(&xLastWakeTime, xFrequency);
+// printf("%" PRIu64 ",", time_us_64());
+// printf("%4.2f,", ((float) alt.get_pressure()) / PRESSURE_SCALE_F);
+// printf("%4.2f,", ((float) alt.get_altitude()) / ALTITUDE_SCALE_F);
+// printf("%4.2f,", ((float) alt.get_temperature()) / TEMPERATURE_SCALE_F);
+// printf("%4.2f,", adxl375.scale(adxl375.get_ax()));
+// printf("%4.2f,", adxl375.scale(adxl375.get_ay()));
+// printf("%4.2f,", adxl375.scale(adxl375.get_az()));
+// printf("%4.2f,", iim42653.scale_accel(iim42653.get_ax()));
+// printf("%4.2f,", iim42653.scale_accel(iim42653.get_ay()));
+// printf("%4.2f,", iim42653.scale_accel(iim42653.get_az()));
+// printf("%4.2f,", iim42653.scale_gyro(iim42653.get_gx()));
+// printf("%4.2f,", iim42653.scale_gyro(iim42653.get_gy()));
+// printf("%4.2f,", iim42653.scale_gyro(iim42653.get_gz()));
+// printf("%" PRIi16 ",", mmc5983ma.get_ax());
+// printf("%" PRIi16 ",", mmc5983ma.get_ay());
+// printf("%" PRIi16 ",", mmc5983ma.get_az());
+// printf("\r\n");
+ log_entry_t log_entry;
+ populate_log_entry(&log_entry);
+ printf("\nWriting the following entry!\n");
+ print_log_entry(reinterpret_cast<const uint8_t *>(&log_entry));
+ if (use_circular_buffer) {
+ logger.write_circular_buffer(reinterpret_cast<const uint8_t *>(&log_entry));
+ } else {
+ logger.write_memory(reinterpret_cast<const uint8_t *>(&log_entry), true);
+ }
+ stdio_flush();
+ }
+
+}
+
+//TODO: This task is getting increasingly complex and involved, it may be worth migrating to a class of its own
+static void pose_estimation_task(void * unused_arg) {
+ printf("--POSE: INITIALIZING DATA MEMBERS\n");
+ TickType_t xLastWakeTime;
+ const TickType_t xFrequency = pdMS_TO_TICKS(1000 / ORIENTATION_ESTIMATION_RATE_HZ);
+ xLastWakeTime = xTaskGetTickCount();
+ int orient_count = 0;
+
+ Quaternionf q_k(1, 0, 0, 0); //Initialize to straight upright
+ Quaternionf q_k_est = q_k;
+ Matrix4f P_k = Matrix4f::Identity()*0.01f; //TODO: Tune this initialization value
+ Matrix4f P_k_est = P_k;
+
+ //TODO: Store covariance values somewhere reasonable instead of hardcoding them
+ Matrix3f gyro_covariance = Matrix3f::Identity()*0.05f*M_PI/180.0f; //0.05deg/s RMSE @ 100HZ Bandwidth
+ Matrix<float, 6, 6> accel_mag_covariance;
+ accel_mag_covariance << 0.00065f, 0, 0, 0, 0, 0,
+ 0, 0.00065f, 0, 0, 0, 0,
+ 0, 0, 0.00070f, 0, 0, 0,
+ 0, 0, 0, 0.00120f, 0, 0,
+ 0, 0, 0, 0, 0.00120f, 0,
+ 0, 0, 0, 0, 0, 0.00120f;
+ //accel_mag_covariance *= 3;
+
+ //Stored intermediate equation matrices
+ Matrix4f gyro_skew; //Skew-symmetric matrix equivalent of gyroscope output
+ Matrix4f I_4 = Matrix4f::Identity(); //4x4 Identity matrix, used for F_k calculation
+
+ Matrix4f F_k; //State Transition Matrix
+ Matrix4f H_k; //Observation Matrix
+ Matrix4f K_k; //Kalman Gain Matrix
+ Matrix<float, 4, 3> J_process_k; //Jacobian for process (gyro) covariance transformation
+ Matrix<float, 4, 6> J_observation_k; //Jacobian for observation (accel/mag) covariance transformation
+ Matrix4f process_noise_transformed; //Matrix of transformed process noise
+ Matrix4f observation_noise_transformed; //Matrix of transformed observation noise
+ Matrix<float, 4, 1> z_k; //Measurement vector
+ Matrix<float, 4, 1> z_k_est; //Estimated measurement vector, used for Kalman filter calculation
+
+ while (1) {
+ vTaskDelayUntil(&xLastWakeTime, xFrequency);
+
+ //printf("-------- BEGINNING UPDATE COMPUTATION --------\n");
+ //Get all required sensor values and compute intermediate values
+ float imu_ax = -IIM42653::scale_accel(iim42653.get_ax());
+ float imu_ay = -IIM42653::scale_accel(iim42653.get_ay());
+ float imu_az = IIM42653::scale_accel(iim42653.get_az());
+ float imu_gx = -IIM42653::scale_gyro(iim42653.get_gx())/180.0f*M_PI;
+ float imu_gy = -IIM42653::scale_gyro(iim42653.get_gy())/180.0f*M_PI;
+ float imu_gz = IIM42653::scale_gyro(iim42653.get_gz())/180.0f*M_PI;
+ float mag_x = -MMC5983MA::scale_mag(mmc5983ma.get_ay()); //TODO: Not convinced mag axes are correct
+ float mag_y = MMC5983MA::scale_mag(mmc5983ma.get_ax());
+ float mag_z = -MMC5983MA::scale_mag(mmc5983ma.get_az());
+
+ //Normalize accelerometer and magnetometer measurements
+ float imu_a_mag = std::sqrt(std::pow(imu_ax, 2) + std::pow(imu_ay, 2) + std::pow(imu_az, 2));
+ float mag_mag = std::sqrt(std::pow(mag_x, 2) + std::pow(mag_y, 2) + std::pow(mag_z, 2));
+ imu_ax /= imu_a_mag;
+ imu_ay /= imu_a_mag;
+ imu_az /= imu_a_mag;
+ mag_x /= mag_mag;
+ mag_y /= mag_mag;
+ mag_z /= mag_mag;
+
+ printf("--- [I] INITIALIZATION | IMU Accel direct outputs (x, y, z): [%4.3f, %4.3f, %4.3f]\n", imu_ax, imu_ay, imu_az);
+ printf("--- [I] INITIALIZATION | IMU Gyro direct outputs (x, y, z): [%4.3f, %4.3f, %4.3f]\n", imu_gx, imu_gy, imu_gz);
+ printf("--- [I] INITIALIZATION | Magnetometer direct outputs (x, y, z): [%4.3f, %4.3f, %4.3f]\n", mag_x, mag_y, mag_z);
+
+ float mag_D = imu_ax*mag_x + imu_ay*mag_y + imu_az*mag_z;
+ float mag_N = std::sqrt(1.0f - std::pow(mag_D, 2));
+ printf("--- [I] INITIALIZATION | Magnetometer values (mag_mag, mag_D, mag_N): [%2.4f, %2.4f, %2.4f]\n", mag_mag, mag_D, mag_N);
+
+ //UPDATE | Calculate Kalman gain
+ //TODO: This Jacobian calculation is FUGLY, and very computationally intensive
+ // Separate out common math, vectorize, and put it in a function somewhere?
+ float pd_mD_ax = mag_x/(2*mag_D);
+ float pd_mD_ay = mag_y/(2*mag_D);
+ float pd_mD_az = mag_z/(2*mag_D);
+ float pd_mD_mx = imu_ax/(2*mag_D);
+ float pd_mD_my = imu_ay/(2*mag_D);
+ float pd_mD_mz = imu_az/(2*mag_D);
+ float pd_mN_ax = -mag_D/mag_N*pd_mD_ax;
+ float pd_mN_ay = -mag_D/mag_N*pd_mD_ay;
+ float pd_mN_az = -mag_D/mag_N*pd_mD_az;
+ float pd_mN_mx = -mag_D/mag_N*pd_mD_mx;
+ float pd_mN_my = -mag_D/mag_N*pd_mD_my;
+ float pd_mN_mz = -mag_D/mag_N*pd_mD_mz;
+ float common_num = (imu_ay*mag_z - imu_az*mag_y);
+ float common_denom = std::pow(mag_N, 2);
+
+ float J_o_4_1 = (-pd_mN_ax*common_num)/common_denom;
+ float J_o_4_2 = (mag_z*mag_N - pd_mN_ay*common_num)/common_denom;
+ float J_o_4_3 = (-mag_y*mag_N - pd_mN_az*common_num)/common_denom;
+ float J_o_4_4 = (-pd_mN_mx*common_num)/common_denom;
+ float J_o_4_5 = (-imu_az*mag_N - pd_mN_my*common_num)/common_denom;
+ float J_o_4_6 = (imu_ay*mag_N - pd_mN_mz*common_num)/common_denom;
+ J_observation_k << 1.0f, 0, 0, 0, 0, 0,
+ 0, 1.0f, 0, 0, 0, 0,
+ 0, 0, 1.0f, 0, 0, 0,
+ J_o_4_1, J_o_4_2, J_o_4_3, J_o_4_4, J_o_4_5, J_o_4_6;
+ //printf("- [U] CALC KALMAN GAIN | [J_o_4_1 - J_o_4_6] after calculation, from J_observation_k: [%4.2f | %4.2f | %4.2f | %4.2f | %4.2f | %4.2f]\n", J_observation_k(3, 0), J_observation_k(3, 1), J_observation_k(3, 2), J_observation_k(3, 3), J_observation_k(3, 4), J_observation_k(3, 5));
+
+ observation_noise_transformed = J_observation_k*accel_mag_covariance*J_observation_k.transpose();
+ //printf("- [U] CALC KALMAN GAIN | Diagonal of observation_noise_transformed after transformation: [%2.4f, %2.4f, %2.4f, %2.4f]\n", observation_noise_transformed(0, 0), observation_noise_transformed(1, 1), observation_noise_transformed(2, 2), observation_noise_transformed(3, 3));
+
+ H_k << -q_k.y(), q_k.z(), -q_k.w(), q_k.x(),
+ q_k.x(), q_k.w(), q_k.z(), q_k.y(),
+ q_k.w(), -q_k.x(), -q_k.y(), q_k.z(),
+ q_k.z(), q_k.y(), q_k.x(), q_k.w();
+ H_k *= 2;
+ //printf("- [U] CALC KALMAN GAIN | First column of H_k after computation: [%2.4f, %2.4f, %2.4f, %2.4f]\n", H_k(0, 0), H_k(1, 0), H_k(2, 0), H_k(3, 0));
+
+ K_k = P_k*H_k.transpose()*(H_k*P_k*H_k.transpose() + observation_noise_transformed).inverse();
+ //printf("- [U] CALC KALMAN GAIN | First column of K_k after computation: [%2.4f, %2.4f, %2.4f, %2.4f]\n", K_k(0, 0), K_k(1, 0), K_k(2, 0), K_k(3, 0));
+
+ //UPDATE | Calculate current state estimate based on accel/mag measurements
+ z_k << imu_ax, imu_ay, imu_az, ((imu_ay*mag_z - imu_az*mag_y)/mag_N);
+ z_k_est = H_k*q_k_est.coeffs(); //TODO: Confirm quaternion multiplication, output and check
+ q_k = q_k_est.coeffs() + K_k*(z_k - z_k_est); //TODO: Confirm quaternion arithmetic, output and check
+ q_k.normalize(); //Ensure state output is a proper rotation quaternion
+ //printf("- [U] CALC STATE ESTIMATE | See below block for direct output\n");
+
+ //UPDATE | Calculate state covariance based on accel/mag measurements
+ P_k = (I_4 - K_k*H_k)*P_k_est;
+ //printf("- [U] CALC STATE COVAR | First column of P_k after computation: [%2.4f, %2.4f, %2.4f, %2.4f]\n", P_k(0, 0), P_k(1, 1), P_k(2, 2), P_k(3, 3));
+
+ //printf("-------- COMPLETED UPDATE COMPUTATION! --------\n\n");
+ //if (orient_count == ORIENTATION_ESTIMATION_RATE_HZ) {
+ printf("~~> Estimate (q_k) Coefficients [w, x, y, z]: [%1.4f, %1.4f, %1.4f, %1.4f]\n", q_k.w(), q_k.x(), q_k.y(), q_k.z());
+ Vector3f testVect = q_k.toRotationMatrix().eulerAngles(2, 1, 0)*180.0f/M_PI;
+ printf("~~> Estimate (q_k) in Euler [Yaw, Pitch, Roll]: [%3.3f, %3.3f, %3.3f]\n", testVect[0], testVect[1], testVect[2]);
+ Vector3f testAccelVect(imu_ax, imu_ay, imu_az);
+ Vector3f testAccelVectRotated = q_k._transformVector(testAccelVect);
+ printf("~~> Estimate (q_k) rotated accel magnitude vector: [%2.4f, %2.4f, %2.4f]\n\n", testAccelVectRotated[0], testAccelVectRotated[1], testAccelVectRotated[2]);
+
+ // orient_count = 0;
+ //}
+ //orient_count++;
+
+ //printf("-------- BEGINNING PREDICT COMPUTATION --------\n");
+
+ //Predict next state based on gyroscope measurements
+ gyro_skew << 0, -imu_gx, -imu_gy, -imu_gz,
+ imu_gx, 0, imu_gz, -imu_gy,
+ imu_gy, -imu_gz, 0, imu_gx,
+ imu_gz, imu_gy, -imu_gx, 0;
+ //printf("- [P] PREDICT STATE | Top second element of gyro_skew after set: [%4.2f]\n", gyro_skew(0, 1));
+
+ F_k = I_4 + (0.5f/ORIENTATION_ESTIMATION_RATE_HZ)*gyro_skew;
+ //printf("- [P] PREDICT STATE | First column of F_k after set: [%2.4f, %2.4f, %2.4f, %2.4f]\n", F_k(0, 0), F_k(1, 0), F_k(2, 0), F_k(3, 0));
+
+ q_k_est = F_k*q_k.coeffs();
+ q_k_est.normalize(); //TODO: CONFIRM normalization necessary at intermediary steps
+ //printf("- [P] PREDICT STATE | State estimate (q_k_est) coefficients after predict step: [%1.4f, %1.4f, %1.4f, %1.4f]\n", q_k_est.w(), q_k_est.x(), q_k_est.y(), q_k_est.z());
+
+ //Predict next covariance based on gyroscope measurements + Jacobian-transformed measurement variance
+ J_process_k << q_k.x(), q_k.y(), q_k.z(),
+ -1.0f*q_k.w(), q_k.z(), -1.0f*q_k.y(),
+ -1.0f*q_k.z(), -1.0f*q_k.w(), q_k.x(),
+ q_k.y(), -1.0f*q_k.x(), -1.0f*q_k.w();
+ //printf("- [P] PREDICT COVAR | Top left element of J_process_k after computation: [%4.2f]\n", J_process_k(0, 0));
+
+ process_noise_transformed = std::pow(0.5f/ORIENTATION_ESTIMATION_RATE_HZ, 2) *
+ J_process_k*gyro_covariance*J_process_k.transpose();
+ //printf("- [P] PREDICT COVAR | Diagonal of process_noise_transformed after transformation: [%2.4f, %2.4f, %2.4f, %2.4f]\n", process_noise_transformed(0, 0), process_noise_transformed(1, 1), process_noise_transformed(2, 2), process_noise_transformed(3, 3));
+
+ P_k_est = F_k*P_k*F_k.transpose() + process_noise_transformed;
+ //printf("- [P] PREDICT COVAR | Diagonal of P_k_est after prediction computation: [%2.4f, %2.4f, %2.4f, %2.4f]\n", P_k_est(0, 0), P_k_est(1, 1), P_k_est(2, 2), P_k_est(3, 3));
+ //printf("-------- PREDICT COMPUTATION COMPLETED! --------\n\n\n");
+ }
+}
+
+static void sample_cmd_func() {
+ static bool sampling = false;
+
+ if (sampling == false) {
+ vTaskSuspendAll();
+
+ xTaskCreate(MS5607::update_ms5607_task, "update_ms5607", 256, &alt, SENSOR_SAMPLE_PRIORITY, &(alt.update_task_handle));
+ xTaskCreate(ADXL375::update_adxl375_task, "update_adxl375", 256, &adxl375, SENSOR_SAMPLE_PRIORITY, &(adxl375.update_task_handle));
+ xTaskCreate(IIM42653::update_iim42653_task, "update_iim42653", 256, &iim42653, SENSOR_SAMPLE_PRIORITY, &(iim42653.update_task_handle));
+ xTaskCreate(MMC5983MA::update_mmc5983ma_task, "update_mmc5983ma", 256, &mmc5983ma, SENSOR_SAMPLE_PRIORITY, &(mmc5983ma.update_task_handle));
+
+ xTaskCreate(MS5607::ms5607_sample_handler, "ms5607_sample_handler", 256, &alt, EVENT_HANDLER_PRIORITY, &(alt.sample_handler_task_handle));
+
+ vTaskCoreAffinitySet( alt.update_task_handle, 0x01 );
+ vTaskCoreAffinitySet( adxl375.update_task_handle, 0x01 );
+ vTaskCoreAffinitySet( iim42653.update_task_handle, 0x01 );
+ vTaskCoreAffinitySet( mmc5983ma.update_task_handle, 0x01 );
+
+ vTaskCoreAffinitySet( alt.sample_handler_task_handle, 0x01 );
+ sampling = true;
+ xTaskResumeAll();
+ } else {
+ printf("Stopping sample!\n");
+ vTaskSuspendAll();
+
+ vTaskDelete(alt.update_task_handle);
+ vTaskDelete(adxl375.update_task_handle);
+ vTaskDelete(iim42653.update_task_handle);
+ vTaskDelete(mmc5983ma.update_task_handle);
+
+ vTaskDelete(alt.sample_handler_task_handle);
+
+ alt.update_task_handle = NULL;
+ adxl375.update_task_handle = NULL;
+ iim42653.update_task_handle = NULL;
+ mmc5983ma.update_task_handle = NULL;
+
+ alt.sample_handler_task_handle = NULL;
+
+ sampling = false;
+ xTaskResumeAll();
+ }
+}
+
+
+static void debug_cmd_func() {
+ if (logging_handle == NULL) {
+ vTaskSuspendAll();
+ xTaskCreate(logging_task, "logging", 256, NULL, LOGGING_PRIORITY, const_cast<TaskHandle_t *>(&logging_handle));
+ vTaskCoreAffinitySet(logging_handle, 0x02);
+ xTaskResumeAll();
+ } else {
+ vTaskSuspendAll();
+ vTaskDelete(logging_handle);
+ logging_handle = NULL;
+ xTaskResumeAll();
+ }
+}
+
+static void circular_cmd_func() {
+ if (logging_handle != NULL) {
+ vTaskSuspend(logging_handle);
+ }
+ if (!use_circular_buffer) {
+ logger.initialize_circular_buffer(PAD_BUFFER_SIZE);
+ use_circular_buffer = true;
+ } else {
+ logger.flush_circular_buffer(true);
+ use_circular_buffer = false;
+ }
+ if (logging_handle != NULL) {
+ vTaskResume(logging_handle);
+ }
+}
+
+static void read_cmd_func() {
+ if (logging_handle != NULL) {
+ vTaskSuspend(logging_handle);
+ }
+ if (use_circular_buffer) {
+ logger.read_circular_buffer();
+ } else {
+ logger.read_memory();
+ }
+ vTaskResume(logging_handle);
+}
+
+static void populate_log_entry(log_entry_t * log_entry) {
+ log_entry->time_us = time_us_64();
+
+ adc_select_input(4);
+ log_entry->temperature_chip = adc_read();
+ log_entry->state = PAD;
+ log_entry->deploy_percent = 80;
+ log_entry->pressure = alt.get_pressure();
+ log_entry->altitude = alt.get_altitude();
+ log_entry->temperature_alt = alt.get_temperature();
+
+ log_entry->ax = iim42653.get_ax();
+ log_entry->ay = iim42653.get_ay();
+ log_entry->az = iim42653.get_az();
+ log_entry->gx = iim42653.get_gx();
+ log_entry->gy = iim42653.get_gy();
+ log_entry->gz = iim42653.get_gz();
+
+ log_entry->mag_x = mmc5983ma.get_ax();
+ log_entry->mag_y = mmc5983ma.get_ay();
+ log_entry->mag_z = mmc5983ma.get_az();
+
+ log_entry->high_g_x = adxl375.get_ax();
+ log_entry->high_g_y = adxl375.get_ay();
+ log_entry->high_g_z = adxl375.get_az();
+
+ log_entry->data0 = get_rand_64();
+ log_entry->data1 = get_rand_64();
+ log_entry->data2 = get_rand_32();
+ log_entry->data3 = get_rand_32();
+}
+
+static void write_cmd_func() {
+ if (logging_handle != NULL) {
+ vTaskSuspend(logging_handle);
+ }
+ uint64_t start = time_us_64();
+ log_entry_t log_entry;
+ populate_log_entry(&log_entry);
+ printf("\nWriting the following entry!\n");
+ print_log_entry(reinterpret_cast<const uint8_t *>(&log_entry));
+ if (use_circular_buffer) {
+ logger.write_circular_buffer(reinterpret_cast<const uint8_t *>(&log_entry));
+ } else {
+ logger.write_memory(reinterpret_cast<const uint8_t *>(&log_entry), true);
+ }
+ uint64_t end = time_us_64();
+ printf("\nTook %" PRIu64 " us to write that entry!\n", (end - start));
+ if (logging_handle != NULL) {
+ vTaskResume(logging_handle);
+ }
+}
+
+static void erase_cmd_func() {
+ if (logging_handle != NULL) {
+ vTaskSuspend(logging_handle);
+ }
+ logger.erase_memory();
+ if (logging_handle != NULL) {
+ vTaskResume(logging_handle);
+ }
+}
+
+static void orient_cmd_func() {
+ /*
+ float pitch_rad = std::atan(imu_ay/std::sqrt(std::pow(imu_ax, 2) + std::pow(imu_az, 2)));
+ float roll_rad = std::atan(imu_ax/std::sqrt(std::pow(imu_ay, 2) + std::pow(imu_az, 2)));
+ float yaw_rad = std::atan2(-mag_y*std::cos(roll_rad) + mag_z*std::sin(roll_rad),
+ mag_x*std::cos(pitch_rad) + mag_y*std::sin(pitch_rad)*std::sin(roll_rad) + mag_z*std::cos(roll_rad) * std::sin(pitch_rad));
+ */
+
+ static TaskHandle_t pose_estimation_handle = NULL;
+ static bool estimating = false;
+
+ if (!estimating) {
+ printf("================ BEGINNING STATE ESTIMATION ================\n");
+ vTaskSuspendAll();
+
+ //TODO: Assign pose estimation unique priority?
+ xTaskCreate(pose_estimation_task, "pose_estimation", 1024, NULL,
+ SENSOR_SAMPLE_PRIORITY, &pose_estimation_handle);
+ vTaskCoreAffinitySet( pose_estimation_handle, 0x01 );
+
+ estimating = true;
+ xTaskResumeAll();
+ } else {
+ printf("================= ENDING STATE ESTIMATION ================\n");
+ vTaskSuspendAll();
+
+ vTaskDelete(pose_estimation_handle);
+ pose_estimation_handle = NULL;
+
+ estimating = false;
+ xTaskResumeAll();
+ }
+}
+
diff --git a/tools/servo_test.cpp b/tools/servo_test.cpp
index c5e8e6e..9c26c25 100644
--- a/tools/servo_test.cpp
+++ b/tools/servo_test.cpp
@@ -3,16 +3,14 @@
#include "pico/stdio.h"
#include "pwm.hpp"
-#define MOSFET_PIN 1
-
PWM pwm;
int main() {
stdio_init_all();
// Initialize MOSFET
- gpio_init(MOSFET_PIN);
- gpio_set_dir(MOSFET_PIN, GPIO_OUT);
- gpio_put(MOSFET_PIN, 1);
+ gpio_init(MICRO_DEFAULT_SERVO_ENABLE);
+ gpio_set_dir(MICRO_DEFAULT_SERVO_ENABLE, GPIO_OUT);
+ gpio_put(MICRO_DEFAULT_SERVO_ENABLE, 1);
pwm.init();
uint8_t duty_cycle = 13;
while (1) {