diff --git a/README.md b/README.md index 9b7936eda..05353d6b2 100644 --- a/README.md +++ b/README.md @@ -61,6 +61,7 @@ You can easily run the sensor hardware interface, the sensor hardware monitor an ```bash ros2 launch nebula_ros nebula_launch.py sensor_model:=Pandar64 +ros2 launch nebula_ros nebula_launch.py sensor_model:=Falcon sensor_ip:=172.168.1.10 ``` If you don't want to launch the hardware (i.e. when you are working from a rosbag), set the `launch_hw` flag to false: @@ -99,6 +100,8 @@ Supported models, where sensor_model is the ROS param to be used at launch: | Velodyne | VLP-16-HiRes | VLP16 | | :x: | | Velodyne | VLP-32 | VLP32 | VLP32.yaml | :warning: | | Velodyne | VLS-128 | VLS128 | VLS128.yaml | :warning: | +| Innovusion | Falcon | Falcon | Falcon.yaml | :warning: | +| Innovusion | Robin | Robin | Robin.yaml | :warning: | Test status:\ :heavy_check_mark:: complete\ @@ -222,6 +225,42 @@ Parameters shared by all supported models: | cloud_min_angle | uint16 | 0 | degrees [0, 360] | FoV start angle | | cloud_max_angle | uint16 | 359 | degrees [0, 360] | FoV end angle | +### Innovusion specific parameters + +#### Supported return modes + +| return_mode | Mode | +| --------------- | ------------------ | +| SingleFirst | Single (First) | +| SingleStrongest | Single (Strongest) | +| SingleLast | Single (Last) | +| Dual | Dual | + +#### Hardware interface parameters + +| Parameter | Type | Default | Accepted values | Description | +| --------------- | ------ | --------------- | ----------------- | --------------- | +| frame_id | string | innovusion | | ROS frame ID | +| sensor_ip | string | 172.168.1.11 | | Sensor IP | +| host_ip | string | 255.255.255.255 | | Host IP | +| data_port | uint16 | 8010 | | Sensor port | +| gnss_port | uint16 | 8010 | | GNSS port | +| frequency_ms | uint16 | 100 | milliseconds, > 0 | Time per scan | +| packet_mtu_size | uint16 | 8820 | | Packet MTU size | +| cloud_min_angle | uint16 | 0 | degrees [0, 120] | FoV start angle | +| cloud_max_angle | uint16 | 120 | degrees [0, 120] | FoV end angle | + +#### Driver parameters + +| Parameter | Type | Default | Accepted values | Description | +| ---------------- | ------ | -------- | -------------------- | ------------------------------------- | +| frame_id | string | innovusion | | ROS frame ID | +| calibration_file | string | | | LiDAR calibration file | +| min_range | double | 0.3 | meters, >= 0.3 | Minimum point range published | +| max_range | double | 500.0 | meters, <= 500.0 | Maximum point range published | +| cloud_min_angle | uint16 | 0 | degrees [0, 120] | FoV start angle | +| cloud_max_angle | uint16 | 120 | degrees [0, 120] | FoV end angle + ## Software design overview ![DriverOrganization](docs/diagram.png) diff --git a/nebula_common/include/nebula_common/innovusion/innovusion_common.hpp b/nebula_common/include/nebula_common/innovusion/innovusion_common.hpp new file mode 100644 index 000000000..636640649 --- /dev/null +++ b/nebula_common/include/nebula_common/innovusion/innovusion_common.hpp @@ -0,0 +1,59 @@ +#ifndef NEBULA_INNOVUSION_COMMON_H +#define NEBULA_INNOVUSION_COMMON_H + +#include "nebula_common/nebula_common.hpp" +#include "nebula_common/nebula_status.hpp" + +#include +#include +namespace nebula +{ +namespace drivers +{ +/// @brief struct for Innovusion sensor configuration +struct InnovusionSensorConfiguration : SensorConfigurationBase +{ + double cloud_min_range; + double cloud_max_range; +}; +/// @brief Convert InnovusionSensorConfiguration to string (Overloading the << operator) +/// @param os +/// @param arg +/// @return stream +inline std::ostream & operator<<(std::ostream & os, InnovusionSensorConfiguration const & arg) +{ + os << (SensorConfigurationBase)(arg) << ", cloud_min_range: " << arg.cloud_min_range + << ", cloud_max_range: " << arg.cloud_max_range << "\n"; + return os; +} + +/// @brief struct for Innovusion calibration configuration +struct InnovusionCalibrationConfiguration : CalibrationConfigurationBase +{ + // InnovusionCalibration innovusion_calibration; + inline nebula::Status LoadFromFile(const std::string &) + { + return Status::OK; + } + inline nebula::Status SaveFile(const std::string &) + { + return Status::OK; + } +}; + +/// @brief Convert return mode name to ReturnMode enum (Innovusion-specific ReturnModeFromString) +/// @param return_mode Return mode name (Upper and lower case letters must match) +/// @return Corresponding ReturnMode +inline ReturnMode ReturnModeFromStringInnovusion(const std::string & return_mode) +{ + if (return_mode == "Strongest") return ReturnMode::SINGLE_STRONGEST; + if (return_mode == "Last") return ReturnMode::SINGLE_LAST; + if (return_mode == "Dual") return ReturnMode::DUAL_ONLY; + + return ReturnMode::UNKNOWN; +} + +} // namespace drivers +} // namespace nebula + +#endif // NEBULA_INNOVUSION_COMMON_H diff --git a/nebula_common/include/nebula_common/innovusion/innovusion_status.hpp b/nebula_common/include/nebula_common/innovusion/innovusion_status.hpp new file mode 100644 index 000000000..8ae2c0ec8 --- /dev/null +++ b/nebula_common/include/nebula_common/innovusion/innovusion_status.hpp @@ -0,0 +1,69 @@ +#ifndef Innovusion_STATUS_HPP +#define Innovusion_STATUS_HPP + +#include "nebula_common/nebula_status.hpp" + +#include +#include + +namespace nebula +{ +// from https://marycore.jp/prog/cpp/extends-enum/ + +/// @brief Status definition for Innovusion +struct InnovusionStatus : Status +{ + using Status::Status; + +private: + int _type_num; + +public: + enum InnovusionType { + INVALID_RPM_ERROR = Type_end_of_Status + 1, + INVALID_FOV_ERROR, + INVALID_RETURN_MODE_ERROR, + Type_end_of_Status = INVALID_RPM_ERROR + } _Innovusion_type; + InnovusionStatus() : _type_num(static_cast(Status::OK)) { _type = static_cast(type()); } + InnovusionStatus(Type v) : _type_num(static_cast(v)) { _type = v; } + InnovusionStatus(InnovusionType v) : _type_num(static_cast(v)), _Innovusion_type(v) + { + _type = Type::Type_end_of_Status; + } + InnovusionStatus(int type) : _type_num(type) {} + int type() const { return _type_num; } + friend bool operator==(const InnovusionStatus & L, const InnovusionStatus & R) + { + return L.type() == R.type(); + } + friend bool operator!=(const InnovusionStatus & L, const InnovusionStatus & R) + { + return L.type() != R.type(); + } + + /// @brief Convert Status enum to string (Overloading the << operator) + /// @param os + /// @param arg + /// @return stream + friend std::ostream & operator<<(std::ostream & os, nebula::InnovusionStatus const & arg) + { + switch (arg.type()) { + // Velodyne + case InnovusionStatus::INVALID_RPM_ERROR: + os << "Invalid rotation speed value(range from 300 to 1200, in increments of 60)"; + break; + case InnovusionStatus::INVALID_FOV_ERROR: + os << "Invalid fov value(0 to 359)"; + break; + case InnovusionStatus::INVALID_RETURN_MODE_ERROR: + os << "Invalid return mode(only SINGLE_STRONGEST, SINGLE_LAST, DUAL_ONLY)"; + break; + default: + os << Status(arg._type); + } + return os; + } +}; +} // namespace nebula +#endif // Innovusion_STATUS_HPP diff --git a/nebula_common/include/nebula_common/nebula_common.hpp b/nebula_common/include/nebula_common/nebula_common.hpp index 3baccec73..137cf266d 100644 --- a/nebula_common/include/nebula_common/nebula_common.hpp +++ b/nebula_common/include/nebula_common/nebula_common.hpp @@ -323,6 +323,8 @@ enum class SensorModel { VELODYNE_VLP32MR, VELODYNE_HDL32, VELODYNE_VLP16, + INNOVUSION_FALCON, + INNOVUSION_ROBIN }; /// @brief not used? @@ -401,6 +403,12 @@ inline std::ostream & operator<<(std::ostream & os, nebula::drivers::SensorModel case SensorModel::VELODYNE_VLP16: os << "VLP16"; break; + case SensorModel::INNOVUSION_FALCON: + os << "Falcon"; + break; + case SensorModel::INNOVUSION_ROBIN: + os << "Robin"; + break; case SensorModel::UNKNOWN: os << "Sensor Unknown"; break; @@ -468,6 +476,9 @@ inline SensorModel SensorModelFromString(const std::string & sensor_model) if (sensor_model == "VLP32MR") return SensorModel::VELODYNE_VLP32MR; if (sensor_model == "HDL32") return SensorModel::VELODYNE_HDL32; if (sensor_model == "VLP16") return SensorModel::VELODYNE_VLP16; + // innovusion + if (sensor_model == "Falcon") return SensorModel::INNOVUSION_FALCON; + if (sensor_model == "Robin") return SensorModel::INNOVUSION_ROBIN; return SensorModel::UNKNOWN; } diff --git a/nebula_decoders/CMakeLists.txt b/nebula_decoders/CMakeLists.txt index 463a589c7..cefaf574f 100644 --- a/nebula_decoders/CMakeLists.txt +++ b/nebula_decoders/CMakeLists.txt @@ -40,6 +40,12 @@ ament_auto_add_library(nebula_decoders_velodyne SHARED src/nebula_decoders_velodyne/decoders/vlp32_decoder.cpp ) +# Innovusion +ament_auto_add_library(nebula_decoders_innovusion SHARED + src/nebula_decoders_innovusion/decoders/innovusion_decoder.cpp + src/nebula_decoders_innovusion/innovusion_driver.cpp + ) + if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) ament_lint_auto_find_test_dependencies() diff --git a/nebula_decoders/calibration/innovusion/Falcon.yaml b/nebula_decoders/calibration/innovusion/Falcon.yaml new file mode 100755 index 000000000..11faab83c --- /dev/null +++ b/nebula_decoders/calibration/innovusion/Falcon.yaml @@ -0,0 +1,4 @@ +# Our Lidar is calibrated internally, so there is no need to use calibration files here. +# However, in order to maintain consistency in the Nebula framework, we created an empty calibration file. +# Please ignore it. +yaml_version: 2023110701 diff --git a/nebula_decoders/calibration/innovusion/Robin.yaml b/nebula_decoders/calibration/innovusion/Robin.yaml new file mode 100755 index 000000000..11faab83c --- /dev/null +++ b/nebula_decoders/calibration/innovusion/Robin.yaml @@ -0,0 +1,4 @@ +# Our Lidar is calibrated internally, so there is no need to use calibration files here. +# However, in order to maintain consistency in the Nebula framework, we created an empty calibration file. +# Please ignore it. +yaml_version: 2023110701 diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_innovusion/decoders/innovusion_data_packet.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_innovusion/decoders/innovusion_data_packet.hpp new file mode 100644 index 000000000..ca407df0d --- /dev/null +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_innovusion/decoders/innovusion_data_packet.hpp @@ -0,0 +1,534 @@ +#pragma once + +#include +#include +#include +#include + +#ifndef DEFINE_INNO_COMPACT_STRUCT +#if !(defined(_MSC_VER)) +#define DEFINE_INNO_COMPACT_STRUCT(x) struct __attribute__((packed)) x +#define DEFINE_INNO_COMPACT_STRUCT_END +#else + +#define DEFINE_INNO_COMPACT_STRUCT(x) __pragma(pack(push, 1)) struct x +#define DEFINE_INNO_COMPACT_STRUCT_END __pragma(pack(pop)) +#endif +#endif + +namespace nebula +{ +namespace drivers +{ +namespace innovusion_packet +{ +enum InnoLidarMode { + INNO_LIDAR_MODE_NONE = 0, + INNO_LIDAR_MODE_SLEEP = 1, // falcon & robin + INNO_LIDAR_MODE_STANDBY = 2, // falcon & robin + INNO_LIDAR_MODE_WORK_NORMAL = 3, // falcon & robin + INNO_LIDAR_MODE_WORK_SHORT_RANGE = 4, // falcon + INNO_LIDAR_MODE_WORK_CALIBRATION = 5, // falcon & robin + INNO_LIDAR_MODE_PROTECTION = 6, // falcon & robin + INNO_LIDAR_MODE_WORK_QUIET = 7, // falcon + INNO_LIDAR_MODE_WORK_INTERNAL_1 = 8, // falcon + INNO_LIDAR_MODE_FOTA = 9, // [UDS upgrade & ADC FOTA] + INNO_LIDAR_MODE_WORK_MAX = 10, +}; + +enum InnoLidarStatus { + INNO_LIDAR_STATUS_NONE = 0, + INNO_LIDAR_STATUS_TRANSITION = 1, + INNO_LIDAR_STATUS_NORMAL = 2, + INNO_LIDAR_STATUS_FAILED = 3, + INNO_LIDAR_STATUS_MAX = 4, +}; + +enum InnoTimeSyncConfig { + INNO_TIME_SYNC_CONFIG_HOST = 0, + INNO_TIME_SYNC_CONFIG_PTP = 1, + INNO_TIME_SYNC_CONFIG_GPS = 2, + INNO_TIME_SYNC_CONFIG_FILE = 3, + INNO_TIME_SYNC_CONFIG_NTP = 4, + INNO_TIME_SYNC_CONFIG_MAX = 5, +}; + +enum InputSource { + SOURCE_NO = 0, + SOURCE_FILE, + SOURCE_TCP, + SOURCE_UDP, + SOURCE_PCAP, + SOURCE_MAX, +}; + +enum InnoItemType { + INNO_ITEM_TYPE_NONE = 0, + // Falcon SPHERE POINTCLOUD, InnoBlock + INNO_ITEM_TYPE_SPHERE_POINTCLOUD = 1, + INNO_ITEM_TYPE_MESSAGE = 2, + INNO_ITEM_TYPE_MESSAGE_LOG = 3, + // Falcon SPHERE POINTCLOUD, InnoXyzPoint + INNO_ITEM_TYPE_XYZ_POINTCLOUD = 4, + + // ROBIN_E SPHERE POINTCLOUD, InnoEnBlock + INNO_ROBINE_ITEM_TYPE_SPHERE_POINTCLOUD = 5, + // ROBIN_E SPHERE POINTCLOUD, InnoEnXyzPoint + INNO_ROBINE_ITEM_TYPE_XYZ_POINTCLOUD = 6, + + // ROBIN_W SPHERE POINTCLOUD, InnoEnBlock + INNO_ROBINW_ITEM_TYPE_SPHERE_POINTCLOUD = 7, + // ROBIN_W SPHERE POINTCLOUD, InnoEnXyzPoint + INNO_ROBINW_ITEM_TYPE_XYZ_POINTCLOUD = 8, + + // Falcon2.1 SPHERE POINTCLOUD, InnoEnBlock + INNO_FALCONII_DOT_1_ITEM_TYPE_SPHERE_POINTCLOUD = 9, + // Falcon2.1 XYZ POINTCLOUD, InnoEnXyzPoint + INNO_FALCONII_DOT_1_ITEM_TYPE_XYZ_POINTCLOUD = 10, + + // FalconIII + INNO_FALCONIII_ITEM_TYPE_SPHERE_POINTCLOUD = 11, + INNO_FALCONIII_ITEM_TYPE_XYZ_POINTCLOUD = 12, + + INNO_ITEM_TYPE_MAX = 13, +}; + +enum InnoReflectanceMode { + INNO_REFLECTANCE_MODE_NONE = 0, + INNO_REFLECTANCE_MODE_INTENSITY = 1, + INNO_REFLECTANCE_MODE_REFLECTIVITY = 2, + INNO_REFLECTANCE_MODE_MAX = 3, +}; + +enum InnoMultipleReturnMode { + INNO_MULTIPLE_RETURN_MODE_NONE = 0, + INNO_MULTIPLE_RETURN_MODE_SINGLE = 1, + INNO_MULTIPLE_RETURN_MODE_2_STRONGEST = 2, + // one strongest return and one furthest return + INNO_MULTIPLE_RETURN_MODE_2_STRONGEST_FURTHEST = 3, + INNO_MULTIPLE_RETURN_MODE_MAX +}; + +enum InnoDistanceUnitPerMeter { + kInnoDistanceUnitPerMeter200 = 200, // FalconIGK + kInnoDistanceUnitPerMeter400 = 400 // Robin & falcon2.1 +}; + +enum InnoVAngleDiffBase { + kInnoFaconVAngleDiffBase = 196, // FalconIGK,falconII & falcon2.1 + kInnoRobinEVAngleDiffBase = 0, // RobinE + kInnoRobinWVAngleDiffBase = 240, // RobinW +}; + +/************ + Constants +*************/ +typedef double InnoTimestampUs; +#define INNO_CHANNEL_NUMBER_BIT 2 +#define INNO_CHANNEL_NUMBER (1 << INNO_CHANNEL_NUMBER_BIT) +#define INNO_MAX_MULTI_RETURN 2 +#define INNO_SN_SZIE 16 +#define INNO_HW_NUMBER_SIZE 3 +static const uint16_t kInnoMagicNumberDataPacket = 0x176A; +static const uint8_t kInnoMajorVersionDataPacket = 2; // upgrade Major version from 1->2 2023/6/6 +static const uint8_t kInnoMinorVersionDataPacket = 1; +static const uint16_t kInnoMagicNumberStatusPacket = 0x186B; +static const uint8_t kInnoMajorVersionStatusPacket = 2; // upgrade Major version from 1->2 2023/6/6 +static const uint8_t kInnoMinorVersionStatusPacket = 1; + +static const uint32_t kInnoDistanceUnitPerMeter = 400; +static const double kMeterPerInnoDistanceUnit = 1.0 / kInnoDistanceUnitPerMeter; +static const double kMeterPerInnoDistanceUnit200 = 1.0 / kInnoDistanceUnitPerMeter200; // falconIGK +static const double kMeterPerInnoDistanceUnit400 = 1.0 / kInnoDistanceUnitPerMeter400; // robin & falcon2.1 +static const uint32_t kInnoDegreePerPiRad = 180; +static const uint32_t kInnoAngleUnitPerPiRad = 32768; +static const double kRadPerInnoAngleUnit = M_PI / kInnoAngleUnitPerPiRad; +static const double kDegreePerInnoAngleUnit = + 180.0 / kInnoAngleUnitPerPiRad; +static const double kInnoAngleUnitPerDegree = + kInnoAngleUnitPerPiRad / 180.0; +static const int32_t kInnoInvalidAngleInUnit = kInnoAngleUnitPerDegree * 90; +static const uint32_t kInnoChannelNumberBit = INNO_CHANNEL_NUMBER_BIT; +static const uint32_t kInnoChannelNumber = INNO_CHANNEL_NUMBER; +static const uint32_t kInnoMaxMultiReturn = INNO_MAX_MULTI_RETURN; +static const int16_t kInnoVAngleDiffBase = 196; + +static const int kInnoBaseFaultEnd = 64; +static const double kInnoNopROI = 10000.0; +static const uint32_t kConvertSize = 1024 * 1024 * 10; + +union InputParam { + struct { + enum InputSource source_type; + char lidar_ip[16]; + } base_param; + + struct { + enum InputSource source_type; + char lidar_ip[16]; + char filename[256]; + int32_t play_rate; + int32_t rewind; + int64_t skip; + } file_param; + + struct { + enum InputSource source_type; + char lidar_ip[16]; + double read_timeout_sec; + int64_t skip; + } tcp_param; + + struct { + enum InputSource source_type; + char lidar_ip[16]; + uint16_t udp_port; + double read_timeout_sec; + int64_t skip; + } udp_param; + + struct { + enum InputSource source_type; + char lidar_ip[16]; + char filename[256]; + int32_t play_rate; + int32_t rewind; + int64_t skip; + uint16_t data_port; + uint16_t status_port; + uint16_t message_port; + } pcap_param; +}; + +#if defined(__MINGW64__) || !defined(_WIN32) +/* 17 bytes per block header */ +typedef DEFINE_INNO_COMPACT_STRUCT(InnoBlockHeader) { + /* horizontal angle, 0 is straight forward, right is positive, + unit is kRadPerInnoAngleUnit rad, range (-PI to PI) */ + int16_t h_angle; + /* vertical angle, 0 is the horizon, up is positive, + unit is kRadPerInnoAngleUnit rad, range (-PI to PI) */ + int16_t v_angle; + /* relative timestamp (to ts_start_us) in 10us, 0-655,350us */ + uint16_t ts_10us; + uint16_t scan_idx; /* point idx within the scan line */ + uint16_t scan_id: 9; /* id of the scan line */ + // real angle is h_angle + h_angle_diff_1 + int64_t h_angle_diff_1: 9; + int64_t h_angle_diff_2: 10; + int64_t h_angle_diff_3: 11; + // real angle is v_angle + v_angle_diff_1 + kVAngleDiffBase * channel + int64_t v_angle_diff_1: 8; // 196 + [-128, 127] + int64_t v_angle_diff_2: 9; // 392 + [-256, 255] + int64_t v_angle_diff_3: 9; // 588 + [-256, 255] + /* 0: in sparse region + 0x01: in vertical slow region + 0x10: in horizontal slow region + 0x11: in center ROI */ + uint64_t in_roi: 2; + uint64_t facet: 3; + uint64_t reserved_flags: 2; /* all 0 */ +} InnoBlockHeader; +DEFINE_INNO_COMPACT_STRUCT_END +#else +/* 17 bytes per block header */ +DEFINE_INNO_COMPACT_STRUCT(InnoBlockHeader) { + /* horizontal angle, 0 is straight forward, right is positive, + unit is kRadPerInnoAngleUnit rad, range (-PI to PI) */ + int16_t h_angle; + /* vertical angle, 0 is the horizon, up is positive, + unit is kRadPerInnoAngleUnit rad, range (-PI to PI) */ + int16_t v_angle; + /* relative timestamp (to ts_start_us) in 10us, 0-655,350us */ + uint16_t ts_10us; + uint16_t scan_idx; /* point idx within the scan line */ + union { + uint16_t scan_id : 9; /* id of the scan line */ + struct { + uint8_t scan_id0; + int64_t scan_id1 : 1; + // real angle is h_angle + h_angle_diff_1 + int64_t h_angle_diff_1 : 9; + int64_t h_angle_diff_2 : 10; + int64_t h_angle_diff_3 : 11; + // real angle is v_angle + v_angle_diff_1 + kVAngleDiffBase * channel + int64_t v_angle_diff_1 : 8; // 196 + [-128, 127] + int64_t v_angle_diff_2 : 9; // 392 + [-256, 255] + int64_t v_angle_diff_3 : 9; // 588 + [-256, 255] + /* 0: in sparse region + 0x01: in vertical slow region + 0x11: in center ROI */ + uint64_t in_roi : 2; + uint64_t facet : 3; + uint64_t reserved_flags : 2; /* all 0 */ + }; + }; +}; +DEFINE_INNO_COMPACT_STRUCT_END +#endif + +typedef DEFINE_INNO_COMPACT_STRUCT(InnoXyzrD) { + double x; + double y; + double z; + double radius; +} InnoXyzrD; +DEFINE_INNO_COMPACT_STRUCT_END + +/* compact format, 16 + 8 + 2 = 26 bytes per point */ +typedef DEFINE_INNO_COMPACT_STRUCT(InnoXyzPoint) { + float x; + float y; + float z; + float radius; + uint16_t ts_10us; + uint16_t scan_id: 9; /* id of the scan line */ + uint16_t in_roi: 2; + uint16_t facet: 3; + uint16_t multi_return: 1; + uint16_t reserved_flags: 1; /* all 0 */ + uint32_t is_2nd_return: 1; + uint32_t scan_idx: 14; /* point idx within the scan line */ + uint32_t refl: 9; /* reflectance, 1-254, 255 means a reflector */ + /* or intensity, also 1-254 & 255=reflector */ + uint32_t type: 2; /* 0: normal, 1: ground, 2: fog */ + uint32_t elongation: 4; /* elongation */ + uint32_t channel: 2; + uint16_t ring_id; +} InnoXyzPoint; +DEFINE_INNO_COMPACT_STRUCT_END + +/* compact format, 4 bytes per point */ +typedef DEFINE_INNO_COMPACT_STRUCT(InnoChannelPoint) { + uint32_t radius: 17; /* distance in distance unit, range [0, 655.35m] */ + uint32_t refl: 8; /* reflectance, 1-254, 255 means a reflector */ + /* or intensity, also 1-254 & 255=reflector */ + uint32_t is_2nd_return: 1; /* 0: 1st return, 1: 2nd return */ + uint32_t type: 2; /* 0: normal, 1: ground, 2: fog */ + uint32_t elongation: 4; /* elongation */ +} InnoChannelPoint; +DEFINE_INNO_COMPACT_STRUCT_END + +typedef DEFINE_INNO_COMPACT_STRUCT(InnoBlock) { + InnoBlockHeader header; + InnoChannelPoint points[0]; +} InnoBlock; +DEFINE_INNO_COMPACT_STRUCT_END + +/* 17 + 4 * 4 = 33 bytes */ +typedef DEFINE_INNO_COMPACT_STRUCT(InnoBlock1) { + InnoBlockHeader header; + InnoChannelPoint points[INNO_CHANNEL_NUMBER]; +} InnoBlock1; +DEFINE_INNO_COMPACT_STRUCT_END + +/* 17 + 8 * 4 = 49 bytes */ +typedef DEFINE_INNO_COMPACT_STRUCT(InnoBlock2) { + InnoBlockHeader header; + InnoChannelPoint points[INNO_CHANNEL_NUMBER * INNO_MAX_MULTI_RETURN]; +} InnoBlock2; +DEFINE_INNO_COMPACT_STRUCT_END + +/* compact format, 8 bytes per point */ +typedef DEFINE_INNO_COMPACT_STRUCT(InnoEnChannelPoint) { + uint16_t reflectance; /* reflectance, falcon 1-65535,robin 1-4095 */ + uint16_t intensity; /* intensity, falcon 1-65535,robin 1-4095 */ + uint32_t elongation: 7; /* elongation unit: 1ns */ + uint32_t is_2nd_return: 1; /* 0: 1st return, 1: 2nd return */ + uint32_t radius : 19; /* distance in distance unit, distance unit:1/400m, range [0, 655.35m] */ + uint32_t type : 2; /* 0: normal, 1: ground, 2: fog */ + uint32_t firing: 1; /* 0: weak, 1: strong */ + uint32_t reserved_flags : 2; /* all 0 */ +} InnoEnChannelPoint; +DEFINE_INNO_COMPACT_STRUCT_END + +/* compact format, 30 bytes per point */ +typedef DEFINE_INNO_COMPACT_STRUCT(InnoEnXyzPoint) { + float x; + float y; + float z; + float radius; + uint16_t ts_10us; + uint16_t scan_id : 10; /* id of the scan line */ + uint16_t in_roi : 2; + uint16_t facet : 3; + uint16_t multi_return : 1; /* multi return mode,true mean the 2nd point*/ + uint16_t scan_idx : 14; /* point idx within the scan line */ + uint16_t type : 2; /* 0: normal, 1: ground, 2: fog */ + uint16_t reflectance; /* reflectance, falcon 1-65535,robin 1-4095 */ + uint16_t intensity; /* intensity, falcon 1-65535,robin 1-4095 */ + uint8_t elongation : 7; /* elongation, unit: 1ns */ + uint8_t is_2nd_return : 1; + uint8_t channel : 3; /* max 8 channel */ + uint8_t firing : 1; + uint8_t reserved_flags : 4; /* all 0 */ + uint16_t ring_id; +} InnoEnXyzPoint; +DEFINE_INNO_COMPACT_STRUCT_END + +/* 18 bytes per EnBlock header */ +typedef DEFINE_INNO_COMPACT_STRUCT(InnoEnBlockHeader) { + /* horizontal angle, 0 is straight forward, right is positive, + unit is kRadPerInnoAngleUnit rad, range (-PI to PI) */ + int16_t h_angle; + /* vertical angle, 0 is the horizon, up is positive, + unit is kRadPerInnoAngleUnit rad, range (-PI to PI) */ + int16_t v_angle; + /* relative timestamp (to ts_start_us) in 10us, 0-655,350us */ + uint16_t ts_10us; + // real angle is h_angle + h_angle_diff_1 + int64_t h_angle_diff_1 : 11; + int64_t h_angle_diff_2 : 11; + int64_t h_angle_diff_3 : 12; + // real angle is v_angle + v_angle_diff_1 + kVAngleDiffBase * channel + int64_t v_angle_diff_1 : 10; + int64_t v_angle_diff_2 : 10; + int64_t v_angle_diff_3 : 10; + uint16_t scan_idx; /* point idx within the scan line */ + uint16_t scan_id : 9; /* id of the scan line */ + /* 0: in sparse region + 0x01: in vertical slow region + 0x11: in center ROI + only for falcon */ + uint16_t in_roi : 2; + uint16_t facet : 3; + uint16_t reserved_flags : 2; /* all 0 */ +} InnoEnBlockHeader; +DEFINE_INNO_COMPACT_STRUCT_END + +typedef DEFINE_INNO_COMPACT_STRUCT(InnoEnBlock) { + InnoEnBlockHeader header; + InnoEnChannelPoint points[0]; +} InnoEnBlock; +DEFINE_INNO_COMPACT_STRUCT_END + +/* 18 + 4 * 8 = 50 bytes */ +typedef DEFINE_INNO_COMPACT_STRUCT(InnoEnBlock1) { + InnoEnBlockHeader header; + InnoEnChannelPoint points[INNO_CHANNEL_NUMBER]; +} InnoEnBlock1; +DEFINE_INNO_COMPACT_STRUCT_END + +/* 18 + 8 * 8 = 82 bytes */ +typedef DEFINE_INNO_COMPACT_STRUCT(InnoEnBlock2) { + InnoEnBlockHeader header; + InnoEnChannelPoint points[INNO_CHANNEL_NUMBER * INNO_MAX_MULTI_RETURN]; +} InnoEnBlock2; +DEFINE_INNO_COMPACT_STRUCT_END + + +static inline size_t innoblock_get_idx(size_t channel, size_t r) { + /* r0_ch0 r0_ch1 r0_ch2 r0_ch3 r1_ch0 r1_ch1 r1_ch2 r1_ch3 */ + return channel + (r << kInnoChannelNumberBit); +} + +typedef DEFINE_INNO_COMPACT_STRUCT(InnoMessage) { + uint32_t size; // size of the whole InnoMessage, + // i.e. size of content + sizeof(InnoMessage) + uint32_t src; + uint64_t id; + uint32_t level; /* enum InnoMessageLevel */ + uint32_t code; /* message code */ + int32_t reserved[4]; /* all 0 */ + char content[0]; /* 0 end string */ +} InnoMessage; +DEFINE_INNO_COMPACT_STRUCT_END + +/* + Fixed header structure to indicate the firmware/software version. + This structure won't change during firmware update in the future. +*/ +typedef DEFINE_INNO_COMPACT_STRUCT(InnoCommonVersion) { + /* 2 byte */ + uint16_t magic_number; + + /* 2 byte */ + uint8_t major_version; + uint8_t minor_version; + + /* 2 byte */ + uint16_t fw_sequence; +} InnoCommonVersion; +DEFINE_INNO_COMPACT_STRUCT_END + +typedef DEFINE_INNO_COMPACT_STRUCT(InnoCommonHeader) { + /* 6 bytes */ + InnoCommonVersion version; + + /* 4 bytes, cover every thing except checksum */ + uint32_t checksum; + + /* 4 bytes */ + uint32_t size; + + /* 2 bytes */ + uint8_t source_id : 4; /* up to 16 different LiDAR source */ + uint8_t timestamp_sync_type : 4; /* enum InnoTimestampSyncType */ + uint8_t lidar_type; /* enum InnoLidarType */ + /* 8 bytes */ + InnoTimestampUs ts_start_us; /* epoch time of start of frame, in micro-sec */ + + /* 2 bytes */ + uint8_t lidar_mode; /* enum InnoLidarMode */ + uint8_t lidar_status; /* enum InnoLidarStatus */ +} InnoCommonHeader; +DEFINE_INNO_COMPACT_STRUCT_END + +/* + * Main data packet definition + * 26 + 12 + 10 + 2 + 4 + 16 = 70 bytes, max overhead is 70/1472 = 4.7%, + */ +typedef DEFINE_INNO_COMPACT_STRUCT(InnoDataPacket) { + InnoCommonHeader common; + + /* 12 bytes */ + uint64_t idx; /* frame index, start from 0 */ + uint16_t sub_idx; /* sub-frame index, start from 0 for every frame */ + uint16_t sub_seq; /* sequence within a sub-frame */ + + /* 10 byte */ + /* type in enum InnoItemType, each type uses independent global idx */ + uint32_t type :8; + uint32_t item_number :24; /* max 4 * 1024 * 1024 */ + uint16_t item_size; /* max 65535, 0 means variable size */ + uint32_t topic; /* reserved */ + + /* 2 bytes */ + uint16_t scanner_direction :1; /* 0: top->bottom, 1: bottom->top */ + uint16_t use_reflectance :1; /* 0: intensity mode, 1: reflectance mode */ + uint16_t multi_return_mode :3; /* ... */ + uint16_t confidence_level :2; /* 0: no confidence, 3: higest */ + uint16_t is_last_sub_frame :1; /* 1: the last sub frame of a frame */ + uint16_t is_last_sequence :1; /* 1: the last piece of a sub frame */ + uint16_t has_tail :1; /* has additional tail struct after points */ + uint16_t frame_sync_locked :1; /* 1: frame sync has locked */ + uint16_t is_first_sub_frame :1; /* 1: the first sub frame of a frame */ + uint16_t last_four_channel :1; + uint16_t reserved_flag :3; /* all 0 */ + + /* 4 bytes */ + int16_t roi_h_angle; /* configured ROI in InnoAngleUnit */ + int16_t roi_v_angle; + uint32_t extend_reserved[4]; /* add more extend reserved area 16 byte */ +// MSVC compiler does not support multi-dimensional flexible arrays. +# if !defined(_MSC_VER) + union { + char payload[0]; + InnoBlock1 inno_block1s[0]; + InnoBlock2 inno_block2s[0]; + InnoMessage messages[0]; + InnoXyzPoint xyz_points[0]; + // Robin & Falcon2.1 + InnoEnBlock1 inno_en_block1s[0]; + InnoEnBlock2 inno_en_block2s[0]; + InnoEnXyzPoint en_xyz_points[0]; + }; +#else + char payload[0]; +#endif +} InnoDataPacket; +DEFINE_INNO_COMPACT_STRUCT_END + +} // namespace innovusion_packet +} // namespace drivers +} // namespace nebula diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_innovusion/decoders/innovusion_decoder.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_innovusion/decoders/innovusion_decoder.hpp new file mode 100644 index 000000000..0e7b2573d --- /dev/null +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_innovusion/decoders/innovusion_decoder.hpp @@ -0,0 +1,436 @@ +#pragma once + +#include "nebula_decoders/nebula_decoders_innovusion/decoders/innovusion_data_packet.hpp" +#include "nebula_decoders/nebula_decoders_innovusion/decoders/innovusion_scan_decoder.hpp" +#include "nebula_decoders/nebula_decoders_innovusion/decoders/nps_adjustment.hpp" +#include "nebula_decoders/nebula_decoders_innovusion/decoders/robin_nps_adjustment.hpp" + +#include + +#include "innovusion_msgs/msg/innovusion_packet.hpp" +#include "innovusion_msgs/msg/innovusion_scan.hpp" +namespace nebula +{ +namespace drivers +{ +namespace innovusion_packet +{ +class InnoBlockAngles { + public: + int16_t h_angle; + int16_t v_angle; +}; + +class InnoBlockFullAngles { + public: + InnoBlockAngles angles[kInnoChannelNumber]; +}; + +template +class InnoDataPacketPointsCallbackParams { + public: + InnoDataPacket pkt; + Block block; + Point pt; + InnoBlockFullAngles angle; + uint16_t channel; + uint16_t multi_return; +}; + +class InnovusionDecoder : public InnovusionScanDecoder +{ +protected: + /// @brief Configuration for this decoder + const std::shared_ptr sensor_configuration_; + const std::shared_ptr calibration_configuration_; + + /// @brief The sensor definition, used for return mode and time offset handling + /// @brief The point cloud new points get added to + NebulaPointCloudPtr decode_pc_; + /// @brief The point cloud that is returned when a scan is complete + NebulaPointCloudPtr output_pc_; + /// @brief The timestamp of the last completed scan in nanoseconds + uint64_t output_scan_timestamp_ns_; + rclcpp::Logger logger_; + std::vector xyz_from_sphere_; + +private: + static int init_; + static int v_angle_offset_[INNO_ITEM_TYPE_MAX][kInnoChannelNumber]; + static const uint32_t kTableShift_ = 9; + static const uint32_t kTableStep_ = 1 << kTableShift_; + static const uint32_t kTableHalfStep_ = 1 << (kTableShift_ - 1); + static const uint32_t kTableMask_ = kTableStep_ - 1; + static const uint32_t kVTableSizeBits_ = 4; + static const uint32_t kHTableSizeBits_ = 6; + static const uint32_t kVTableSize_ = 1 << kVTableSizeBits_; + static const uint32_t kHTableSize_ = 1 << kHTableSizeBits_; + static const uint32_t kVTableEffeHalfSize_ = 6; + static const uint32_t kHTableEffeHalfSize_ = 22; + static const uint32_t kXZSize_ = 2; + static const double kAdjustmentUnitInMeter_; + static const double kAdjustmentUnitInMeterRobin_; + static const uint32_t kHRobinTableEffeHalfSize_ = 27; + static const uint32_t kXYZSize_ = 3; + static const uint32_t kRobinScanlines_ = 192; + static const uint32_t RobinWTDCChannelNumber = 48; + static const uint32_t RobinETDCChannelNumber = 32; + static const uint8_t robinw_channel_mapping[48]; + // use first 32 entries for robine + static const uint8_t robine_channel_mapping[48]; + static const int32_t kAngleTableSize = 2 * kInnoAngleUnitPerPiRad; + static const int32_t kASinTableSize = 10000; + static const int32_t kATanTableSize = 45000; + static const int32_t kAtanTableScale = 10000; + static const int32_t kAsinTableScale = 10000; + + static float sin_table_[]; + static float cos_table_[]; + static int32_t asin_table_[]; + static int32_t atan_table_[]; + static int8_t robin_nps_adjustment_[kRobinScanlines_][kHTableSize_][kXYZSize_]; + static int8_t nps_adjustment_[kVTableSize_][kHTableSize_][kInnoChannelNumber][kXZSize_]; + double current_ts_start_ = 0.0; + static constexpr double us_in_second_c = 1000000.0; + static constexpr double ten_us_in_second_c = 100000.0; + +public: + /// @brief Constructor + /// @param sensor_configuration SensorConfiguration for this decoder + /// @param calibration_configuration Calibration for this decoder + explicit InnovusionDecoder( + const std::shared_ptr & sensor_configuration, + const std::shared_ptr & calibration_configuration); + + int unpack(const innovusion_msgs::msg::InnovusionPacket & packet) override; + + std::tuple getPointcloud() override; + + static double lookup_cos_table_in_unit(int i); + + static double lookup_sin_table_in_unit(int i); + + static inline bool is_xyz_data(uint32_t packet_type) { + InnoItemType inno_type = static_cast(packet_type); + bool bSuccess = false; + if(inno_type == INNO_ITEM_TYPE_XYZ_POINTCLOUD || inno_type == INNO_ROBINE_ITEM_TYPE_XYZ_POINTCLOUD + ||inno_type == INNO_ROBINW_ITEM_TYPE_XYZ_POINTCLOUD||inno_type== INNO_FALCONII_DOT_1_ITEM_TYPE_XYZ_POINTCLOUD) { + bSuccess = true; + } + return bSuccess; + } + + static inline bool is_sphere_data(uint32_t packet_type) { + InnoItemType inno_type = static_cast(packet_type); + bool bSuccess = false; + if(inno_type == INNO_ITEM_TYPE_SPHERE_POINTCLOUD || inno_type == INNO_ROBINE_ITEM_TYPE_SPHERE_POINTCLOUD + ||inno_type == INNO_ROBINW_ITEM_TYPE_SPHERE_POINTCLOUD||inno_type== INNO_FALCONII_DOT_1_ITEM_TYPE_SPHERE_POINTCLOUD) { + bSuccess = true; + } + return bSuccess; + } + + static inline bool is_en_xyz_data(uint32_t packet_type) { + InnoItemType inno_type = static_cast(packet_type); + bool bSuccess = false; + if(inno_type == INNO_ROBINE_ITEM_TYPE_XYZ_POINTCLOUD + ||inno_type == INNO_ROBINW_ITEM_TYPE_XYZ_POINTCLOUD||inno_type== INNO_FALCONII_DOT_1_ITEM_TYPE_XYZ_POINTCLOUD) { + bSuccess = true; + } + return bSuccess; + } + + static inline bool is_en_sphere_data(uint32_t packet_type) { + InnoItemType inno_type = static_cast(packet_type); + bool bSuccess = false; + if(inno_type == INNO_ROBINE_ITEM_TYPE_SPHERE_POINTCLOUD || inno_type == INNO_ROBINW_ITEM_TYPE_SPHERE_POINTCLOUD + ||inno_type == INNO_FALCONII_DOT_1_ITEM_TYPE_SPHERE_POINTCLOUD) { + bSuccess = true; + } + return bSuccess; + } + + inline static void lookup_xz_adjustment_(const InnoBlockAngles &angles, uint32_t ch, double *x, + double *z) { + uint32_t v = angles.v_angle / 512; + uint32_t h = angles.h_angle / 512; + v += kVTableEffeHalfSize_; + h += kHTableEffeHalfSize_; + // avoid index out-of-bound + v = v & (kVTableSize_ - 1); + h = h & (kHTableSize_ - 1); + int8_t *addr_x = &nps_adjustment_[v][h][ch][0]; + int8_t *addr_z = addr_x + 1; + *x = *addr_x * kAdjustmentUnitInMeter_; + *z = *addr_z * kAdjustmentUnitInMeter_; + return; + } + + inline static void lookup_xyz_adjustment_(const InnoBlockAngles &angles, uint32_t scan_id, double adj[]) { + int h_angle = angles.h_angle + (kHRobinTableEffeHalfSize_ << kTableShift_); + int h_index = h_angle >> kTableShift_; + // avoid index out-of-bound + h_index = h_index & (kHTableSize_ - 1); + if (h_index > kHTableSize_ - 2) { + h_index = kHTableSize_ - 2; + } + + int h_offset = h_angle & kTableMask_; + int h_offset2 = kTableStep_ - h_offset; + + for (int i = 0; i < 3; i++) { + int u = robin_nps_adjustment_[scan_id][h_index][i]; + int v = robin_nps_adjustment_[scan_id][h_index + 1][i]; + int t = u * h_offset2 + v * h_offset + kTableHalfStep_; + int w = t >> kTableShift_; + adj[i] = w * kAdjustmentUnitInMeterRobin_; + } + + return; + } + + static inline size_t get_data_packet_size(InnoItemType type, uint32_t item_count, InnoMultipleReturnMode mode) { + size_t unit_size = 0; + switch (type) { + case INNO_ITEM_TYPE_SPHERE_POINTCLOUD: + if (mode == INNO_MULTIPLE_RETURN_MODE_SINGLE) { + unit_size = sizeof(InnoBlock1); + } else if (mode == INNO_MULTIPLE_RETURN_MODE_2_STRONGEST || + mode == INNO_MULTIPLE_RETURN_MODE_2_STRONGEST_FURTHEST) { + unit_size = sizeof(InnoBlock2); + } else { + return 0; + } + break; + case INNO_ITEM_TYPE_XYZ_POINTCLOUD: + unit_size = sizeof(InnoXyzPoint); + break; + case INNO_ROBINE_ITEM_TYPE_SPHERE_POINTCLOUD: + case INNO_ROBINW_ITEM_TYPE_SPHERE_POINTCLOUD: + case INNO_FALCONII_DOT_1_ITEM_TYPE_SPHERE_POINTCLOUD: + if (mode == INNO_MULTIPLE_RETURN_MODE_SINGLE) { + unit_size = sizeof(InnoEnBlock1); + } else if (mode == INNO_MULTIPLE_RETURN_MODE_2_STRONGEST || + mode == INNO_MULTIPLE_RETURN_MODE_2_STRONGEST_FURTHEST) { + unit_size = sizeof(InnoEnBlock2); + } else { + return 0; + } + break; + case INNO_ROBINE_ITEM_TYPE_XYZ_POINTCLOUD: + case INNO_ROBINW_ITEM_TYPE_XYZ_POINTCLOUD: + case INNO_FALCONII_DOT_1_ITEM_TYPE_XYZ_POINTCLOUD: + unit_size = sizeof(InnoEnXyzPoint); + break; + default: + break; + } + return sizeof(InnoDataPacket) + item_count * unit_size; + } + + static void init_f(void); + + static int init_f_robin(void); + + static int init_f_falcon(void); + + + template + static inline void get_block_full_angles(InnoBlockFullAngles *full, const BlockHeader &b, InnoItemType type) { + full->angles[0].h_angle = b.h_angle; + full->angles[0].v_angle = b.v_angle; + full->angles[1].h_angle = b.h_angle + b.h_angle_diff_1; + full->angles[1].v_angle = b.v_angle + b.v_angle_diff_1 + v_angle_offset_[type][1]; + full->angles[2].h_angle = b.h_angle + b.h_angle_diff_2; + full->angles[2].v_angle = b.v_angle + b.v_angle_diff_2 + v_angle_offset_[type][2]; + full->angles[3].h_angle = b.h_angle + b.h_angle_diff_3; + full->angles[3].v_angle = b.v_angle + b.v_angle_diff_3 + v_angle_offset_[type][3]; + } + + static bool check_data_packet(const InnoDataPacket &pkt, size_t size); + + static void get_xyzr_meter(const InnoBlockAngles angles, const uint32_t radius_unit, const uint32_t channel, + InnoXyzrD *result, InnoItemType type = INNO_ITEM_TYPE_SPHERE_POINTCLOUD); + + static inline void get_xyz_point(const InnoBlockHeader &block, const InnoChannelPoint &cp, + const InnoBlockAngles angles, const uint32_t channel, InnoXyzPoint *pt) { + InnoXyzrD xyzr; + get_xyzr_meter(angles, cp.radius, channel, &xyzr); + pt->x = xyzr.x; + pt->y = xyzr.y; + pt->z = xyzr.z; + pt->radius = xyzr.radius; + pt->ts_10us = block.ts_10us; + pt->scan_idx = block.scan_idx; + pt->scan_id = block.scan_id; + pt->in_roi = block.in_roi; + pt->facet = block.facet; + pt->reserved_flags = block.reserved_flags; + pt->refl = cp.refl; + pt->type = cp.type; + pt->elongation = cp.elongation; + pt->channel = channel; + pt->is_2nd_return = cp.is_2nd_return; + } + + static inline void get_xyz_point(const InnoEnBlockHeader &block, const InnoEnChannelPoint &cp, + const InnoBlockAngles angles, const uint32_t channel, InnoEnXyzPoint *pt, + InnoItemType type) { + InnoXyzrD xyzr; + uint32_t scan_id = 0; + if (type == INNO_FALCONII_DOT_1_ITEM_TYPE_SPHERE_POINTCLOUD) { + scan_id = block.scan_id; + get_xyzr_meter(angles, cp.radius, channel, &xyzr, type); + } else if (type == INNO_ROBINE_ITEM_TYPE_SPHERE_POINTCLOUD || type == INNO_ROBINW_ITEM_TYPE_SPHERE_POINTCLOUD) { + const uint8_t *channel_mapping; + int tdc_channel_number; + if (type == INNO_ROBINE_ITEM_TYPE_SPHERE_POINTCLOUD) { + channel_mapping = &robine_channel_mapping[0]; + tdc_channel_number = RobinETDCChannelNumber; + } else { + channel_mapping = &robinw_channel_mapping[0]; + tdc_channel_number = RobinWTDCChannelNumber; + } + int index = block.scan_id * 4 + channel; + scan_id = channel_mapping[index] + block.facet * tdc_channel_number; + get_xyzr_meter(angles, cp.radius, scan_id, &xyzr, type); + } + pt->x = xyzr.x; + pt->y = xyzr.y; + pt->z = xyzr.z; + pt->radius = xyzr.radius; + pt->ts_10us = block.ts_10us; + pt->scan_idx = block.scan_idx; + pt->scan_id = scan_id; + pt->in_roi = block.in_roi; + pt->facet = block.facet; + pt->reflectance = cp.reflectance; + pt->intensity = cp.intensity; + pt->type = cp.type; + pt->elongation = cp.elongation; + pt->channel = channel; + pt->is_2nd_return = cp.is_2nd_return; + pt->firing = cp.firing; + } + + static inline void get_block_size_and_number_return(const InnoDataPacket &pkt, uint32_t *block_size_in_byte, + uint32_t *number_return) { + if (is_en_sphere_data(pkt.type)) { + if (pkt.multi_return_mode == INNO_MULTIPLE_RETURN_MODE_2_STRONGEST || + pkt.multi_return_mode == INNO_MULTIPLE_RETURN_MODE_2_STRONGEST_FURTHEST) { + *block_size_in_byte = sizeof(InnoEnBlock2); + *number_return = 2; + } else if (pkt.multi_return_mode == INNO_MULTIPLE_RETURN_MODE_SINGLE) { + *block_size_in_byte = sizeof(InnoEnBlock1); + *number_return = 1; + } else { + std::cout << "invalid return mode " << pkt.multi_return_mode << std::endl; + } + } else { + if (pkt.multi_return_mode == INNO_MULTIPLE_RETURN_MODE_2_STRONGEST || + pkt.multi_return_mode == INNO_MULTIPLE_RETURN_MODE_2_STRONGEST_FURTHEST) { + *block_size_in_byte = sizeof(InnoBlock2); + *number_return = 2; + } else if (pkt.multi_return_mode == INNO_MULTIPLE_RETURN_MODE_SINGLE) { + *block_size_in_byte = sizeof(InnoBlock1); + *number_return = 1; + } else { + std::cout << "invalid return mode " << pkt.multi_return_mode << std::endl; + } + } + return; + } + + static inline int get_return_times(const InnoMultipleReturnMode mode) { + return mode >= INNO_MULTIPLE_RETURN_MODE_2_STRONGEST ? 2 : 1; + } + + static inline uint32_t get_points_count(const InnoDataPacket &pkt) { + if (is_xyz_data(pkt.type)) { + return pkt.item_number; + } else if (pkt.type == INNO_ITEM_TYPE_SPHERE_POINTCLOUD) { + uint32_t item_count = 0; + auto count_callback = [&](const InnoDataPacketPointsCallbackParams &in_params) { + if (in_params.pt.radius > 0) { + item_count++; + } + }; + + if (InnovusionDecoder::iterate_inno_data_packet_cpoints(pkt, count_callback) == 0) { + std::cerr << "iterate_inno_data_packet_cpoints failed" << std::endl; + } + + return item_count; + } else if (is_en_sphere_data(pkt.type)) { + uint32_t item_count = 0; + auto count_callback = [&](const InnoDataPacketPointsCallbackParams &in_params) { + if (in_params.pt.radius > 0) { + item_count++; + } + }; + + (void)InnovusionDecoder::iterate_inno_data_packet_cpoints(pkt, count_callback); + return item_count; + } else { + std::cout << "invalid type " << pkt.type << std::endl; + return -1; + } + } + + template + static uint32_t iterate_inno_data_packet_cpoints(const InnoDataPacket &in_pkt, Callback in_callback) { + uint32_t out_count{0}; + uint32_t unit_size{0}; + uint32_t mr = InnovusionDecoder::get_return_times(static_cast(in_pkt.multi_return_mode)); + + if (mr == 2) { + unit_size = sizeof(Block2); + } else if (mr == 1) { + unit_size = sizeof(Block1); + } else { + std::cerr<<"return times of return mode "<(sizeof(int8_t)) * unit_size); + std::memcpy(&block, &byte_ptr, sizeof(const Block *)); + } + if (block == nullptr) { + std::cerr<<"bad block"<(&full_angles, block->header, static_cast(in_pkt.type)); + uint32_t ch1 = 0; + for (; ch1 < kInnoChannelNumber; ch1++) { + uint32_t m1 = 0; + for (; m1 < mr; m1++) { + const Point &pt = block->points[ch1 + (m1 << kInnoChannelNumberBit)]; + const InnoDataPacketPointsCallbackParams in_params{ + in_pkt, *block, pt, full_angles, static_cast(ch1), static_cast(m1)}; + in_callback(in_params); + out_count++; + } + } + } + return out_count; + } + +private: + void setup_table_(double inno_angle_unit); + static bool convert_to_xyz_pointcloud(const InnoDataPacket &src, InnoDataPacket *dest, size_t dest_size, bool append); + void data_packet_parse_(const InnoDataPacket *pkt); + template + void point_xyz_data_parse_(bool is_en_data, bool is_use_refl, uint32_t point_num, PointType point_ptr); +}; +} // namespace innovusion_packet +} // namespace drivers +} // namespace nebula diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_innovusion/decoders/innovusion_scan_decoder.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_innovusion/decoders/innovusion_scan_decoder.hpp new file mode 100644 index 000000000..bf62f756a --- /dev/null +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_innovusion/decoders/innovusion_scan_decoder.hpp @@ -0,0 +1,39 @@ +#ifndef NEBULA_WS_INNOVUSION_SCAN_DECODER_HPP +#define NEBULA_WS_INNOVUSION_SCAN_DECODER_HPP + +#include "nebula_common/innovusion/innovusion_common.hpp" +#include "nebula_common/point_types.hpp" + +#include "innovusion_msgs/msg/innovusion_packet.hpp" +#include "innovusion_msgs/msg/innovusion_scan.hpp" + +#include + +namespace nebula +{ +namespace drivers +{ +/// @brief Base class for Innovusion LiDAR decoder +class InnovusionScanDecoder +{ +public: + InnovusionScanDecoder(InnovusionScanDecoder && c) = delete; + InnovusionScanDecoder & operator=(InnovusionScanDecoder && c) = delete; + InnovusionScanDecoder(const InnovusionScanDecoder & c) = delete; + InnovusionScanDecoder & operator=(const InnovusionScanDecoder & c) = delete; + + virtual ~InnovusionScanDecoder() = default; + InnovusionScanDecoder() = default; + + /// @brief Parses InnovusionPacket and add its points to the point cloud + /// @param innovusion_packet The incoming InnovusionPacket + /// @return The last azimuth processed + virtual int unpack(const innovusion_msgs::msg::InnovusionPacket & innovusion_packet) = 0; + + /// @brief Returns the point cloud and timestamp of the last scan + /// @return A tuple of point cloud and timestamp in nanoseconds + virtual std::tuple getPointcloud() = 0; +}; +} // namespace drivers +} // namespace nebula +#endif // NEBULA_WS_INNOVUSION_SCAN_DECODER_HPP diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_innovusion/decoders/nps_adjustment.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_innovusion/decoders/nps_adjustment.hpp new file mode 100644 index 000000000..9d51bbddc --- /dev/null +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_innovusion/decoders/nps_adjustment.hpp @@ -0,0 +1,149 @@ +/** + * Copyright (C) 2021 - Innovusion Inc. + * + * All Rights Reserved. + * + * $Id$ + */ + +#ifndef SDK_COMMON_NPS_ADJUSTMENT_H_ +#define SDK_COMMON_NPS_ADJUSTMENT_H_ +#ifdef __cplusplus +#include +namespace nebula +{ +namespace drivers +{ +namespace innovusion_packet +{ +#else // __cplusplus +#include +#endif // __cplusplus + +static const double kInnoPs2Nps[2][4][13][45] = {{{ + {-0.028944,-0.028472,-0.027968,-0.027968,-0.027968,-0.027580,-0.027199,-0.026856,-0.026528,-0.026204,-0.026728,-0.026728,-0.026496,-0.026270,-0.026093,-0.025926,-0.025771,-0.025626,-0.025532,-0.025450,-0.025420,-0.025362,-0.025356,-0.025362,-0.025421,-0.025450,-0.025532,-0.025626,-0.025771,-0.025926,-0.026093,-0.026270,-0.026496,-0.026728,-0.026728,-0.026204,-0.026528,-0.026856,-0.027199,-0.027580,-0.027968,-0.027968,-0.027968,-0.028472,-0.028944}, // NOLINT + {-0.028944,-0.028472,-0.027987,-0.027968,-0.027968,-0.027580,-0.027199,-0.026856,-0.026528,-0.026204,-0.026728,-0.026728,-0.026496,-0.026270,-0.026093,-0.025926,-0.025771,-0.025626,-0.025532,-0.025450,-0.025420,-0.025362,-0.025356,-0.025362,-0.025421,-0.025450,-0.025532,-0.025626,-0.025771,-0.025926,-0.026093,-0.026270,-0.026496,-0.026728,-0.026728,-0.026204,-0.026528,-0.026856,-0.027199,-0.027580,-0.027968,-0.027968,-0.027987,-0.028472,-0.028944}, // NOLINT + {-0.028944,-0.028472,-0.027987,-0.027968,-0.027968,-0.027580,-0.027199,-0.026856,-0.026528,-0.026204,-0.025927,-0.025652,-0.025398,-0.025155,-0.024960,-0.024781,-0.024611,-0.024453,-0.024349,-0.024259,-0.024226,-0.024163,-0.024157,-0.024163,-0.024226,-0.024259,-0.024349,-0.024453,-0.024611,-0.024781,-0.024960,-0.025155,-0.025398,-0.025657,-0.025927,-0.026204,-0.026528,-0.026856,-0.027199,-0.027580,-0.027968,-0.027968,-0.027987,-0.028472,-0.028944}, // NOLINT + {-0.028944,-0.028472,-0.027987,-0.027553,-0.027092,-0.026693,-0.026285,-0.025907,-0.025548,-0.025199,-0.024894,-0.024557,-0.024319,-0.024053,-0.023838,-0.023641,-0.023455,-0.023286,-0.023170,-0.023073,-0.023034,-0.022968,-0.022960,-0.022968,-0.023035,-0.023073,-0.023170,-0.023286,-0.023458,-0.023641,-0.023838,-0.024053,-0.024319,-0.024557,-0.024894,-0.025199,-0.025548,-0.025914,-0.026285,-0.026701,-0.027092,-0.027553,-0.027987,-0.028472,-0.028944}, // NOLINT + {-0.028944,-0.027724,-0.027191,-0.026711,-0.026241,-0.025781,-0.025360,-0.024915,-0.024557,-0.024174,-0.023797,-0.023469,-0.023167,-0.022918,-0.022680,-0.022463,-0.022262,-0.022077,-0.021949,-0.021843,-0.021798,-0.021726,-0.021718,-0.021727,-0.021798,-0.021843,-0.021949,-0.022077,-0.022262,-0.022466,-0.022684,-0.022918,-0.023167,-0.023475,-0.023797,-0.024174,-0.024557,-0.024915,-0.025360,-0.025781,-0.026241,-0.026711,-0.027191,-0.027724,-0.028944}, // NOLINT + {-0.027724,-0.027724,-0.026433,-0.025914,-0.025395,-0.024889,-0.024395,-0.023942,-0.023505,-0.023123,-0.022715,-0.022353,-0.022020,-0.021742,-0.021439,-0.021198,-0.021022,-0.020819,-0.020676,-0.020560,-0.020509,-0.020431,-0.020421,-0.020432,-0.020509,-0.020560,-0.020679,-0.020819,-0.021022,-0.021198,-0.021439,-0.021742,-0.022020,-0.022353,-0.022715,-0.023123,-0.023505,-0.023942,-0.024395,-0.024889,-0.025395,-0.025914,-0.026444,-0.027724,-0.027724}, // NOLINT + {-0.025671,-0.025671,-0.025671,-0.025082,-0.024519,-0.023958,-0.023450,-0.022948,-0.022474,-0.022006,-0.021599,-0.021196,-0.020828,-0.020519,-0.020190,-0.019923,-0.019725,-0.019501,-0.019346,-0.019216,-0.019157,-0.019073,-0.019061,-0.019073,-0.019158,-0.019216,-0.019346,-0.019501,-0.019725,-0.019923,-0.020190,-0.020525,-0.020828,-0.021203,-0.021599,-0.022006,-0.022474,-0.022948,-0.023450,-0.023958,-0.024519,-0.025082,-0.025671,-0.025671,-0.025671}, // NOLINT + {-0.025671,-0.025671,-0.025671,-0.024273,-0.023633,-0.023049,-0.022456,-0.021908,-0.021369,-0.020893,-0.020440,-0.020000,-0.019591,-0.019204,-0.018881,-0.018584,-0.018362,-0.018118,-0.017941,-0.017797,-0.017731,-0.017639,-0.017626,-0.017639,-0.017731,-0.017799,-0.017944,-0.018118,-0.018366,-0.018589,-0.018881,-0.019204,-0.019591,-0.020000,-0.020449,-0.020903,-0.021369,-0.021908,-0.022456,-0.023062,-0.023633,-0.024273,-0.025671,-0.025671,-0.025671}, // NOLINT + {-0.025671,-0.023485,-0.023485,-0.023485,-0.022789,-0.022110,-0.021478,-0.020868,-0.020279,-0.019758,-0.019203,-0.018710,-0.018294,-0.017863,-0.017509,-0.017176,-0.016925,-0.016650,-0.016455,-0.016294,-0.016162,-0.016117,-0.016102,-0.016117,-0.016162,-0.016294,-0.016455,-0.016654,-0.016925,-0.017176,-0.017509,-0.017863,-0.018302,-0.018710,-0.019203,-0.019758,-0.020279,-0.020868,-0.021478,-0.022110,-0.022789,-0.023485,-0.023485,-0.023485,-0.025671}, // NOLINT + {-0.023485,-0.023485,-0.023485,-0.023485,-0.021926,-0.021167,-0.020457,-0.019773,-0.019113,-0.018514,-0.017955,-0.017393,-0.016890,-0.016452,-0.016055,-0.015681,-0.015340,-0.015090,-0.014870,-0.016294,-0.016162,-0.016117,-0.016102,-0.016117,-0.016162,-0.016294,-0.014874,-0.015094,-0.015345,-0.015681,-0.016055,-0.016452,-0.016890,-0.017403,-0.017955,-0.018526,-0.019113,-0.019773,-0.020457,-0.021167,-0.021926,-0.023485,-0.023485,-0.023485,-0.023485}, // NOLINT + {-0.023485,-0.023485,-0.021053,-0.021053,-0.021053,-0.020203,-0.019421,-0.019773,-0.019113,-0.018514,-0.017955,-0.017393,-0.016890,-0.016452,-0.016055,-0.015681,-0.015340,-0.015090,-0.014870,-0.014870,-0.016162,-0.016117,-0.016102,-0.016117,-0.016162,-0.014874,-0.014874,-0.015094,-0.015345,-0.015681,-0.016055,-0.016452,-0.016890,-0.017403,-0.017955,-0.018526,-0.019113,-0.019773,-0.019421,-0.020220,-0.021071,-0.021071,-0.021071,-0.023485,-0.023485}, // NOLINT + {-0.021053,-0.021053,-0.021053,-0.021053,-0.021053,-0.020203,-0.019421,-0.019421,-0.019113,-0.018514,-0.017955,-0.017393,-0.016890,-0.016452,-0.016055,-0.015681,-0.015340,-0.015090,-0.014870,-0.014870,-0.014870,-0.016117,-0.016102,-0.016117,-0.014874,-0.014874,-0.014874,-0.015094,-0.015345,-0.015681,-0.016055,-0.016452,-0.016890,-0.017403,-0.017955,-0.018526,-0.019113,-0.019421,-0.019421,-0.020220,-0.021071,-0.021071,-0.021071,-0.021071,-0.021071}, // NOLINT + {-0.021053,-0.021053,-0.021053,-0.021053,-0.021053,-0.020203,-0.019421,-0.019421,-0.019421,-0.018514,-0.017955,-0.017393,-0.016890,-0.016452,-0.016055,-0.015681,-0.015340,-0.015090,-0.014870,-0.014870,-0.014870,-0.016117,-0.016102,-0.016117,-0.014874,-0.014874,-0.014874,-0.015094,-0.015345,-0.015681,-0.016055,-0.016452,-0.016890,-0.017403,-0.017955,-0.018526,-0.019421,-0.019421,-0.019421,-0.020220,-0.021071,-0.021071,-0.021071,-0.021071,-0.021071}, // NOLINT +}, +{ + {-0.028015,-0.028015,-0.027527,-0.027089,-0.026626,-0.026384,-0.026384,-0.026384,-0.026054,-0.025727,-0.025449,-0.025172,-0.024916,-0.024672,-0.024475,-0.025289,-0.025289,-0.025143,-0.025048,-0.024966,-0.024936,-0.024877,-0.024871,-0.024877,-0.024936,-0.024966,-0.025048,-0.025143,-0.025289,-0.025289,-0.024475,-0.024672,-0.024916,-0.025177,-0.025449,-0.025727,-0.026054,-0.026384,-0.026384,-0.026384,-0.026626,-0.027089,-0.027527,-0.028015,-0.028015}, // NOLINT + {-0.028015,-0.028015,-0.027527,-0.027089,-0.026626,-0.026223,-0.026384,-0.026384,-0.026054,-0.025727,-0.025449,-0.025172,-0.024916,-0.024672,-0.024475,-0.025289,-0.025289,-0.025143,-0.025048,-0.024966,-0.024936,-0.024877,-0.024871,-0.024877,-0.024936,-0.024966,-0.025048,-0.025143,-0.025289,-0.025289,-0.024475,-0.024672,-0.024916,-0.025177,-0.025449,-0.025727,-0.026054,-0.026384,-0.026384,-0.026231,-0.026626,-0.027089,-0.027527,-0.028015,-0.028015}, // NOLINT + {-0.028015,-0.028015,-0.027527,-0.027089,-0.026626,-0.026223,-0.026384,-0.026384,-0.026054,-0.025727,-0.025449,-0.025172,-0.024916,-0.024672,-0.024475,-0.024294,-0.024123,-0.023964,-0.023859,-0.023769,-0.023735,-0.023672,-0.023665,-0.023672,-0.023735,-0.023769,-0.023859,-0.023964,-0.024123,-0.024294,-0.024475,-0.024672,-0.024916,-0.025177,-0.025449,-0.025727,-0.026054,-0.026384,-0.026384,-0.026231,-0.026626,-0.027089,-0.027527,-0.028015,-0.028015}, // NOLINT + {-0.028015,-0.028015,-0.027527,-0.027089,-0.026626,-0.026223,-0.025812,-0.025431,-0.025069,-0.024718,-0.024411,-0.024071,-0.023831,-0.023563,-0.023346,-0.023148,-0.022960,-0.022790,-0.022673,-0.022575,-0.022536,-0.022469,-0.022461,-0.022469,-0.022537,-0.022575,-0.022673,-0.022790,-0.022963,-0.023148,-0.023346,-0.023563,-0.023831,-0.024071,-0.024411,-0.024718,-0.025069,-0.025438,-0.025812,-0.026231,-0.026626,-0.027089,-0.027527,-0.028015,-0.028015}, // NOLINT + {-0.027265,-0.027265,-0.026727,-0.026244,-0.025770,-0.025307,-0.024883,-0.024433,-0.024073,-0.023686,-0.023307,-0.022976,-0.022672,-0.022420,-0.022180,-0.021961,-0.021759,-0.021573,-0.021443,-0.021337,-0.021291,-0.021219,-0.021210,-0.021219,-0.021291,-0.021337,-0.021443,-0.021573,-0.021759,-0.021965,-0.022184,-0.022420,-0.022672,-0.022982,-0.023307,-0.023686,-0.024073,-0.024433,-0.024883,-0.025307,-0.025770,-0.026244,-0.026727,-0.027265,-0.027265}, // NOLINT + {-0.027265,-0.027265,-0.025966,-0.025442,-0.024919,-0.024409,-0.023911,-0.023454,-0.023013,-0.022628,-0.022217,-0.021851,-0.021516,-0.021236,-0.020929,-0.020686,-0.020509,-0.020304,-0.020160,-0.020043,-0.019992,-0.019913,-0.019903,-0.019914,-0.019992,-0.020043,-0.020163,-0.020304,-0.020509,-0.020686,-0.020929,-0.021236,-0.021516,-0.021851,-0.022217,-0.022628,-0.023013,-0.023454,-0.023911,-0.024409,-0.024919,-0.025442,-0.025977,-0.027265,-0.027265}, // NOLINT + {-0.025199,-0.025199,-0.025199,-0.024605,-0.024037,-0.023471,-0.022959,-0.022453,-0.021974,-0.021502,-0.021091,-0.020685,-0.020314,-0.020002,-0.019670,-0.019400,-0.019201,-0.018975,-0.018818,-0.018687,-0.018627,-0.018542,-0.018531,-0.018542,-0.018629,-0.018687,-0.018818,-0.018975,-0.019201,-0.019400,-0.019670,-0.020008,-0.020314,-0.020692,-0.021091,-0.021502,-0.021974,-0.022453,-0.022959,-0.023471,-0.024037,-0.024605,-0.025199,-0.025199,-0.025199}, // NOLINT + {-0.025199,-0.025199,-0.025199,-0.023790,-0.023144,-0.022555,-0.021956,-0.021403,-0.020859,-0.020379,-0.019922,-0.019478,-0.019065,-0.018674,-0.018349,-0.018048,-0.017824,-0.017578,-0.017399,-0.017254,-0.017187,-0.017095,-0.017081,-0.017095,-0.017187,-0.017256,-0.017402,-0.017578,-0.017829,-0.018053,-0.018349,-0.018674,-0.019065,-0.019478,-0.019930,-0.020389,-0.020859,-0.021403,-0.021956,-0.022567,-0.023144,-0.023790,-0.025199,-0.025199,-0.025199}, // NOLINT + {-0.025199,-0.022994,-0.022994,-0.022994,-0.022291,-0.021606,-0.020968,-0.020352,-0.019758,-0.019232,-0.018671,-0.018174,-0.017754,-0.017319,-0.016961,-0.016625,-0.016372,-0.016094,-0.015897,-0.015735,-0.015602,-0.015556,-0.015541,-0.015556,-0.015602,-0.015735,-0.015897,-0.016098,-0.016372,-0.016625,-0.016961,-0.017319,-0.017762,-0.018174,-0.018671,-0.019232,-0.019758,-0.020352,-0.020968,-0.021606,-0.022291,-0.022994,-0.022994,-0.022994,-0.025199}, // NOLINT + {-0.022994,-0.022994,-0.022994,-0.022994,-0.021419,-0.020653,-0.019936,-0.019245,-0.018579,-0.017974,-0.017410,-0.016842,-0.016334,-0.015892,-0.015490,-0.015113,-0.014769,-0.014516,-0.014294,-0.014112,-0.013964,-0.013911,-0.013893,-0.013911,-0.013964,-0.014115,-0.014298,-0.014521,-0.014774,-0.015113,-0.015490,-0.015892,-0.016334,-0.016852,-0.017410,-0.017986,-0.018579,-0.019245,-0.019936,-0.020653,-0.021419,-0.022994,-0.022994,-0.022994,-0.022994}, // NOLINT + {-0.022994,-0.022994,-0.020535,-0.020535,-0.020535,-0.019676,-0.018887,-0.018109,-0.017395,-0.016676,-0.017410,-0.016842,-0.016334,-0.015892,-0.015490,-0.015113,-0.014769,-0.014516,-0.014294,-0.014112,-0.013964,-0.013911,-0.013893,-0.013911,-0.013964,-0.014115,-0.014298,-0.014521,-0.014774,-0.015113,-0.015490,-0.015892,-0.016334,-0.016852,-0.017410,-0.016689,-0.017409,-0.018109,-0.018887,-0.019693,-0.020553,-0.020553,-0.020553,-0.022994,-0.022994}, // NOLINT + {-0.020535,-0.020535,-0.020535,-0.020535,-0.020535,-0.019676,-0.018887,-0.018109,-0.017395,-0.016676,-0.016676,-0.016842,-0.016334,-0.015892,-0.015490,-0.015113,-0.014769,-0.014516,-0.014294,-0.014112,-0.013964,-0.013911,-0.013893,-0.013911,-0.013964,-0.014115,-0.014298,-0.014521,-0.014774,-0.015113,-0.015490,-0.015892,-0.016334,-0.016852,-0.016689,-0.016689,-0.017409,-0.018109,-0.018887,-0.019693,-0.020553,-0.020553,-0.020553,-0.020553,-0.020553}, // NOLINT + {-0.020535,-0.020535,-0.020535,-0.020535,-0.020535,-0.019676,-0.018887,-0.018109,-0.017395,-0.016676,-0.016676,-0.016676,-0.016334,-0.015892,-0.015490,-0.015113,-0.014769,-0.014516,-0.014294,-0.014112,-0.013964,-0.013911,-0.013893,-0.013911,-0.013964,-0.014115,-0.014298,-0.014521,-0.014774,-0.015113,-0.015490,-0.015892,-0.016334,-0.016689,-0.016689,-0.016689,-0.017409,-0.018109,-0.018887,-0.019693,-0.020553,-0.020553,-0.020553,-0.020553,-0.020553}, // NOLINT +}, +{ + {-0.026806,-0.026627,-0.026627,-0.026627,-0.026160,-0.025754,-0.025340,-0.024957,-0.024972,-0.024972,-0.024972,-0.024693,-0.024436,-0.024189,-0.023991,-0.023809,-0.023636,-0.023477,-0.023370,-0.023280,-0.023245,-0.023182,-0.023175,-0.023182,-0.023245,-0.023280,-0.023370,-0.023477,-0.023636,-0.023809,-0.023991,-0.024189,-0.024436,-0.024698,-0.024972,-0.024972,-0.024972,-0.024964,-0.025340,-0.025762,-0.026160,-0.026627,-0.026627,-0.026627,-0.026806}, // NOLINT + {-0.026806,-0.026627,-0.026627,-0.026627,-0.026160,-0.025754,-0.025340,-0.024957,-0.024592,-0.024972,-0.024972,-0.024693,-0.024436,-0.024189,-0.023991,-0.023809,-0.023636,-0.023477,-0.023370,-0.023280,-0.023245,-0.023182,-0.023175,-0.023182,-0.023245,-0.023280,-0.023370,-0.023477,-0.023636,-0.023809,-0.023991,-0.024189,-0.024436,-0.024698,-0.024972,-0.024972,-0.024592,-0.024964,-0.025340,-0.025762,-0.026160,-0.026627,-0.026627,-0.026627,-0.026806}, // NOLINT + {-0.026806,-0.026806,-0.026627,-0.026627,-0.026160,-0.025754,-0.025340,-0.024957,-0.024592,-0.024972,-0.024972,-0.024693,-0.024436,-0.024189,-0.023991,-0.023809,-0.023636,-0.023477,-0.023370,-0.023280,-0.023245,-0.023182,-0.023175,-0.023182,-0.023245,-0.023280,-0.023370,-0.023477,-0.023636,-0.023809,-0.023991,-0.024189,-0.024436,-0.024698,-0.024972,-0.024972,-0.024592,-0.024964,-0.025340,-0.025762,-0.026160,-0.026627,-0.026627,-0.026806,-0.026806}, // NOLINT + {-0.026806,-0.026806,-0.026627,-0.026627,-0.026160,-0.025754,-0.025340,-0.024957,-0.024592,-0.024238,-0.023929,-0.023587,-0.023344,-0.023074,-0.022856,-0.022656,-0.022467,-0.022295,-0.022178,-0.022078,-0.022039,-0.021972,-0.021964,-0.021972,-0.022040,-0.022078,-0.022178,-0.022295,-0.022470,-0.022656,-0.022856,-0.023074,-0.023344,-0.023587,-0.023929,-0.024238,-0.024592,-0.024964,-0.025340,-0.025762,-0.026160,-0.026627,-0.026627,-0.026806,-0.026806}, // NOLINT + {-0.026806,-0.026806,-0.026265,-0.025778,-0.025301,-0.024834,-0.024406,-0.023953,-0.023590,-0.023200,-0.022817,-0.022484,-0.022178,-0.021924,-0.021682,-0.021461,-0.021257,-0.021069,-0.020939,-0.020831,-0.020786,-0.020712,-0.020704,-0.020713,-0.020786,-0.020831,-0.020939,-0.021069,-0.021257,-0.021465,-0.021686,-0.021924,-0.022178,-0.022490,-0.022817,-0.023200,-0.023590,-0.023953,-0.024406,-0.024834,-0.025301,-0.025778,-0.026265,-0.026806,-0.026806}, // NOLINT + {-0.026806,-0.026806,-0.025500,-0.024972,-0.024445,-0.023930,-0.023428,-0.022968,-0.022523,-0.022134,-0.021720,-0.021351,-0.021013,-0.020730,-0.020421,-0.020176,-0.019997,-0.019791,-0.019646,-0.019527,-0.019476,-0.019397,-0.019386,-0.019397,-0.019476,-0.019527,-0.019648,-0.019791,-0.019997,-0.020176,-0.020421,-0.020730,-0.021013,-0.021351,-0.021720,-0.022134,-0.022523,-0.022968,-0.023428,-0.023930,-0.024445,-0.024972,-0.025511,-0.026806,-0.026806}, // NOLINT + {-0.024728,-0.024728,-0.024728,-0.024129,-0.023556,-0.022985,-0.022469,-0.021958,-0.021475,-0.020999,-0.020585,-0.020175,-0.019801,-0.019486,-0.019151,-0.018879,-0.018677,-0.018450,-0.018291,-0.018159,-0.018099,-0.018013,-0.018002,-0.018013,-0.018100,-0.018159,-0.018291,-0.018450,-0.018677,-0.018879,-0.019151,-0.019492,-0.019801,-0.020183,-0.020585,-0.020999,-0.021475,-0.021958,-0.022469,-0.022985,-0.023556,-0.024129,-0.024728,-0.024728,-0.024728}, // NOLINT + {-0.024728,-0.024728,-0.024728,-0.023307,-0.022656,-0.022061,-0.021457,-0.020899,-0.020350,-0.019866,-0.019405,-0.018957,-0.018540,-0.018145,-0.017817,-0.017514,-0.017288,-0.017039,-0.016859,-0.016712,-0.016645,-0.016551,-0.016538,-0.016551,-0.016645,-0.016714,-0.016862,-0.017039,-0.017292,-0.017519,-0.017817,-0.018145,-0.018540,-0.018957,-0.019413,-0.019876,-0.020350,-0.020899,-0.021457,-0.022074,-0.022656,-0.023307,-0.024728,-0.024728,-0.024728}, // NOLINT + {-0.024728,-0.022504,-0.022504,-0.022504,-0.021795,-0.021104,-0.020460,-0.019838,-0.019238,-0.018707,-0.018141,-0.017639,-0.017216,-0.016776,-0.016415,-0.016076,-0.015821,-0.015540,-0.015341,-0.015177,-0.015043,-0.014997,-0.014981,-0.014997,-0.015043,-0.015177,-0.015341,-0.015544,-0.015821,-0.016076,-0.016415,-0.016776,-0.017224,-0.017639,-0.018141,-0.018707,-0.019238,-0.019838,-0.020460,-0.021104,-0.021795,-0.022504,-0.022504,-0.022504,-0.024728}, // NOLINT + {-0.022504,-0.022504,-0.022504,-0.022504,-0.020913,-0.020139,-0.019416,-0.018718,-0.018045,-0.017435,-0.016865,-0.016292,-0.015780,-0.015333,-0.014928,-0.014547,-0.014199,-0.013944,-0.013720,-0.013535,-0.013386,-0.013333,-0.013315,-0.013333,-0.013386,-0.013538,-0.013724,-0.013948,-0.014204,-0.014547,-0.014928,-0.015333,-0.015780,-0.016303,-0.016865,-0.017447,-0.018045,-0.018718,-0.019416,-0.020139,-0.020913,-0.022504,-0.022504,-0.022504,-0.022504}, // NOLINT + {-0.022504,-0.022504,-0.020018,-0.020018,-0.020018,-0.019151,-0.018354,-0.017568,-0.016847,-0.016121,-0.015477,-0.014830,-0.014300,-0.013805,-0.013338,-0.012917,-0.014199,-0.013944,-0.013720,-0.013535,-0.013386,-0.013333,-0.013315,-0.013333,-0.013386,-0.013538,-0.013724,-0.013948,-0.014204,-0.012917,-0.013347,-0.013805,-0.014300,-0.014842,-0.015477,-0.016134,-0.016862,-0.017568,-0.018354,-0.019168,-0.020036,-0.020036,-0.020036,-0.022504,-0.022504}, // NOLINT + {-0.020018,-0.020018,-0.020018,-0.020018,-0.020018,-0.019151,-0.018354,-0.017568,-0.016847,-0.016121,-0.015477,-0.014830,-0.014300,-0.013805,-0.013338,-0.012917,-0.012917,-0.013944,-0.013720,-0.013535,-0.013386,-0.013333,-0.013315,-0.013333,-0.013386,-0.013538,-0.013724,-0.013948,-0.012917,-0.012917,-0.013347,-0.013805,-0.014300,-0.014842,-0.015477,-0.016134,-0.016862,-0.017568,-0.018354,-0.019168,-0.020036,-0.020036,-0.020036,-0.020036,-0.020036}, // NOLINT + {-0.020018,-0.020018,-0.020018,-0.020018,-0.020018,-0.019151,-0.018354,-0.017568,-0.016847,-0.016121,-0.015477,-0.014830,-0.014300,-0.013805,-0.013338,-0.012917,-0.012917,-0.012917,-0.013720,-0.013535,-0.013386,-0.013333,-0.013315,-0.013333,-0.013386,-0.013538,-0.013724,-0.012917,-0.012917,-0.012917,-0.013347,-0.013805,-0.014300,-0.014842,-0.015477,-0.016134,-0.016862,-0.017568,-0.018354,-0.019168,-0.020036,-0.020036,-0.020036,-0.020036,-0.020036}, // NOLINT +}, +{ + {-0.026349,-0.026349,-0.025804,-0.025313,-0.024870,-0.024870,-0.024870,-0.024483,-0.024116,-0.023759,-0.023448,-0.023103,-0.023508,-0.023508,-0.023508,-0.023325,-0.023151,-0.022990,-0.022883,-0.022792,-0.022757,-0.022694,-0.022687,-0.022694,-0.022757,-0.022792,-0.022883,-0.022990,-0.023151,-0.023325,-0.023508,-0.023508,-0.023508,-0.023103,-0.023448,-0.023759,-0.024116,-0.024491,-0.024870,-0.024870,-0.024870,-0.025313,-0.025804,-0.026349,-0.026349}, // NOLINT + {-0.026349,-0.026349,-0.025804,-0.025313,-0.024870,-0.024870,-0.024870,-0.024483,-0.024116,-0.023759,-0.023448,-0.023103,-0.022859,-0.023508,-0.023508,-0.023325,-0.023151,-0.022990,-0.022883,-0.022792,-0.022757,-0.022694,-0.022687,-0.022694,-0.022757,-0.022792,-0.022883,-0.022990,-0.023151,-0.023325,-0.023508,-0.023508,-0.022859,-0.023103,-0.023448,-0.023759,-0.024116,-0.024491,-0.024870,-0.024870,-0.024870,-0.025313,-0.025804,-0.026349,-0.026349}, // NOLINT + {-0.026349,-0.026349,-0.025804,-0.025313,-0.024832,-0.024870,-0.024870,-0.024483,-0.024116,-0.023759,-0.023448,-0.023103,-0.022859,-0.023508,-0.023508,-0.023325,-0.023151,-0.022990,-0.022883,-0.022792,-0.022757,-0.022694,-0.022687,-0.022694,-0.022757,-0.022792,-0.022883,-0.022990,-0.023151,-0.023325,-0.023508,-0.023508,-0.022859,-0.023103,-0.023448,-0.023759,-0.024116,-0.024491,-0.024870,-0.024870,-0.024832,-0.025313,-0.025804,-0.026349,-0.026349}, // NOLINT + {-0.026349,-0.026349,-0.025804,-0.025313,-0.024832,-0.024870,-0.024870,-0.024483,-0.024116,-0.023759,-0.023448,-0.023103,-0.022859,-0.022587,-0.022367,-0.022165,-0.021974,-0.021802,-0.021683,-0.021583,-0.021543,-0.021476,-0.021468,-0.021476,-0.021544,-0.021583,-0.021683,-0.021802,-0.021977,-0.022165,-0.022367,-0.022587,-0.022859,-0.023103,-0.023448,-0.023759,-0.024116,-0.024491,-0.024870,-0.024870,-0.024832,-0.025313,-0.025804,-0.026349,-0.026349}, // NOLINT + {-0.026349,-0.026349,-0.025804,-0.025313,-0.024832,-0.024362,-0.023931,-0.023474,-0.023108,-0.022716,-0.022330,-0.021994,-0.021685,-0.021429,-0.021185,-0.020963,-0.020757,-0.020567,-0.020436,-0.020327,-0.020281,-0.020208,-0.020199,-0.020208,-0.020281,-0.020327,-0.020436,-0.020567,-0.020757,-0.020966,-0.021189,-0.021429,-0.021685,-0.022000,-0.022330,-0.022716,-0.023108,-0.023474,-0.023931,-0.024362,-0.024832,-0.025313,-0.025804,-0.026349,-0.026349}, // NOLINT + {-0.026349,-0.026349,-0.025035,-0.024503,-0.023972,-0.023453,-0.022946,-0.022483,-0.022034,-0.021642,-0.021225,-0.020852,-0.020511,-0.020226,-0.019915,-0.019668,-0.019487,-0.019279,-0.019133,-0.019013,-0.018961,-0.018881,-0.018871,-0.018882,-0.018961,-0.019013,-0.019135,-0.019279,-0.019487,-0.019668,-0.019915,-0.020226,-0.020511,-0.020852,-0.021225,-0.021642,-0.022034,-0.022483,-0.022946,-0.023453,-0.023972,-0.024503,-0.025047,-0.026349,-0.026349}, // NOLINT + {-0.024259,-0.024259,-0.024259,-0.023654,-0.023077,-0.022501,-0.021980,-0.021465,-0.020978,-0.020498,-0.020080,-0.019667,-0.019289,-0.018971,-0.018633,-0.018359,-0.018156,-0.017926,-0.017766,-0.017633,-0.017572,-0.017486,-0.017474,-0.017486,-0.017574,-0.017633,-0.017766,-0.017926,-0.018156,-0.018359,-0.018633,-0.018977,-0.019289,-0.019674,-0.020080,-0.020498,-0.020978,-0.021465,-0.021980,-0.022501,-0.023077,-0.023654,-0.024259,-0.024259,-0.024259}, // NOLINT + {-0.024259,-0.024259,-0.024259,-0.022826,-0.022169,-0.021569,-0.020960,-0.020397,-0.019843,-0.019355,-0.018889,-0.018437,-0.018017,-0.017618,-0.017287,-0.016981,-0.016753,-0.016502,-0.016320,-0.016172,-0.016104,-0.016010,-0.015996,-0.016010,-0.016104,-0.016174,-0.016323,-0.016502,-0.016757,-0.016986,-0.017287,-0.017618,-0.018017,-0.018437,-0.018898,-0.019364,-0.019843,-0.020397,-0.020960,-0.021582,-0.022169,-0.022826,-0.024259,-0.024259,-0.024259}, // NOLINT + {-0.024259,-0.022016,-0.022016,-0.022016,-0.021300,-0.020602,-0.019953,-0.019325,-0.018720,-0.018184,-0.017613,-0.017106,-0.016679,-0.016235,-0.015871,-0.015528,-0.015270,-0.014987,-0.014786,-0.014621,-0.014485,-0.014439,-0.014423,-0.014439,-0.014485,-0.014621,-0.014786,-0.014991,-0.015270,-0.015528,-0.015871,-0.016235,-0.016687,-0.017106,-0.017613,-0.018184,-0.018720,-0.019325,-0.019953,-0.020602,-0.021300,-0.022016,-0.022016,-0.022016,-0.024259}, // NOLINT + {-0.022016,-0.022016,-0.022016,-0.022016,-0.020408,-0.019627,-0.018897,-0.018193,-0.017514,-0.016898,-0.016323,-0.015744,-0.015227,-0.014776,-0.014366,-0.013982,-0.013630,-0.013373,-0.013147,-0.012961,-0.012810,-0.012756,-0.012738,-0.012756,-0.012810,-0.012964,-0.013151,-0.013378,-0.013636,-0.013982,-0.014366,-0.014776,-0.015227,-0.015754,-0.016323,-0.016910,-0.017514,-0.018193,-0.018897,-0.019627,-0.020408,-0.022016,-0.022016,-0.022016,-0.022016}, // NOLINT + {-0.022016,-0.022016,-0.019502,-0.019502,-0.019502,-0.018627,-0.017822,-0.017029,-0.016301,-0.015568,-0.014918,-0.014264,-0.013729,-0.013230,-0.012758,-0.012332,-0.011936,-0.011644,-0.011383,-0.011173,-0.011003,-0.010942,-0.010921,-0.010942,-0.011006,-0.011176,-0.011387,-0.011644,-0.011936,-0.012332,-0.012767,-0.013230,-0.013729,-0.014276,-0.014918,-0.015581,-0.016316,-0.017029,-0.017822,-0.018644,-0.019521,-0.019521,-0.019521,-0.022016,-0.022016}, // NOLINT + {-0.019502,-0.019502,-0.019502,-0.019502,-0.019502,-0.017606,-0.016674,-0.015793,-0.014964,-0.015568,-0.014918,-0.014264,-0.013729,-0.013230,-0.012758,-0.012332,-0.011936,-0.011644,-0.011383,-0.011173,-0.011003,-0.010942,-0.010921,-0.010942,-0.011006,-0.011176,-0.011387,-0.011644,-0.011936,-0.012332,-0.012767,-0.013230,-0.013729,-0.014276,-0.014918,-0.015581,-0.014981,-0.015793,-0.016693,-0.017606,-0.019521,-0.019521,-0.019521,-0.019521,-0.019521}, // NOLINT + {-0.019502,-0.019502,-0.019502,-0.019502,-0.017606,-0.017606,-0.016674,-0.015793,-0.014964,-0.014964,-0.014918,-0.014264,-0.013729,-0.013230,-0.012758,-0.012332,-0.011936,-0.011644,-0.011383,-0.011173,-0.011003,-0.010942,-0.010921,-0.010942,-0.011006,-0.011176,-0.011387,-0.011644,-0.011936,-0.012332,-0.012767,-0.013230,-0.013729,-0.014276,-0.014918,-0.014981,-0.014981,-0.015793,-0.016693,-0.017606,-0.017606,-0.019521,-0.019521,-0.019521,-0.019521}, // NOLINT +}}, +{{ + {0.030798,0.030561,0.029220,0.029220,0.029220,0.029045,0.028891,0.028728,0.028591,0.028466,0.027581,0.027581,0.027492,0.027415,0.027333,0.027267,0.027215,0.027178,0.027133,0.027105,0.027068,0.027068,0.027061,0.027068,0.027069,0.027105,0.027133,0.027178,0.027215,0.027267,0.027333,0.027415,0.027492,0.027581,0.027581,0.028466,0.028591,0.028728,0.028891,0.029045,0.029220,0.029220,0.029220,0.030561,0.030798}, // NOLINT + {0.030798,0.030561,0.030324,0.029220,0.029220,0.029045,0.028891,0.028728,0.028591,0.028466,0.027581,0.027581,0.027492,0.027415,0.027333,0.027267,0.027215,0.027178,0.027133,0.027105,0.027068,0.027068,0.027061,0.027068,0.027069,0.027105,0.027133,0.027178,0.027215,0.027267,0.027333,0.027415,0.027492,0.027581,0.027581,0.028466,0.028591,0.028728,0.028891,0.029045,0.029220,0.029220,0.030324,0.030561,0.030798}, // NOLINT + {0.030798,0.030561,0.030324,0.029220,0.029220,0.029045,0.028891,0.028728,0.028591,0.028466,0.028337,0.028215,0.028122,0.028044,0.027957,0.027890,0.027835,0.027795,0.027747,0.027717,0.027681,0.027680,0.027673,0.027680,0.027681,0.027717,0.027747,0.027795,0.027835,0.027890,0.027957,0.028044,0.028122,0.028221,0.028337,0.028466,0.028591,0.028728,0.028891,0.029045,0.029220,0.029220,0.030324,0.030561,0.030798}, // NOLINT + {0.030798,0.030561,0.030324,0.030104,0.029925,0.029710,0.029554,0.029381,0.029236,0.029110,0.028974,0.028872,0.028752,0.028669,0.028578,0.028507,0.028449,0.028410,0.028360,0.028328,0.028290,0.028290,0.028282,0.028290,0.028291,0.028328,0.028360,0.028410,0.028452,0.028507,0.028578,0.028669,0.028752,0.028872,0.028974,0.029110,0.029236,0.029389,0.029554,0.029719,0.029925,0.030104,0.030324,0.030561,0.030798}, // NOLINT + {0.030798,0.031311,0.031060,0.030826,0.030616,0.030428,0.030233,0.030080,0.029905,0.029772,0.029651,0.029523,0.029424,0.029315,0.029220,0.029146,0.029088,0.029047,0.028995,0.028964,0.028924,0.028923,0.028915,0.028923,0.028924,0.028964,0.028995,0.029047,0.029088,0.029149,0.029224,0.029315,0.029424,0.029528,0.029651,0.029772,0.029905,0.030080,0.030233,0.030428,0.030616,0.030826,0.031060,0.031311,0.030798}, // NOLINT + {0.031311,0.031311,0.031789,0.031553,0.031332,0.031134,0.030960,0.030777,0.030617,0.030455,0.030336,0.030202,0.030098,0.029985,0.029914,0.029837,0.029754,0.029711,0.029657,0.029625,0.029584,0.029584,0.029576,0.029584,0.029584,0.029625,0.029659,0.029711,0.029754,0.029837,0.029914,0.029985,0.030098,0.030202,0.030336,0.030455,0.030617,0.030777,0.030960,0.031134,0.031332,0.031553,0.031800,0.031311,0.031311}, // NOLINT + {0.032577,0.032577,0.032577,0.032319,0.032098,0.031891,0.031687,0.031497,0.031338,0.031193,0.031046,0.030908,0.030801,0.030684,0.030615,0.030536,0.030450,0.030406,0.030353,0.030320,0.030277,0.030277,0.030269,0.030277,0.030278,0.030320,0.030353,0.030406,0.030450,0.030536,0.030615,0.030689,0.030801,0.030913,0.031046,0.031193,0.031338,0.031497,0.031687,0.031891,0.032098,0.032319,0.032577,0.032577,0.032577}, // NOLINT + {0.032577,0.032577,0.032577,0.033128,0.032887,0.032650,0.032471,0.032283,0.032111,0.031938,0.031786,0.031650,0.031541,0.031452,0.031351,0.031270,0.031182,0.031141,0.031085,0.031051,0.031008,0.031009,0.031000,0.031009,0.031008,0.031052,0.031087,0.031141,0.031185,0.031274,0.031351,0.031452,0.031541,0.031650,0.031793,0.031944,0.032111,0.032283,0.032471,0.032660,0.032887,0.033128,0.032577,0.032577,0.032577}, // NOLINT + {0.032577,0.033927,0.033927,0.033927,0.033689,0.033478,0.033261,0.033068,0.032900,0.032730,0.032601,0.032462,0.032320,0.032230,0.032132,0.032050,0.031960,0.031917,0.031862,0.031828,0.031812,0.031786,0.031777,0.031786,0.031812,0.031828,0.031862,0.031919,0.031960,0.032050,0.032132,0.032230,0.032325,0.032462,0.032601,0.032730,0.032900,0.033068,0.033261,0.033478,0.033689,0.033927,0.033927,0.033927,0.032577}, // NOLINT + {0.033927,0.033927,0.033927,0.033927,0.034563,0.034348,0.034126,0.033930,0.033761,0.033581,0.033431,0.033286,0.033181,0.033058,0.032960,0.032879,0.032818,0.032746,0.032691,0.031828,0.031812,0.031786,0.031777,0.031786,0.031812,0.031828,0.032693,0.032748,0.032821,0.032879,0.032960,0.033058,0.033181,0.033292,0.033431,0.033588,0.033761,0.033930,0.034126,0.034348,0.034563,0.033927,0.033927,0.033927,0.033927}, // NOLINT + {0.033927,0.033927,0.035470,0.035470,0.035470,0.035254,0.035039,0.033930,0.033761,0.033581,0.033431,0.033286,0.033181,0.033058,0.032960,0.032879,0.032818,0.032746,0.032691,0.032691,0.031812,0.031786,0.031777,0.031786,0.031812,0.032693,0.032693,0.032748,0.032821,0.032879,0.032960,0.033058,0.033181,0.033292,0.033431,0.033588,0.033761,0.033930,0.035039,0.035263,0.035480,0.035480,0.035480,0.033927,0.033927}, // NOLINT + {0.035470,0.035470,0.035470,0.035470,0.035470,0.035254,0.035039,0.035039,0.033761,0.033581,0.033431,0.033286,0.033181,0.033058,0.032960,0.032879,0.032818,0.032746,0.032691,0.032691,0.032691,0.031786,0.031777,0.031786,0.032693,0.032693,0.032693,0.032748,0.032821,0.032879,0.032960,0.033058,0.033181,0.033292,0.033431,0.033588,0.033761,0.035039,0.035039,0.035263,0.035480,0.035480,0.035480,0.035480,0.035480}, // NOLINT + {0.035470,0.035470,0.035470,0.035470,0.035470,0.035254,0.035039,0.035039,0.035039,0.033581,0.033431,0.033286,0.033181,0.033058,0.032960,0.032879,0.032818,0.032746,0.032691,0.032691,0.032691,0.031786,0.031777,0.031786,0.032693,0.032693,0.032693,0.032748,0.032821,0.032879,0.032960,0.033058,0.033181,0.033292,0.033431,0.033588,0.035039,0.035039,0.035039,0.035263,0.035480,0.035480,0.035480,0.035480,0.035480}, // NOLINT +}, +{ + {0.030840,0.030840,0.030601,0.030378,0.030197,0.028990,0.028990,0.028990,0.028852,0.028725,0.028595,0.028472,0.028377,0.028298,0.028211,0.027464,0.027464,0.027427,0.027381,0.027352,0.027316,0.027315,0.027308,0.027315,0.027316,0.027352,0.027381,0.027427,0.027464,0.027464,0.028211,0.028298,0.028377,0.028477,0.028595,0.028725,0.028852,0.028990,0.028990,0.028990,0.030197,0.030378,0.030601,0.030840,0.030840}, // NOLINT + {0.030840,0.030840,0.030601,0.030378,0.030197,0.029980,0.028990,0.028990,0.028852,0.028725,0.028595,0.028472,0.028377,0.028298,0.028211,0.027464,0.027464,0.027427,0.027381,0.027352,0.027316,0.027315,0.027308,0.027315,0.027316,0.027352,0.027381,0.027427,0.027464,0.027464,0.028211,0.028298,0.028377,0.028477,0.028595,0.028725,0.028852,0.028990,0.028990,0.029989,0.030197,0.030378,0.030601,0.030840,0.030840}, // NOLINT + {0.030840,0.030840,0.030601,0.030378,0.030197,0.029980,0.028990,0.028990,0.028852,0.028725,0.028595,0.028472,0.028377,0.028298,0.028211,0.028143,0.028087,0.028047,0.027999,0.027968,0.027931,0.027930,0.027923,0.027930,0.027931,0.027968,0.027999,0.028047,0.028087,0.028143,0.028211,0.028298,0.028377,0.028477,0.028595,0.028725,0.028852,0.028990,0.028990,0.029989,0.030197,0.030378,0.030601,0.030840,0.030840}, // NOLINT + {0.030840,0.030840,0.030601,0.030378,0.030197,0.029980,0.029822,0.029647,0.029501,0.029373,0.029235,0.029133,0.029011,0.028927,0.028835,0.028764,0.028705,0.028665,0.028615,0.028583,0.028544,0.028544,0.028536,0.028544,0.028545,0.028583,0.028615,0.028665,0.028708,0.028764,0.028835,0.028927,0.029011,0.029133,0.029235,0.029373,0.029501,0.029655,0.029822,0.029989,0.030197,0.030378,0.030601,0.030840,0.030840}, // NOLINT + {0.031594,0.031594,0.031340,0.031104,0.030892,0.030702,0.030505,0.030350,0.030174,0.030039,0.029917,0.029787,0.029688,0.029578,0.029481,0.029407,0.029349,0.029307,0.029255,0.029223,0.029182,0.029182,0.029174,0.029182,0.029182,0.029223,0.029255,0.029307,0.029349,0.029410,0.029485,0.029578,0.029688,0.029793,0.029917,0.030039,0.030174,0.030350,0.030505,0.030702,0.030892,0.031104,0.031340,0.031594,0.031594}, // NOLINT + {0.031594,0.031594,0.032074,0.031836,0.031613,0.031413,0.031237,0.031053,0.030891,0.030727,0.030607,0.030472,0.030367,0.030253,0.030181,0.030103,0.030019,0.029976,0.029922,0.029889,0.029849,0.029848,0.029840,0.029848,0.029849,0.029889,0.029924,0.029976,0.030019,0.030103,0.030181,0.030253,0.030367,0.030472,0.030607,0.030727,0.030891,0.031053,0.031237,0.031413,0.031613,0.031836,0.032086,0.031594,0.031594}, // NOLINT + {0.032869,0.032869,0.032869,0.032608,0.032385,0.032176,0.031970,0.031778,0.031618,0.031471,0.031323,0.031183,0.031076,0.030958,0.030889,0.030809,0.030722,0.030678,0.030624,0.030590,0.030547,0.030547,0.030539,0.030547,0.030548,0.030590,0.030624,0.030678,0.030722,0.030809,0.030889,0.030963,0.031076,0.031189,0.031323,0.031471,0.031618,0.031778,0.031970,0.032176,0.032385,0.032608,0.032869,0.032869,0.032869}, // NOLINT + {0.032869,0.032869,0.032869,0.033423,0.033180,0.032942,0.032761,0.032571,0.032398,0.032223,0.032070,0.031933,0.031823,0.031733,0.031632,0.031550,0.031461,0.031420,0.031363,0.031329,0.031285,0.031286,0.031278,0.031286,0.031285,0.031330,0.031365,0.031420,0.031464,0.031554,0.031632,0.031733,0.031823,0.031933,0.032077,0.032230,0.032398,0.032571,0.032761,0.032951,0.033180,0.033423,0.032869,0.032869,0.032869}, // NOLINT + {0.032869,0.034230,0.034230,0.034230,0.033990,0.033777,0.033558,0.033364,0.033195,0.033023,0.032893,0.032754,0.032610,0.032519,0.032421,0.032338,0.032247,0.032204,0.032148,0.032114,0.032098,0.032071,0.032062,0.032071,0.032098,0.032114,0.032148,0.032206,0.032247,0.032338,0.032421,0.032519,0.032615,0.032754,0.032893,0.033023,0.033195,0.033364,0.033558,0.033777,0.033990,0.034230,0.034230,0.034230,0.032869}, // NOLINT + {0.034230,0.034230,0.034230,0.034230,0.034873,0.034656,0.034432,0.034236,0.034064,0.033883,0.033733,0.033587,0.033481,0.033357,0.033258,0.033176,0.033115,0.033042,0.032987,0.032954,0.032939,0.032911,0.032902,0.032911,0.032939,0.032955,0.032989,0.033045,0.033118,0.033176,0.033258,0.033357,0.033481,0.033592,0.033733,0.033890,0.034064,0.034236,0.034432,0.034656,0.034873,0.034230,0.034230,0.034230,0.034230}, // NOLINT + {0.034230,0.034230,0.035790,0.035790,0.035790,0.035572,0.035356,0.035159,0.034952,0.034807,0.033733,0.033587,0.033481,0.033357,0.033258,0.033176,0.033115,0.033042,0.032987,0.032954,0.032939,0.032911,0.032902,0.032911,0.032939,0.032955,0.032989,0.033045,0.033118,0.033176,0.033258,0.033357,0.033481,0.033592,0.033733,0.034814,0.034960,0.035159,0.035356,0.035582,0.035800,0.035800,0.035800,0.034230,0.034230}, // NOLINT + {0.035790,0.035790,0.035790,0.035790,0.035790,0.035572,0.035356,0.035159,0.034952,0.034807,0.034807,0.033587,0.033481,0.033357,0.033258,0.033176,0.033115,0.033042,0.032987,0.032954,0.032939,0.032911,0.032902,0.032911,0.032939,0.032955,0.032989,0.033045,0.033118,0.033176,0.033258,0.033357,0.033481,0.033592,0.034814,0.034814,0.034960,0.035159,0.035356,0.035582,0.035800,0.035800,0.035800,0.035800,0.035800}, // NOLINT + {0.035790,0.035790,0.035790,0.035790,0.035790,0.035572,0.035356,0.035159,0.034952,0.034807,0.034807,0.034807,0.033481,0.033357,0.033258,0.033176,0.033115,0.033042,0.032987,0.032954,0.032939,0.032911,0.032902,0.032911,0.032939,0.032955,0.032989,0.033045,0.033118,0.033176,0.033258,0.033357,0.033481,0.034814,0.034814,0.034814,0.034960,0.035159,0.035356,0.035582,0.035800,0.035800,0.035800,0.035800,0.035800}, // NOLINT +}, +{ + {0.031877,0.030652,0.030652,0.030652,0.030469,0.030249,0.030089,0.029913,0.028852,0.028852,0.028852,0.028728,0.028632,0.028552,0.028464,0.028395,0.028338,0.028298,0.028249,0.028218,0.028181,0.028180,0.028173,0.028180,0.028181,0.028218,0.028249,0.028298,0.028338,0.028395,0.028464,0.028552,0.028632,0.028733,0.028852,0.028852,0.028852,0.029920,0.030089,0.030258,0.030469,0.030652,0.030652,0.030652,0.031877}, // NOLINT + {0.031877,0.030652,0.030652,0.030652,0.030469,0.030249,0.030089,0.029913,0.029764,0.028852,0.028852,0.028728,0.028632,0.028552,0.028464,0.028395,0.028338,0.028298,0.028249,0.028218,0.028181,0.028180,0.028173,0.028180,0.028181,0.028218,0.028249,0.028298,0.028338,0.028395,0.028464,0.028552,0.028632,0.028733,0.028852,0.028852,0.029764,0.029920,0.030089,0.030258,0.030469,0.030652,0.030652,0.030652,0.031877}, // NOLINT + {0.031877,0.031877,0.030652,0.030652,0.030469,0.030249,0.030089,0.029913,0.029764,0.028852,0.028852,0.028728,0.028632,0.028552,0.028464,0.028395,0.028338,0.028298,0.028249,0.028218,0.028181,0.028180,0.028173,0.028180,0.028181,0.028218,0.028249,0.028298,0.028338,0.028395,0.028464,0.028552,0.028632,0.028733,0.028852,0.028852,0.029764,0.029920,0.030089,0.030258,0.030469,0.030652,0.030652,0.031877,0.031877}, // NOLINT + {0.031877,0.031877,0.030652,0.030652,0.030469,0.030249,0.030089,0.029913,0.029764,0.029635,0.029496,0.029392,0.029269,0.029185,0.029092,0.029019,0.028960,0.028920,0.028869,0.028837,0.028798,0.028798,0.028790,0.028798,0.028799,0.028837,0.028869,0.028920,0.028963,0.029019,0.029092,0.029185,0.029269,0.029392,0.029496,0.029635,0.029764,0.029920,0.030089,0.030258,0.030469,0.030652,0.030652,0.031877,0.031877}, // NOLINT + {0.031877,0.031877,0.031620,0.031382,0.031167,0.030976,0.030776,0.030620,0.030442,0.030306,0.030183,0.030052,0.029951,0.029840,0.029743,0.029667,0.029608,0.029566,0.029513,0.029481,0.029441,0.029440,0.029432,0.029440,0.029441,0.029481,0.029513,0.029566,0.029608,0.029670,0.029746,0.029840,0.029951,0.030057,0.030183,0.030306,0.030442,0.030620,0.030776,0.030976,0.031167,0.031382,0.031620,0.031877,0.031877}, // NOLINT + {0.031877,0.031877,0.032359,0.032119,0.031893,0.031691,0.031513,0.031327,0.031164,0.030999,0.030877,0.030741,0.030635,0.030520,0.030448,0.030369,0.030284,0.030241,0.030186,0.030153,0.030112,0.030111,0.030103,0.030112,0.030112,0.030153,0.030188,0.030241,0.030284,0.030369,0.030448,0.030520,0.030635,0.030741,0.030877,0.030999,0.031164,0.031327,0.031513,0.031691,0.031893,0.032119,0.032371,0.031877,0.031877}, // NOLINT + {0.033159,0.033159,0.033159,0.032896,0.032671,0.032460,0.032252,0.032059,0.031897,0.031749,0.031599,0.031459,0.031350,0.031231,0.031161,0.031080,0.030993,0.030949,0.030895,0.030860,0.030817,0.030817,0.030809,0.030817,0.030818,0.030860,0.030895,0.030949,0.030993,0.031080,0.031161,0.031236,0.031350,0.031464,0.031599,0.031749,0.031897,0.032059,0.032252,0.032460,0.032671,0.032896,0.033159,0.033159,0.033159}, // NOLINT + {0.033159,0.033159,0.033159,0.033718,0.033473,0.033232,0.033050,0.032859,0.032684,0.032508,0.032354,0.032215,0.032104,0.032013,0.031911,0.031829,0.031739,0.031698,0.031640,0.031606,0.031562,0.031563,0.031554,0.031563,0.031562,0.031607,0.031642,0.031698,0.031742,0.031833,0.031911,0.032013,0.032104,0.032215,0.032360,0.032514,0.032684,0.032859,0.033050,0.033242,0.033473,0.033718,0.033159,0.033159,0.033159}, // NOLINT + {0.033159,0.034532,0.034532,0.034532,0.034290,0.034076,0.033855,0.033659,0.033489,0.033315,0.033184,0.033044,0.032899,0.032808,0.032709,0.032625,0.032534,0.032490,0.032434,0.032400,0.032384,0.032357,0.032348,0.032357,0.032384,0.032400,0.032434,0.032492,0.032534,0.032625,0.032709,0.032808,0.032904,0.033044,0.033184,0.033315,0.033489,0.033659,0.033855,0.034076,0.034290,0.034532,0.034532,0.034532,0.033159}, // NOLINT + {0.034532,0.034532,0.034532,0.034532,0.035182,0.034964,0.034738,0.034540,0.034368,0.034185,0.034033,0.033886,0.033780,0.033655,0.033556,0.033473,0.033411,0.033338,0.033282,0.033249,0.033234,0.033206,0.033197,0.033206,0.033234,0.033250,0.033284,0.033340,0.033414,0.033473,0.033556,0.033655,0.033780,0.033892,0.034033,0.034192,0.034368,0.034540,0.034738,0.034964,0.035182,0.034532,0.034532,0.034532,0.034532}, // NOLINT + {0.034532,0.034532,0.036110,0.036110,0.036110,0.035890,0.035673,0.035474,0.035266,0.035120,0.034969,0.034824,0.034683,0.034564,0.034461,0.034384,0.033411,0.033338,0.033282,0.033249,0.033234,0.033206,0.033197,0.033206,0.033234,0.033250,0.033284,0.033340,0.033414,0.034384,0.034465,0.034564,0.034683,0.034829,0.034969,0.035127,0.035273,0.035474,0.035673,0.035900,0.036120,0.036120,0.036120,0.034532,0.034532}, // NOLINT + {0.036110,0.036110,0.036110,0.036110,0.036110,0.035890,0.035673,0.035474,0.035266,0.035120,0.034969,0.034824,0.034683,0.034564,0.034461,0.034384,0.034384,0.033338,0.033282,0.033249,0.033234,0.033206,0.033197,0.033206,0.033234,0.033250,0.033284,0.033340,0.034384,0.034384,0.034465,0.034564,0.034683,0.034829,0.034969,0.035127,0.035273,0.035474,0.035673,0.035900,0.036120,0.036120,0.036120,0.036120,0.036120}, // NOLINT + {0.036110,0.036110,0.036110,0.036110,0.036110,0.035890,0.035673,0.035474,0.035266,0.035120,0.034969,0.034824,0.034683,0.034564,0.034461,0.034384,0.034384,0.034384,0.033282,0.033249,0.033234,0.033206,0.033197,0.033206,0.033234,0.033250,0.033284,0.034384,0.034384,0.034384,0.034465,0.034564,0.034683,0.034829,0.034969,0.035127,0.035273,0.035474,0.035673,0.035900,0.036120,0.036120,0.036120,0.036120,0.036120}, // NOLINT +}, +{ + {0.032159,0.032159,0.031900,0.031659,0.030356,0.030356,0.030356,0.030177,0.030027,0.029896,0.029756,0.029651,0.028716,0.028716,0.028716,0.028646,0.028589,0.028548,0.028499,0.028468,0.028430,0.028429,0.028421,0.028429,0.028430,0.028468,0.028499,0.028548,0.028589,0.028646,0.028716,0.028716,0.028716,0.029651,0.029756,0.029896,0.030027,0.030185,0.030356,0.030356,0.030356,0.031659,0.031900,0.032159,0.032159}, // NOLINT + {0.032159,0.032159,0.031900,0.031659,0.030356,0.030356,0.030356,0.030177,0.030027,0.029896,0.029756,0.029651,0.029527,0.028716,0.028716,0.028646,0.028589,0.028548,0.028499,0.028468,0.028430,0.028429,0.028421,0.028429,0.028430,0.028468,0.028499,0.028548,0.028589,0.028646,0.028716,0.028716,0.029527,0.029651,0.029756,0.029896,0.030027,0.030185,0.030356,0.030356,0.030356,0.031659,0.031900,0.032159,0.032159}, // NOLINT + {0.032159,0.032159,0.031900,0.031659,0.031442,0.030356,0.030356,0.030177,0.030027,0.029896,0.029756,0.029651,0.029527,0.028716,0.028716,0.028646,0.028589,0.028548,0.028499,0.028468,0.028430,0.028429,0.028421,0.028429,0.028430,0.028468,0.028499,0.028548,0.028589,0.028646,0.028716,0.028716,0.029527,0.029651,0.029756,0.029896,0.030027,0.030185,0.030356,0.030356,0.031442,0.031659,0.031900,0.032159,0.032159}, // NOLINT + {0.032159,0.032159,0.031900,0.031659,0.031442,0.030356,0.030356,0.030177,0.030027,0.029896,0.029756,0.029651,0.029527,0.029442,0.029348,0.029275,0.029215,0.029174,0.029123,0.029090,0.029051,0.029051,0.029043,0.029051,0.029052,0.029090,0.029123,0.029174,0.029218,0.029275,0.029348,0.029442,0.029527,0.029651,0.029756,0.029896,0.030027,0.030185,0.030356,0.030356,0.031442,0.031659,0.031900,0.032159,0.032159}, // NOLINT + {0.032159,0.032159,0.031900,0.031659,0.031442,0.031248,0.031047,0.030889,0.030709,0.030571,0.030447,0.030315,0.030213,0.030101,0.030003,0.029927,0.029867,0.029825,0.029771,0.029739,0.029698,0.029697,0.029689,0.029698,0.029698,0.029739,0.029771,0.029825,0.029867,0.029930,0.030007,0.030101,0.030213,0.030320,0.030447,0.030571,0.030709,0.030889,0.031047,0.031248,0.031442,0.031659,0.031900,0.032159,0.032159}, // NOLINT + {0.032159,0.032159,0.032643,0.032400,0.032172,0.031969,0.031789,0.031601,0.031436,0.031270,0.031147,0.031009,0.030903,0.030787,0.030713,0.030634,0.030549,0.030505,0.030450,0.030416,0.030375,0.030374,0.030366,0.030374,0.030375,0.030416,0.030452,0.030505,0.030549,0.030634,0.030713,0.030787,0.030903,0.031009,0.031147,0.031270,0.031436,0.031601,0.031789,0.031969,0.032172,0.032400,0.032655,0.032159,0.032159}, // NOLINT + {0.033449,0.033449,0.033449,0.033184,0.032956,0.032744,0.032534,0.032339,0.032175,0.032026,0.031875,0.031733,0.031624,0.031504,0.031433,0.031352,0.031263,0.031219,0.031164,0.031130,0.031085,0.031086,0.031077,0.031086,0.031086,0.031130,0.031164,0.031219,0.031263,0.031352,0.031433,0.031508,0.031624,0.031739,0.031875,0.032026,0.032175,0.032339,0.032534,0.032744,0.032956,0.033184,0.033449,0.033449,0.033449}, // NOLINT + {0.033449,0.033449,0.033449,0.034012,0.033765,0.033522,0.033338,0.033146,0.032969,0.032791,0.032636,0.032497,0.032385,0.032293,0.032190,0.032107,0.032017,0.031975,0.031917,0.031882,0.031838,0.031839,0.031830,0.031839,0.031838,0.031884,0.031919,0.031975,0.032020,0.032111,0.032190,0.032293,0.032385,0.032497,0.032642,0.032798,0.032969,0.033146,0.033338,0.033532,0.033765,0.034012,0.033449,0.033449,0.033449}, // NOLINT + {0.033449,0.034834,0.034834,0.034834,0.034590,0.034374,0.034151,0.033954,0.033782,0.033607,0.033475,0.033334,0.033187,0.033095,0.032996,0.032912,0.032819,0.032775,0.032719,0.032685,0.032668,0.032641,0.032632,0.032641,0.032668,0.032685,0.032719,0.032778,0.032819,0.032912,0.032996,0.033095,0.033192,0.033334,0.033475,0.033607,0.033782,0.033954,0.034151,0.034374,0.034590,0.034834,0.034834,0.034834,0.033449}, // NOLINT + {0.034834,0.034834,0.034834,0.034834,0.035491,0.035271,0.035044,0.034844,0.034670,0.034486,0.034333,0.034185,0.034078,0.033952,0.033852,0.033769,0.033706,0.033633,0.033577,0.033543,0.033528,0.033500,0.033490,0.033500,0.033528,0.033544,0.033579,0.033635,0.033709,0.033769,0.033852,0.033952,0.034078,0.034191,0.034333,0.034493,0.034670,0.034844,0.035044,0.035271,0.035491,0.034834,0.034834,0.034834,0.034834}, // NOLINT + {0.034834,0.034834,0.036428,0.036428,0.036428,0.036207,0.035988,0.035788,0.035578,0.035432,0.035279,0.035133,0.034991,0.034871,0.034768,0.034691,0.034631,0.034557,0.034500,0.034467,0.034454,0.034426,0.034416,0.034426,0.034455,0.034469,0.034502,0.034557,0.034631,0.034691,0.034772,0.034871,0.034991,0.035139,0.035279,0.035439,0.035586,0.035788,0.035988,0.036217,0.036438,0.036438,0.036438,0.034834,0.034834}, // NOLINT + {0.036428,0.036428,0.036428,0.036428,0.036428,0.037247,0.037021,0.036833,0.036625,0.035432,0.035279,0.035133,0.034991,0.034871,0.034768,0.034691,0.034631,0.034557,0.034500,0.034467,0.034454,0.034426,0.034416,0.034426,0.034455,0.034469,0.034502,0.034557,0.034631,0.034691,0.034772,0.034871,0.034991,0.035139,0.035279,0.035439,0.036633,0.036833,0.037030,0.037247,0.036438,0.036438,0.036438,0.036438,0.036438}, // NOLINT + {0.036428,0.036428,0.036428,0.036428,0.037247,0.037247,0.037021,0.036833,0.036625,0.036625,0.035279,0.035133,0.034991,0.034871,0.034768,0.034691,0.034631,0.034557,0.034500,0.034467,0.034454,0.034426,0.034416,0.034426,0.034455,0.034469,0.034502,0.034557,0.034631,0.034691,0.034772,0.034871,0.034991,0.035139,0.035279,0.036633,0.036633,0.036833,0.037030,0.037247,0.037247,0.036438,0.036438,0.036438,0.036438}, // NOLINT +}}}; + +#ifdef __cplusplus +} // namespace innovusion_packet +} // namespace drivers +} // namespace nebula +#endif // __cplusplus +#endif // SDK_COMMON_NPS_ADJUSTMENT_H_ diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_innovusion/decoders/robin_nps_adjustment.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_innovusion/decoders/robin_nps_adjustment.hpp new file mode 100644 index 000000000..c40527781 --- /dev/null +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_innovusion/decoders/robin_nps_adjustment.hpp @@ -0,0 +1,996 @@ +/** + * Copyright (C) 2021 - Innovusion Inc. + * + * All Rights Reserved. + * + * $Id$ + */ + +#ifndef SDK_COMMON_ROBIN_NPS_ADJUSTMENT_H_ +#define SDK_COMMON_ROBIN_NPS_ADJUSTMENT_H_ + +namespace nebula +{ +namespace drivers +{ +namespace innovusion_packet +{ +static const double robinE_kInnoPs2Nps[3][128][54] = {{ + {-18.738998,-17.302019,-15.920963,-14.595973,-13.327192,-12.114538,-10.958294,-9.858318,-8.814581,-7.827036,-6.895518,-6.019965,-5.200223,-4.436130,-3.727526,-3.074255,-2.476137,-1.933033,-1.444724,-1.011093,-0.632007,-0.307324,-0.036934,0.179267,0.341361,0.449405,0.503440,0.503489,0.449554,0.341609,0.179614,-0.036488,-0.306779,-0.631364,-1.010352,-1.443886,-1.932097,-2.475105,-3.073127,-3.726302,-4.434812,-5.198811,-6.018461,-6.893922,-7.825348,-8.812803,-9.856452,-10.956340,-12.112498,-13.325068,-14.593766,-15.918675,-17.299651,-18.736553}, // NOLINT + {-19.012749,-17.575831,-16.194722,-14.869622,-13.600672,-12.387937,-11.231461,-10.131260,-9.087252,-8.099395,-7.167595,-6.291779,-5.471709,-4.707315,-3.998406,-3.344831,-2.746444,-2.203027,-1.714484,-1.280621,-0.901327,-0.576463,-0.305909,-0.089578,0.072609,0.180718,0.234787,0.234836,0.180868,0.072858,-0.089230,-0.305462,-0.575917,-0.900683,-1.279879,-1.713644,-2.202090,-2.745410,-3.343701,-3.997181,-4.705995,-5.470295,-6.290272,-7.165996,-8.097705,-9.085472,-10.129391,-11.229505,-12.385895,-13.598546,-14.867412,-16.192431,-17.573460,-19.010301}, // NOLINT + {-19.286402,-17.849524,-16.468394,-15.143220,-13.874118,-12.661226,-11.504563,-10.404126,-9.359878,-8.371768,-7.439681,-6.563523,-5.743175,-4.978456,-4.269260,-3.615391,-3.016702,-2.473027,-1.984232,-1.550142,-1.170630,-0.845588,-0.574881,-0.358432,-0.196143,-0.087968,-0.033866,-0.033817,-0.087819,-0.195894,-0.358084,-0.574433,-0.845041,-1.169985,-1.549399,-1.983391,-2.472088,-3.015667,-3.614259,-4.268033,-4.977134,-5.741759,-6.562014,-7.438080,-8.370075,-9.358095,-10.402255,-11.502604,-12.659180,-13.871988,-15.141007,-16.466099,-17.847150,-19.283950}, // NOLINT + {-19.559979,-18.123099,-16.741986,-15.416742,-14.147563,-12.934452,-11.777637,-10.676909,-9.632459,-8.644021,-7.711706,-6.835263,-6.014604,-5.249599,-4.540088,-3.885931,-3.286938,-2.743025,-2.253970,-1.819656,-1.439954,-1.114712,-0.843849,-0.627271,-0.464891,-0.356654,-0.302519,-0.302469,-0.356504,-0.464641,-0.626922,-0.843400,-1.114165,-1.439308,-1.818911,-2.253127,-2.742084,-3.285901,-3.884798,-4.538859,-5.248275,-6.013186,-6.833751,-7.710102,-8.642326,-9.630674,-10.675035,-11.775676,-12.932404,-14.145430,-15.414526,-16.739689,-18.120722,-19.557525}, // NOLINT + {-19.833463,-18.396676,-17.015507,-15.690181,-14.420871,-13.207669,-12.050650,-10.949742,-9.905021,-8.916326,-7.983701,-7.106963,-6.286031,-5.520712,-4.810902,-4.156454,-3.557205,-3.013035,-2.523704,-2.089161,-1.709254,-1.383833,-1.112815,-0.896120,-0.733639,-0.625338,-0.571172,-0.571122,-0.625188,-0.733389,-0.895771,-1.112366,-1.383284,-1.708607,-2.088415,-2.522860,-3.012094,-3.556166,-4.155318,-4.809670,-5.519385,-6.284610,-7.105449,-7.982094,-8.914628,-9.903233,-10.947865,-12.048685,-13.205618,-14.418735,-15.687962,-17.013207,-18.394296,-19.831005}, // NOLINT + {-20.106867,-18.670149,-17.288950,-15.963577,-14.694156,-13.480801,-12.323547,-11.222470,-10.177486,-9.188564,-8.255655,-7.378633,-6.557397,-5.791790,-5.081691,-4.426958,-3.827433,-3.282972,-2.793424,-2.358658,-1.978540,-1.652948,-1.381787,-1.164955,-1.002382,-0.894022,-0.839826,-0.839776,-0.893872,-1.002132,-1.164605,-1.381337,-1.652399,-1.977891,-2.357911,-2.792578,-3.282028,-3.826392,-4.425821,-5.080458,-5.790461,-6.555974,-7.377116,-8.254046,-9.186864,-10.175695,-11.220591,-12.321579,-13.478747,-14.692018,-15.961355,-17.286647,-18.667766,-20.104406}, // NOLINT + {-20.380181,-18.943513,-17.562306,-16.236878,-14.967374,-13.753870,-12.596450,-11.495142,-10.449933,-9.460762,-8.527574,-7.650268,-6.828756,-6.062841,-5.352460,-4.697444,-4.097648,-3.552929,-3.063137,-2.628150,-2.247830,-1.922061,-1.650757,-1.433795,-1.271133,-1.162706,-1.108478,-1.108428,-1.162555,-1.270883,-1.433444,-1.650306,-1.921511,-2.247181,-2.627402,-3.062290,-3.551984,-4.096606,-4.696305,-5.351225,-6.061510,-6.827331,-7.648749,-8.525962,-9.459059,-10.448140,-11.493260,-12.594479,-13.751813,-14.965232,-16.234653,-17.560000,-18.941127,-20.377717}, // NOLINT + {-20.653449,-19.216796,-17.835592,-16.510093,-15.240505,-14.026882,-12.869270,-11.767764,-10.722348,-9.732899,-8.799452,-7.921869,-7.100052,-6.333814,-5.623205,-4.967911,-4.367842,-3.822863,-3.332843,-2.897629,-2.517113,-2.191169,-1.919698,-1.702633,-1.539879,-1.431393,-1.377131,-1.377081,-1.431243,-1.539628,-1.702282,-1.919246,-2.190618,-2.516462,-2.896879,-3.331995,-3.821917,-4.366798,-4.966770,-5.621968,-6.332482,-7.098624,-7.920348,-8.797839,-9.731193,-10.720552,-11.765879,-12.867296,-14.024822,-15.238360,-16.507865,-17.833282,-19.214407,-20.650982}, // NOLINT + {-20.926539,-19.489998,-18.108795,-16.783256,-15.513587,-14.299840,-13.142055,-12.040343,-10.994674,-10.005011,-9.071303,-8.193436,-7.371348,-6.604877,-5.893927,-5.238360,-4.638028,-4.092794,-3.602538,-3.167101,-2.786385,-2.460273,-2.188661,-1.971474,-1.808624,-1.700078,-1.645784,-1.645733,-1.699927,-1.808372,-1.971122,-2.188209,-2.459720,-2.785734,-3.166350,-3.601688,-4.091846,-4.636982,-5.237217,-5.892688,-6.603543,-7.369919,-8.191913,-9.069686,-10.003303,-10.992875,-12.038455,-13.140079,-14.297777,-15.511439,-16.781025,-18.106482,-19.487605,-20.924069}, // NOLINT + {-21.199584,-19.763105,-18.381932,-17.056370,-15.786617,-14.572680,-13.414777,-12.312866,-11.266972,-10.277070,-9.343097,-8.464968,-7.642596,-6.875856,-6.164629,-5.508806,-4.908194,-4.362729,-3.872213,-3.436566,-3.055655,-2.729370,-2.457620,-2.240302,-2.077368,-1.968758,-1.914437,-1.914386,-1.968607,-2.077117,-2.239950,-2.457167,-2.728818,-3.055002,-3.435814,-3.871362,-4.361780,-4.907147,-5.507661,-6.163388,-6.874519,-7.641165,-8.463442,-9.341478,-10.275359,-11.265171,-12.310975,-13.412798,-14.570614,-15.784466,-17.054136,-18.379616,-19.760709,-21.197111}, // NOLINT + {-21.472600,-20.036108,-18.654969,-17.329391,-16.059520,-14.845536,-13.687419,-12.585334,-11.539230,-10.549089,-9.614864,-8.736472,-7.913829,-7.146808,-6.435316,-5.779214,-5.178343,-4.632632,-4.141887,-3.706025,-3.324920,-2.998467,-2.726574,-2.509136,-2.346112,-2.237441,-2.183089,-2.183039,-2.237290,-2.345859,-2.508782,-2.726121,-2.997914,-3.324267,-3.705272,-4.141035,-4.631681,-5.177294,-5.778067,-6.434073,-7.145469,-7.912395,-8.734943,-9.613243,-10.547376,-11.537426,-12.583441,-13.685437,-14.843468,-16.057367,-17.327154,-18.652650,-20.033710,-21.470124}, // NOLINT + {-21.745379,-20.309033,-18.927944,-17.602326,-16.332386,-15.118216,-13.960039,-12.857752,-11.811437,-10.821062,-9.886582,-9.007938,-8.184964,-7.417746,-6.705971,-6.049600,-5.448478,-4.902504,-4.411535,-3.975473,-3.594181,-3.267555,-2.995525,-2.777965,-2.614854,-2.506124,-2.451742,-2.451691,-2.505972,-2.614601,-2.777611,-2.995070,-3.267000,-3.593526,-3.974718,-4.410681,-4.901551,-5.447427,-6.048452,-6.704726,-7.416405,-8.183527,-9.006408,-9.884958,-10.819346,-11.809630,-12.855856,-13.958055,-15.116145,-16.330229,-17.600086,-18.925623,-20.306632,-21.742900}, // NOLINT + {-22.018155,-20.581913,-19.200842,-17.875178,-16.605179,-15.390950,-14.232569,-13.130115,-12.083593,-11.093001,-10.158275,-9.279366,-8.456199,-7.688617,-6.976600,-6.319972,-5.718595,-5.172384,-4.681195,-4.244912,-3.863429,-3.536643,-3.264442,-3.046793,-2.883595,-2.774806,-2.720395,-2.720344,-2.774654,-2.883342,-3.046439,-3.263987,-3.536087,-3.862773,-4.244156,-4.680340,-5.171430,-5.717542,-6.318821,-6.975352,-7.687273,-8.454761,-9.277833,-10.156648,-11.091283,-12.081783,-13.128215,-14.230581,-15.388875,-16.603020,-17.872935,-19.198517,-20.579508,-22.015673}, // NOLINT + {-22.290836,-20.854637,-19.473637,-18.148019,-16.877914,-15.663583,-14.505050,-13.402423,-12.355698,-11.364898,-10.429922,-9.550761,-8.727321,-7.959521,-7.247220,-6.590327,-5.988697,-5.442259,-4.950830,-4.514343,-4.132676,-3.805720,-3.533384,-3.315624,-3.152336,-3.043488,-2.989047,-2.988997,-3.043336,-3.152082,-3.315269,-3.532928,-3.805163,-4.132018,-4.513586,-4.949974,-5.441303,-5.987642,-6.589175,-7.245971,-7.958176,-8.725880,-9.549225,-10.428294,-11.363177,-12.353886,-13.400521,-14.503060,-15.661506,-16.875751,-18.145773,-19.471309,-20.852229,-22.288350}, // NOLINT + {-22.563414,-21.127362,-19.746372,-18.420733,-17.150564,-15.936115,-14.777475,-13.674671,-12.627756,-11.636719,-10.701526,-9.822120,-8.998422,-8.230349,-7.517806,-6.860658,-6.258785,-5.712094,-5.220454,-4.783766,-4.401913,-4.074797,-3.802323,-3.584447,-3.421076,-3.312170,-3.257700,-3.257649,-3.312017,-3.420822,-3.584092,-3.801866,-4.074239,-4.401255,-4.783008,-5.219596,-5.711136,-6.257728,-6.859504,-7.516554,-8.229002,-8.996979,-9.820582,-10.699895,-11.634995,-12.625941,-13.672767,-14.775481,-15.934035,-17.148399,-18.418484,-19.744041,-21.124951,-22.560925}, // NOLINT + {-22.835893,-21.399936,-20.019008,-18.693321,-17.423141,-16.208630,-15.049824,-13.946868,-12.899770,-11.908485,-10.973092,-10.093443,-9.269496,-8.501169,-7.788361,-7.130950,-6.528839,-5.981915,-5.490073,-5.053180,-4.671140,-4.343869,-4.071258,-3.853269,-3.689813,-3.580851,-3.526352,-3.526301,-3.580698,-3.689558,-3.852913,-4.070800,-4.343310,-4.670481,-5.052420,-5.489213,-5.980956,-6.527782,-7.129794,-7.787107,-8.499819,-9.268051,-10.091903,-10.971458,-11.906759,-12.897953,-13.944961,-15.047828,-16.206547,-17.420973,-18.691069,-20.016674,-21.397522,-22.833401}, // NOLINT + {-23.108290,-21.672401,-20.291527,-18.965866,-17.695656,-16.481032,-15.322128,-14.219011,-13.171724,-12.180259,-11.244617,-10.364710,-9.540539,-8.771951,-8.058900,-7.401241,-6.798898,-6.251748,-5.759677,-5.322586,-4.940369,-4.612937,-4.340190,-4.122093,-3.958551,-3.849532,-3.795005,-3.794954,-3.849379,-3.958296,-4.121736,-4.339732,-4.612378,-4.939709,-5.321825,-5.758816,-6.250787,-6.797838,-7.400084,-8.057645,-8.770599,-9.539091,-10.363167,-11.242980,-12.178530,-13.169904,-14.217100,-15.320129,-16.478946,-17.693484,-18.963611,-20.289190,-21.669984,-23.105795}, // NOLINT + {-23.380557,-21.944851,-20.563996,-19.238354,-17.968083,-16.753400,-15.594365,-14.491110,-13.443627,-12.451991,-11.516105,-10.635982,-9.811547,-9.042727,-8.329407,-7.671508,-7.068932,-6.521553,-6.029272,-5.591993,-5.209587,-4.881999,-4.609118,-4.390918,-4.227286,-4.118213,-4.063657,-4.063606,-4.118059,-4.227031,-4.390561,-4.608659,-4.881438,-5.208926,-5.591231,-6.028409,-6.520591,-7.067871,-7.670348,-8.328150,-9.041373,-9.810097,-10.634437,-11.514466,-12.450260,-13.441804,-14.489197,-15.592363,-16.751311,-17.965909,-19.236096,-20.561655,-21.942431,-23.378059}, // NOLINT + {-23.652783,-22.217141,-20.836397,-19.510739,-18.240462,-17.025672,-15.866524,-14.763160,-13.715481,-12.723622,-11.787544,-10.907196,-10.082534,-9.313444,-8.599905,-7.941766,-7.338936,-6.791345,-6.298858,-5.861375,-5.478797,-5.151056,-4.878044,-4.659722,-4.496023,-4.386893,-4.332310,-4.332258,-4.386739,-4.495767,-4.659364,-4.877584,-5.150494,-5.478134,-5.860611,-6.297994,-6.790382,-7.337873,-7.940604,-8.598646,-9.312088,-10.081082,-10.905648,-11.785902,-12.721888,-13.713656,-14.761244,-15.864519,-17.023580,-18.238284,-19.508478,-20.834054,-22.214717,-23.650281}, // NOLINT + {-23.924825,-22.489353,-21.108670,-19.783057,-18.512739,-17.297893,-16.138648,-15.035076,-13.987284,-12.995237,-12.058947,-11.178417,-10.353469,-9.584148,-8.870363,-8.211993,-7.608947,-7.061124,-6.568422,-6.130748,-5.748005,-5.420105,-5.146965,-4.928537,-4.764758,-4.655573,-4.600962,-4.600911,-4.655419,-4.764502,-4.928178,-5.146505,-5.419543,-5.747341,-6.129983,-6.567556,-7.060159,-7.607882,-8.210830,-8.869102,-9.582790,-10.352014,-11.176867,-12.057304,-12.993500,-13.985455,-15.033157,-16.136641,-17.295798,-18.510558,-19.780792,-21.106323,-22.486927,-23.922320}, // NOLINT + {-24.196769,-22.761472,-21.380858,-20.055285,-18.784948,-17.570041,-16.410694,-15.307021,-14.259034,-13.266801,-12.330304,-11.449500,-10.624383,-9.854842,-9.140802,-8.482201,-7.878928,-7.330884,-6.837982,-6.400123,-6.017205,-5.689145,-5.415884,-5.197357,-5.033490,-4.924252,-4.869614,-4.869563,-4.924098,-5.033233,-5.196998,-5.415423,-5.688581,-6.016540,-6.399357,-6.837115,-7.329917,-7.877861,-8.481036,-9.139539,-9.853481,-10.622926,-11.447948,-12.328658,-13.265062,-14.257203,-15.305100,-16.408684,-17.567943,-18.782765,-20.053018,-21.378509,-22.759042,-24.194262}, // NOLINT + {-24.468695,-23.033505,-21.653046,-20.327442,-19.057096,-17.842115,-16.682671,-15.578876,-14.530727,-13.538322,-12.601637,-11.720617,-10.895281,-10.125483,-9.411221,-8.752387,-8.148891,-7.600629,-7.107532,-6.669482,-6.286396,-5.958195,-5.684799,-5.466166,-5.302227,-5.192931,-5.138267,-5.138215,-5.192777,-5.301970,-5.465806,-5.684337,-5.957631,-6.285730,-6.668714,-7.106663,-7.599661,-8.147823,-8.751219,-9.409956,-10.124120,-10.893822,-11.719062,-12.599988,-13.536580,-14.528893,-15.576951,-16.680658,-17.840014,-19.054910,-20.325171,-21.650693,-23.031072,-24.466185}, // NOLINT + {-24.740479,-23.305435,-21.925043,-20.599512,-19.329140,-18.114176,-16.954592,-15.850662,-14.802377,-13.809782,-12.872891,-11.991636,-11.166109,-10.396100,-9.681608,-9.022556,-8.418836,-7.870372,-7.377066,-6.938832,-6.555576,-6.227235,-5.953711,-5.734978,-5.570955,-5.461610,-5.406919,-5.406867,-5.461455,-5.570697,-5.734617,-5.953248,-6.226670,-6.554908,-6.938063,-7.376196,-7.869402,-8.417766,-9.021387,-9.680340,-10.394735,-11.164648,-11.990079,-12.871240,-13.808038,-14.800540,-15.848734,-16.952576,-18.112072,-19.326950,-20.597238,-21.922687,-23.302999,-24.737965}, // NOLINT + {-25.012159,-23.577271,-22.196944,-20.871471,-19.601123,-18.386081,-17.226444,-16.122387,-15.073960,-14.081200,-13.144116,-12.262719,-11.436912,-10.666687,-9.951979,-9.292693,-8.688763,-8.140092,-7.646592,-7.208175,-6.824757,-6.496267,-6.222620,-6.003785,-5.839685,-5.730289,-5.675571,-5.675520,-5.730134,-5.839427,-6.003424,-6.222156,-6.495700,-6.824089,-7.207405,-7.645721,-8.139120,-8.687691,-9.291522,-9.950709,-10.665320,-11.435448,-12.261159,-13.142462,-14.079453,-15.072120,-16.120457,-17.224424,-18.383974,-19.598930,-20.869194,-22.194585,-23.574832,-25.009641}, // NOLINT + {-25.283724,-23.848997,-22.468775,-21.143395,-19.873020,-18.657920,-17.498227,-16.394062,-15.345494,-14.352570,-13.415305,-12.533681,-11.707683,-10.937228,-10.222321,-9.562823,-8.958673,-8.409796,-7.916103,-7.477506,-7.093927,-6.765307,-6.491525,-6.272591,-6.108414,-5.998967,-5.944223,-5.944172,-5.998811,-6.108155,-6.272229,-6.491060,-6.764739,-7.093257,-7.476735,-7.915231,-8.408823,-8.957599,-9.561650,-10.221050,-10.935859,-11.706216,-12.532119,-13.413649,-14.350820,-15.343652,-16.392129,-17.496205,-18.655810,-19.870824,-21.141115,-22.466413,-23.846555,-25.281204}, // NOLINT + {-25.555167,-24.120627,-22.740526,-21.415203,-20.144831,-18.929745,-17.769945,-16.665672,-15.616960,-14.623889,-13.686444,-12.804634,-11.978422,-11.207779,-10.492638,-9.832917,-9.228564,-8.679486,-8.185601,-7.746847,-7.363095,-7.034317,-6.760426,-6.541392,-6.377142,-6.267644,-6.212876,-6.212824,-6.267489,-6.376883,-6.541030,-6.759961,-7.033749,-7.362425,-7.746075,-8.184727,-8.678511,-9.227489,-9.831742,-10.491364,-11.206408,-11.976953,-12.803070,-13.684785,-14.622136,-15.615115,-16.663737,-17.767919,-18.927632,-20.142632,-21.412920,-22.738161,-24.118181,-25.552643}, // NOLINT + {-25.826517,-24.392159,-23.012192,-21.686924,-20.416566,-19.201386,-18.041630,-16.937239,-15.888397,-14.895158,-13.957541,-13.075538,-12.249130,-11.478274,-10.762923,-10.102993,-9.498436,-8.949160,-8.455089,-8.016144,-7.632247,-7.303334,-7.029325,-6.810194,-6.645869,-6.536321,-6.481528,-6.481476,-6.536166,-6.645610,-6.809831,-7.028858,-7.302765,-7.631576,-8.015370,-8.454214,-8.948184,-9.497359,-10.101816,-10.761647,-11.476901,-12.247659,-13.073971,-13.955879,-14.893402,-15.886550,-16.935300,-18.039602,-19.199270,-20.414365,-21.684638,-23.009824,-24.389710,-25.823991}, // NOLINT + {-26.097765,-24.663576,-23.283730,-21.958548,-20.688240,-19.473066,-18.313182,-17.208716,-16.159761,-15.166414,-14.228579,-13.346404,-12.519797,-11.748742,-11.033150,-10.373053,-9.768290,-9.218820,-8.724562,-8.285454,-7.901394,-7.572346,-7.298219,-7.078994,-6.914595,-6.804998,-6.750179,-6.750127,-6.804842,-6.914336,-7.078630,-7.297752,-7.571776,-7.900721,-8.284678,-8.723685,-9.217842,-9.767211,-10.371874,-11.031872,-11.747366,-12.518324,-13.344834,-14.226915,-15.164656,-16.157910,-17.206775,-18.311151,-19.470947,-20.686035,-21.956259,-23.281359,-24.661124,-26.095235}, // NOLINT + {-26.368896,-24.934906,-23.555262,-22.230084,-20.959821,-19.744628,-18.584722,-17.480154,-16.431070,-15.437544,-14.499594,-13.617243,-12.790436,-12.019179,-11.303439,-10.643085,-10.038125,-9.488463,-8.994025,-8.554741,-8.170548,-7.841356,-7.567111,-7.347794,-7.183320,-7.073675,-7.018832,-7.018780,-7.073518,-7.183060,-7.347430,-7.566643,-7.840785,-8.169874,-8.553964,-8.993146,-9.487483,-10.037044,-10.641904,-11.302159,-12.017801,-12.788960,-13.615671,-14.497927,-15.435783,-16.429217,-17.478210,-18.582688,-19.742507,-20.957613,-22.227792,-23.552888,-24.932451,-26.366363}, // NOLINT + {-26.639883,-25.206138,-23.826600,-22.501523,-21.231316,-20.016124,-18.856139,-17.751527,-16.702323,-15.708658,-14.770554,-13.888013,-13.061032,-12.289586,-11.573621,-10.913102,-10.307942,-9.758067,-9.263478,-8.824027,-8.439677,-8.110354,-7.835998,-7.616589,-7.452046,-7.342351,-7.287484,-7.287431,-7.342194,-7.451785,-7.616224,-7.835530,-8.109782,-8.439002,-8.823249,-9.262598,-9.757086,-10.306859,-10.911920,-11.572339,-12.288205,-13.059554,-13.886439,-14.768884,-15.706894,-16.700467,-17.749580,-18.854102,-20.013999,-21.229105,-22.499227,-23.824222,-25.203680,-26.637347}, // NOLINT + {-26.910823,-25.477260,-24.097841,-22.772903,-21.502726,-20.287541,-19.127521,-18.022803,-16.973591,-15.979725,-15.041461,-14.158756,-13.331598,-12.559958,-11.843810,-11.183084,-10.577737,-10.027682,-9.532913,-9.093306,-8.708802,-8.379351,-8.104883,-7.885379,-7.720768,-7.611026,-7.556136,-7.556083,-7.610870,-7.720507,-7.885013,-8.104413,-8.378778,-8.708126,-9.092527,-9.532031,-10.026699,-10.576653,-11.181899,-11.842526,-12.558576,-13.330118,-14.157179,-15.039789,-15.977958,-16.971733,-18.020853,-19.125481,-20.285414,-21.500512,-22.770605,-24.095460,-25.474799,-26.908284}, // NOLINT + {-27.181617,-25.748274,-24.369018,-23.044177,-21.774048,-20.558863,-19.398837,-18.294038,-17.244656,-16.250735,-15.312332,-14.429463,-13.602124,-12.830303,-12.113962,-11.453046,-10.847513,-10.297314,-9.802339,-9.362568,-8.977922,-8.648342,-8.373763,-8.154169,-7.989489,-7.879702,-7.824787,-7.824735,-7.879545,-7.989227,-8.153803,-8.373293,-8.647768,-8.977244,-9.361788,-9.801457,-10.296329,-10.846427,-11.451860,-12.112676,-12.828918,-13.600641,-14.427883,-15.310658,-16.248966,-17.242795,-18.292085,-19.396794,-20.556732,-21.771831,-23.041875,-24.366634,-25.745810,-27.179075}, // NOLINT + {-28.448765,-27.127714,-25.855786,-24.633384,-23.460796,-22.338370,-21.266334,-20.244891,-19.274236,-18.354471,-17.485715,-16.668061,-15.901518,-15.186191,-14.522048,-13.909115,-13.347378,-12.836821,-12.377432,-11.969176,-11.612028,-11.305960,-11.050946,-10.846952,-10.693972,-10.591972,-10.540954,-10.540907,-10.591833,-10.693740,-10.846626,-11.050527,-11.305449,-11.611426,-11.968482,-12.376646,-12.835944,-13.346411,-13.908059,-14.520902,-15.184958,-15.900197,-16.666654,-17.484222,-18.352894,-19.272575,-20.243148,-21.264510,-22.336467,-23.458815,-24.631326,-25.853653,-27.125508,-28.446488}, // NOLINT + {-28.720877,-27.400086,-26.128370,-24.906115,-23.733667,-22.611326,-21.539340,-20.517933,-19.547243,-18.627442,-17.758625,-16.940895,-16.174281,-15.458845,-14.794601,-14.181556,-13.619720,-13.109049,-12.649551,-12.241195,-11.883957,-11.577806,-11.322728,-11.118670,-10.965641,-10.863615,-10.812582,-10.812535,-10.863475,-10.965408,-11.118344,-11.322309,-11.577295,-11.883353,-12.240499,-12.648764,-13.108171,-13.618752,-14.180498,-14.793454,-15.457610,-16.172959,-16.939485,-17.757130,-18.625862,-19.545580,-20.516188,-21.537514,-22.609421,-23.731683,-24.904055,-26.126235,-27.397877,-28.718597}, // NOLINT + {-28.992925,-27.672400,-26.400903,-25.178814,-24.006495,-22.884265,-21.812309,-20.790913,-19.820215,-18.900382,-18.031519,-17.213710,-16.446987,-15.731484,-15.067133,-14.453985,-13.892034,-13.381279,-12.921664,-12.513210,-12.155880,-11.849647,-11.594484,-11.390387,-11.237314,-11.135259,-11.084211,-11.084164,-11.135118,-11.237081,-11.390060,-11.594064,-11.849135,-12.155275,-12.512514,-12.920876,-13.380400,-13.891065,-14.452926,-15.065984,-15.730247,-16.445662,-17.212299,-18.030022,-18.898801,-19.818550,-20.789165,-21.810480,-22.882357,-24.004508,-25.176751,-26.398765,-27.670188,-28.990642}, // NOLINT + {-29.264948,-27.944660,-26.673381,-25.451467,-24.279267,-23.157132,-22.085255,-21.063853,-20.093160,-19.173298,-18.304380,-17.486506,-16.719728,-16.004102,-15.339656,-14.726390,-14.164342,-13.653466,-13.193764,-12.785214,-12.427791,-12.121488,-11.866262,-11.662108,-11.508985,-11.406903,-11.355839,-11.355792,-11.406763,-11.508752,-11.661781,-11.865841,-12.120975,-12.427185,-12.784516,-13.192975,-13.652586,-14.163371,-14.725329,-15.338506,-16.002863,-16.718402,-17.485092,-18.302881,-19.171714,-20.091492,-21.062104,-22.083424,-23.155222,-24.277278,-25.449401,-26.671241,-27.942446,-29.262662}, // NOLINT + {-29.536842,-28.216874,-26.945805,-25.724113,-24.552021,-23.429917,-22.358117,-21.336769,-20.366070,-19.446187,-18.577218,-17.759282,-16.992424,-16.276706,-15.612161,-14.998796,-14.436643,-13.925665,-13.465839,-13.057217,-12.699712,-12.393325,-12.138036,-11.933814,-11.780657,-11.678545,-11.627467,-11.627420,-11.678405,-11.780423,-11.933487,-12.137615,-12.392811,-12.699105,-13.056518,-13.465048,-13.924783,-14.435670,-14.997734,-15.611009,-16.275465,-16.991095,-17.757867,-18.575717,-19.444601,-20.364401,-21.335017,-22.356284,-23.428004,-24.550030,-25.722045,-26.943662,-28.214657,-29.534554}, // NOLINT + {-29.808715,-28.489012,-27.218187,-25.996624,-24.824703,-23.702731,-22.630966,-21.609646,-20.638949,-19.719038,-18.850024,-18.032031,-17.265089,-16.549285,-15.884650,-15.271189,-14.708929,-14.197852,-13.737949,-13.329211,-12.971623,-12.665160,-12.409807,-12.205529,-12.052328,-11.950187,-11.899095,-11.899049,-11.950047,-12.052094,-12.205201,-12.409386,-12.664645,-12.971015,-13.328511,-13.737157,-14.196968,-14.707955,-15.270125,-15.883496,-16.548042,-17.263758,-18.030613,-18.848521,-19.717449,-20.637277,-21.607892,-22.629130,-23.700815,-24.822709,-25.994554,-27.216041,-28.486793,-29.806425}, // NOLINT + {-30.080534,-28.761111,-27.490500,-26.269133,-25.097388,-23.975465,-22.903778,-21.882488,-20.911795,-19.991875,-19.122811,-18.304753,-17.537750,-16.821858,-16.157124,-15.543568,-14.981202,-14.470026,-14.010042,-13.601204,-13.243526,-12.936987,-12.681576,-12.477242,-12.323999,-12.221830,-12.170724,-12.170677,-12.221689,-12.323765,-12.476914,-12.681154,-12.936472,-13.242917,-13.600503,-14.009250,-14.469142,-14.980227,-15.542502,-16.155968,-16.820614,-17.536418,-18.303334,-19.121306,-19.990285,-20.910121,-21.880731,-22.901940,-23.973547,-25.095392,-26.267060,-27.488352,-28.758889,-30.078241}, // NOLINT + {-30.352274,-29.033151,-27.762776,-26.541585,-25.369947,-24.248170,-23.176549,-22.155293,-21.184608,-20.264666,-19.395568,-18.577453,-17.810384,-17.094399,-16.429581,-15.815932,-15.253468,-14.742189,-14.282101,-13.873188,-13.515429,-13.208818,-12.953314,-12.748943,-12.595669,-12.493472,-12.442352,-12.442305,-12.493331,-12.595433,-12.748613,-12.952891,-13.208302,-13.514820,-13.872486,-14.281307,-14.741303,-15.252491,-15.814864,-16.428424,-17.093153,-17.809050,-18.576032,-19.394060,-20.263073,-21.182932,-22.153533,-23.174709,-24.246249,-25.367948,-26.539510,-27.760625,-29.030927,-30.349978}, // NOLINT + {-30.624013,-29.305124,-28.034987,-26.813989,-25.642511,-24.520834,-23.449240,-22.428055,-21.457388,-20.537415,-19.668296,-18.850126,-18.082992,-17.366938,-16.702021,-16.088280,-15.525722,-15.014349,-14.554166,-14.145164,-13.787328,-13.480640,-13.225076,-13.020660,-12.867337,-12.765114,-12.713980,-12.713933,-12.764972,-12.867102,-13.020331,-13.224653,-13.480123,-13.786717,-14.144461,-14.553371,-15.013461,-15.524743,-16.087211,-16.700862,-17.365690,-18.081655,-18.848702,-19.666787,-20.535820,-21.455709,-22.426294,-23.447397,-24.518911,-25.640510,-26.811911,-28.032833,-29.302897,-30.621715}, // NOLINT + {-30.895652,-29.577040,-28.307144,-27.086343,-25.914999,-24.793453,-23.721964,-22.700794,-21.730115,-20.810155,-19.940999,-19.122784,-18.355577,-17.639444,-16.974443,-16.360615,-15.797963,-15.286502,-14.826226,-14.417137,-14.059219,-13.752460,-13.496836,-13.292368,-13.139006,-13.036755,-12.985608,-12.985561,-13.036614,-13.138770,-13.292038,-13.496412,-13.751942,-14.058608,-14.416433,-14.825430,-15.285613,-15.796983,-16.359545,-16.973283,-17.638194,-18.354239,-19.121358,-19.939487,-20.808558,-21.728434,-22.699030,-23.720119,-24.791527,-25.912995,-27.084262,-28.304988,-29.574811,-30.893350}, // NOLINT + {-31.167170,-29.848900,-28.579252,-27.358642,-26.187447,-25.066035,-23.994615,-22.973485,-22.002858,-21.082846,-20.213673,-19.395408,-18.628128,-17.911938,-17.246856,-16.632936,-16.070193,-15.558638,-15.098277,-14.689101,-14.331117,-14.024280,-13.768593,-13.564072,-13.410674,-13.308397,-13.257236,-13.257189,-13.308255,-13.410438,-13.563742,-13.768168,-14.023761,-14.330505,-14.688396,-15.097479,-15.557748,-16.069212,-16.631864,-17.245694,-17.910686,-18.626788,-19.393981,-20.212159,-21.081246,-22.001174,-22.971719,-23.992767,-25.064107,-26.185440,-27.356559,-28.577094,-29.846667,-31.164866}, // NOLINT + {-31.438718,-30.120724,-28.851294,-27.630890,-26.459864,-25.338540,-24.267218,-23.246142,-22.275534,-21.355507,-20.486318,-19.668009,-18.900680,-18.184373,-17.519246,-16.905238,-16.342412,-15.830766,-15.370321,-14.961063,-14.602990,-14.296096,-14.040348,-13.835777,-13.682340,-13.580038,-13.528865,-13.528817,-13.579896,-13.682103,-13.835445,-14.039923,-14.295576,-14.602377,-14.960357,-15.369522,-15.829875,-16.341429,-16.904164,-17.518082,-18.183120,-18.899338,-19.666579,-20.484802,-21.353906,-22.273849,-23.244373,-24.265368,-25.336610,-26.457855,-27.628804,-28.849132,-30.118489,-31.436411}, // NOLINT + {-31.710068,-30.392439,-29.123284,-27.903107,-26.732217,-25.611019,-24.539782,-23.518758,-22.548146,-21.628169,-20.758938,-19.940580,-19.173190,-18.456855,-17.791623,-17.177537,-16.614618,-16.102903,-15.642356,-15.233019,-14.874868,-14.567902,-14.312100,-14.107483,-13.954006,-13.851679,-13.800493,-13.800445,-13.851536,-13.953769,-14.107151,-14.311674,-14.567382,-14.874254,-15.232312,-15.641556,-16.102010,-16.613634,-17.176461,-17.790457,-18.455600,-19.171847,-19.939148,-20.757420,-21.626566,-22.546459,-23.516987,-24.537929,-25.609086,-26.730205,-27.901018,-29.121120,-30.390201,-31.707758}, // NOLINT + {-31.981478,-30.664112,-29.395220,-28.175225,-27.004518,-25.883472,-24.812303,-23.791337,-22.820778,-21.900778,-21.031524,-20.213129,-19.445671,-18.729288,-18.063981,-17.449812,-16.886813,-16.374981,-15.914397,-15.504969,-15.146744,-14.839710,-14.583850,-14.379190,-14.225672,-14.123319,-14.072121,-14.072073,-14.123177,-14.225434,-14.378858,-14.583424,-14.839189,-15.146129,-15.504261,-15.913596,-16.374087,-16.885828,-17.448735,-18.062813,-18.728031,-19.444325,-20.211695,-21.030004,-21.899173,-22.819088,-23.789564,-24.810447,-25.881537,-27.002504,-28.173134,-29.393053,-30.661872,-31.979165}, // NOLINT + {-32.252780,-30.935724,-29.667086,-28.447315,-27.276770,-26.155872,-25.084783,-24.063875,-23.093350,-22.173365,-21.304085,-20.485666,-19.718177,-19.001701,-18.336324,-17.722074,-17.158995,-16.647081,-16.186402,-15.776906,-15.418612,-15.111526,-14.855598,-14.650878,-14.497338,-14.394960,-14.343749,-14.343701,-14.394817,-14.497100,-14.650545,-14.855171,-15.111004,-15.417996,-15.776197,-16.185599,-16.646186,-17.158008,-17.720996,-18.335154,-19.000442,-19.716829,-20.484230,-21.302563,-22.171757,-23.091658,-24.062099,-25.082926,-26.153934,-27.274754,-28.445221,-29.664916,-30.933481,-32.250465}, // NOLINT + {-32.524003,-31.207281,-29.938910,-28.719345,-27.548957,-26.428161,-25.357218,-24.336376,-23.365861,-22.445902,-21.576619,-20.758169,-19.990626,-19.274082,-18.608636,-17.994320,-17.431167,-16.919190,-16.458413,-16.048845,-15.690475,-15.383316,-15.127343,-14.922578,-14.769000,-14.666600,-14.615377,-14.615329,-14.666457,-14.768762,-14.922244,-15.126915,-15.382794,-15.689858,-16.048135,-16.457609,-16.918294,-17.430178,-17.993240,-18.607465,-19.272821,-19.989277,-20.756732,-21.575095,-22.444292,-23.364166,-24.334598,-25.355358,-26.426220,-27.546938,-28.717249,-29.936738,-31.205035,-32.521686}, // NOLINT + {-32.795182,-31.478766,-30.210660,-28.991321,-27.821151,-26.700485,-25.629610,-24.608838,-23.638388,-22.718407,-21.849120,-21.030651,-20.263054,-19.546505,-18.880954,-18.266553,-17.703325,-17.191270,-16.730417,-16.320771,-15.962339,-15.655103,-15.399086,-15.194287,-15.040665,-14.938240,-14.887005,-14.886957,-14.938097,-15.040427,-15.193953,-15.398658,-15.654580,-15.961722,-16.320059,-16.729612,-17.190372,-17.702334,-18.265471,-18.879782,-19.545242,-20.261702,-21.029211,-21.847594,-22.716795,-23.636690,-24.607057,-25.627748,-26.698542,-27.819129,-28.989222,-30.208485,-31.476517,-32.792861}, // NOLINT + {-33.066279,-31.750189,-30.482361,-29.263243,-28.093250,-26.972712,-25.901958,-24.881255,-23.910849,-22.990891,-22.121595,-21.303056,-20.535456,-19.818821,-19.153251,-18.538784,-17.975470,-17.463340,-17.002410,-16.592694,-16.234191,-15.926902,-15.670827,-15.465979,-15.312328,-15.209880,-15.158633,-15.158585,-15.209736,-15.312089,-15.465644,-15.670398,-15.926378,-16.233572,-16.591981,-17.001604,-17.462440,-17.974478,-18.537700,-19.152076,-19.817557,-20.534102,-21.301614,-22.120066,-22.989276,-23.909149,-24.879472,-25.900093,-26.970766,-28.091225,-29.261141,-30.480183,-31.747938,-33.063956}, // NOLINT + {-33.337317,-32.021544,-30.753998,-29.535110,-28.365289,-27.244906,-26.174262,-25.153637,-24.183273,-23.263340,-22.394035,-21.575507,-20.807840,-20.091152,-19.425510,-18.810991,-18.247603,-17.735399,-17.274398,-16.864606,-16.506047,-16.198684,-15.942565,-15.737672,-15.583989,-15.481519,-15.430261,-15.430213,-15.481375,-15.583750,-15.737337,-15.942135,-16.198159,-16.505427,-16.863892,-17.273591,-17.734498,-18.246610,-18.809906,-19.424334,-20.089886,-20.806484,-21.574063,-22.392504,-23.261723,-24.181571,-25.151851,-26.172395,-27.242957,-28.363262,-29.533006,-30.751818,-32.019290,-33.334991}, // NOLINT + {-33.608283,-32.292842,-31.025572,-29.806914,-28.637286,-27.517070,-26.446499,-25.425973,-24.455648,-23.535748,-22.666449,-21.847891,-21.080198,-20.363463,-19.697771,-19.083180,-18.519723,-18.007448,-17.546376,-17.136502,-16.777880,-16.470484,-16.214301,-16.009366,-15.855650,-15.753158,-15.701889,-15.701841,-15.753014,-15.855411,-16.009031,-16.213870,-16.469958,-16.777260,-17.135787,-17.545567,-18.006546,-18.518728,-19.082094,-19.696593,-20.362195,-21.078841,-21.846445,-22.664915,-23.534129,-24.453943,-25.424185,-26.444629,-27.515119,-28.635256,-29.804807,-31.023389,-32.290585,-33.605954}, // NOLINT + {-33.879207,-32.564013,-31.297084,-30.078660,-28.909231,-27.789144,-26.718735,-25.698271,-24.727999,-23.808125,-22.938826,-22.120257,-21.352533,-20.635763,-19.970003,-19.355354,-18.791830,-18.279486,-17.818343,-17.408413,-17.049726,-16.742265,-16.486035,-16.281059,-16.127311,-16.024797,-15.973516,-15.973468,-16.024653,-16.127071,-16.280723,-16.485603,-16.741739,-17.049105,-17.407697,-17.817533,-18.278583,-18.790833,-19.354266,-19.968824,-20.634493,-21.351173,-22.118809,-22.937291,-23.806503,-24.726292,-25.696481,-26.716862,-27.787190,-28.907199,-30.076550,-31.294898,-32.561754,-33.876876}, // NOLINT + {-34.149991,-32.835229,-31.568528,-30.350354,-29.181117,-28.061193,-26.990903,-25.970526,-25.000312,-24.080467,-23.211179,-22.392591,-21.624845,-20.908033,-20.242225,-19.627511,-19.063924,-18.551514,-18.090306,-17.680320,-17.321563,-17.014043,-16.757765,-16.552750,-16.398969,-16.296436,-16.245144,-16.245096,-16.296291,-16.398729,-16.552414,-16.757333,-17.013516,-17.320941,-17.679603,-18.089495,-18.550610,-19.062927,-19.626422,-20.241044,-20.906761,-21.623483,-22.391140,-23.209641,-24.078843,-24.998603,-25.968733,-26.989028,-28.059237,-29.179082,-30.348242,-31.566340,-32.832967,-34.147657}, // NOLINT + {-34.420740,-33.106317,-31.839916,-30.621986,-29.452970,-28.333189,-27.263023,-26.242737,-25.272586,-24.352780,-23.483501,-22.664906,-21.897130,-21.180285,-20.514424,-19.899645,-19.336006,-18.823539,-18.362257,-17.952205,-17.593390,-17.285821,-17.029494,-16.824440,-16.670630,-16.568074,-16.516772,-16.516724,-16.567929,-16.670390,-16.824103,-17.029061,-17.285293,-17.592767,-17.951486,-18.361444,-18.822633,-19.335007,-19.898553,-20.513241,-21.179011,-21.895767,-22.663454,-23.481961,-24.351154,-25.270875,-26.240942,-27.261145,-28.331230,-29.450933,-30.619871,-31.837725,-33.104052,-34.418404}, // NOLINT + {-34.691414,-33.377352,-32.111235,-30.893559,-29.724740,-28.605171,-27.535094,-26.514918,-25.544822,-24.625048,-23.755790,-22.937196,-22.169393,-21.452505,-20.786640,-20.171796,-19.608074,-19.095544,-18.634201,-18.224094,-17.865219,-17.557594,-17.301220,-17.096126,-16.942281,-16.839712,-16.788400,-16.788352,-16.839567,-16.942040,-17.095789,-17.300787,-17.557065,-17.864594,-18.223375,-18.633387,-19.094636,-19.607073,-20.170703,-20.785455,-21.451229,-22.168028,-22.935741,-23.754248,-24.623419,-25.543108,-26.513120,-27.533214,-28.603210,-29.722700,-30.891441,-32.109041,-33.375084,-34.689075}, // NOLINT + {-34.962015,-33.648296,-32.382491,-31.165069,-29.996455,-28.877031,-27.807124,-26.787029,-25.817012,-24.897290,-24.028048,-23.209452,-22.441620,-21.724712,-21.058770,-20.443876,-19.880129,-19.367534,-18.906136,-18.495966,-18.137033,-17.829362,-17.572944,-17.367811,-17.213940,-17.111349,-17.060028,-17.059979,-17.111204,-17.213698,-17.367473,-17.572510,-17.828832,-18.136407,-18.495245,-18.905321,-19.366625,-19.879127,-20.442781,-21.057584,-21.723435,-22.440252,-23.207996,-24.026504,-24.895659,-25.815296,-26.785229,-27.805242,-28.875068,-29.994412,-31.162948,-32.380295,-33.646026,-34.959673}, // NOLINT + {-35.232547,-33.919189,-32.653685,-31.436519,-30.268123,-29.148842,-28.079113,-27.059116,-26.089169,-25.169492,-24.300263,-23.481677,-22.713846,-21.996893,-21.330913,-20.715985,-20.152160,-19.639514,-19.178060,-18.767832,-18.408835,-18.101129,-17.844665,-17.639497,-17.485602,-17.382987,-17.331655,-17.331607,-17.382842,-17.485360,-17.639158,-17.844230,-18.100598,-18.408208,-18.767110,-19.177244,-19.638604,-20.151156,-20.714889,-21.329724,-21.995613,-22.712476,-23.480219,-24.298716,-25.167859,-26.087451,-27.057313,-28.077228,-29.146875,-30.266078,-31.434396,-32.651486,-33.916916,-35.230202}, // NOLINT + {-35.502997,-34.190003,-32.924813,-31.707911,-30.539735,-29.420650,-28.351038,-27.331156,-26.361281,-25.441658,-24.572464,-23.753869,-22.986033,-22.269059,-21.603035,-20.988069,-20.424214,-19.911486,-19.449976,-19.039693,-18.680660,-18.372887,-18.116384,-17.911184,-17.757262,-17.654624,-17.603283,-17.603235,-17.654479,-17.757020,-17.910845,-18.115948,-18.372355,-18.680032,-19.038970,-19.449158,-19.910574,-20.423209,-20.986970,-21.601845,-22.267778,-22.984661,-23.752409,-24.570916,-25.440023,-26.359560,-27.329350,-28.349150,-29.418681,-30.537687,-31.705785,-32.922612,-34.187727,-35.500649}, // NOLINT + {-35.773338,-34.460748,-33.195873,-31.979240,-30.811284,-29.692403,-28.622915,-27.603150,-26.633345,-25.713785,-24.844625,-24.026045,-23.258193,-22.541197,-21.875144,-21.260125,-20.696214,-20.183451,-19.721887,-19.311550,-18.952452,-18.644645,-18.388100,-18.182864,-18.028915,-17.926261,-17.874911,-17.874862,-17.926115,-18.028673,-18.182525,-18.387663,-18.644113,-18.951824,-19.310826,-19.721068,-20.182538,-20.695207,-21.259025,-21.873952,-22.539914,-23.256819,-24.024583,-24.843075,-25.712147,-26.631622,-27.601342,-28.621025,-29.690431,-30.809233,-31.977111,-33.193668,-34.458469,-35.770988}, // NOLINT + {-36.043672,-34.731416,-33.466864,-32.250510,-31.082780,-29.964090,-28.894748,-27.875097,-26.905396,-25.985877,-25.116766,-24.298186,-23.530328,-22.813321,-22.147218,-21.532147,-20.968215,-20.455404,-19.993785,-19.583398,-19.224261,-18.916398,-18.659813,-18.454543,-18.300568,-18.197898,-18.146538,-18.146490,-18.197752,-18.300325,-18.454203,-18.659376,-18.915865,-19.223631,-19.582673,-19.992965,-20.454489,-20.967207,-21.531046,-22.146024,-22.812036,-23.528953,-24.296721,-25.115213,-25.984237,-26.903670,-27.873287,-28.892855,-29.962116,-31.080726,-32.248378,-33.464656,-34.729135,-36.041318}, // NOLINT + {-36.313893,-35.001988,-33.737784,-32.521711,-31.354215,-30.235708,-29.166510,-28.146997,-27.177376,-26.257938,-25.388850,-24.570294,-23.802446,-23.085409,-22.419295,-21.804202,-21.240210,-20.727338,-20.265675,-19.855240,-19.496054,-19.188164,-18.931524,-18.726222,-18.572221,-18.469534,-18.418166,-18.418117,-18.469388,-18.571977,-18.725881,-18.931087,-19.187629,-19.495424,-19.854514,-20.264853,-20.726422,-21.239200,-21.803099,-22.418100,-23.084121,-23.801068,-24.568827,-25.387295,-26.256295,-27.175648,-28.145185,-29.164615,-30.233731,-31.352159,-32.519577,-33.735574,-34.999704,-36.311537}, // NOLINT + {-36.584049,-35.272538,-34.008642,-32.792849,-31.625593,-30.507278,-29.438265,-28.418859,-27.449339,-26.529951,-25.660903,-24.842377,-24.074524,-23.357472,-22.691351,-22.076223,-21.512183,-20.999270,-20.537555,-20.127073,-19.767842,-19.459896,-19.203232,-18.997899,-18.843873,-18.741170,-18.689793,-18.689745,-18.741024,-18.843629,-18.997558,-19.202794,-19.459361,-19.767210,-20.126345,-20.536732,-20.998353,-21.511171,-22.075118,-22.690153,-23.356183,-24.073144,-24.840907,-25.659345,-26.528307,-27.447608,-28.417044,-29.436367,-30.505299,-31.623534,-32.790712,-34.006430,-35.270251,-36.581690}, // NOLINT + {-36.854100,-35.542989,-34.279431,-33.063922,-31.896907,-30.778799,-29.709950,-28.690668,-27.721243,-26.801929,-25.932935,-25.114429,-24.346590,-23.629522,-22.963375,-22.348215,-21.784131,-21.271193,-20.809426,-20.398883,-20.039624,-19.731635,-19.474938,-19.269575,-19.115526,-19.012805,-18.961421,-18.961372,-19.012659,-19.115282,-19.269233,-19.474499,-19.731099,-20.038991,-20.398154,-20.808602,-21.270274,-21.783118,-22.347109,-22.962176,-23.628231,-24.345208,-25.112958,-25.931375,-26.800282,-27.719510,-28.688850,-29.708049,-30.776817,-31.894845,-33.061782,-34.277216,-35.540699,-36.851738}, // NOLINT + {-37.738308,-36.551178,-35.406422,-34.304558,-33.246101,-32.231454,-31.260950,-30.335031,-29.453980,-28.618088,-27.827590,-27.082736,-26.383685,-25.730646,-25.123746,-24.563131,-24.048906,-23.581175,-23.160017,-22.785483,-22.457658,-22.176578,-21.942280,-21.754805,-21.614163,-21.520382,-21.473464,-21.473421,-21.520254,-21.613950,-21.754506,-21.941896,-22.176109,-22.457105,-22.784846,-23.159297,-23.580371,-24.048020,-24.562162,-25.122696,-25.729516,-26.382476,-27.081447,-27.826223,-28.616644,-29.452461,-30.333437,-31.259282,-32.229714,-33.244290,-34.302678,-35.404475,-36.549164,-37.736229}, // NOLINT + {-38.006716,-36.820039,-35.675690,-34.574198,-33.516053,-32.501684,-31.531426,-30.605724,-29.724858,-28.889096,-28.098755,-27.353995,-26.655073,-26.002085,-25.395242,-24.834671,-24.320480,-23.852766,-23.431621,-23.057109,-22.729286,-22.448210,-22.213917,-22.026435,-21.885794,-21.792012,-21.745092,-21.745049,-21.791883,-21.885580,-22.026135,-22.213533,-22.447741,-22.728733,-23.056471,-23.430899,-23.851961,-24.319592,-24.833702,-25.394191,-26.000954,-26.653862,-27.352704,-28.097387,-28.887651,-29.723337,-30.604128,-31.529756,-32.499943,-33.514240,-34.572316,-35.673741,-36.818022,-38.004636}, // NOLINT + {-38.275094,-37.088863,-35.944923,-34.843795,-33.785968,-32.771874,-31.801892,-30.876387,-29.995715,-29.160139,-28.369906,-27.625241,-26.926404,-26.273511,-25.666721,-25.106203,-24.592047,-24.124359,-23.703242,-23.328728,-23.000914,-22.719845,-22.485551,-22.298066,-22.157422,-22.063637,-22.016720,-22.016677,-22.063509,-22.157208,-22.297766,-22.485167,-22.719376,-23.000359,-23.328089,-23.702520,-24.123553,-24.591158,-25.105233,-25.665668,-26.272378,-26.925191,-27.623949,-28.368536,-29.158692,-29.994192,-30.874789,-31.800221,-32.770130,-33.784154,-34.841911,-35.942971,-37.086845,-38.273012}, // NOLINT + {-38.543433,-37.357655,-36.214124,-35.113369,-34.055851,-33.042048,-32.072312,-31.147042,-30.266549,-29.431137,-28.641039,-27.896501,-27.197743,-26.544928,-25.938206,-25.377727,-24.863606,-24.395946,-23.974830,-23.600344,-23.272535,-22.991466,-22.757184,-22.569696,-22.429052,-22.335266,-22.288348,-22.288305,-22.335137,-22.428838,-22.569396,-22.756799,-22.990996,-23.271980,-23.599704,-23.974106,-24.395139,-24.862716,-25.376755,-25.937152,-26.543793,-27.196528,-27.895207,-28.639667,-29.429688,-30.265024,-31.145442,-32.070639,-33.040303,-34.054034,-35.111483,-36.212170,-37.355634,-38.541348}, // NOLINT + {-38.811716,-37.626415,-36.483297,-35.382897,-34.325713,-33.312182,-32.342717,-31.417662,-30.537365,-29.702106,-28.912155,-28.167747,-27.469064,-26.816332,-26.209675,-25.649240,-25.135157,-24.667525,-24.246432,-23.871956,-23.544158,-23.263095,-23.028815,-22.841322,-22.700681,-22.606894,-22.559976,-22.559933,-22.606766,-22.700466,-22.841021,-23.028429,-23.262624,-23.543602,-23.871316,-24.245707,-24.666717,-25.134266,-25.648267,-26.208620,-26.815196,-27.467848,-28.166452,-28.910782,-29.700656,-30.535838,-31.416061,-32.341042,-33.310434,-34.323894,-35.381009,-36.481341,-37.624392,-38.809629}, // NOLINT + {-39.080009,-37.895143,-36.752432,-35.652402,-34.595548,-33.582331,-32.613093,-31.688264,-30.808165,-29.973034,-29.183254,-28.438954,-27.740353,-27.087718,-26.481145,-25.920745,-25.406702,-24.939095,-24.518024,-24.143563,-23.815775,-23.534716,-23.300418,-23.112948,-22.972309,-22.878523,-22.831604,-22.831561,-22.878394,-22.972094,-23.112647,-23.300032,-23.534245,-23.815219,-24.142921,-24.517299,-24.938286,-25.405810,-25.919771,-26.480089,-27.086581,-27.739136,-28.437657,-29.181878,-29.971582,-30.806637,-31.686661,-32.611416,-33.580582,-34.593727,-35.650512,-36.750474,-37.893118,-39.077919}, // NOLINT + {-39.348216,-38.163829,-37.021534,-35.921875,-34.865354,-33.852405,-32.883447,-31.958855,-31.078946,-30.244016,-29.454334,-28.710154,-28.011684,-27.359100,-26.752585,-26.192242,-25.678239,-25.210658,-24.789618,-24.415169,-24.087391,-23.806338,-23.572044,-23.384581,-23.243938,-23.150151,-23.103232,-23.103189,-23.150021,-23.243722,-23.384279,-23.571657,-23.805865,-24.086833,-24.414527,-24.788892,-25.209847,-25.677346,-26.191266,-26.751527,-27.357961,-28.010465,-28.708855,-29.452957,-30.242562,-31.077415,-31.957250,-32.881768,-33.850653,-34.863531,-35.919983,-37.019574,-38.161801,-39.346124}, // NOLINT + {-39.616415,-38.432481,-37.290602,-36.191311,-35.135125,-34.122472,-33.153775,-32.229405,-31.349689,-30.514938,-29.725401,-28.981341,-28.282977,-27.630468,-27.024008,-26.463731,-25.949769,-25.482240,-25.061198,-24.686768,-24.359003,-24.077957,-23.843669,-23.656207,-23.515565,-23.421779,-23.374861,-23.374817,-23.421649,-23.515350,-23.655905,-23.843281,-24.077484,-24.358445,-24.686125,-25.060470,-25.481429,-25.948874,-26.462754,-27.022948,-27.629328,-28.281757,-28.980041,-29.724022,-30.513481,-31.348157,-32.227797,-33.152094,-34.120718,-35.133300,-36.189416,-37.288640,-38.430451,-39.614321}, // NOLINT + {-39.884568,-38.701092,-37.559636,-36.460725,-35.404868,-34.392532,-33.424078,-32.499922,-31.620419,-30.785824,-29.996443,-29.252511,-28.554240,-27.901824,-27.295432,-26.735193,-26.221291,-25.753758,-25.332779,-24.958366,-24.630622,-24.349573,-24.115292,-23.927831,-23.787192,-23.693406,-23.646489,-23.646445,-23.693277,-23.786976,-23.927529,-24.114904,-24.349099,-24.630063,-24.957722,-25.332050,-25.752945,-26.220395,-26.734214,-27.294371,-27.900682,-28.553017,-29.251209,-29.995063,-30.784366,-31.618885,-32.498313,-33.422394,-34.390775,-35.403041,-36.458828,-37.557671,-38.699060,-39.882472}, // NOLINT + {-40.152684,-38.969673,-37.828635,-36.730101,-35.674582,-34.662527,-33.694354,-32.770438,-31.891123,-31.056709,-30.267473,-29.523663,-28.825499,-28.173168,-27.566847,-27.006673,-26.492804,-26.025310,-25.604356,-25.229971,-24.902218,-24.621194,-24.386913,-24.199455,-24.058818,-23.965034,-23.918117,-23.918073,-23.964904,-24.058602,-24.199152,-24.386525,-24.620720,-24.901658,-25.229326,-25.603626,-26.024497,-26.491907,-27.005693,-27.565785,-28.172024,-28.824274,-29.522359,-30.266091,-31.055249,-31.889586,-32.768827,-33.692669,-34.660769,-35.672753,-36.728202,-37.826668,-38.967639,-40.150586}, // NOLINT + {-40.420781,-39.238214,-38.097599,-36.999446,-35.944263,-34.932511,-33.964604,-33.040949,-32.161796,-31.327543,-30.538482,-29.794784,-29.096739,-28.444498,-27.838247,-27.278138,-26.764310,-26.296870,-25.875927,-25.501550,-25.173821,-24.892804,-24.658533,-24.471080,-24.330445,-24.236661,-24.189744,-24.189701,-24.236531,-24.330228,-24.470777,-24.658144,-24.892329,-25.173261,-25.500904,-25.875197,-26.296055,-26.763412,-27.277156,-27.837183,-28.443353,-29.095513,-29.793479,-30.537097,-31.326081,-32.160257,-33.039336,-33.962916,-34.930750,-35.942432,-36.997545,-38.095629,-39.236178,-40.418680}, // NOLINT + {-40.688797,-39.506722,-38.366527,-37.268754,-36.213916,-35.202483,-34.234826,-33.311379,-32.432462,-31.598408,-30.809475,-30.065936,-29.367972,-28.715817,-28.109641,-27.549585,-27.035809,-26.568406,-26.147484,-25.773131,-25.445422,-25.164414,-24.930151,-24.742706,-24.602070,-24.508289,-24.461372,-24.461329,-24.508158,-24.601853,-24.742402,-24.929762,-25.163938,-25.444860,-25.772485,-26.146752,-26.567590,-27.034909,-27.548602,-28.108576,-28.714670,-29.366744,-30.064628,-30.808089,-31.596944,-32.430921,-33.309764,-34.233136,-35.200721,-36.212083,-37.266851,-38.364555,-39.504683,-40.686694}, // NOLINT + {-40.956797,-39.775185,-38.635420,-37.538032,-36.483509,-35.472379,-34.505026,-33.581810,-32.703133,-31.869243,-31.080448,-30.337029,-29.639174,-28.987121,-28.381020,-27.821032,-27.307299,-26.839934,-26.419043,-26.044711,-25.717019,-25.436023,-25.201768,-25.014316,-24.873699,-24.779916,-24.733000,-24.732957,-24.779785,-24.873482,-25.014013,-25.201378,-25.435547,-25.716457,-26.044064,-26.418310,-26.839117,-27.306399,-27.820048,-28.379953,-28.985972,-29.637945,-30.335720,-31.079060,-31.867777,-32.701590,-33.580192,-34.503334,-35.470615,-36.481673,-37.536126,-38.633446,-39.773144,-40.954691}, // NOLINT + {-41.224692,-40.043589,-38.904276,-37.807274,-36.753123,-35.742305,-34.775190,-33.852222,-32.973713,-32.140027,-31.351403,-30.608103,-29.910392,-29.258418,-28.652390,-28.092466,-27.578782,-27.111456,-26.690596,-26.316291,-25.988614,-25.707625,-25.473383,-25.285939,-25.145320,-25.051543,-25.004628,-25.004585,-25.051412,-25.145103,-25.285635,-25.472992,-25.707148,-25.988051,-26.315642,-26.689863,-27.110638,-27.577880,-28.091481,-28.651322,-29.257268,-29.909161,-30.606792,-31.350013,-32.138559,-32.972169,-33.850603,-34.773496,-35.740538,-36.751285,-37.805366,-38.902300,-40.041546,-41.222584}, // NOLINT + {-41.492644,-40.312016,-39.173096,-38.076506,-37.022689,-36.012165,-35.045332,-34.122604,-33.244336,-32.410804,-31.622338,-30.879183,-30.181552,-29.529701,-28.923749,-28.363889,-27.850246,-27.382972,-26.962143,-26.587862,-26.260200,-25.979225,-25.744996,-25.557559,-25.416944,-25.323169,-25.276256,-25.276213,-25.323039,-25.416726,-25.557254,-25.744605,-25.978747,-26.259637,-26.587212,-26.961408,-27.382153,-27.849343,-28.362903,-28.922679,-29.528550,-30.180320,-30.877871,-31.620947,-32.409334,-33.242790,-34.120982,-35.043636,-36.010396,-37.020848,-38.074595,-39.171118,-40.309970,-41.490534}, // NOLINT + {-41.760548,-40.580352,-39.441879,-38.345656,-37.292182,-36.282008,-35.315445,-34.392964,-33.514906,-32.681542,-31.893255,-31.150236,-30.452736,-29.800967,-29.195096,-28.635302,-28.121737,-27.654481,-27.233688,-26.859427,-26.531789,-26.250831,-26.016608,-25.829185,-25.688569,-25.594796,-25.547884,-25.547840,-25.594665,-25.688351,-25.828880,-26.016216,-26.250353,-26.531225,-26.858776,-27.232952,-27.653660,-28.120832,-28.634314,-29.194025,-29.799814,-30.451502,-31.148922,-31.891861,-32.680071,-33.513358,-34.391340,-35.313747,-36.280237,-37.290339,-38.343744,-39.439899,-40.578304,-41.758436}, // NOLINT + {-42.028366,-40.848662,-39.710625,-38.614795,-37.561695,-36.551795,-35.585532,-34.663294,-33.785499,-32.952297,-32.164150,-31.421266,-30.723896,-30.072180,-29.466432,-28.906705,-28.393180,-27.925983,-27.505222,-27.130991,-26.803372,-26.522446,-26.288219,-26.100800,-25.960191,-25.866422,-25.819512,-25.819468,-25.866291,-25.959973,-26.100495,-26.287826,-26.521967,-26.802806,-27.130339,-27.504485,-27.925161,-28.392274,-28.905715,-29.465359,-30.071026,-30.722661,-31.419951,-32.162755,-32.950823,-33.783949,-34.661668,-35.583832,-36.550022,-37.559851,-38.612880,-39.708642,-40.846612,-42.026251}, // NOLINT + {-42.296134,-41.116926,-39.979331,-38.883896,-37.831159,-36.821571,-35.855589,-34.933578,-34.055965,-33.223010,-32.435029,-31.692279,-30.995029,-30.343469,-29.737754,-29.178092,-28.664630,-28.197478,-27.776754,-27.402531,-27.074955,-26.794031,-26.559827,-26.372421,-26.231814,-26.138049,-26.091140,-26.091096,-26.137917,-26.231595,-26.372115,-26.559434,-26.793552,-27.074389,-27.401878,-27.776016,-28.196655,-28.663723,-29.177101,-29.736680,-30.342313,-30.993792,-31.690961,-32.433633,-33.221535,-34.054413,-34.931950,-35.853887,-36.819795,-37.829313,-38.881979,-39.977346,-41.114874,-42.294018}, // NOLINT + {-42.563849,-41.385158,-40.248000,-39.152965,-38.100551,-37.091333,-36.125614,-35.203875,-34.326467,-33.493710,-32.705888,-31.963287,-31.266157,-30.614679,-30.009066,-29.449498,-28.936083,-28.468980,-28.048281,-27.674094,-27.346534,-27.065624,-26.831434,-26.644034,-26.503436,-26.409675,-26.362768,-26.362724,-26.409543,-26.503217,-26.643728,-26.831041,-27.065144,-27.345966,-27.673440,-28.047543,-28.468156,-28.935175,-29.448506,-30.007991,-30.613521,-31.264918,-31.961968,-32.704489,-33.492233,-34.324913,-35.202246,-36.123910,-37.089556,-38.098702,-39.151045,-40.246012,-41.383104,-42.561730}, // NOLINT + {-42.831576,-41.653344,-40.516629,-39.421992,-38.369984,-37.361060,-36.395614,-35.474129,-34.596936,-33.764382,-32.976725,-32.234278,-31.537240,-30.885891,-30.280368,-29.720876,-29.207504,-28.740464,-28.319798,-27.945656,-27.618105,-27.337215,-27.103040,-26.915649,-26.775058,-26.681301,-26.634395,-26.634351,-26.681169,-26.774839,-26.915342,-27.102646,-27.336734,-27.617537,-27.945002,-28.319058,-28.739639,-29.206594,-29.719882,-30.279291,-30.884732,-31.535999,-32.232957,-32.975325,-33.762903,-34.595380,-35.472497,-36.393907,-37.359281,-38.368133,-39.420070,-40.514639,-41.651287,-42.829455}, // NOLINT + {-43.099230,-41.921494,-40.785220,-39.690985,-38.639336,-37.630707,-36.665574,-35.744353,-34.867386,-34.035047,-33.247545,-32.505263,-31.808350,-31.157090,-30.551653,-29.992221,-29.478928,-29.011926,-28.591312,-28.217203,-27.889674,-27.608800,-27.374644,-27.187264,-27.046679,-26.952926,-26.906023,-26.905979,-26.952795,-27.046460,-27.186957,-27.374249,-27.608318,-27.889105,-28.216548,-28.590572,-29.011100,-29.478017,-29.991226,-30.550575,-31.155929,-31.807108,-32.503940,-33.246143,-34.033567,-34.865829,-35.742719,-36.663865,-37.628925,-38.637483,-39.689061,-40.783227,-41.919435,-43.097106}, // NOLINT + {-43.366840,-42.189591,-41.053765,-39.959944,-38.908635,-37.900372,-36.935519,-36.014549,-35.137799,-34.305651,-33.518342,-32.776185,-32.079432,-31.428283,-30.822930,-30.263571,-29.750343,-29.283387,-28.862821,-28.488742,-28.161242,-27.880393,-27.646246,-27.458881,-27.318300,-27.224552,-27.177651,-27.177607,-27.224420,-27.318080,-27.458574,-27.645851,-27.879910,-28.160673,-28.488086,-28.862079,-29.282560,-29.749431,-30.262574,-30.821850,-31.427121,-32.078188,-32.774860,-33.516938,-34.304168,-35.136239,-36.012913,-36.933808,-37.898588,-38.906779,-39.958018,-41.051771,-42.187530,-43.364714}, // NOLINT + {-43.634406,-42.457640,-41.322276,-40.228857,-39.177928,-38.169974,-37.205462,-36.284718,-35.408212,-34.576267,-33.789150,-33.047114,-32.350477,-31.699443,-31.094194,-30.534916,-30.021751,-29.554847,-29.134324,-28.760284,-28.432808,-28.151978,-27.917847,-27.730491,-27.589920,-27.496177,-27.449279,-27.449235,-27.496045,-27.589700,-27.730183,-27.917451,-28.151495,-28.432238,-28.759627,-29.133581,-29.554019,-30.020837,-30.533919,-31.093112,-31.698279,-32.349232,-33.045788,-33.787744,-34.574782,-35.406650,-36.283080,-37.203749,-38.168188,-39.176070,-40.226929,-41.320280,-42.455576,-43.632278}, // NOLINT + {-43.901915,-42.725667,-41.590744,-40.497735,-39.447177,-38.439565,-37.475309,-36.554862,-35.678585,-34.846821,-34.059874,-33.318027,-32.621525,-31.970604,-31.365445,-30.806239,-30.293149,-29.826299,-29.405819,-29.031813,-28.704369,-28.423560,-28.189445,-28.002103,-27.861539,-27.767803,-27.720906,-27.720862,-27.767671,-27.861318,-28.001795,-28.189049,-28.423076,-28.703798,-29.031156,-29.405075,-29.825469,-30.292234,-30.805240,-31.364362,-31.969438,-32.620278,-33.316699,-34.058466,-34.845335,-35.677022,-36.553222,-37.473594,-38.437776,-39.445317,-40.495804,-41.588745,-42.723601,-43.899784}, // NOLINT + {-44.169432,-42.993640,-41.859171,-40.766577,-39.716389,-38.709102,-37.745169,-36.824977,-35.948945,-35.117375,-34.330611,-33.588918,-32.892555,-32.241737,-31.636681,-31.077562,-30.564537,-30.097745,-29.677315,-29.303341,-28.975908,-28.695146,-28.461043,-28.273711,-28.133160,-28.039427,-27.992534,-27.992490,-28.039295,-28.132939,-28.273402,-28.460646,-28.694661,-28.975337,-29.302682,-29.676569,-30.096915,-30.563621,-31.076562,-31.635597,-32.240570,-32.891306,-33.587588,-34.329201,-35.115887,-35.947379,-36.823334,-37.743451,-38.707312,-39.714527,-40.764645,-41.857169,-42.991572,-44.167298}, // NOLINT + {-44.436848,-43.261562,-42.127557,-41.035381,-39.985567,-38.978591,-38.014972,-37.095058,-36.219256,-35.387906,-34.601322,-33.859796,-33.163562,-32.512868,-31.907908,-31.348875,-30.835918,-30.369183,-29.948795,-29.574867,-29.247481,-28.966717,-28.732638,-28.545319,-28.404778,-28.311052,-28.264162,-28.264117,-28.310919,-28.404557,-28.545009,-28.732241,-28.966232,-29.246908,-29.574207,-29.948049,-30.368351,-30.835001,-31.347873,-31.906823,-32.511700,-33.162312,-33.858465,-34.599910,-35.386415,-36.217688,-37.093414,-38.013253,-38.976799,-39.983703,-41.033446,-42.125553,-43.259491,-44.434712}, // NOLINT + {-44.704202,-43.529452,-42.395902,-41.304143,-40.254734,-39.248096,-38.284821,-37.365116,-36.489551,-35.658417,-34.872027,-34.130638,-33.434555,-32.783977,-32.179124,-31.620175,-31.107287,-30.640612,-30.220275,-29.846382,-29.519027,-29.238300,-29.004232,-28.816931,-28.676393,-28.582677,-28.535789,-28.535745,-28.582544,-28.676171,-28.816621,-29.003834,-29.237814,-29.518453,-29.845721,-30.219528,-30.639779,-31.106369,-31.619172,-32.178037,-32.782807,-33.433303,-34.129305,-34.870613,-35.656925,-36.487981,-37.363469,-38.283099,-39.246301,-40.252867,-41.302206,-42.393896,-43.527379,-44.702064}, // NOLINT + {-44.971534,-43.797332,-42.664205,-41.572866,-40.523810,-39.517540,-38.554514,-37.635143,-36.759823,-35.928900,-35.142689,-34.401479,-33.705530,-33.055083,-32.450325,-31.891465,-31.378651,-30.912033,-30.491748,-30.117896,-29.790574,-29.509864,-29.275824,-29.088536,-28.948016,-28.854301,-28.807417,-28.807373,-28.854168,-28.947794,-29.088225,-29.275425,-29.509377,-29.790000,-30.117234,-30.491000,-30.911198,-31.377731,-31.890460,-32.449236,-33.053911,-33.704276,-34.400144,-35.141274,-35.927406,-36.758251,-37.633494,-38.552791,-39.515742,-40.521941,-41.570926,-42.662197,-43.795257,-44.969394}, // NOLINT + {-45.238812,-44.065083,-42.932464,-41.841546,-40.792878,-39.786962,-38.824224,-37.905132,-37.030065,-36.199355,-35.413329,-34.672295,-33.976498,-33.326155,-32.721511,-32.162746,-31.650000,-31.183451,-30.763216,-30.389408,-30.062117,-29.781434,-29.547415,-29.360139,-29.219631,-29.125925,-29.079045,-29.079000,-29.125792,-29.219409,-29.359829,-29.547015,-29.780946,-30.061541,-30.388745,-30.762466,-31.182616,-31.649079,-32.161740,-32.720421,-33.324981,-33.975242,-34.670958,-35.411912,-36.197859,-37.028491,-37.903482,-38.822499,-39.785162,-40.791007,-41.839604,-42.930453,-44.063005,-45.236670}, // NOLINT + {-45.506045,-44.332827,-43.200678,-42.110186,-41.061902,-40.056329,-39.093914,-38.175108,-37.300280,-36.469792,-35.683964,-34.943087,-34.247430,-33.597223,-32.992694,-32.433997,-31.921346,-31.454862,-31.034674,-30.660911,-30.333659,-30.053006,-29.819003,-29.631746,-29.491248,-29.397549,-29.350672,-29.350628,-29.397416,-29.491026,-29.631434,-29.818603,-30.052518,-30.333083,-30.660247,-31.033924,-31.454025,-31.920423,-32.432990,-32.991602,-33.596048,-34.246173,-34.941749,-35.682545,-36.468293,-37.298704,-38.173455,-39.092186,-40.054528,-41.060028,-42.108241,-43.198665,-44.330747,-45.503900}, // NOLINT + {-45.773225,-44.600527,-43.468847,-42.378785,-41.330892,-40.325666,-39.363573,-38.445045,-37.570462,-36.740202,-35.954567,-35.213868,-34.518344,-33.868283,-33.263847,-32.705257,-32.192675,-31.726261,-31.306133,-30.932391,-30.605191,-30.324566,-30.090590,-29.903349,-29.762862,-29.669173,-29.622300,-29.622255,-29.669039,-29.762639,-29.903037,-30.090190,-30.324077,-30.604614,-30.931727,-31.305382,-31.725423,-32.191752,-32.704248,-33.262754,-33.867107,-34.517085,-35.212527,-35.953146,-36.738702,-37.568884,-38.443390,-39.361843,-40.323862,-41.329016,-42.376839,-43.466832,-44.598445,-45.771078}, // NOLINT + {-46.040356,-44.868175,-43.736970,-42.647344,-41.599835,-40.594956,-39.633220,-38.714951,-37.840603,-37.010587,-36.225160,-35.484615,-34.789260,-34.139314,-33.534999,-32.976500,-32.464001,-31.997651,-31.577573,-31.203909,-30.876723,-30.596126,-30.362175,-30.174953,-30.034478,-29.940796,-29.893927,-29.893883,-29.940662,-30.034255,-30.174640,-30.361774,-30.595637,-30.876145,-31.203244,-31.576820,-31.996812,-32.463076,-32.975490,-33.533905,-34.138135,-34.788000,-35.483272,-36.223737,-37.009084,-37.839023,-38.713294,-39.631488,-40.593150,-41.597957,-42.645395,-43.734953,-44.866091,-46.038206}, // NOLINT + {-46.542857,-45.503745,-44.500393,-43.533384,-42.603269,-41.710526,-40.855660,-40.039079,-39.261200,-38.522386,-37.822979,-37.163291,-36.543604,-35.964174,-35.425236,-34.927020,-34.469693,-34.053430,-33.678386,-33.344691,-33.052463,-32.801795,-32.592771,-32.425475,-32.299938,-32.216214,-32.174326,-32.174288,-32.216099,-32.299747,-32.425208,-32.592428,-32.801376,-33.051968,-33.344122,-33.677741,-34.052712,-34.468900,-34.926154,-35.424298,-35.963164,-36.542523,-37.162139,-37.821759,-38.521097,-39.259844,-40.037656,-40.854171,-41.708974,-42.601654,-43.531707,-44.498657,-45.501949,-46.541004}, // NOLINT + {-46.805501,-45.766974,-44.764169,-43.797668,-42.868005,-41.975740,-41.121237,-40.305022,-39.527476,-38.788957,-38.089835,-37.430394,-36.810933,-36.231709,-35.692955,-35.194888,-34.737709,-34.321572,-33.946648,-33.613037,-33.320888,-33.070287,-32.861321,-32.694062,-32.568559,-32.484856,-32.442978,-32.442940,-32.484741,-32.568367,-32.693794,-32.860978,-33.069867,-33.320393,-33.612466,-33.946003,-34.320852,-34.736915,-35.194021,-35.692016,-36.230698,-36.809851,-37.429241,-38.088613,-38.787666,-39.526118,-40.303598,-41.119747,-41.974186,-42.866388,-43.795990,-44.762431,-45.765177,-46.803646}, // NOLINT + {-47.068120,-46.030185,-45.027928,-44.061932,-43.132747,-42.240902,-41.386806,-40.570956,-39.793741,-39.055537,-38.356681,-37.697497,-37.078258,-36.499234,-35.960665,-35.462734,-35.005719,-34.589710,-34.214883,-33.881379,-33.589309,-33.338765,-33.129870,-32.962649,-32.837180,-32.753500,-32.711631,-32.711592,-32.753385,-32.836988,-32.962381,-33.129526,-33.338345,-33.588813,-33.880807,-34.214237,-34.588989,-35.004925,-35.461866,-35.959724,-36.498222,-37.077174,-37.696343,-38.355458,-39.054245,-39.792382,-40.569530,-41.385314,-42.239347,-43.131129,-44.060252,-45.026188,-46.028386,-47.066264}, // NOLINT + {-47.330722,-46.293379,-45.291670,-44.326183,-43.397455,-42.506041,-41.652357,-40.836884,-40.059983,-39.322087,-38.623518,-37.964580,-37.345575,-36.766753,-36.228369,-35.730644,-35.273727,-34.857838,-34.483130,-34.149718,-33.857728,-33.607267,-33.398418,-33.231238,-33.105800,-33.022139,-32.980283,-32.980245,-33.022024,-33.105609,-33.230970,-33.398073,-33.606846,-33.857231,-34.149146,-34.482484,-34.857116,-35.272932,-35.729775,-36.227428,-36.765739,-37.344490,-37.963425,-38.622293,-39.320793,-40.058622,-40.835457,-41.650864,-42.504484,-43.395835,-44.324501,-45.289927,-46.291578,-47.328864}, // NOLINT + {-47.593294,-46.556554,-45.555394,-44.590397,-43.662167,-42.771193,-41.917898,-41.102786,-40.326250,-39.588653,-38.890346,-38.231660,-37.612878,-37.034265,-36.496061,-35.998490,-35.541730,-35.125976,-34.751369,-34.418055,-34.126149,-33.875752,-33.666964,-33.499828,-33.374421,-33.290781,-33.248935,-33.248897,-33.290666,-33.374229,-33.499560,-33.666619,-33.875331,-34.125652,-34.417482,-34.750721,-35.125254,-35.540934,-35.997620,-36.495118,-37.033250,-37.611792,-38.230503,-38.889119,-39.587358,-40.324888,-41.101357,-41.916403,-42.769634,-43.660545,-44.588713,-45.553650,-46.554751,-47.591434}, // NOLINT + {-47.855876,-46.819710,-45.819100,-44.854637,-43.926874,-43.036298,-42.183425,-41.368670,-40.592481,-39.855179,-39.157164,-38.498730,-37.880190,-37.301770,-36.763751,-36.266351,-35.809730,-35.394111,-35.019608,-34.686390,-34.394567,-34.144242,-33.935509,-33.768412,-33.643040,-33.559422,-33.517587,-33.517549,-33.559307,-33.642848,-33.768143,-33.935163,-34.143821,-34.394069,-34.685817,-35.018960,-35.393388,-35.808932,-36.265480,-36.762807,-37.300754,-37.879102,-38.497572,-39.155936,-39.853882,-40.591117,-41.367239,-42.181929,-43.034738,-43.925251,-44.852951,-45.817355,-46.817905,-47.854014}, // NOLINT + {-48.118421,-47.082849,-46.082790,-45.118835,-44.191538,-43.301382,-42.448935,-41.634560,-40.858709,-40.121707,-39.423969,-38.765786,-38.147469,-37.569298,-37.031434,-36.534200,-36.077724,-35.662199,-35.287843,-34.954724,-34.662982,-34.412726,-34.204030,-34.036996,-33.911660,-33.828064,-33.786240,-33.786201,-33.827948,-33.911468,-34.036727,-34.203684,-34.412304,-34.662483,-34.954149,-35.287194,-35.661474,-36.076926,-36.533328,-37.030489,-37.568281,-38.146381,-38.764626,-39.422740,-40.120409,-40.857343,-41.633128,-42.447437,-43.299819,-44.189912,-45.117148,-46.081043,-47.081043,-48.116557}, // NOLINT + {-48.380950,-47.345972,-46.346463,-45.383025,-44.456208,-43.566506,-42.714432,-41.900425,-41.124893,-40.388228,-39.690768,-39.032837,-38.414753,-37.836756,-37.299112,-36.802043,-36.345714,-35.930326,-35.556078,-35.223057,-34.931397,-34.681203,-34.472572,-34.305587,-34.180280,-34.096705,-34.054892,-34.054853,-34.096590,-34.180087,-34.305317,-34.472225,-34.680780,-34.930898,-35.222482,-35.555428,-35.929601,-36.344915,-36.801170,-37.298166,-37.835738,-38.413663,-39.031676,-39.689538,-40.386928,-41.123525,-41.898991,-42.712933,-43.564942,-44.454581,-45.381336,-46.344714,-47.344164,-48.379085}, // NOLINT + {-48.643457,-47.609078,-46.610119,-45.647190,-44.720835,-43.831587,-42.979918,-42.166269,-41.391093,-40.654726,-39.957554,-39.299889,-38.682028,-38.104246,-37.566784,-37.069881,-36.613710,-36.198460,-35.824306,-35.491383,-35.199812,-34.949693,-34.741113,-34.574173,-34.448899,-34.365347,-34.323544,-34.323505,-34.365231,-34.448706,-34.573903,-34.740766,-34.949269,-35.199312,-35.490807,-35.823655,-36.197734,-36.612910,-37.069007,-37.565836,-38.103226,-38.680937,-39.298727,-39.956322,-40.653425,-41.389724,-42.164834,-42.978417,-43.830021,-44.719206,-45.645500,-46.608368,-47.607268,-48.641589}, // NOLINT + {-48.905951,-47.872160,-46.873756,-45.911339,-44.985464,-44.096666,-43.245389,-42.432132,-41.657277,-40.921226,-40.224332,-39.566927,-38.949304,-38.371726,-37.834447,-37.337713,-36.881681,-36.466573,-36.092538,-35.759704,-35.468220,-35.218173,-35.009653,-34.842757,-34.717517,-34.633988,-34.592196,-34.592158,-34.633872,-34.717324,-34.842487,-35.009306,-35.217749,-35.467720,-35.759128,-36.091886,-36.465846,-36.880879,-37.336838,-37.833498,-38.370705,-38.948211,-39.565763,-40.223099,-40.919923,-41.655906,-42.430695,-43.243886,-44.095099,-44.983833,-45.909646,-46.872004,-47.870348,-48.904082}, // NOLINT + {-49.168412,-48.135221,-47.137374,-46.175471,-45.250085,-44.361701,-43.510843,-42.697957,-41.923446,-41.187708,-40.491100,-39.833936,-39.216554,-38.639192,-38.102106,-37.605536,-37.149658,-36.734681,-36.360757,-36.028035,-35.736629,-35.486658,-35.278192,-35.111341,-34.986136,-34.902629,-34.860849,-34.860810,-34.902513,-34.985942,-35.111070,-35.277844,-35.486233,-35.736128,-36.027458,-36.360105,-36.733953,-37.148856,-37.604660,-38.101157,-38.638170,-39.215460,-39.832771,-40.489865,-41.186404,-41.922074,-42.696518,-43.509339,-44.360132,-45.248453,-46.173777,-47.135619,-48.133408,-49.166541}, // NOLINT + {-49.430861,-48.398262,-47.400972,-46.439585,-45.514665,-44.626735,-43.776284,-42.963767,-42.189602,-41.454181,-40.757858,-40.100974,-39.483805,-38.906661,-38.369758,-37.873355,-37.417640,-37.002786,-36.628980,-36.296353,-36.005036,-35.755133,-35.546730,-35.379925,-35.254754,-35.171270,-35.129501,-35.129462,-35.171153,-35.254560,-35.379654,-35.546382,-35.754708,-36.004534,-36.295775,-36.628326,-37.002057,-37.416836,-37.872478,-38.368807,-38.905638,-39.482709,-40.099808,-40.756621,-41.452875,-42.188228,-42.962327,-43.774777,-44.625164,-45.513031,-46.437888,-47.399215,-48.396447,-49.428988}, // NOLINT + {-49.693285,-48.661283,-47.664552,-46.703684,-45.779241,-44.891768,-44.041710,-43.229567,-42.455755,-41.720640,-41.024613,-40.367973,-39.751048,-39.174106,-38.637405,-38.141125,-37.685598,-37.270887,-36.897201,-36.564674,-36.273440,-36.023610,-35.815267,-35.648511,-35.523372,-35.439911,-35.398153,-35.398114,-35.439794,-35.523178,-35.648239,-35.814919,-36.023185,-36.272938,-36.564095,-36.896547,-37.270157,-37.684794,-38.140246,-38.636453,-39.173081,-39.749951,-40.366806,-41.023375,-41.719333,-42.454380,-43.228125,-44.040202,-44.890195,-45.777605,-46.701986,-47.662793,-48.659466,-49.691410}, // NOLINT + {-49.955695,-48.924292,-47.928117,-46.967761,-46.043797,-45.156760,-44.307123,-43.495355,-42.721872,-41.987087,-41.291345,-40.634970,-40.018289,-39.441556,-38.905043,-38.408981,-37.953561,-37.538984,-37.165412,-36.832985,-36.541843,-36.292089,-36.083803,-35.917097,-35.791990,-35.708551,-35.666805,-35.666766,-35.708435,-35.791796,-35.916825,-36.083454,-36.291663,-36.541340,-36.832405,-37.164757,-37.538254,-37.952755,-38.408101,-38.904090,-39.440530,-40.017191,-40.633801,-41.290106,-41.985778,-42.720495,-43.493911,-44.305613,-45.155186,-46.042160,-46.966061,-47.926356,-48.922473,-49.953818}, // NOLINT + {-50.218078,-49.187278,-48.191658,-47.231820,-46.308337,-45.421751,-44.572513,-43.761126,-42.988003,-42.253523,-41.558064,-40.901962,-40.285507,-39.708995,-39.172679,-38.676786,-38.221520,-37.807078,-37.433624,-37.101304,-36.810246,-36.560568,-36.352339,-36.185669,-36.060607,-35.977192,-35.935457,-35.935418,-35.977075,-36.060412,-36.185396,-36.351989,-36.560141,-36.809743,-37.100724,-37.432968,-37.806346,-38.220713,-38.675905,-39.171725,-39.707968,-40.284408,-40.900791,-41.556823,-42.252213,-42.986624,-43.759681,-44.571002,-45.420175,-46.306697,-47.230118,-48.189896,-49.185457,-50.216200}, // NOLINT + {-50.480440,-49.450239,-48.455179,-47.495861,-46.572814,-45.686683,-44.837894,-44.026890,-43.254116,-42.519949,-41.824779,-41.168934,-40.552724,-39.976427,-39.440302,-38.944585,-38.489472,-38.075167,-37.701831,-37.369616,-37.078646,-36.829040,-36.620873,-36.454252,-36.329225,-36.245833,-36.204109,-36.204070,-36.245716,-36.329030,-36.453979,-36.620523,-36.828613,-37.078142,-37.369035,-37.701174,-38.074435,-38.488665,-38.943703,-39.439346,-39.975399,-40.551623,-41.167762,-41.823536,-42.518637,-43.252736,-44.025443,-44.836381,-45.685105,-46.571172,-47.494158,-48.453415,-49.448416,-50.478560}, // NOLINT + {-50.742821,-49.713181,-48.718680,-47.759881,-46.837366,-45.951676,-45.103260,-44.292630,-43.520201,-42.786360,-42.091483,-41.435905,-40.819921,-40.243853,-39.707926,-39.212379,-38.757421,-38.343252,-37.970040,-37.637924,-37.347043,-37.097501,-36.889406,-36.722832,-36.597841,-36.514473,-36.472761,-36.472722,-36.514356,-36.597646,-36.722559,-36.889056,-37.097073,-37.346538,-37.637342,-37.969382,-38.342519,-38.756613,-39.211496,-39.706969,-40.242823,-40.818819,-41.434732,-42.090239,-42.785047,-43.518819,-44.291181,-45.101745,-45.950097,-46.835723,-47.758175,-48.716914,-49.711356,-50.740939}, // NOLINT + {-51.005114,-49.976122,-48.982161,-48.023884,-47.101851,-46.216604,-45.368607,-44.558367,-43.786276,-43.052795,-42.358176,-41.702870,-41.087129,-40.511271,-39.975535,-39.480166,-39.025364,-38.611349,-38.238239,-37.906230,-37.615437,-37.365984,-37.157938,-36.991420,-36.866459,-36.783113,-36.741413,-36.741374,-36.782996,-36.866264,-36.991147,-37.157588,-37.365555,-37.614931,-37.905647,-38.237581,-38.610615,-39.024555,-39.479282,-39.974577,-40.510239,-41.086026,-41.701695,-42.356930,-43.051480,-43.784893,-44.556917,-45.367090,-46.215022,-47.100206,-48.022177,-48.980393,-49.974295,-51.003230}, // NOLINT + {-51.267401,-50.239007,-49.245621,-48.287885,-47.366331,-46.481511,-45.633935,-44.824074,-44.052342,-43.319180,-42.624854,-41.969818,-41.354324,-40.778678,-40.243152,-39.747948,-39.293302,-38.879428,-38.506438,-38.174532,-37.883835,-37.634450,-37.426470,-37.259999,-37.135075,-37.051754,-37.010065,-37.010026,-37.051636,-37.134880,-37.259725,-37.426118,-37.634021,-37.883329,-38.173949,-38.505779,-38.878693,-39.292492,-39.747063,-40.242193,-40.777646,-41.353220,-41.968642,-42.623608,-43.317863,-44.050957,-44.822622,-45.632417,-46.479928,-47.364684,-48.286176,-49.243852,-50.237178,-51.265515}, // NOLINT + {-51.529639,-50.501899,-49.509061,-48.551825,-47.630767,-46.746410,-45.899256,-45.089772,-44.318402,-43.585527,-42.891523,-42.236744,-41.621502,-41.046079,-40.510739,-40.015724,-39.561237,-39.147488,-38.774629,-38.442835,-38.152221,-37.902918,-37.695000,-37.528578,-37.403690,-37.320394,-37.278718,-37.278678,-37.320276,-37.403494,-37.528304,-37.694648,-37.902489,-38.151714,-38.442251,-38.773969,-39.146751,-39.560426,-40.014837,-40.509778,-41.045045,-41.620396,-42.235566,-42.890275,-43.584209,-44.317015,-45.088319,-45.897736,-46.744825,-47.629118,-48.550114,-49.507289,-50.500068,-51.527750}, // NOLINT + {-51.791915,-50.764730,-49.772479,-48.815793,-47.895192,-47.011310,-46.164557,-45.355454,-44.584430,-43.851891,-43.158180,-42.503674,-41.888693,-41.313472,-40.778330,-40.283493,-39.829172,-39.415557,-39.042824,-38.711140,-38.420616,-38.171383,-37.963529,-37.797157,-37.672310,-37.589034,-37.547370,-37.547330,-37.588916,-37.672114,-37.796882,-37.963177,-38.170953,-38.420108,-38.710556,-39.042163,-39.414819,-39.828359,-40.282606,-40.777368,-41.312437,-41.887585,-42.502495,-43.156930,-43.850571,-44.583042,-45.353999,-46.163035,-47.009723,-47.893542,-48.814080,-49.770706,-50.762898,-51.790025}, // NOLINT + {-52.054189,-51.027564,-50.035876,-49.079697,-48.159628,-47.276156,-46.429839,-45.621125,-44.850465,-44.118227,-43.424827,-42.770590,-42.155845,-41.580855,-41.045915,-40.551256,-40.097088,-39.683619,-39.311013,-38.979424,-38.689002,-38.439848,-38.232058,-38.065738,-37.940922,-37.857674,-37.816022,-37.815983,-37.857556,-37.940726,-38.065463,-38.231705,-38.439417,-38.688494,-38.978839,-39.310352,-39.682881,-40.096275,-40.550368,-41.044952,-41.579819,-42.154736,-42.769409,-43.423576,-44.116906,-44.849075,-45.619668,-46.428315,-47.274567,-48.157975,-49.077983,-50.034100,-51.025730,-52.052297}, // NOLINT + {-52.316343,-51.290373,-50.299246,-49.343599,-48.424002,-47.541002,-46.695106,-45.886776,-45.116469,-44.384538,-43.691461,-43.037496,-42.422983,-41.848230,-41.313492,-40.819025,-40.365008,-39.951678,-39.579197,-39.247721,-38.957384,-38.708319,-38.500585,-38.334313,-38.209536,-38.126313,-38.084674,-38.084634,-38.126195,-38.209339,-38.334038,-38.500232,-38.707888,-38.956875,-39.247135,-39.578534,-39.950939,-40.364194,-40.818135,-41.312528,-41.847192,-42.421873,-43.036314,-43.690208,-44.383215,-45.115077,-45.885317,-46.693580,-47.539412,-48.422348,-49.341882,-50.297469,-51.288537,-52.314449}, // NOLINT + {-52.578534,-51.553157,-50.562600,-49.607481,-48.688351,-47.805833,-46.960353,-46.152416,-45.382458,-44.650888,-43.958083,-43.304387,-42.690143,-42.115598,-41.581063,-41.086775,-40.632920,-40.219733,-39.847378,-39.516007,-39.225768,-38.976774,-38.769112,-38.602893,-38.478152,-38.394953,-38.353326,-38.353287,-38.394835,-38.477955,-38.602618,-38.768758,-38.976342,-39.225259,-39.515421,-39.846714,-40.218993,-40.632104,-41.085884,-41.580098,-42.114559,-42.689032,-43.303203,-43.956829,-44.649564,-45.381065,-46.150955,-46.958826,-47.804241,-48.686696,-49.605763,-50.560821,-51.551318,-52.576638}, // NOLINT + {-52.840684,-51.815927,-50.825931,-49.871342,-48.952756,-48.070638,-47.225584,-46.418039,-45.648437,-44.917197,-44.224694,-43.571276,-42.957266,-42.382966,-41.848625,-41.354517,-40.900828,-40.487785,-40.115556,-39.784298,-39.494155,-39.245234,-39.037637,-38.871467,-38.746767,-38.663593,-38.621978,-38.621938,-38.663474,-38.746570,-38.871191,-39.037283,-39.244802,-39.493645,-39.783710,-40.114891,-40.487044,-40.900012,-41.353625,-41.847659,-42.381926,-42.956153,-43.570091,-44.223438,-44.915871,-45.647043,-46.416576,-47.224055,-48.069044,-48.951098,-49.869622,-50.824150,-51.814087,-52.838786}, // NOLINT + {-53.102829,-52.078661,-51.089239,-50.135174,-49.217074,-48.335456,-47.490798,-46.683641,-45.914408,-45.183491,-44.491287,-43.838150,-43.224397,-42.650312,-42.116181,-41.622249,-41.168731,-40.755831,-40.383731,-40.052585,-39.762530,-39.513693,-39.306161,-39.140040,-39.015379,-38.932232,-38.890630,-38.890590,-38.932114,-39.015181,-39.139763,-39.305807,-39.513260,-39.762019,-40.051997,-40.383065,-40.755090,-41.167913,-41.621356,-42.115213,-42.649270,-43.223283,-43.836964,-44.490030,-45.182164,-45.913011,-46.682177,-47.489268,-48.333860,-49.215415,-50.133452,-51.087456,-52.076819,-53.100929}, // NOLINT + {-53.364918,-52.341370,-51.352523,-50.398996,-49.481375,-48.600209,-47.756005,-46.949232,-46.180417,-45.449772,-44.757885,-44.105018,-43.491505,-42.917668,-42.383729,-41.889979,-41.436627,-41.023872,-40.651901,-40.320866,-40.030906,-39.782151,-39.574685,-39.408613,-39.283992,-39.200870,-39.159282,-39.159242,-39.200752,-39.283794,-39.408336,-39.574330,-39.781717,-40.030395,-40.320277,-40.651235,-41.023129,-41.435808,-41.889085,-42.382760,-42.916625,-43.490389,-44.103830,-44.756626,-45.448443,-46.179019,-46.947766,-47.754473,-48.598612,-49.479714,-50.397272,-51.350738,-52.339526,-53.363016}, // NOLINT + {-53.627008,-52.604065,-51.615784,-50.662788,-49.745664,-48.864972,-48.021174,-47.214804,-46.446269,-45.716044,-45.024450,-44.371864,-43.758620,-43.184983,-42.651271,-42.157705,-41.704526,-41.291922,-40.920065,-40.589149,-40.299285,-40.050609,-39.843207,-39.677193,-39.552608,-39.469510,-39.427934,-39.427894,-39.469392,-39.552410,-39.676916,-39.842851,-40.050175,-40.298773,-40.588559,-40.919398,-41.291178,-41.703706,-42.156810,-42.650300,-43.183939,-43.757503,-44.370675,-45.023190,-45.714713,-46.444870,-47.213337,-48.019640,-48.863373,-49.744001,-50.661063,-51.613997,-52.602219,-53.625105}, // NOLINT + {-53.889061,-52.866727,-51.879022,-50.926567,-50.009941,-49.129661,-48.286335,-47.480360,-46.712207,-45.982298,-45.291006,-44.638704,-44.025704,-43.452313,-42.918803,-42.425415,-41.972405,-41.559941,-41.188232,-40.857422,-40.567658,-40.319060,-40.111728,-39.945768,-39.821221,-39.738150,-39.696586,-39.696546,-39.738031,-39.821023,-39.945491,-40.111372,-40.318625,-40.567146,-40.856831,-41.187564,-41.559197,-41.971584,-42.424519,-42.917832,-43.451268,-44.024586,-44.637514,-45.289744,-45.980966,-46.710806,-47.478890,-48.284800,-49.128060,-50.008276,-50.924839,-51.877233,-52.864879,-53.887155}, // NOLINT + {-54.151078,-53.129369,-52.142237,-51.190314,-50.274184,-49.394400,-48.551481,-47.745892,-46.978114,-46.248485,-45.557558,-44.905532,-44.292790,-43.719628,-43.186327,-42.693142,-42.240286,-41.827981,-41.456392,-41.125694,-40.836033,-40.587503,-40.380249,-40.214342,-40.089838,-40.006789,-39.965238,-39.965198,-40.006670,-40.089639,-40.214065,-40.379892,-40.587068,-40.835520,-41.125102,-41.455723,-41.827235,-42.239464,-42.692245,-43.185355,-43.718581,-44.291670,-44.904340,-45.556294,-46.247151,-46.976711,-47.744421,-48.549943,-49.392797,-50.272517,-51.188585,-52.140446,-53.127519,-54.149170}, // NOLINT + {-54.413080,-53.391984,-52.405428,-51.454039,-50.538412,-49.659092,-48.816573,-48.011411,-47.243999,-46.514762,-45.824095,-45.172351,-44.559861,-43.986935,-43.453846,-42.960835,-42.508161,-42.096003,-41.724548,-41.393968,-41.104397,-40.855965,-40.648768,-40.482914,-40.358448,-40.275428,-40.233890,-40.233850,-40.275308,-40.358249,-40.482636,-40.648411,-40.855530,-41.103883,-41.393376,-41.723878,-42.095256,-42.507338,-42.959936,-43.452872,-43.985887,-44.558739,-45.171158,-45.822830,-46.513426,-47.242595,-48.009938,-48.815034,-49.657487,-50.536743,-51.452308,-52.403635,-53.390132,-54.411170}, // NOLINT + {-54.675066,-53.654569,-52.668595,-51.717745,-50.802616,-49.923774,-49.081704,-48.276922,-47.509873,-46.780973,-46.090619,-45.439151,-44.826923,-44.254237,-43.721355,-43.228543,-42.776030,-42.364023,-41.992700,-41.662236,-41.372764,-41.124415,-40.917286,-40.751486,-40.627060,-40.544066,-40.502542,-40.502502,-40.543947,-40.626861,-40.751207,-40.916928,-41.123979,-41.372249,-41.661643,-41.992029,-42.363275,-42.775206,-43.227643,-43.720380,-44.253187,-44.825800,-45.437956,-46.089352,-46.779636,-47.508466,-48.275447,-49.080163,-49.922167,-50.800945,-51.716011,-52.666800,-53.652715,-54.673155}, // NOLINT +}, // NOLINT +{ + {90.381169,89.264869,87.895676,86.280410,84.426514,82.341633,80.034563,77.513856,74.788661,71.868502,68.762879,65.481902,62.035647,58.434346,54.688400,50.808369,46.804766,42.688440,38.469636,34.159308,29.768327,25.307334,20.787171,16.218526,11.612128,6.978788,2.329414,-2.325415,-6.974800,-11.608160,-16.214589,-20.783273,-25.303487,-29.764540,-34.155591,-38.465998,-42.684891,-46.801315,-50.805025,-54.685171,-58.431241,-62.032675,-65.479069,-68.760193,-71.865970,-74.786290,-77.511651,-80.032531,-82.339777,-84.424840,-86.278921,-87.894375,-89.263759,-90.380251}, // NOLINT + {90.369724,89.258917,87.894805,86.284217,84.434556,82.353699,80.050015,77.532313,74.809619,71.891423,68.787435,65.507765,62.062146,58.461168,54.715095,50.834497,46.830109,42.712212,38.491967,34.179767,29.786651,25.323316,20.800433,16.228954,11.619734,6.983412,2.330949,-2.326950,-6.979423,-11.615766,-16.225016,-20.796536,-25.319469,-29.782865,-34.176051,-38.488331,-42.708665,-46.826660,-50.831156,-54.711870,-58.458066,-62.059177,-65.504936,-68.784753,-71.888896,-74.807253,-77.530113,-80.047988,-82.351849,-84.432888,-86.282735,-87.893512,-89.257814,-90.368815}, // NOLINT + {90.358242,89.252904,87.893899,86.288032,84.442632,82.365660,80.065436,77.550706,74.830576,71.914520,68.812162,65.533493,62.088697,58.487907,54.741775,50.860649,46.855227,42.736136,38.514300,34.200244,29.804846,25.339156,20.813707,16.239674,11.627422,6.988070,2.332494,-2.328495,-6.984082,-11.623454,-16.235737,-20.809810,-25.335310,-29.801061,-34.196529,-38.510665,-42.732590,-46.851780,-50.857309,-54.738552,-58.484809,-62.085731,-65.530667,-68.809485,-71.911997,-74.828215,-77.548512,-80.063414,-82.363816,-84.440971,-86.286556,-87.892613,-89.251809,-90.357340}, // NOLINT + {90.346738,89.246834,87.892968,86.291821,84.450797,82.377608,80.080911,77.569017,74.851539,71.937372,68.836808,65.559337,62.115218,58.514792,54.768443,50.886811,46.880311,42.760163,38.536641,34.220740,29.823394,25.355070,20.826966,16.250057,11.634957,6.992681,2.334023,-2.330025,-6.988693,-11.630989,-16.246119,-20.823070,-25.351224,-29.819609,-34.217025,-38.533007,-42.756618,-46.876865,-50.883474,-54.765222,-58.511696,-62.112256,-65.556515,-68.834134,-71.934854,-74.849182,-77.566828,-80.078895,-82.375771,-84.449142,-86.290353,-87.891689,-89.245746,-90.345844}, // NOLINT + {90.335201,89.240812,87.892022,86.295578,84.458836,82.389641,80.096366,77.587570,74.872576,71.960520,68.861483,65.585167,62.141869,58.541663,54.795167,50.912987,46.905740,42.784412,38.559054,34.241238,29.841716,25.370994,20.840261,16.260730,11.642572,6.997266,2.335555,-2.331556,-6.993277,-11.638604,-16.256793,-20.836365,-25.367149,-29.837932,-34.237524,-38.555421,-42.780869,-46.902296,-50.909651,-54.791949,-58.538570,-62.138910,-65.582348,-68.858814,-71.958006,-74.870224,-77.585386,-80.094356,-82.387810,-84.457187,-86.294116,-87.890750,-89.239732,-90.334315}, // NOLINT + {90.323641,89.234748,87.891055,86.299357,84.466932,82.401622,80.111691,77.605991,74.893473,71.983598,68.886154,65.611015,62.168395,58.568501,54.821892,50.939181,46.931010,42.808177,38.581448,34.261759,29.859956,25.386922,20.853715,16.271118,11.650032,7.001868,2.337195,-2.333196,-6.997880,-11.646064,-16.267181,-20.849819,-25.383078,-29.856173,-34.258047,-38.577817,-42.804636,-46.927569,-50.935848,-54.818676,-58.565411,-62.165439,-65.608201,-68.883489,-71.981088,-74.891126,-77.603812,-80.109687,-82.399797,-84.465290,-86.297902,-87.889790,-89.233675,-90.322763}, // NOLINT + {90.312054,89.228637,87.890058,86.303091,84.475015,82.413594,80.127144,77.624399,74.914452,72.006681,68.910843,65.636868,62.195030,58.595346,54.848639,50.965391,46.956324,42.832226,38.603886,34.282318,29.878341,25.402882,20.867200,16.281661,11.657828,7.006431,2.338683,-2.334684,-7.002442,-11.653861,-16.277725,-20.863305,-25.399038,-29.874559,-34.278607,-38.600255,-42.828686,-46.952884,-50.962059,-54.845425,-58.592258,-62.192077,-65.634057,-68.908182,-72.004176,-74.912110,-77.622226,-80.125146,-82.411774,-84.473379,-86.301642,-87.888801,-89.227572,-90.311183}, // NOLINT + {90.300468,89.222506,87.889051,86.306793,84.483056,82.425566,80.142538,77.642811,74.935476,72.029715,68.935531,65.662729,62.221523,58.621943,54.875390,50.991616,46.981610,42.856217,38.626375,34.302842,29.896719,25.418850,20.880211,16.292225,11.665450,7.011254,2.340220,-2.336221,-7.007266,-11.661482,-16.288289,-20.876316,-25.415007,-29.892937,-34.299132,-38.622746,-42.852679,-46.978172,-50.988287,-54.872179,-58.618859,-62.218574,-65.659922,-68.932873,-72.027215,-74.933139,-77.640644,-80.140545,-82.423753,-84.481427,-86.305351,-87.887800,-89.221449,-90.299605}, // NOLINT + {90.288799,89.216357,87.888021,86.310507,84.491117,82.437548,80.157976,77.661248,74.956387,72.052811,68.960261,65.688604,62.248167,58.649132,54.902152,51.017863,47.006968,42.880296,38.648872,34.323391,29.915058,25.434830,20.893706,16.302917,11.673091,7.015954,2.341755,-2.337756,-7.011966,-11.669124,-16.298981,-20.889811,-25.430987,-29.911277,-34.319681,-38.645244,-42.876759,-47.003531,-51.014536,-54.898943,-58.646051,-62.245221,-65.685801,-68.957607,-72.050315,-74.954055,-77.659085,-80.155989,-82.435741,-84.489495,-86.309073,-87.886778,-89.215307,-90.287944}, // NOLINT + {90.277134,89.210177,87.886989,86.314240,84.499193,82.449421,80.173401,77.679674,74.977358,72.075881,68.984939,65.714480,62.274743,58.676045,54.928941,51.044230,47.032317,42.904535,38.671295,34.343969,29.933449,25.450803,20.907181,16.313344,11.680758,7.020374,2.343310,-2.339311,-7.016385,-11.676791,-16.309408,-20.903286,-25.446961,-29.929669,-34.340260,-38.667668,-42.900999,-47.028883,-51.040905,-54.925735,-58.672966,-62.271800,-65.711681,-68.982290,-72.073389,-74.975030,-77.677517,-80.171420,-82.447620,-84.497578,-86.312813,-87.885753,-89.209135,-90.276288}, // NOLINT + {90.265485,89.203962,87.885918,86.317938,84.507170,82.461437,80.188776,77.698100,74.998355,72.098967,69.009666,65.740396,62.301397,58.702970,54.955789,51.070489,47.057672,42.928630,38.693828,34.364588,29.951887,25.466841,20.920641,16.323944,11.688420,7.025002,2.344858,-2.340860,-7.021014,-11.684453,-16.320009,-20.916747,-25.462999,-29.948107,-34.360881,-38.690203,-42.925097,-47.054239,-51.067167,-54.952586,-58.699894,-62.298457,-65.737600,-69.007021,-72.096481,-74.996033,-77.695948,-80.186801,-82.459642,-84.505561,-86.316517,-87.884689,-89.202927,-90.264646}, // NOLINT + {90.253720,89.197733,87.884852,86.321607,84.515187,82.473240,80.204229,77.716533,75.019347,72.122053,69.034368,65.766313,62.327765,58.729972,54.982603,51.096755,47.083059,42.952604,38.716225,34.385187,29.970352,25.482810,20.934092,16.334508,11.696089,7.029633,2.346429,-2.342431,-7.025645,-11.692122,-16.330573,-20.930198,-25.478969,-29.966573,-34.381480,-38.712600,-42.949072,-47.079628,-51.093435,-54.979402,-58.726899,-62.324829,-65.763521,-69.031728,-72.119570,-75.017030,-77.714387,-80.202260,-82.471452,-84.513585,-86.320194,-87.883631,-89.196706,-90.252889}, // NOLINT + {90.241988,89.191520,87.883773,86.325255,84.523193,82.485255,80.219613,77.734965,75.040341,72.145181,69.059129,65.792225,62.354731,58.756787,55.009415,51.123066,47.108457,42.976768,38.738855,34.405797,29.988753,25.498878,20.946983,16.345094,11.703738,7.034279,2.347967,-2.343969,-7.030291,-11.699771,-16.341159,-20.943090,-25.495037,-29.984975,-34.402091,-38.735232,-42.973238,-47.105028,-51.119748,-55.006217,-58.753717,-62.351798,-65.789436,-69.056492,-72.142703,-75.038029,-77.732824,-80.217649,-82.483473,-84.521597,-86.323848,-87.882559,-89.190501,-90.241166}, // NOLINT + {90.230234,89.185232,87.882658,86.328976,84.531209,82.497202,80.235020,77.753400,75.061336,72.168320,69.083883,65.818161,62.381341,58.783921,55.036329,51.149418,47.133875,43.001015,38.761373,34.426428,30.007229,25.514855,20.960413,16.355795,11.711430,7.038918,2.349526,-2.345528,-7.034930,-11.707464,-16.351860,-20.956520,-25.511015,-30.003451,-34.422723,-38.757752,-42.997486,-47.130448,-51.146103,-55.033133,-58.780854,-62.378412,-65.815376,-69.081250,-72.165847,-75.059029,-77.751265,-80.233062,-82.495427,-84.529620,-86.327577,-87.881451,-89.184221,-90.229419}, // NOLINT + {90.218452,89.179000,87.881552,86.332621,84.539198,82.509080,80.250434,77.771826,75.082342,72.191373,69.108632,65.844109,62.408014,58.810826,55.063192,51.175756,47.159333,43.025066,38.783900,34.447085,30.025690,25.530917,20.973847,16.366360,11.719151,7.043563,2.351074,-2.347075,-7.039575,-11.715184,-16.362425,-20.969954,-25.527077,-30.021913,-34.443381,-38.780279,-43.021538,-47.155908,-51.172443,-55.059999,-58.807762,-62.405088,-65.841328,-69.106004,-72.188905,-75.080040,-77.769696,-80.248482,-82.507310,-84.537616,-86.331229,-87.880353,-89.177997,-90.217645}, // NOLINT + {90.206647,89.172700,87.880415,86.336194,84.547178,82.521043,80.265817,77.790264,75.103372,72.214404,69.133401,65.870069,62.434725,58.837841,55.090033,51.201992,47.184692,43.049133,38.806499,34.467746,30.044104,25.546981,20.987285,16.376952,11.726768,7.048217,2.352628,-2.348629,-7.044229,-11.722801,-16.373017,-20.983393,-25.543141,-30.040328,-34.464043,-38.802880,-43.045607,-47.181269,-51.198681,-55.086843,-58.834780,-62.431802,-65.867291,-69.130777,-72.211940,-75.101075,-77.788139,-80.263871,-82.519280,-84.545602,-86.334809,-87.879223,-89.171704,-90.205848}, // NOLINT + {90.194830,89.166367,87.879232,86.339803,84.555168,82.532922,80.281235,77.808708,75.124382,72.237609,69.158183,65.895959,62.461448,58.864822,55.116939,51.228371,47.210213,43.073428,38.829083,34.488428,30.062653,25.563079,21.000730,16.387644,11.734466,7.052868,2.354196,-2.350197,-7.048880,-11.730500,-16.383710,-20.996838,-25.559240,-30.058878,-34.484727,-38.825465,-43.069904,-47.206792,-51.225062,-55.113751,-58.861764,-62.458528,-65.893186,-69.155563,-72.235149,-75.122090,-77.806589,-80.279295,-82.531165,-84.553599,-86.338425,-87.878048,-89.165379,-90.194040}, // NOLINT + {90.182974,89.160081,87.878072,86.343431,84.563130,82.544856,80.296643,77.827188,75.145400,72.260837,69.182990,65.922029,62.488177,58.891927,55.143815,51.254737,47.235705,43.097629,38.851707,34.509235,30.081152,25.579148,21.014182,16.398422,11.742142,7.057526,2.355774,-2.351776,-7.053538,-11.738175,-16.394488,-21.010290,-25.575310,-30.077378,-34.505534,-38.848091,-43.094106,-47.232286,-51.251430,-55.140630,-58.888873,-62.485261,-65.919260,-69.180374,-72.258382,-75.143113,-77.825074,-80.294708,-82.543105,-84.561567,-86.342060,-87.876895,-89.159101,-90.182192}, // NOLINT + {90.171133,89.153723,87.876918,86.347020,84.571125,82.556740,80.312018,77.845691,75.166431,72.283903,69.207780,65.948030,62.514971,58.918899,55.170793,51.281200,47.261113,43.121857,38.874365,34.529882,30.099644,25.595241,21.027642,16.408737,11.749890,7.062182,2.357285,-2.353286,-7.058194,-11.745923,-16.404803,-21.023751,-25.591403,-30.095871,-34.526182,-38.870749,-43.118335,-47.257696,-51.277895,-55.167611,-58.915847,-62.512058,-65.945264,-69.205169,-72.281453,-75.164149,-77.843583,-80.310090,-82.554996,-84.569569,-86.345656,-87.875749,-89.152750,-90.170359}, // NOLINT + {90.159223,89.147362,87.875710,86.350618,84.579074,82.568653,80.327454,77.864013,75.187469,72.307075,69.232607,65.974217,62.541691,58.945960,55.197699,51.307616,47.286720,43.146109,38.896943,34.550549,30.118223,25.611305,21.041110,16.419390,11.757607,7.066847,2.358845,-2.354846,-7.062859,-11.753641,-16.415456,-21.037220,-25.607468,-30.114450,-34.546850,-38.893329,-43.142589,-47.283304,-51.304314,-55.194519,-58.942912,-62.538782,-65.971455,-69.230001,-72.304630,-75.185193,-77.861911,-80.325532,-82.566915,-84.577525,-86.349261,-87.874549,-89.146398,-90.158456}, // NOLINT + {90.147296,89.140988,87.874494,86.354198,84.587030,82.580557,80.342861,77.882551,75.208517,72.330248,69.257429,66.000026,62.568483,58.973131,55.224656,51.334060,47.312254,43.170339,38.919606,34.571346,30.136794,25.627307,21.054588,16.430207,11.765269,7.071503,2.360433,-2.356434,-7.067515,-11.761303,-16.426273,-21.050698,-25.623470,-30.133022,-34.567649,-38.915993,-43.166821,-47.308841,-51.330761,-55.221479,-58.970086,-62.565578,-65.997268,-69.254826,-72.327807,-75.206246,-77.880454,-80.340944,-82.578826,-84.585488,-86.352848,-87.873340,-89.140031,-90.146538}, // NOLINT + {90.135402,89.134606,87.873358,86.357784,84.595004,82.592455,80.358260,77.901015,75.229561,72.353443,69.282331,66.026126,62.595369,59.000200,55.251659,51.360515,47.337807,43.194586,38.942303,34.592083,30.155349,25.643555,21.068076,16.440821,11.773175,7.076187,2.362004,-2.358006,-7.072199,-11.769209,-16.436887,-21.064186,-25.639719,-30.151578,-34.588387,-38.938691,-43.191069,-47.334395,-51.357218,-55.248485,-58.997157,-62.592467,-66.023372,-69.279733,-72.351007,-75.227294,-77.898924,-80.356350,-82.590730,-84.593468,-86.356442,-87.872211,-89.133657,-90.134652}, // NOLINT + {90.123468,89.128206,87.872108,86.361359,84.602932,82.604454,80.373681,77.919462,75.250640,72.376610,69.307118,66.052010,62.622106,59.027312,55.278639,51.387021,47.363373,43.218954,38.964982,34.612843,30.173866,25.659739,21.081574,16.451564,11.780768,7.080862,2.363557,-2.359559,-7.076874,-11.776803,-16.447631,-21.077685,-25.655904,-30.170095,-34.609148,-38.961372,-43.215439,-47.359964,-51.383726,-55.275467,-59.024273,-62.619207,-66.049260,-69.304524,-72.374179,-75.248379,-77.917377,-80.371776,-82.602736,-84.601404,-86.360024,-87.870969,-89.127265,-90.122726}, // NOLINT + {90.111517,89.121795,87.870842,86.364892,84.610884,82.616303,80.389095,77.937912,75.271693,72.399807,69.331970,66.078308,62.648898,59.054438,55.305692,51.413475,47.388957,43.243266,38.987712,34.633637,30.192510,25.675882,21.095082,16.462254,11.788478,7.085550,2.365132,-2.361133,-7.081562,-11.784513,-16.458321,-21.091193,-25.672047,-30.188741,-34.629943,-38.984103,-43.239753,-47.385549,-51.410182,-55.302523,-59.051402,-62.646003,-66.075562,-69.329380,-72.397381,-75.269437,-77.935833,-80.387196,-82.614591,-84.609362,-86.363565,-87.869710,-89.120862,-90.110784}, // NOLINT + {90.099546,89.115363,87.869589,86.368483,84.618820,82.628162,80.404508,77.956392,75.292770,72.423019,69.356861,66.104302,62.675716,59.081504,55.332745,51.440040,47.414568,43.267596,39.010429,34.654432,30.211105,25.692239,21.108601,16.472956,11.796206,7.090232,2.366676,-2.362678,-7.086244,-11.792240,-16.469023,-21.104713,-25.688405,-30.207336,-34.650739,-39.006821,-43.264085,-47.411162,-51.436749,-55.329579,-59.078470,-62.672824,-66.101560,-69.354276,-72.420597,-75.290519,-77.954318,-80.402616,-82.626457,-84.617305,-86.367163,-87.868465,-89.114438,-90.098820}, // NOLINT + {90.087550,89.108921,87.868339,86.372030,84.626744,82.640128,80.419926,77.974869,75.313820,72.446235,69.381744,66.130428,62.702564,59.108782,55.359813,51.466539,47.440196,43.291948,39.033146,34.675438,30.229788,25.708237,21.122131,16.483616,11.803953,7.094917,2.368276,-2.364277,-7.090930,-11.799987,-16.479683,-21.118243,-25.704404,-30.226019,-34.671746,-39.029540,-43.288438,-47.436792,-51.463250,-55.356650,-59.105752,-62.699676,-66.127690,-69.379163,-72.443819,-75.311574,-77.972801,-80.418040,-82.638430,-84.625237,-86.370717,-87.867223,-89.108004,-90.086833}, // NOLINT + {90.075549,89.102470,87.867090,86.375571,84.634673,82.651899,80.435421,77.993394,75.334953,72.469465,69.406651,66.156531,62.729444,59.135953,55.386873,51.493080,47.465837,43.316317,39.055915,34.696090,30.248374,25.724432,21.135672,16.494353,11.811705,7.099613,2.369826,-2.365827,-7.095625,-11.807740,-16.490420,-21.131784,-25.720599,-30.244606,-34.692399,-39.052310,-43.312809,-47.462435,-51.489794,-55.383712,-59.132926,-62.726559,-66.153796,-69.404075,-72.467053,-75.332713,-77.991332,-80.433541,-82.650206,-84.633172,-86.374266,-87.865982,-89.101561,-90.074840}, // NOLINT + {90.063538,89.095997,87.865800,86.379096,84.642628,82.663870,80.450785,78.011861,75.356046,72.492821,69.431523,66.182657,62.756315,59.163154,55.413774,51.519677,47.491495,43.340706,39.078666,34.717002,30.266991,25.740641,21.149224,16.505092,11.819470,7.104305,2.371374,-2.367376,-7.100318,-11.815505,-16.501160,-21.145336,-25.736808,-30.263224,-34.713312,-39.075063,-43.337199,-47.488095,-51.516394,-55.410616,-59.160130,-62.753434,-66.179926,-69.428951,-72.490414,-75.353812,-78.009804,-80.448911,-82.662184,-84.641134,-86.377797,-87.864699,-89.095096,-90.062837}, // NOLINT + {90.051510,89.089527,87.864591,86.382617,84.650565,82.675769,80.466270,78.030390,75.377157,72.515959,69.456488,66.208851,62.783234,59.190380,55.441184,51.546260,47.517177,43.365110,39.101461,34.737789,30.285807,25.756913,21.162787,16.515913,11.827229,7.108999,2.372974,-2.368975,-7.105011,-11.823264,-16.511982,-21.158900,-25.753081,-30.282041,-34.734100,-39.097859,-43.361605,-47.513779,-51.542978,-55.438029,-59.187359,-62.780356,-66.206124,-69.453920,-72.513557,-75.374927,-78.028338,-80.464402,-82.674089,-84.649078,-86.381326,-87.863498,-89.088633,-90.050818}, // NOLINT + {90.039452,89.083052,87.863278,86.386124,84.658496,82.687684,80.481651,78.048922,75.398277,72.539216,69.481433,66.234952,62.810141,59.217622,55.468172,51.572914,47.542884,43.389337,39.124295,34.758691,30.304421,25.773082,21.176362,16.526643,11.835072,7.113700,2.374561,-2.370563,-7.109713,-11.831107,-16.522712,-21.172475,-25.769251,-30.300656,-34.755003,-39.120694,-43.385834,-47.539489,-51.569635,-55.465019,-59.214604,-62.807267,-66.232229,-69.478869,-72.536819,-75.396053,-78.046876,-80.479790,-82.686012,-84.657017,-86.384841,-87.862193,-89.082167,-90.038768}, // NOLINT + {90.027419,89.076563,87.861960,86.389668,84.666425,82.699600,80.497107,78.067383,75.419606,72.562501,69.506371,66.261120,62.837092,59.244871,55.495364,51.599504,47.568595,43.413798,39.147097,34.779631,30.323097,25.789344,21.189948,16.537326,11.842817,7.118406,2.376126,-2.372128,-7.114419,-11.838852,-16.533395,-21.186062,-25.785513,-30.319333,-34.775944,-39.143498,-43.410297,-47.565201,-51.596228,-55.492214,-59.241856,-62.834221,-66.258402,-69.503813,-72.560108,-75.417387,-78.065343,-80.495252,-82.697935,-84.664952,-86.388392,-87.860882,-89.075686,-90.026743}, // NOLINT + {90.015357,89.070065,87.860670,86.393190,84.674347,82.711487,80.512578,78.085908,75.440554,72.585785,69.531363,66.287328,62.864042,59.272155,55.522520,51.626143,47.594322,43.438543,39.169959,34.800520,30.341809,25.805604,21.203546,16.548095,11.850565,7.123121,2.377703,-2.373704,-7.119133,-11.846600,-16.544164,-21.199660,-25.801774,-30.338045,-34.796834,-39.166361,-43.435043,-47.590931,-51.622869,-55.519373,-59.269143,-62.861175,-66.284614,-69.528809,-72.583398,-75.438340,-78.083874,-80.510730,-82.709828,-84.672882,-86.391921,-87.859601,-89.069196,-90.014690}, // NOLINT + {88.629121,87.678730,86.471260,85.012487,83.308760,81.367188,79.195336,76.801307,74.193744,71.381565,68.374186,65.181392,61.813023,58.279690,54.591703,50.759938,46.795285,42.708841,38.511925,34.215833,29.832032,25.372077,20.847611,16.270125,11.651717,7.003531,2.337799,-2.333800,-6.999543,-11.647751,-16.266192,-20.843721,-25.368240,-29.828260,-34.212136,-38.508313,-42.705324,-46.791872,-50.756638,-54.588527,-58.276645,-61.810119,-65.178636,-68.371585,-71.379127,-74.191475,-76.799214,-79.193424,-81.365462,-83.307224,-85.011145,-86.470115,-87.677785,-88.628377}, // NOLINT + {88.592418,87.647441,86.445117,84.991173,83.292008,81.354645,79.186659,76.796181,74.191695,71.382278,68.377274,65.186490,61.819853,58.287765,54.600752,50.769588,46.805326,42.718850,38.521641,34.225012,29.840483,25.379565,20.854105,16.275224,11.655257,7.005754,2.338540,-2.334541,-7.001767,-11.651291,-16.271291,-20.850215,-25.375729,-29.836711,-34.221316,-38.518030,-42.715334,-46.801914,-50.766291,-54.597578,-58.284723,-61.816951,-65.183737,-68.374677,-71.379844,-74.189431,-76.794093,-79.184753,-81.352925,-83.290478,-84.989838,-86.443980,-87.646503,-88.591682}, // NOLINT + {88.555683,87.616126,86.418956,84.969866,83.275248,81.342141,79.177980,76.790987,74.189640,71.382994,68.380411,65.191620,61.826520,58.295864,54.609780,50.779259,46.815251,42.728976,38.531377,34.234233,29.848918,25.387028,20.860127,16.280342,11.659007,7.008026,2.339326,-2.335327,-7.004038,-11.655041,-16.276409,-20.856237,-25.383193,-29.845147,-34.230538,-38.527767,-42.725461,-46.811841,-50.775964,-54.606608,-58.292825,-61.823622,-65.188871,-68.377818,-71.380564,-74.187381,-76.788904,-79.176079,-81.340427,-83.273725,-84.968537,-86.417825,-87.615195,-88.554954}, // NOLINT + {88.518940,87.584789,86.392774,84.948548,83.258462,81.329576,79.169333,76.785784,74.187603,71.383730,68.383530,65.196774,61.833463,58.303964,54.618864,50.788871,46.825223,42.738822,38.541077,34.243398,29.857270,25.394541,20.866632,16.285607,11.662692,7.010402,2.340112,-2.336113,-7.006415,-11.658727,-16.281674,-20.862743,-25.390707,-29.853500,-34.239703,-38.537469,-42.735308,-46.821815,-50.785578,-54.615695,-58.300928,-61.830568,-65.194029,-68.380941,-71.381305,-74.185348,-76.783707,-79.167437,-81.327867,-83.256945,-84.947226,-86.391650,-87.583866,-88.518219}, // NOLINT + {88.482128,87.553436,86.366570,84.927271,83.241710,81.316931,79.160586,76.780610,74.185565,71.384479,68.386669,65.201957,61.840302,58.312098,54.627944,50.798598,46.835244,42.748864,38.550616,34.252635,29.865826,25.402070,20.873122,16.290533,11.666437,7.012617,2.340845,-2.336847,-7.008629,-11.662471,-16.286601,-20.869233,-25.398236,-29.862057,-34.248941,-38.547008,-42.745352,-46.831838,-50.795307,-54.624777,-58.309065,-61.837410,-65.199214,-68.384084,-71.382059,-74.183316,-76.778537,-79.158696,-81.315229,-83.240199,-84.925956,-86.365454,-87.552521,-88.481415}, // NOLINT + {88.445312,87.522046,86.340362,84.905870,83.224907,81.304413,79.151893,76.775430,74.183536,71.385211,68.389801,65.207135,61.847109,58.320212,54.637040,50.808340,46.845258,42.758891,38.560582,34.261849,29.874316,25.409619,20.879602,16.295705,11.670192,7.014869,2.341612,-2.337613,-7.010882,-11.666226,-16.291772,-20.875713,-25.405785,-29.870547,-34.258156,-38.556975,-42.755381,-46.841854,-50.805051,-54.633876,-58.317181,-61.844220,-65.204397,-68.387220,-71.382795,-74.181291,-76.773363,-79.150009,-81.302716,-83.223402,-84.904562,-86.339252,-87.521138,-88.444606}, // NOLINT + {88.408473,87.490648,86.314119,84.884517,83.208172,81.291821,79.143207,76.770255,74.181510,71.386003,68.392967,65.212314,61.854009,58.328405,54.646153,50.818091,46.855275,42.768912,38.570479,34.271129,29.882772,25.417110,20.886075,16.300890,11.673974,7.017147,2.342375,-2.338376,-7.013159,-11.670009,-16.296958,-20.882186,-25.413277,-29.879004,-34.267437,-38.566874,-42.765403,-46.851873,-50.814805,-54.642991,-58.325377,-61.851124,-65.209579,-68.390390,-71.383591,-74.179270,-76.768192,-79.141328,-81.290131,-83.206674,-84.883215,-86.313016,-87.489747,-88.407775}, // NOLINT + {88.371596,87.459226,86.287876,84.863144,83.191305,81.279252,79.134517,76.765080,74.179491,71.386748,68.396135,65.217513,61.860897,58.336544,54.655281,50.827852,46.865334,42.778930,38.580125,34.280397,29.891309,25.424711,20.891998,16.305781,11.677709,7.019437,2.343166,-2.339167,-7.015450,-11.673743,-16.301849,-20.888111,-25.420878,-29.887542,-34.276706,-38.576521,-42.775423,-46.861933,-50.824568,-54.652121,-58.333518,-61.858015,-65.214782,-68.393562,-71.384340,-74.177256,-76.763023,-79.132643,-81.277567,-83.189813,-84.861849,-86.286781,-87.458333,-88.370906}, // NOLINT + {88.334729,87.427777,86.261605,84.841761,83.174512,81.266684,79.125739,76.759896,74.177478,71.387466,68.399307,65.222709,61.867772,58.344779,54.664417,50.837619,46.875408,42.789016,38.589916,34.289649,29.899849,25.432246,20.898453,16.311156,11.681457,7.021723,2.343917,-2.339919,-7.017736,-11.677492,-16.307224,-20.894565,-25.428414,-29.896083,-34.285959,-38.586313,-42.785510,-46.872009,-50.834336,-54.661260,-58.341756,-61.864892,-65.219981,-68.396738,-71.385063,-74.175248,-76.757844,-79.123871,-81.265005,-83.173027,-84.840473,-86.260517,-87.426891,-88.334046}, // NOLINT + {88.297813,87.396307,86.235320,84.820367,83.157665,81.254108,79.117120,76.754747,74.175419,71.388261,68.402497,65.227960,61.874661,58.352959,54.673559,50.847401,46.885490,42.799144,38.599753,34.298950,29.908365,25.439802,20.904910,16.316323,11.685248,7.024014,2.344694,-2.340695,-7.020027,-11.681283,-16.312391,-20.901023,-25.435971,-29.904599,-34.295262,-38.596151,-42.795639,-46.882093,-50.844121,-54.670405,-58.349940,-61.871785,-65.225236,-68.399931,-71.385862,-74.173193,-76.752700,-79.115258,-81.252436,-83.156187,-84.819086,-86.234239,-87.395428,-88.297138}, // NOLINT + {88.260840,87.364819,86.209025,84.798960,83.140825,81.241545,79.108430,76.749576,74.173505,71.389004,68.405694,65.233186,61.881503,58.361190,54.682761,50.857201,46.895594,42.809228,38.609590,34.308227,29.917047,25.447424,20.911372,16.321437,11.689028,7.026312,2.345458,-2.341460,-7.022324,-11.685063,-16.317506,-20.907486,-25.443593,-29.913282,-34.304539,-38.605989,-42.805725,-46.892199,-50.853923,-54.679609,-58.358173,-61.878630,-65.230465,-68.403133,-71.386610,-74.171284,-76.747535,-79.106574,-81.239878,-83.139353,-84.797685,-86.207951,-87.363948,-88.260172}, // NOLINT + {88.223894,87.333330,86.182703,84.777540,83.124006,81.228919,79.099729,76.744417,74.171509,71.389763,68.408896,65.238431,61.888467,58.369232,54.691938,50.866984,46.905716,42.819342,38.619455,34.317574,29.925472,25.455051,20.917840,16.326599,11.692774,7.028613,2.346226,-2.342227,-7.024626,-11.688809,-16.322668,-20.913954,-25.451220,-29.921708,-34.313887,-38.615855,-42.815840,-46.902323,-50.863708,-54.688788,-58.366218,-61.885597,-65.235714,-68.406339,-71.387374,-74.169293,-76.742381,-79.097879,-81.227258,-83.122540,-84.776273,-86.181637,-87.332467,-88.223234}, // NOLINT + {88.186848,87.301783,86.156373,84.756139,83.107155,81.216323,79.091032,76.739257,74.169435,71.390636,68.412125,65.243670,61.895355,58.377633,54.701155,50.876858,46.915852,42.829622,38.629318,34.326937,29.934039,25.462589,20.924315,16.331847,11.696565,7.030913,2.347003,-2.343005,-7.026926,-11.692600,-16.327916,-20.920429,-25.458759,-29.930275,-34.323251,-38.625720,-42.826122,-46.912461,-50.873584,-54.698008,-58.374622,-61.892489,-65.240956,-68.409572,-71.388251,-74.167224,-76.737226,-79.089187,-81.214669,-83.105696,-84.754879,-86.155313,-87.300926,-88.186197}, // NOLINT + {88.149849,87.270231,86.130028,84.734669,83.090295,81.203764,79.082336,76.734103,74.167523,71.391449,68.415345,65.248934,61.902223,58.385897,54.710374,50.886692,46.926013,42.839513,38.639342,34.336310,29.942655,25.470212,20.930797,16.337163,11.700341,7.033220,2.347793,-2.343794,-7.029233,-11.696376,-16.333233,-20.926912,-25.466383,-29.938893,-34.332625,-38.635745,-42.836015,-46.922623,-50.883420,-54.707230,-58.382890,-61.899360,-65.246224,-68.412796,-71.389068,-74.165317,-76.732078,-79.080496,-81.202116,-83.088842,-84.733415,-86.128976,-87.269383,-88.149205}, // NOLINT + {88.112802,87.238661,86.103658,84.713221,83.073430,81.191188,79.073645,76.728950,74.165550,71.392301,68.418590,65.254269,61.909329,58.394174,54.719623,50.896547,46.936177,42.849689,38.649097,34.345623,29.951232,25.478032,20.937288,16.342027,11.704186,7.035532,2.348523,-2.344525,-7.031545,-11.700222,-16.338097,-20.933402,-25.474203,-29.947470,-34.341939,-38.645501,-42.846192,-46.932789,-50.893277,-54.716481,-58.391169,-61.906470,-65.251563,-68.416045,-71.389925,-74.163349,-76.726930,-79.071812,-81.189547,-83.071984,-84.711974,-86.102613,-87.237820,-88.112166}, // NOLINT + {88.075726,87.207078,86.077290,84.691756,83.056537,81.178493,79.064948,76.723806,74.163511,71.393110,68.421853,65.259587,61.916293,58.402403,54.728811,50.906407,46.946378,42.860040,38.659014,34.355047,29.959828,25.485513,20.943786,16.347250,11.707910,7.037842,2.349308,-2.345309,-7.033855,-11.703946,-16.343320,-20.939901,-25.481684,-29.956067,-34.351364,-38.655419,-42.856545,-46.942992,-50.903139,-54.725672,-58.399401,-61.913437,-65.256885,-68.419312,-71.390738,-74.161315,-76.721791,-79.063121,-81.176857,-83.055097,-84.690516,-86.076253,-87.206244,-88.075098}, // NOLINT + {88.038638,87.175469,86.050893,84.670283,83.039727,81.165948,79.056257,76.718667,74.161628,71.393930,68.425116,65.264936,61.923278,58.410974,54.738153,50.916299,46.956586,42.870253,38.668953,34.364406,29.968520,25.493000,20.950294,16.352746,11.711794,7.040160,2.350081,-2.346083,-7.036173,-11.707829,-16.348816,-20.946410,-25.489172,-29.964759,-34.360724,-38.665360,-42.866760,-46.953201,-50.913034,-54.735016,-58.407975,-61.920425,-65.262237,-68.422579,-71.391562,-74.159437,-76.716658,-79.054435,-81.164319,-83.038294,-84.669050,-86.049862,-87.174643,-88.038018}, // NOLINT + {88.001521,87.143844,86.024493,84.648802,83.022845,81.153309,79.047565,76.713525,74.159671,71.394798,68.428403,65.270093,61.930268,58.419113,54.747484,50.926291,46.966808,42.880476,38.678891,34.373822,29.977116,25.500754,20.956812,16.357856,11.715598,7.042486,2.350882,-2.346883,-7.038499,-11.711634,-16.353926,-20.952927,-25.496927,-29.973356,-34.370141,-38.675299,-42.876983,-46.963426,-50.923028,-54.744349,-58.416116,-61.927419,-65.267398,-68.425871,-71.392436,-74.157484,-76.711521,-79.045749,-81.151686,-83.021419,-84.647576,-86.023470,-87.143026,-88.000909}, // NOLINT + {87.964387,87.112199,85.998077,84.627315,83.005946,81.140697,79.038877,76.708398,74.157720,71.395672,68.431684,65.275561,61.937299,58.427449,54.756720,50.936249,46.977051,42.890719,38.688871,34.383203,29.985849,25.508294,20.963339,16.363036,11.719386,7.044808,2.351676,-2.347677,-7.040821,-11.715422,-16.359107,-20.959455,-25.504467,-29.982090,-34.379523,-38.685280,-42.887228,-46.973670,-50.932988,-54.753589,-58.424455,-61.934452,-65.272869,-68.429156,-71.393314,-74.155539,-76.706399,-79.037067,-81.139080,-83.004526,-84.626096,-85.997061,-87.111388,-87.963783}, // NOLINT + {87.927230,87.080542,85.971645,84.605810,82.989060,81.128119,79.030143,76.703266,74.155744,71.396532,68.434992,65.280878,61.944337,58.435806,54.766084,50.946199,46.987310,42.900979,38.698849,34.392494,29.994366,25.516201,20.969875,16.368289,11.723219,7.047134,2.352450,-2.348452,-7.043147,-11.719255,-16.364359,-20.965992,-25.512374,-29.990608,-34.388815,-38.695260,-42.897490,-46.983931,-50.942940,-54.762955,-58.432816,-61.941494,-65.278191,-68.432468,-71.394179,-74.153568,-76.701273,-79.028339,-81.126508,-82.987647,-84.604598,-85.970637,-87.079740,-87.926634}, // NOLINT + {87.890067,87.048824,85.945200,84.584297,82.972170,81.115465,79.021505,76.698149,74.153815,71.397412,68.438294,65.286247,61.951389,58.444230,54.775409,50.956171,46.997581,42.911258,38.708816,34.402051,30.003131,25.523875,20.976423,16.373549,11.727043,7.049472,2.353235,-2.349236,-7.045485,-11.723079,-16.369620,-20.972539,-25.520049,-29.999374,-34.398373,-38.705228,-42.907771,-46.994204,-50.952915,-54.772283,-58.441242,-61.948550,-65.283564,-68.435774,-71.395063,-74.151644,-76.696161,-79.019707,-81.113860,-82.970764,-84.583092,-85.944199,-87.048029,-87.889479}, // NOLINT + {87.852847,87.017173,85.918738,84.562783,82.955269,81.102856,79.012824,76.693033,74.151896,71.398303,68.441627,65.291612,61.958466,58.452625,54.784793,50.966150,47.007876,42.921556,38.718856,34.411640,30.011853,25.531564,20.982980,16.378808,11.730847,7.051806,2.354008,-2.350009,-7.047819,-11.726883,-16.374879,-20.979097,-25.527739,-30.008096,-34.407963,-38.715269,-42.918070,-47.004501,-50.962896,-54.781669,-58.449641,-61.955630,-65.288932,-68.439112,-71.395958,-74.149730,-76.691051,-79.011032,-81.101258,-82.953869,-84.561585,-85.917745,-87.016385,-87.852266}, // NOLINT + {87.815626,86.985460,85.892270,84.541257,82.938396,81.090241,79.004142,76.687919,74.149983,71.399219,68.444978,65.297030,61.965549,58.461056,54.794167,50.976095,47.018191,42.931935,38.728870,34.421078,30.020525,25.539328,20.989548,16.384084,11.734766,7.054144,2.354815,-2.350817,-7.050157,-11.730802,-16.380155,-20.985665,-25.535503,-30.016769,-34.417402,-38.725284,-42.928450,-47.014818,-50.972843,-54.791046,-58.458074,-61.962717,-65.294354,-68.442466,-71.396880,-74.147822,-76.685942,-79.002355,-81.088649,-82.937003,-84.540067,-85.891284,-86.984680,-87.815054}, // NOLINT + {87.778384,86.953743,85.865787,84.519724,82.921477,81.077693,78.995459,76.682842,74.148081,71.400118,68.448333,65.302472,61.972659,58.469447,54.803769,50.986280,47.028519,42.942250,38.738920,34.430660,30.029294,25.547072,20.996126,16.389313,11.738344,7.056480,2.355587,-2.351589,-7.052493,-11.734381,-16.385384,-20.992244,-25.543247,-30.025538,-34.426985,-38.735336,-42.938768,-47.025148,-50.983031,-54.800650,-58.466468,-61.969829,-65.299800,-68.445826,-71.397783,-74.145925,-76.680871,-78.993679,-81.076107,-82.920091,-84.518540,-85.864808,-86.952971,-87.777820}, // NOLINT + {87.741123,86.921995,85.839294,84.498180,82.904556,81.065019,78.986793,76.677708,74.146170,71.401056,68.451710,65.307907,61.979730,58.477903,54.812996,50.996116,47.038870,42.952554,38.748981,34.440132,30.037962,25.554823,21.002716,16.394563,11.742232,7.058791,2.356370,-2.352372,-7.054805,-11.738269,-16.390634,-20.998834,-25.550999,-30.034207,-34.436458,-38.745398,-42.949073,-47.035501,-50.992869,-54.809881,-58.474928,-61.976904,-65.305238,-68.449207,-71.398726,-74.144019,-76.675742,-78.985018,-81.063440,-82.903177,-84.497004,-85.838323,-86.921231,-87.740567}, // NOLINT + {87.703846,86.890246,85.812793,84.476631,82.887646,81.052349,78.978143,76.672626,74.144285,71.401995,68.455055,65.313348,61.986932,58.486351,54.822423,51.006269,47.049158,42.962886,38.759050,34.449633,30.046547,25.562626,21.009316,16.399871,11.746289,7.061179,2.357158,-2.353159,-7.057192,-11.742326,-16.395943,-21.005435,-25.558803,-30.042793,-34.445960,-38.755469,-42.959407,-47.045790,-51.003024,-54.819310,-58.483378,-61.984109,-65.310683,-68.452556,-71.399669,-74.142140,-76.670666,-78.976375,-81.050776,-82.886273,-84.475462,-85.811830,-86.889489,-87.703298}, // NOLINT + {87.666548,86.858476,85.786283,84.455079,82.870734,81.039769,78.969464,76.667544,74.142397,71.402946,68.458483,65.318784,61.994088,58.494859,54.831863,51.016376,47.059738,42.973258,38.769129,34.459179,30.055524,25.570349,21.015927,16.405275,11.750324,7.063537,2.357970,-2.353972,-7.059550,-11.746361,-16.401347,-21.012046,-25.566526,-30.051771,-34.455507,-38.765548,-42.969780,-47.056373,-51.013133,-54.828752,-58.491890,-61.991269,-65.316124,-68.455989,-71.400625,-74.140256,-76.665589,-78.967701,-81.038203,-82.869368,-84.453917,-85.785326,-86.857727,-87.666008}, // NOLINT + {87.629215,86.826694,85.759759,84.433520,82.853812,81.027187,78.960791,76.662465,74.140497,71.403899,68.461899,65.324291,62.001254,58.503353,54.841352,51.026434,47.070037,42.983686,38.779275,34.468769,30.064155,25.578159,21.022549,16.410537,11.754130,7.065891,2.358754,-2.354756,-7.061904,-11.750167,-16.406609,-21.018669,-25.574337,-30.060403,-34.465098,-38.775696,-42.980209,-47.066673,-51.023194,-54.838244,-58.500386,-61.998438,-65.321635,-68.459409,-71.401583,-74.138362,-76.660517,-78.959035,-81.025627,-82.852453,-84.432365,-85.758811,-86.825953,-87.628684}, // NOLINT + {87.591900,86.794896,85.733226,84.411959,82.836894,81.014584,78.952134,76.657391,74.138685,71.404871,68.465373,65.329789,62.008443,58.511905,54.850773,51.036391,47.080464,42.994124,38.789400,34.478360,30.073087,25.585961,21.029182,16.415820,11.757963,7.068259,2.359534,-2.355535,-7.064272,-11.754000,-16.411892,-21.025302,-25.582140,-30.069335,-34.474690,-38.785823,-42.990649,-47.077102,-51.033153,-54.847667,-58.508942,-62.005631,-65.327136,-68.462887,-71.402560,-74.136554,-76.655448,-78.950384,-81.013030,-82.835542,-84.410812,-85.732285,-86.794163,-87.591377}, // NOLINT + {87.554551,86.763068,85.706682,84.390388,82.819972,81.001956,78.943437,76.652320,74.136798,71.405874,68.468779,65.335289,62.015686,58.520408,54.860343,51.046695,47.090965,43.004523,38.799548,34.487973,30.081904,25.594029,21.035827,16.421141,11.761807,7.070617,2.360324,-2.356325,-7.066630,-11.757844,-16.417214,-21.031947,-25.590208,-30.078154,-34.484304,-38.795971,-43.001049,-47.087605,-51.043459,-54.857241,-58.517448,-62.012877,-65.332640,-68.466298,-71.403568,-74.134673,-76.650382,-78.941692,-81.000409,-82.818627,-84.389247,-85.705748,-86.762344,-87.554036}, // NOLINT + {87.517192,86.731265,85.680135,84.368812,82.803052,80.989343,78.934834,76.647274,74.134992,71.406860,68.472206,65.340824,62.022886,58.528921,54.869920,51.056904,47.101427,43.015016,38.809713,34.497580,30.090723,25.601649,21.042482,16.426481,11.765695,7.073002,2.361132,-2.357133,-7.069015,-11.761732,-16.422555,-21.038602,-25.597828,-30.086974,-34.493912,-38.806138,-43.011544,-47.098070,-51.053670,-54.866820,-58.525964,-62.020080,-65.338179,-68.469729,-71.404558,-74.132872,-76.645342,-78.933096,-80.987802,-82.801714,-84.367678,-85.679209,-86.730548,-87.516686}, // NOLINT + {87.479806,86.699432,85.653580,84.347230,82.786125,80.976740,78.926197,76.642220,74.133151,71.407864,68.475697,65.346376,62.030170,58.537506,54.879453,51.067054,47.111830,43.025552,38.819897,34.507029,30.099563,25.609448,21.049148,16.431835,11.769616,7.075340,2.361916,-2.357918,-7.071354,-11.765653,-16.427909,-21.045269,-25.605628,-30.095814,-34.503362,-38.816323,-43.022082,-47.108474,-51.063822,-54.876355,-58.534552,-62.027369,-65.343735,-68.473224,-71.405567,-74.131036,-76.640294,-78.924465,-80.975207,-82.784794,-84.346104,-85.652662,-86.698724,-87.479307}, // NOLINT + {86.103959,85.307075,84.252666,82.945471,81.391031,79.595483,77.565508,75.308696,72.832955,70.146799,67.259156,64.179543,60.917629,57.483774,53.888390,50.142411,46.256915,42.243317,38.113195,33.878113,29.550318,25.141763,20.664638,16.131473,11.554360,6.946093,2.318746,-2.314747,-6.942106,-11.550396,-16.127543,-20.660754,-25.137935,-29.546558,-33.874432,-38.109604,-42.239824,-46.253532,-50.139148,-53.885256,-57.480778,-60.914780,-64.176848,-67.256624,-70.144437,-72.830769,-75.306693,-77.563694,-79.593862,-81.389608,-82.944249,-84.251648,-85.306264,-86.103356}, // NOLINT + {86.042728,85.251171,84.201913,82.899682,81.349958,79.558892,77.533148,75.280311,72.808264,70.125432,67.241001,64.164159,60.904987,57.473308,53.879932,50.135706,46.251709,42.239313,38.110186,33.876081,29.548897,25.140865,20.664187,16.131116,11.554226,6.946085,2.318757,-2.314758,-6.942098,-11.550262,-16.127186,-20.660303,-25.137038,-29.545138,-33.872401,-38.106595,-42.235823,-46.248328,-50.132445,-53.876801,-57.470315,-60.902140,-64.161467,-67.238473,-70.123074,-72.806083,-75.278313,-77.531339,-79.557277,-81.348541,-82.898466,-84.200901,-85.250366,-86.042131}, // NOLINT + {85.981465,85.195237,84.151134,82.853859,81.308860,79.522265,77.500817,75.251905,72.783577,70.104251,67.222865,64.148794,60.892140,57.462847,53.871444,50.129016,46.246518,42.235396,38.107435,33.874018,29.547516,25.140062,20.663727,16.130831,11.554019,6.945835,2.318712,-2.314713,-6.941848,-11.550055,-16.126901,-20.659843,-25.136236,-29.543758,-33.870339,-38.103846,-42.231907,-46.243139,-50.125757,-53.868315,-57.459857,-60.889297,-64.146106,-67.220341,-70.101897,-72.781401,-75.249912,-77.499013,-79.520655,-81.307448,-82.852649,-84.150130,-85.194439,-85.980876}, // NOLINT + {85.920168,85.139277,84.100335,82.808027,81.267742,79.485651,77.468433,75.223538,72.758885,70.082990,67.204730,64.133570,60.879414,57.452411,53.863072,50.122339,46.241342,42.231493,38.104386,33.871977,29.546103,25.139056,20.663261,16.130545,11.553911,6.945772,2.318698,-2.314699,-6.941786,-11.549947,-16.126616,-20.659377,-25.135230,-29.542345,-33.868299,-38.100798,-42.228005,-46.237965,-50.119082,-53.859945,-57.449423,-60.876574,-64.130885,-67.202210,-70.080640,-72.756713,-75.221550,-77.466635,-79.484047,-81.266336,-82.806824,-84.099337,-85.138486,-85.919586}, // NOLINT + {85.858828,85.083292,84.049518,82.762159,81.226625,79.449003,77.436068,75.195140,72.734205,70.061699,67.186607,64.118360,60.866680,57.441988,53.854684,50.115670,46.236173,42.227591,38.101558,33.869957,29.544767,25.138237,20.662791,16.130188,11.553774,6.945723,2.318694,-2.314695,-6.941736,-11.549810,-16.126259,-20.658908,-25.134411,-29.541010,-33.866280,-38.097971,-42.224104,-46.232797,-50.112415,-53.851559,-57.439002,-60.863843,-64.115679,-67.184090,-70.059354,-72.732037,-75.193156,-77.434275,-79.447404,-81.225226,-82.760962,-84.048527,-85.082508,-85.858253}, // NOLINT + {85.797480,85.027283,83.998675,82.716286,81.185500,79.412431,77.403690,75.166753,72.709543,70.040338,67.168490,64.103056,60.853864,57.431546,53.846376,50.109017,46.231034,42.223678,38.098697,33.867921,29.543400,25.137329,20.661780,16.129849,11.553646,6.945667,2.318669,-2.314670,-6.941680,-11.549682,-16.125920,-20.657897,-25.133504,-29.539643,-33.864244,-38.095110,-42.220192,-46.227660,-50.105764,-53.843253,-57.428564,-60.851030,-64.100379,-67.165977,-70.037997,-72.707380,-75.164775,-77.401902,-79.410838,-81.184106,-82.715095,-83.997690,-85.026506,-85.796912}, // NOLINT + {85.736073,84.971240,83.947810,82.670395,81.144364,79.375758,77.371316,75.138399,72.684891,70.019235,67.150379,64.087801,60.841336,57.421158,53.837955,50.102385,46.225902,42.219765,38.095916,33.865943,29.542061,25.136468,20.661298,16.129741,11.553529,6.945613,2.318645,-2.314647,-6.941626,-11.549566,-16.125812,-20.657415,-25.132644,-29.538306,-33.862267,-38.092331,-42.216281,-46.222530,-50.099134,-53.834835,-57.418178,-60.838504,-64.085127,-67.147870,-70.016898,-72.682733,-75.136426,-77.369534,-79.374171,-81.142977,-82.669211,-83.946833,-84.970471,-85.735513}, // NOLINT + {85.674650,84.915173,83.896925,82.624480,81.103208,79.339117,77.338938,75.110000,72.660195,69.997998,67.132294,64.072569,60.828703,57.410776,53.829512,50.095775,46.220785,42.216106,38.093050,33.863939,29.540731,25.135632,20.660819,16.129480,11.553413,6.945568,2.318654,-2.314655,-6.941581,-11.549450,-16.125552,-20.656937,-25.131808,-29.536976,-33.860264,-38.089466,-42.212623,-46.217414,-50.092526,-53.826395,-57.407799,-60.825875,-64.069899,-67.129788,-69.995665,-72.658042,-75.108032,-77.337161,-79.337536,-81.101827,-82.623303,-83.895954,-84.914411,-85.674097}, // NOLINT + {85.613190,84.859076,83.846017,82.578564,81.062044,79.302510,77.306558,75.081579,72.635528,69.976718,67.114192,64.057344,60.816000,57.400406,53.821160,50.089048,46.215681,42.211923,38.090266,33.861983,29.539553,25.134770,20.660346,16.129177,11.553286,6.945522,2.318643,-2.314644,-6.941535,-11.549323,-16.125249,-20.656464,-25.130947,-29.535799,-33.858310,-38.086683,-42.208442,-46.212312,-50.085802,-53.818045,-57.397431,-60.813175,-64.054677,-67.111691,-69.974389,-72.633379,-75.079616,-77.304786,-79.300935,-81.060669,-82.577393,-83.845053,-84.858321,-85.612645}, // NOLINT + {85.551700,84.802957,83.795089,82.532624,81.020871,79.265827,77.274176,75.053218,72.610851,69.955503,67.096119,64.042120,60.803361,57.390053,53.812835,50.082539,46.210588,42.208137,38.087508,33.860178,29.538106,25.134052,20.659878,16.128906,11.553165,6.945481,2.318627,-2.314629,-6.941494,-11.549201,-16.124978,-20.655997,-25.130229,-29.534352,-33.856505,-38.083927,-42.204658,-46.207220,-50.079294,-53.809722,-57.387082,-60.800539,-64.039456,-67.093622,-69.953179,-72.608707,-75.051259,-77.272410,-79.264257,-81.019502,-82.531460,-83.794132,-84.802209,-85.551162}, // NOLINT + {85.490187,84.746810,83.744139,82.486670,80.979683,79.229170,77.241790,75.024907,72.586154,69.934194,67.078044,64.026846,60.790714,57.379711,53.804490,50.075997,46.205517,42.204492,38.084762,33.858122,29.536812,25.133183,20.659417,16.128705,11.553060,6.945445,2.318616,-2.314618,-6.941458,-11.549097,-16.124777,-20.655536,-25.129361,-29.533059,-33.854450,-38.081182,-42.201014,-46.202152,-50.072754,-53.801380,-57.376742,-60.787895,-64.024186,-67.075550,-69.931874,-72.584015,-75.022954,-77.240029,-79.227606,-80.978321,-82.485513,-83.743189,-84.746069,-85.489657}, // NOLINT + {85.428622,84.690640,83.693169,82.440697,80.938489,79.192539,77.209399,74.996452,72.561508,69.913063,67.059990,64.011784,60.778116,57.369390,53.796198,50.069411,46.200459,42.200697,38.081929,33.856150,29.535533,25.132367,20.658963,16.128569,11.552963,6.945411,2.318615,-2.314616,-6.941425,-11.549000,-16.124641,-20.655082,-25.128545,-29.531781,-33.852479,-38.078350,-42.197220,-46.197096,-50.066170,-53.793090,-57.366423,-60.775300,-64.009127,-67.057500,-69.910748,-72.559373,-74.994504,-77.207643,-79.190981,-80.937133,-82.439546,-83.692226,-84.689907,-85.428099}, // NOLINT + {85.367037,84.634439,83.642178,82.394711,80.897239,79.155813,77.177017,74.968063,72.536948,69.891911,67.041939,63.996553,60.765454,57.359068,53.787894,50.062914,46.195422,42.196914,38.079187,33.854227,29.534269,25.131597,20.658516,16.128030,11.553007,6.945382,2.318622,-2.314624,-6.941395,-11.549044,-16.124102,-20.654635,-25.127775,-29.530518,-33.850557,-38.075609,-42.193439,-46.192060,-50.059675,-53.784788,-57.356104,-60.762642,-63.993900,-67.039453,-69.889599,-72.534817,-74.966120,-77.175267,-79.154261,-80.895889,-82.393567,-83.641242,-84.633713,-85.366521}, // NOLINT + {85.305389,84.578198,83.591168,82.348709,80.856063,79.119191,77.144613,74.939693,72.512193,69.870662,67.023898,63.981324,60.752953,57.348798,53.779622,50.056401,46.190396,42.193146,38.076463,33.852364,29.533035,25.130751,20.658077,16.127863,11.552774,6.945355,2.318572,-2.314573,-6.941368,-11.548811,-16.123935,-20.654197,-25.126930,-29.529284,-33.848694,-38.072886,-42.189672,-46.187036,-50.053164,-53.776519,-57.345837,-60.750144,-63.978674,-67.021416,-69.868355,-72.510067,-74.937755,-77.142869,-79.117645,-80.854719,-82.347571,-83.590238,-84.577479,-85.304881}, // NOLINT + {85.243759,84.521976,83.540137,82.302723,80.814849,79.082498,77.112221,74.911312,72.487635,69.849468,67.005868,63.966207,60.740254,57.338535,53.771363,50.049898,46.185306,42.189397,38.073736,33.850463,29.531729,25.129908,20.657646,16.127632,11.552671,6.945327,2.318577,-2.314578,-6.941341,-11.548708,-16.123705,-20.653766,-25.126088,-29.527979,-33.846794,-38.070161,-42.185924,-46.181947,-50.046663,-53.768262,-57.335577,-60.737448,-63.963560,-67.003389,-69.847165,-72.485514,-74.909379,-77.110482,-79.080958,-80.813511,-82.301591,-83.539215,-84.521264,-85.243259}, // NOLINT + {85.182094,84.465691,83.489086,82.256662,80.773563,79.045822,77.079823,74.882941,72.462994,69.828221,66.987847,63.951054,60.727763,57.328265,53.763121,50.043403,46.180506,42.185661,38.071062,33.848553,29.530518,25.129236,20.657224,16.127639,11.552643,6.945307,2.318574,-2.314575,-6.941321,-11.548681,-16.123712,-20.653344,-25.125416,-29.526769,-33.844886,-38.067487,-42.182190,-46.177150,-50.040171,-53.760022,-57.325310,-60.724960,-63.948411,-66.985372,-69.825923,-72.460878,-74.881014,-77.078090,-79.044287,-80.772232,-82.255537,-83.488171,-84.464986,-85.181601}, // NOLINT + {85.120377,84.409391,83.438016,82.210616,80.732350,79.009094,77.047428,74.854562,72.438497,69.807112,66.969830,63.935894,60.715240,57.317794,53.754890,50.036926,46.175413,42.181941,38.068347,33.846698,29.529275,25.128752,20.656810,16.127354,11.552529,6.945285,2.318612,-2.314614,-6.941299,-11.548566,-16.123427,-20.652931,-25.124933,-29.525526,-33.843032,-38.064774,-42.178472,-46.172058,-50.033696,-53.751794,-57.314841,-60.712440,-63.933255,-66.967359,-69.804818,-72.436386,-74.852640,-77.045701,-79.007565,-80.731025,-82.209498,-83.437107,-84.408694,-85.119892}, // NOLINT + {85.058626,84.353063,83.386925,82.164553,80.691102,78.972396,77.015029,74.826135,72.413701,69.785944,66.951835,63.920741,60.702676,57.307830,53.746667,50.030426,46.170454,42.178236,38.065689,33.844615,29.528102,25.127821,20.656406,16.127272,11.552462,6.945271,2.318605,-2.314606,-6.941285,-11.548500,-16.123346,-20.652527,-25.124002,-29.524354,-33.840949,-38.062117,-42.174768,-46.167100,-50.027198,-53.743574,-57.304881,-60.699879,-63.918105,-66.949369,-69.783654,-72.411595,-74.824218,-77.013307,-78.970873,-80.689783,-82.163441,-83.386024,-84.352373,-85.058149}, // NOLINT + {84.996840,84.296715,83.335815,82.118480,80.649783,78.935726,76.982623,74.797813,72.389089,69.764812,66.933846,63.905660,60.690174,57.297516,53.738472,50.024144,46.165606,42.174675,38.063049,33.842881,29.526922,25.127067,20.656011,16.127010,11.552398,6.945266,2.318578,-2.314579,-6.941279,-11.548436,-16.123084,-20.652133,-25.123248,-29.523175,-33.839216,-38.059478,-42.171208,-46.162255,-50.020918,-53.735381,-57.294569,-60.687381,-63.903028,-66.931384,-69.762527,-72.386987,-74.795901,-76.980906,-78.934210,-80.648471,-82.117376,-83.334921,-84.296033,-84.996371}, // NOLINT + {84.935051,84.240340,83.284686,82.072387,80.608573,78.899043,76.950221,74.769449,72.364454,69.743669,66.915866,63.890593,60.677542,57.287309,53.730297,50.017749,46.160578,42.171026,38.060374,33.841205,29.525700,25.126335,20.655625,16.126811,11.552342,6.945263,2.318596,-2.314597,-6.941277,-11.548380,-16.122885,-20.651747,-25.122517,-29.521954,-33.837541,-38.056805,-42.167561,-46.157229,-50.014525,-53.727208,-57.284366,-60.674752,-63.887965,-66.913408,-69.741389,-72.362358,-74.767542,-76.948510,-78.897533,-80.607267,-82.071289,-83.283798,-84.239665,-84.934590}, // NOLINT + {84.873218,84.183945,83.233538,82.026284,80.567281,78.862266,76.917797,74.741080,72.339846,69.722589,66.897903,63.875592,60.665138,57.277120,53.722111,50.011215,46.155668,42.167266,38.057749,33.839413,29.524507,25.125550,20.655249,16.126677,11.552291,6.945259,2.318612,-2.314613,-6.941272,-11.548329,-16.122751,-20.651371,-25.121732,-29.520761,-33.835750,-38.054181,-42.163803,-46.152321,-50.007994,-53.719025,-57.274179,-60.662351,-63.872968,-66.895449,-69.720312,-72.337755,-74.739179,-76.916092,-78.860762,-80.565982,-82.025193,-83.232658,-84.183277,-84.872764}, // NOLINT + {84.811356,84.127518,83.182366,81.980170,80.525951,78.825578,76.885404,74.712711,72.315204,69.701384,66.879944,63.860407,60.652689,57.266994,53.713969,50.004803,46.150770,42.163572,38.055136,33.837601,29.523365,25.124958,20.654883,16.126628,11.552234,6.945253,2.318594,-2.314596,-6.941266,-11.548272,-16.122702,-20.651005,-25.121141,-29.519620,-33.833940,-38.051568,-42.160111,-46.147424,-50.001583,-53.710886,-57.264056,-60.649906,-63.857786,-66.877494,-69.699112,-72.313117,-74.710815,-76.883705,-78.824080,-80.524658,-81.979086,-83.181493,-84.126858,-84.810910}, // NOLINT + {84.749466,84.071064,83.131181,81.934033,80.484657,78.788830,76.853073,74.684349,72.290644,69.680306,66.862114,63.845350,60.640155,57.256775,53.705834,49.998450,46.145896,42.159948,38.052543,33.835885,29.522246,25.124283,20.654526,16.126418,11.552196,6.945267,2.318625,-2.314627,-6.941281,-11.548234,-16.122493,-20.650649,-25.120467,-29.518502,-33.832224,-38.048977,-42.156487,-46.142552,-49.995233,-53.702753,-57.253839,-60.637374,-63.842733,-66.859668,-69.678039,-72.288562,-74.682458,-76.851380,-78.787338,-80.483371,-81.932955,-83.130316,-84.070411,-84.749028}, // NOLINT + {84.687541,84.014601,83.079976,81.887885,80.443342,78.752115,76.820597,74.655995,72.266049,69.659108,66.844056,63.830309,60.627725,57.246657,53.697716,49.992030,46.141034,42.156335,38.049950,33.834085,29.521126,25.123610,20.654179,16.126297,11.552122,6.945305,2.318616,-2.314617,-6.941319,-11.548160,-16.122372,-20.650303,-25.119794,-29.517383,-33.830425,-38.046385,-42.152876,-46.137692,-49.988815,-53.694638,-57.243725,-60.624948,-63.827696,-66.841614,-69.656845,-72.263972,-74.654110,-76.818910,-78.750629,-80.442062,-81.886815,-83.079118,-84.013956,-84.687111}, // NOLINT + {84.625612,83.958108,83.028753,81.841729,80.402017,78.715361,76.788215,74.627643,72.241495,69.637995,66.826137,63.815274,60.615304,57.236486,53.689596,49.985703,46.136186,42.152756,38.047434,33.832333,29.519753,25.123065,20.653843,16.126093,11.552141,6.945282,2.318617,-2.314619,-6.941296,-11.548179,-16.122168,-20.649967,-25.119249,-29.516010,-33.828675,-38.043870,-42.149299,-46.132845,-49.982489,-53.686520,-57.233557,-60.612530,-63.812664,-66.823699,-69.635737,-72.239423,-74.625763,-76.786533,-78.713882,-80.400744,-81.840665,-83.027901,-83.957471,-84.625190}, // NOLINT + {84.563631,83.901587,82.977513,81.795560,80.360687,78.678576,76.755779,74.599283,72.216880,69.616892,66.808212,63.800275,60.602871,57.226395,53.681519,49.979392,46.131368,42.149176,38.044843,33.830641,29.518921,25.122318,20.653516,16.125920,11.552116,6.945284,2.318623,-2.314624,-6.941298,-11.548155,-16.121995,-20.649641,-25.118503,-29.515179,-33.826983,-38.041281,-42.145720,-46.128030,-49.976181,-53.678445,-57.223468,-60.600100,-63.797669,-66.805778,-69.614638,-72.214813,-74.597409,-76.754103,-78.677102,-80.359420,-81.794503,-82.976669,-83.900957,-84.563216}, // NOLINT + {84.501615,83.845052,82.926256,81.749376,80.319387,78.641877,76.723509,74.570938,72.192302,69.595815,66.790356,63.785216,60.590462,57.216280,53.673463,49.973091,46.126543,42.145610,38.042316,33.828884,29.517771,25.121825,20.653200,16.125904,11.551967,6.945303,2.318642,-2.314644,-6.941317,-11.548005,-16.121980,-20.649325,-25.118011,-29.514029,-33.825227,-38.038755,-42.142156,-46.123206,-49.969882,-53.670392,-57.213356,-60.587694,-63.782614,-66.787927,-69.593565,-72.190240,-74.569069,-76.721838,-78.640409,-80.318127,-81.748326,-82.925420,-83.844430,-84.501208}, // NOLINT + {84.439582,83.788519,82.874983,81.703179,80.277998,78.605126,76.690972,74.542593,72.167744,69.574733,66.772435,63.770249,60.578065,57.206246,53.665416,49.966808,46.121766,42.142052,38.039809,33.827185,29.516710,25.121067,20.652894,16.125742,11.552162,6.945320,2.318642,-2.314644,-6.941334,-11.548201,-16.121818,-20.649019,-25.117253,-29.512970,-33.823529,-38.036249,-42.138599,-46.118432,-49.963602,-53.662347,-57.203325,-60.575301,-63.767651,-66.770009,-69.572488,-72.165686,-74.540729,-76.689307,-78.603665,-80.276744,-81.702136,-82.874153,-83.787905,-84.439184}, // NOLINT + {84.377520,83.731907,82.823691,81.656968,80.236646,78.568397,76.658541,74.514232,72.143180,69.553648,66.754521,63.755272,60.565731,57.196125,53.657375,49.960563,46.116961,42.138563,38.037314,33.825535,29.515644,25.120461,20.652598,16.125574,11.552089,6.945347,2.318659,-2.314661,-6.941361,-11.548128,-16.121650,-20.648724,-25.116648,-29.511904,-33.821880,-38.033756,-42.135112,-46.113628,-49.957358,-53.654310,-57.193208,-60.562970,-63.752677,-66.752100,-69.551408,-72.141128,-74.512373,-76.656882,-78.566942,-80.235400,-81.655932,-82.822869,-83.731300,-84.377129}, // NOLINT + {84.315432,83.675300,82.772382,81.610745,80.195278,78.531629,76.626137,74.485915,72.118625,69.532592,66.736685,63.740295,60.553326,57.186087,53.649407,49.954202,46.112223,42.135087,38.034812,33.823855,29.514639,25.119952,20.652313,16.125511,11.552099,6.945372,2.318680,-2.314682,-6.941386,-11.548137,-16.121587,-20.648439,-25.116140,-29.510900,-33.820201,-38.031255,-42.131637,-46.108892,-49.950999,-53.646343,-57.183172,-60.550569,-63.737704,-66.734268,-69.530357,-72.116577,-74.484062,-76.624484,-78.530180,-80.194038,-81.609717,-82.771567,-83.674701,-84.315049}, // NOLINT + {84.253316,83.618673,82.721055,81.564512,80.153910,78.494866,76.593739,74.457581,72.094062,69.511541,66.718825,63.725364,60.540932,57.176104,53.641358,49.947995,46.107451,42.131593,38.032392,33.821970,29.513557,25.119301,20.652038,16.125404,11.552014,6.945396,2.318689,-2.314690,-6.941410,-11.548053,-16.121480,-20.648164,-25.115489,-29.509819,-33.818318,-38.028836,-42.128145,-46.104122,-49.944795,-53.638297,-57.173192,-60.538178,-63.722777,-66.716413,-69.509311,-72.092020,-74.455734,-76.592092,-78.493424,-80.152677,-81.563491,-82.720248,-83.618082,-84.252941}, // NOLINT + {84.191174,83.562023,82.669711,81.518270,80.112522,78.458082,76.561385,74.429250,72.069468,69.490501,66.701023,63.710390,60.528653,57.166056,53.633404,49.941775,46.102738,42.128104,38.029857,33.820625,29.512544,25.118704,20.651773,16.125354,11.552062,6.945428,2.318712,-2.314714,-6.941442,-11.548101,-16.121431,-20.647900,-25.114892,-29.508807,-33.816973,-38.026302,-42.124657,-46.099411,-49.938577,-53.630346,-57.163148,-60.525903,-63.707807,-66.698614,-69.488275,-72.067432,-74.427409,-76.559744,-78.456646,-80.111296,-81.517255,-82.668911,-83.561439,-84.190807}, // NOLINT + {82.877074,82.217994,81.304502,80.140451,78.730482,77.079904,75.194840,73.081959,70.748643,68.202819,65.452995,62.508188,59.377904,56.072072,52.601063,48.975767,45.207129,41.306617,37.285965,33.157141,28.932364,24.623953,20.244460,15.806976,11.323771,6.808057,2.272886,-2.268888,-6.804070,-11.319808,-15.803049,-20.240580,-24.620132,-28.928613,-33.153472,-37.282388,-41.303144,-45.203769,-48.972530,-52.597960,-56.069112,-59.375095,-62.505539,-65.450514,-68.200512,-70.746518,-73.080022,-75.193097,-77.078359,-78.729141,-80.139316,-81.303576,-82.217280,-82.876573}, // NOLINT + {82.792258,82.138366,81.229976,80.070923,78.665793,77.020027,75.139455,73.030969,70.701862,68.160027,65.414061,62.472869,59.346011,56.043426,52.575473,48.952932,45.186998,41.288974,37.270783,33.144006,28.921265,24.614767,20.237182,15.801260,11.319761,6.805744,2.272087,-2.268089,-6.801758,-11.315798,-15.797333,-20.233302,-24.610947,-28.917515,-33.140338,-37.267208,-41.285502,-45.183639,-48.949698,-52.572373,-56.040468,-59.343205,-62.470223,-65.411583,-68.157724,-70.699742,-73.029037,-75.137717,-77.018488,-78.664457,-80.069793,-81.229056,-82.137658,-82.791763}, // NOLINT + {82.707396,82.058702,81.155422,80.001365,78.601123,76.960059,75.084074,72.979983,70.655083,68.117308,65.375129,62.437596,59.314144,56.014774,52.549873,48.929979,45.166870,41.271348,37.255329,33.130867,28.910130,24.605366,20.229895,15.795578,11.315795,6.803547,2.271316,-2.267318,-6.799560,-11.311833,-15.791651,-20.226016,-24.601546,-28.906381,-33.127200,-37.251754,-41.267877,-45.163513,-48.926747,-52.546774,-56.011819,-59.311341,-62.434953,-65.372654,-68.115009,-70.652967,-72.978056,-75.082341,-76.958525,-78.599792,-80.000242,-81.154508,-82.058001,-82.706908}, // NOLINT + {82.622495,81.979004,81.080837,79.931789,78.536402,76.900061,75.028675,72.929013,70.608265,68.074519,65.336204,62.402274,59.282290,55.986133,52.524289,48.907574,45.146767,41.253662,37.240065,33.117741,28.899010,24.596427,20.222604,15.789981,11.311832,6.800976,2.270519,-2.266520,-6.796990,-11.307870,-15.786055,-20.218725,-24.592608,-28.895261,-33.114074,-37.236491,-41.250193,-45.143412,-48.904343,-52.521193,-55.983180,-59.279489,-62.399634,-65.333734,-68.072224,-70.606154,-72.927090,-75.026946,-76.898533,-78.535078,-79.930672,-81.079930,-81.978309,-82.622014}, // NOLINT + {82.537546,81.899269,81.006224,79.862161,78.471696,76.840105,74.973275,72.877999,70.561563,68.031832,65.297284,62.366984,59.250407,55.957508,52.498669,48.884723,45.126671,41.236137,37.224743,33.104614,28.887963,24.587217,20.215308,15.784425,11.307863,6.798626,2.269732,-2.265734,-6.794640,-11.303901,-15.780499,-20.211430,-24.583398,-28.884215,-33.100948,-37.221171,-41.232669,-45.123318,-48.881495,-52.495575,-55.954557,-59.247609,-62.364348,-65.294817,-68.029541,-70.559455,-72.876080,-74.971552,-76.838582,-78.470377,-79.861050,-81.005324,-81.898581,-82.537072}, // NOLINT + {82.452569,81.819500,80.931583,79.792568,78.406991,76.780073,74.917865,72.826967,70.514782,67.989036,65.258373,62.331703,59.218621,55.928886,52.473088,48.862036,45.106592,41.218617,37.209477,33.091508,28.876902,24.578140,20.208011,15.778706,11.303887,6.796261,2.268949,-2.264951,-6.792275,-11.299924,-15.774780,-20.204133,-24.574322,-28.873154,-33.087843,-37.205905,-41.215150,-45.103240,-48.858810,-52.469996,-55.925938,-59.215826,-62.329070,-65.255910,-67.986749,-70.512678,-72.825053,-74.916147,-76.778556,-78.405677,-79.791463,-80.930689,-81.818818,-82.452102}, // NOLINT + {82.367542,81.739696,80.856913,79.722918,78.342221,76.720014,74.862441,72.775984,70.468029,67.946293,65.219451,62.296396,59.186717,55.900458,52.447512,48.839315,45.086524,41.200675,37.194203,33.078424,28.865824,24.568970,20.200188,15.773005,11.299944,6.793912,2.268156,-2.264157,-6.789926,-11.295982,-15.769079,-20.196310,-24.565152,-28.862078,-33.074760,-37.190633,-41.197209,-45.083173,-48.836090,-52.444422,-55.897513,-59.183925,-62.293766,-65.216991,-67.944010,-70.465930,-72.774075,-74.860728,-76.718502,-78.340914,-79.721819,-80.856025,-81.739022,-82.367082}, // NOLINT + {82.282476,81.659860,80.782215,79.653257,78.277472,76.660055,74.807011,72.724961,70.421172,67.903565,65.180552,62.261122,59.154885,55.871662,52.421956,48.816595,45.066463,41.183184,37.178976,33.065383,28.854790,24.559687,20.192881,15.767551,11.295979,6.791560,2.267400,-2.263402,-6.787573,-11.292017,-15.763625,-20.189004,-24.555870,-28.851044,-33.061720,-37.175407,-41.179720,-45.063114,-48.813372,-52.418868,-55.868720,-59.152096,-62.258495,-65.178096,-67.901286,-70.419078,-72.723057,-74.805303,-76.658548,-78.276171,-79.652164,-80.781334,-81.659192,-82.282023}, // NOLINT + {82.197366,81.579990,80.707490,79.583563,78.212660,76.600025,74.751578,72.673916,70.374407,67.860797,65.141647,62.225903,59.123059,55.843106,52.396413,48.793893,45.046508,41.165800,37.163709,33.052278,28.843800,24.550697,20.185579,15.761965,11.292047,6.789211,2.266600,-2.262602,-6.785224,-11.288085,-15.758040,-20.181701,-24.546880,-28.840054,-33.048616,-37.160141,-41.162338,-45.043161,-48.790672,-52.393327,-55.840166,-59.120273,-62.223279,-65.139194,-67.858522,-70.372316,-72.672017,-74.749875,-76.598524,-78.211364,-79.582476,-80.706615,-81.579328,-82.196920}, // NOLINT + {82.112219,81.500081,80.632735,79.513847,78.147861,76.540012,74.696137,72.622954,70.327629,67.818080,65.102754,62.190664,59.091290,55.814551,52.370863,48.771202,45.026387,41.148257,37.148540,33.039154,28.832735,24.541561,20.178281,15.756333,11.288063,6.786861,2.265833,-2.261834,-6.782875,-11.284101,-15.752407,-20.174404,-24.537745,-28.828990,-33.035493,-37.144973,-41.144795,-45.023041,-48.767983,-52.367780,-55.811614,-59.088507,-62.188044,-65.100305,-67.815810,-70.325543,-72.621059,-74.694439,-76.538516,-78.146571,-79.512766,-80.631867,-81.499427,-82.111780}, // NOLINT + {82.027023,81.420136,80.557951,79.444109,78.083059,76.479927,74.640684,72.571920,70.280842,67.775344,65.063865,62.155342,59.059441,55.785962,52.345346,48.748491,45.006372,41.130724,37.133279,33.026206,28.821715,24.532534,20.170988,15.750713,11.284134,6.784511,2.265052,-2.261054,-6.780525,-11.280172,-15.746788,-20.167111,-24.528718,-28.817971,-33.022545,-37.129713,-41.127263,-45.003028,-48.745274,-52.342265,-55.783027,-59.056661,-62.152725,-65.061420,-67.773077,-70.278761,-72.570031,-74.638991,-76.478437,-78.081775,-79.443035,-80.557089,-81.419488,-82.026591}, // NOLINT + {81.941790,81.340156,80.483137,79.374347,78.018200,76.419860,74.585224,72.520879,70.234052,67.732616,65.024988,62.120209,59.027645,55.757450,52.319827,48.725806,44.986452,41.113202,37.118094,33.013132,28.810711,24.523378,20.163700,15.745142,11.280175,6.782177,2.264269,-2.260271,-6.778191,-11.276213,-15.741216,-20.159824,-24.519562,-28.806968,-33.009472,-37.114530,-41.109744,-44.983110,-48.722590,-52.316748,-55.754517,-59.024867,-62.117595,-65.022546,-67.730353,-70.231975,-72.518994,-74.583536,-76.418376,-78.016922,-79.373279,-80.482281,-81.339515,-81.941366}, // NOLINT + {81.856514,81.260140,80.408295,79.304567,77.953345,76.359810,74.529757,72.469844,70.187297,67.689883,64.986149,62.084945,58.995866,55.728848,52.294336,48.702789,44.966380,41.095696,37.102953,33.000137,28.799706,24.514274,20.156419,15.739629,11.276269,6.779835,2.263490,-2.259491,-6.775849,-11.272307,-15.735704,-20.152543,-24.510459,-28.795963,-32.996478,-37.099389,-41.092238,-44.963040,-48.699576,-52.291260,-55.725918,-58.993092,-62.082335,-64.983711,-67.687625,-70.185224,-72.467964,-74.528075,-76.358331,-77.952072,-79.303505,-80.407446,-81.259507,-81.856096}, // NOLINT + {81.771198,81.180096,80.333428,79.234759,77.888467,76.299700,74.474287,72.418812,70.140463,67.647153,64.947262,62.049722,58.964128,55.700329,52.268841,48.680499,44.946401,41.078204,37.087733,32.987052,28.788714,24.505252,20.149144,15.734161,11.272338,6.777500,2.262718,-2.258720,-6.773514,-11.268376,-15.730236,-20.145269,-24.501437,-28.784972,-32.983394,-37.084171,-41.074748,-44.943062,-48.677288,-52.265767,-55.697402,-58.961357,-62.047115,-64.944828,-67.644899,-70.138395,-72.416937,-74.472610,-76.298227,-77.887201,-79.233704,-80.332586,-81.179469,-81.770788}, // NOLINT + {81.685839,81.100014,80.258529,79.164930,77.823574,76.239607,74.418793,72.367768,70.093717,67.604430,64.908372,62.014529,58.932326,55.671804,52.243385,48.657872,44.926442,41.060723,37.072572,32.974131,28.777777,24.496252,20.141877,15.728272,11.268372,6.775165,2.261954,-2.257956,-6.771179,-11.264410,-15.724347,-20.138001,-24.492437,-28.774035,-32.970474,-37.069010,-41.057269,-44.923104,-48.654663,-52.240314,-55.668880,-58.929558,-62.011926,-64.905941,-67.602179,-70.091654,-72.365897,-74.417122,-76.238139,-77.822313,-79.163881,-80.257693,-81.099395,-81.685436}, // NOLINT + {81.600438,81.019895,80.183600,79.095078,77.758591,76.179418,74.363305,72.316739,70.046957,67.561716,64.869514,61.979301,58.900573,55.643295,52.217899,48.635258,44.906485,41.043258,37.057415,32.961151,28.766825,24.487163,20.134616,15.722754,11.264508,6.772837,2.261196,-2.257197,-6.768851,-11.260547,-15.718830,-20.130741,-24.483350,-28.763084,-32.957495,-37.053854,-41.039804,-44.903149,-48.632051,-52.214830,-55.640373,-58.897808,-61.976700,-64.867087,-67.559470,-70.044898,-72.314873,-74.361639,-76.177956,-77.757337,-79.094035,-80.182771,-81.019282,-81.600042}, // NOLINT + {81.515013,80.939742,80.108643,79.025200,77.693742,76.119370,74.307809,72.265682,70.000147,67.518996,64.830665,61.944120,58.868774,55.614803,52.192480,48.612658,44.886550,41.025801,37.042315,32.948163,28.755859,24.477908,20.127363,15.717179,11.260572,6.770508,2.260374,-2.256375,-6.766522,-11.256611,-15.713255,-20.123488,-24.474095,-28.752119,-32.944507,-37.038756,-41.022349,-44.883216,-48.609452,-52.189413,-55.611884,-58.866012,-61.941523,-64.828242,-67.516754,-69.998093,-72.263822,-74.306148,-76.117913,-77.692494,-79.024164,-80.107821,-80.939136,-81.514624}, // NOLINT + {81.429518,80.859567,80.033657,78.955304,77.628795,76.059214,74.252300,72.214654,69.953352,67.476410,64.791822,61.908965,58.837087,55.586325,52.167018,48.590070,44.866621,41.008519,37.027168,32.935195,28.744892,24.469087,20.120117,15.711858,11.256717,6.768182,2.259606,-2.255608,-6.764196,-11.252756,-15.707934,-20.116243,-24.465274,-28.741153,-32.931541,-37.023610,-41.005069,-44.863289,-48.586867,-52.163953,-55.583409,-58.834328,-61.906372,-64.789402,-67.474172,-69.951302,-72.212798,-74.250644,-76.057763,-77.627552,-78.954274,-80.032842,-80.858968,-81.429137}, // NOLINT + {81.343988,80.779334,79.958643,78.885406,77.563853,75.999041,74.196777,72.163579,69.906570,67.433692,64.752973,61.873787,58.805391,55.557845,52.141669,48.567495,44.846705,40.991114,37.012058,32.922231,28.734033,24.459995,20.112880,15.706274,11.252796,6.765866,2.258830,-2.254832,-6.761880,-11.248835,-15.702351,-20.109005,-24.456183,-28.730295,-32.918577,-37.008501,-40.987665,-44.843375,-48.564294,-52.138606,-55.554931,-58.802635,-61.871197,-64.750557,-67.431458,-69.904525,-72.161728,-74.195126,-75.997595,-77.562617,-78.884382,-79.957834,-80.778743,-81.343614}, // NOLINT + {81.258406,80.699087,79.883599,78.815433,77.498852,75.938872,74.141267,72.112519,69.859813,67.390888,64.714135,61.838564,58.773662,55.529381,52.116175,48.544933,44.826819,40.973562,36.996916,32.909311,28.723027,24.450992,20.105650,15.700746,11.248851,6.763541,2.258089,-2.254090,-6.759555,-11.244890,-15.696822,-20.101776,-24.447180,-28.719289,-32.905658,-36.993360,-40.970115,-44.823491,-48.541733,-52.113115,-55.526470,-58.770909,-61.835977,-64.711723,-67.388658,-69.857773,-72.110674,-74.139622,-75.937432,-77.497622,-78.814416,-79.882798,-80.698502,-81.258039}, // NOLINT + {81.172808,80.618777,79.808528,78.745498,77.433848,75.878728,74.085740,72.061453,69.813002,67.348191,64.675305,61.803418,58.742060,55.500935,52.090771,48.522382,44.806986,40.956165,36.981863,32.896481,28.712199,24.441942,20.098429,15.695212,11.245153,6.761228,2.257315,-2.253316,-6.757242,-11.241192,-15.691289,-20.094555,-24.438131,-28.708461,-32.892829,-36.978309,-40.952718,-44.803659,-48.519185,-52.087713,-55.498027,-58.739311,-61.800835,-64.672897,-67.345966,-69.810966,-72.059613,-74.084100,-75.877294,-77.432624,-78.744487,-79.807732,-80.618200,-81.172448}, // NOLINT + {81.087175,80.538450,79.733427,78.675486,77.368873,75.818501,74.030202,72.010394,69.766256,67.305447,64.636486,61.768260,58.710315,55.472486,52.065387,48.499843,44.787058,40.938757,36.966808,32.883413,28.701288,24.432942,20.091216,15.689773,11.241097,6.758915,2.256555,-2.252557,-6.754929,-11.237137,-15.685850,-20.087343,-24.429131,-28.697551,-32.879762,-36.963255,-40.935312,-44.783733,-48.496647,-52.062332,-55.469580,-58.707568,-61.765680,-64.634082,-67.303226,-69.764224,-72.008559,-74.028568,-75.817073,-77.367655,-78.674482,-79.732639,-80.537879,-81.086824}, // NOLINT + {81.001463,80.458086,79.658294,78.605474,77.303815,75.758300,73.974660,71.959321,69.719456,67.262662,64.597671,61.733116,58.678556,55.444051,52.040013,48.477405,44.767218,40.921376,36.951731,32.870567,28.690340,24.424097,20.084011,15.684177,11.237153,6.756611,2.255783,-2.251785,-6.752625,-11.233193,-15.680254,-20.080138,-24.420286,-28.686604,-32.866917,-36.948178,-40.917932,-44.763895,-48.474211,-52.036961,-55.441148,-58.675812,-61.730540,-64.595270,-67.260445,-69.717429,-71.957490,-73.973031,-75.756878,-77.302604,-78.604476,-79.657512,-80.457523,-81.001119}, // NOLINT + {80.915734,80.377686,79.583136,78.535441,77.238731,75.698091,73.919105,71.908258,69.672658,67.220068,64.558860,61.697960,58.646972,55.415639,52.014657,48.454891,44.747364,40.904003,36.936687,32.857625,28.679485,24.414982,20.076815,15.678789,11.233330,6.754299,2.255028,-2.251030,-6.750314,-11.229369,-15.674866,-20.072943,-24.411172,-28.675750,-32.853976,-36.933136,-40.900561,-44.744042,-48.451700,-52.011607,-55.412739,-58.644232,-61.695387,-64.556464,-67.217855,-69.670636,-71.906433,-73.917482,-75.696675,-77.237526,-78.534450,-79.582362,-80.377130,-80.915397}, // NOLINT + {80.829956,80.297258,79.507950,78.465386,77.173748,75.637856,73.863545,71.857189,69.625876,67.177379,64.520061,61.662854,58.615255,55.387292,51.989305,48.432372,44.727542,40.886661,36.921653,32.844788,28.668712,24.406015,20.069628,15.673210,11.229474,6.751995,2.254253,-2.250254,-6.748009,-11.225514,-15.669287,-20.065756,-24.402205,-28.664977,-32.841140,-36.918103,-40.883220,-44.724222,-48.429183,-51.986257,-55.384395,-58.612518,-61.660285,-64.517669,-67.175171,-69.623859,-71.855369,-73.861927,-75.636445,-77.172549,-78.464401,-79.507183,-80.296709,-80.829627}, // NOLINT + {80.744144,80.216787,79.432736,78.395298,77.108645,75.577670,73.807979,71.806105,69.579112,67.134689,64.481247,61.627744,58.583645,55.358870,51.963972,48.409842,44.707726,40.869325,36.906640,32.831958,28.657786,24.397054,20.062450,15.667614,11.225523,6.749708,2.253504,-2.249506,-6.745722,-11.221562,-15.663692,-20.058578,-24.393245,-28.654052,-32.828311,-36.903092,-40.865886,-44.704408,-48.406655,-51.960926,-55.355975,-58.580910,-61.625178,-64.478858,-67.132485,-69.577099,-71.804289,-73.806367,-75.576266,-77.107452,-78.394320,-79.431975,-80.216245,-80.743822}, // NOLINT + {80.658279,80.136280,79.357491,78.325202,77.043530,75.517386,73.752431,71.755033,69.532518,67.092007,64.442509,61.592659,58.551973,55.330578,51.938652,48.387360,44.687926,40.851990,36.891639,32.819100,28.646941,24.388105,20.055281,15.662064,11.221609,6.747331,2.252726,-2.248727,-6.743346,-11.217649,-15.658142,-20.051409,-24.384296,-28.643208,-32.815454,-36.888092,-40.848553,-44.684609,-48.384175,-51.935609,-55.327686,-58.549241,-61.590097,-64.440125,-67.089808,-69.530510,-71.753222,-73.750824,-75.515987,-77.042343,-78.324231,-79.356737,-80.135745,-80.657965}, // NOLINT + {80.572382,80.055745,79.282218,78.255074,76.978411,75.457145,73.696829,71.703951,69.485483,67.049344,64.403694,61.557537,58.520406,55.302106,51.913355,48.364916,44.668205,40.834802,36.876612,32.806314,28.636177,24.379207,20.048121,15.656756,11.217875,6.745084,2.251965,-2.247967,-6.741098,-11.213915,-15.652834,-20.044250,-24.375400,-28.632444,-32.802669,-36.873065,-40.831366,-44.664891,-48.361733,-51.910314,-55.299217,-58.517678,-61.554978,-64.401314,-67.047149,-69.483480,-71.702146,-73.695227,-75.455752,-76.977230,-78.254110,-79.281472,-80.055218,-80.572076}, // NOLINT + {80.486439,79.975169,79.206918,78.184935,76.913289,75.396788,73.641245,71.652866,69.438763,67.006673,64.364902,61.522450,58.488735,55.273785,51.888060,48.342408,44.648370,40.817373,36.861674,32.793451,28.625368,24.370213,20.040969,15.651325,11.214024,6.742815,2.251211,-2.247213,-6.738829,-11.210064,-15.647403,-20.037099,-24.366405,-28.621636,-32.789806,-36.858128,-40.813938,-44.645057,-48.339227,-51.885022,-55.270898,-58.486010,-61.519895,-64.362525,-67.004482,-69.436764,-71.651066,-73.639649,-75.395401,-76.912115,-78.183977,-79.206178,-79.974650,-80.486141}, // NOLINT + {80.400452,79.894563,79.131590,78.114762,76.848130,75.336553,73.585659,71.601761,69.391995,66.963817,64.326150,61.487367,58.457144,55.245443,51.862777,48.320097,44.628620,40.800204,36.846711,32.780617,28.614632,24.361114,20.033827,15.645894,11.210334,6.740529,2.250448,-2.246449,-6.736544,-11.206374,-15.641973,-20.029957,-24.357307,-28.610901,-32.776974,-36.843167,-40.796771,-44.625309,-48.316918,-51.859741,-55.242560,-58.454422,-61.484816,-64.323778,-66.961630,-69.390001,-71.599966,-73.584069,-75.335172,-76.846962,-78.113811,-79.130857,-79.894051,-80.400161}, // NOLINT + {80.314427,79.813921,79.056234,78.044568,76.782965,75.276256,73.529988,71.550666,69.345212,66.921336,64.287401,61.452309,58.425534,55.217121,51.837521,48.297590,44.608887,40.782918,36.831763,32.767880,28.603775,24.352418,20.026695,15.640420,11.206389,6.738238,2.249697,-2.245699,-6.734253,-11.202430,-15.636498,-20.022825,-24.348612,-28.600045,-32.764238,-36.828220,-40.779486,-44.605578,-48.294413,-51.834488,-55.214240,-58.422816,-61.449762,-64.285032,-66.919153,-69.343223,-71.548876,-73.528404,-75.274881,-76.781804,-78.043623,-79.055508,-79.813416,-80.314144}, // NOLINT + {80.228365,79.733241,78.980850,77.974356,76.717780,75.215965,73.474441,71.499592,69.298441,66.878678,64.248658,61.417226,58.393948,55.188832,51.812274,48.275262,44.589154,40.765678,36.816830,32.755100,28.593006,24.343526,20.019571,15.634951,11.202532,6.735959,2.248942,-2.244944,-6.731973,-11.198573,-15.631030,-20.015701,-24.339720,-28.589276,-32.751459,-36.813288,-40.762248,-44.585846,-48.272087,-51.809243,-55.185955,-58.391233,-61.414682,-64.246293,-66.876501,-69.296457,-71.497808,-73.472863,-75.214596,-76.716625,-77.973418,-78.980132,-79.732744,-80.228089}, // NOLINT +}, // NOLINT +{ + {-13.736620,-18.402800,-22.994259,-27.497783,-31.900627,-36.191334,-40.357660,-44.389381,-48.276413,-52.009257,-55.579404,-58.978505,-62.199090,-65.234269,-68.077678,-70.723474,-73.166441,-75.401716,-77.425283,-79.233232,-80.822209,-82.189405,-83.332379,-84.249153,-84.938143,-85.398152,-85.628390,-85.628477,-85.398415,-84.938580,-84.249764,-83.333161,-82.190356,-80.823325,-79.234511,-77.426720,-75.403307,-73.168180,-70.725357,-68.079698,-65.236420,-62.201364,-58.980895,-55.581902,-52.011853,-48.279100,-44.392148,-40.360497,-36.194231,-31.903574,-27.500768,-22.997271,-18.405827,-13.739649}, // NOLINT + {-13.707078,-18.374858,-22.968519,-27.474640,-31.880461,-36.173978,-40.343765,-44.379017,-48.269803,-52.006596,-55.580593,-58.983447,-62.207998,-65.246972,-68.094109,-70.743525,-73.189844,-75.428507,-77.454984,-79.265653,-80.857064,-82.226383,-83.371198,-84.289450,-84.979537,-85.440293,-85.670908,-85.670996,-85.440556,-84.979976,-84.290062,-83.371981,-82.227335,-80.858182,-79.266934,-77.456424,-75.430100,-73.191586,-70.745411,-68.096132,-65.249126,-62.210275,-58.985840,-55.583093,-52.009195,-48.272492,-44.381786,-40.346605,-36.176877,-31.883409,-27.477626,-22.971532,-18.377885,-13.710107}, // NOLINT + {-13.677526,-18.346993,-22.942772,-27.451384,-31.860140,-36.156757,-40.329864,-44.368699,-48.263151,-52.003686,-55.581562,-58.988495,-62.216836,-65.259722,-68.110534,-70.763547,-73.213366,-75.455211,-77.484677,-79.298061,-80.891959,-82.263398,-83.410013,-84.329694,-85.020921,-85.482430,-85.713425,-85.713513,-85.482694,-85.021360,-84.330307,-83.410797,-82.264351,-80.893079,-79.299343,-77.486119,-75.456807,-73.215111,-70.765435,-68.112560,-65.261879,-62.219116,-58.990890,-55.584065,-52.006288,-48.265843,-44.371471,-40.332706,-36.159659,-31.863090,-27.454371,-22.945785,-18.350021,-13.680556}, // NOLINT + {-13.647891,-18.319202,-22.916985,-27.428097,-31.839545,-36.139495,-40.315815,-44.358458,-48.256450,-52.001037,-55.582590,-58.993402,-62.225678,-65.272337,-68.126952,-70.783549,-73.236897,-75.481853,-77.514359,-79.330456,-80.926731,-82.300388,-83.448829,-84.369996,-85.062323,-85.524572,-85.755943,-85.756031,-85.524836,-85.062763,-84.370610,-83.449614,-82.301343,-80.927853,-79.331741,-77.515803,-75.483452,-73.238644,-70.785440,-68.128981,-65.274496,-62.227961,-58.995800,-55.585095,-52.003642,-48.259144,-44.361232,-40.318658,-36.142398,-31.842497,-27.431085,-22.919999,-18.322230,-13.650920}, // NOLINT + {-13.618227,-18.291082,-22.891131,-27.404802,-31.819151,-36.122003,-40.301742,-44.347802,-48.249607,-51.997994,-55.583554,-58.998297,-62.234382,-65.284943,-68.143314,-70.803528,-73.260218,-75.508373,-77.544002,-79.362845,-80.961575,-82.337373,-83.487634,-84.410246,-85.103715,-85.566715,-85.798461,-85.798550,-85.566979,-85.104155,-84.410861,-83.488421,-82.338330,-80.962698,-79.364132,-77.545448,-75.509973,-73.261968,-70.805422,-68.145345,-65.287105,-62.236668,-59.000698,-55.586062,-52.000601,-48.252303,-44.350578,-40.304588,-36.124908,-31.822104,-27.407792,-22.894146,-18.294110,-13.621256}, // NOLINT + {-13.588489,-18.262985,-22.865232,-27.381359,-31.798552,-36.104547,-40.287838,-44.337298,-48.242912,-51.995000,-55.584493,-59.003147,-62.243175,-65.297557,-68.159659,-70.823483,-73.283619,-75.535132,-77.573646,-79.395220,-80.996442,-82.374354,-83.526402,-84.450546,-85.145126,-85.608856,-85.840976,-85.841065,-85.609121,-85.145567,-84.451161,-83.527190,-82.375313,-80.997568,-79.396508,-77.575095,-75.536735,-73.285371,-70.825379,-68.161693,-65.299722,-62.245464,-59.005551,-55.587004,-51.997610,-48.245611,-44.340077,-40.290686,-36.107453,-31.801507,-27.384350,-22.868248,-18.266014,-13.591518}, // NOLINT + {-13.558703,-18.234924,-22.839312,-27.357943,-31.777908,-36.087045,-40.273659,-44.326767,-48.236066,-51.991964,-55.585382,-59.007967,-62.251850,-65.310147,-68.175972,-70.843414,-73.306984,-75.561736,-77.603264,-79.427574,-81.031257,-82.411324,-83.565161,-84.490816,-85.186493,-85.651000,-85.883495,-85.883584,-85.651266,-85.186935,-84.491433,-83.565950,-82.412284,-81.032384,-79.428865,-77.604715,-75.563342,-73.308739,-70.845313,-68.178009,-65.312315,-62.254141,-59.010374,-55.587896,-51.994577,-48.238768,-44.329548,-40.276509,-36.089954,-31.780865,-27.360935,-22.842329,-18.237952,-13.561731}, // NOLINT + {-13.528728,-18.206803,-22.813318,-27.334519,-31.757283,-36.069479,-40.259529,-44.316183,-48.229118,-51.988955,-55.586244,-59.012754,-62.260629,-65.322918,-68.192267,-70.863322,-73.330355,-75.588362,-77.632852,-79.459937,-81.066070,-82.448288,-83.604026,-84.531082,-85.227883,-85.693124,-85.926013,-85.926102,-85.693390,-85.228325,-84.531700,-83.604817,-82.449249,-81.067199,-79.461229,-77.634305,-75.589970,-73.332112,-70.865224,-68.194307,-65.325088,-62.262923,-59.015164,-55.588761,-51.991570,-48.231823,-44.318966,-40.262381,-36.072389,-31.760240,-27.337512,-22.816335,-18.209831,-13.531757}, // NOLINT + {-13.498988,-18.178619,-22.787284,-27.310975,-31.736539,-36.051831,-40.245269,-44.305516,-48.222286,-51.985836,-55.587029,-59.017502,-62.269252,-65.335194,-68.208539,-70.883204,-73.353674,-75.614934,-77.662429,-79.492284,-81.100893,-82.485246,-83.642779,-84.571324,-85.269269,-85.735258,-85.968531,-85.968620,-85.735524,-85.269712,-84.571943,-83.643571,-82.486209,-81.102023,-79.493579,-77.663884,-75.616544,-73.355434,-70.885108,-68.210581,-65.337367,-62.271548,-59.019915,-55.589549,-51.988454,-48.224993,-44.308302,-40.248123,-36.054743,-31.739498,-27.313969,-22.790301,-18.181648,-13.502015}, // NOLINT + {-13.469048,-18.150417,-22.761153,-27.287295,-31.715688,-36.034333,-40.230979,-44.294821,-48.215334,-51.982715,-55.587842,-59.022225,-62.277914,-65.347674,-68.224776,-70.902994,-73.376987,-75.641415,-77.692034,-79.524616,-81.135693,-82.522203,-83.681534,-84.611612,-85.310651,-85.777412,-86.011048,-86.011137,-85.777679,-85.311095,-84.612232,-83.682327,-82.523168,-81.136826,-79.525913,-77.693491,-75.643028,-73.378749,-70.904901,-68.226821,-65.349850,-62.280214,-59.024640,-55.590365,-51.985335,-48.218043,-44.297609,-40.233836,-36.037247,-31.718648,-27.290291,-22.764171,-18.153446,-13.472075}, // NOLINT + {-13.438859,-18.122223,-22.735039,-27.263624,-31.694991,-36.016497,-40.216723,-44.284081,-48.208306,-51.979540,-55.588574,-59.026883,-62.286486,-65.360127,-68.240955,-70.922842,-73.400287,-75.667962,-77.721581,-79.556926,-81.170475,-82.559140,-83.720291,-84.651868,-85.352033,-85.819550,-86.053566,-86.053655,-85.819818,-85.352478,-84.652489,-83.721086,-82.560106,-81.171609,-79.558225,-77.723041,-75.669577,-73.402052,-70.924752,-68.243002,-65.362306,-62.288789,-59.029301,-55.591099,-51.982163,-48.211018,-44.286871,-40.219582,-36.019413,-31.697953,-27.266621,-22.738058,-18.125252,-13.441886}, // NOLINT + {-13.409083,-18.093950,-22.708806,-27.239942,-31.674131,-35.999018,-40.202282,-44.273286,-48.201248,-51.976335,-55.589305,-59.031516,-62.295295,-65.372500,-68.257144,-70.942674,-73.423557,-75.694564,-77.751185,-79.589239,-81.205244,-82.596093,-83.759048,-84.692130,-85.393414,-85.861688,-86.096082,-86.096172,-85.861956,-85.393860,-84.692751,-83.759844,-82.597060,-81.206380,-79.590540,-77.752646,-75.696181,-73.425325,-70.944586,-68.259194,-65.374682,-62.297600,-59.033936,-55.591832,-51.978961,-48.203962,-44.276079,-40.205142,-36.001936,-31.677094,-27.242939,-22.711826,-18.096980,-13.412110}, // NOLINT + {-13.378967,-18.065490,-22.682511,-27.216235,-31.653227,-35.981064,-40.187910,-44.262450,-48.194150,-51.973044,-55.589943,-59.036130,-62.303544,-65.385007,-68.273319,-70.962464,-73.446811,-75.721058,-77.780675,-79.621542,-81.240030,-82.633015,-83.797932,-84.732386,-85.434797,-85.903825,-86.138600,-86.138689,-85.904093,-85.435243,-84.733009,-83.798729,-82.633985,-81.241168,-79.622845,-77.782139,-75.722678,-73.448582,-70.964379,-68.275373,-65.387192,-62.305853,-59.038554,-55.592473,-51.975672,-48.196867,-44.265244,-40.190773,-35.983983,-31.656192,-27.219234,-22.685532,-18.068519,-13.381993}, // NOLINT + {-13.348805,-18.037199,-22.656234,-27.192249,-31.632232,-35.963184,-40.173448,-44.251566,-48.187014,-51.969708,-55.590562,-59.040697,-62.312094,-65.397239,-68.289406,-70.982214,-73.470044,-75.747503,-77.810210,-79.653832,-81.274787,-82.669961,-83.836691,-84.772621,-85.476174,-85.945962,-86.181117,-86.181207,-85.946231,-85.476621,-84.773245,-83.837489,-82.670932,-81.275927,-79.655138,-77.811677,-75.749125,-73.471818,-70.984132,-68.291463,-65.399426,-62.314405,-59.043123,-55.593095,-51.972339,-48.189733,-44.254363,-40.176312,-35.966105,-31.635198,-27.195249,-22.659255,-18.040229,-13.351831}, // NOLINT + {-13.318618,-18.008561,-22.629828,-27.168386,-31.611232,-35.945387,-40.158925,-44.240655,-48.179827,-51.966448,-55.591158,-59.045228,-62.320568,-65.409639,-68.305517,-71.001963,-73.493244,-75.774041,-77.839736,-79.686108,-81.309546,-82.706880,-83.875447,-84.812879,-85.517547,-85.988098,-86.223634,-86.223724,-85.988368,-85.517995,-84.813504,-83.876247,-82.707852,-81.310688,-79.687415,-77.841204,-75.775665,-73.495020,-71.003883,-68.307576,-65.411829,-62.322882,-59.047658,-55.593694,-51.969082,-48.182548,-44.243454,-40.161792,-35.948309,-31.614199,-27.171387,-22.632850,-18.011591,-13.321643}, // NOLINT + {-13.288392,-17.980077,-22.603426,-27.144638,-31.590186,-35.927362,-40.144409,-44.229684,-48.172570,-51.963185,-55.591706,-59.049725,-62.328988,-65.421934,-68.321628,-71.021766,-73.516492,-75.800562,-77.869221,-79.718377,-81.344318,-82.743796,-83.914200,-84.853132,-85.558932,-86.030234,-86.266151,-86.266241,-86.030504,-85.559381,-84.853758,-83.915001,-82.744770,-81.345461,-79.719686,-77.870692,-75.802189,-73.518271,-71.023690,-68.323690,-65.424127,-62.331305,-59.052157,-55.594245,-51.965821,-48.175294,-44.232486,-40.147277,-35.930286,-31.593155,-27.147640,-22.606448,-17.983107,-13.291417}, // NOLINT + {-13.258067,-17.951601,-22.577077,-27.120717,-31.569054,-35.909452,-40.129785,-44.218662,-48.165306,-51.959675,-55.592214,-59.054269,-62.337378,-65.434240,-68.337679,-71.041465,-73.539636,-75.826958,-77.898708,-79.750632,-81.379040,-82.780700,-83.952950,-84.893365,-85.600307,-86.072370,-86.308668,-86.308758,-86.072640,-85.600756,-84.893992,-83.953753,-82.781675,-81.380185,-79.751944,-77.900181,-75.828588,-73.541417,-71.043391,-68.339744,-65.436436,-62.339698,-59.056704,-55.594756,-51.962314,-48.168033,-44.221466,-40.132655,-35.912378,-31.572024,-27.123719,-22.580100,-17.954631,-13.261092}, // NOLINT + {-13.227797,-17.922821,-22.550564,-27.096667,-31.547921,-35.891376,-40.115132,-44.207545,-48.157998,-51.956106,-55.592668,-59.058610,-62.345743,-65.446428,-68.353738,-71.061161,-73.562787,-75.853395,-77.928170,-79.782834,-81.413775,-82.817609,-83.991697,-84.933583,-85.641684,-86.114504,-86.351185,-86.351275,-86.114775,-85.642134,-84.934211,-83.992501,-82.818586,-81.414922,-79.784147,-77.929646,-75.855027,-73.564571,-71.063090,-68.355806,-65.448627,-62.348066,-59.061048,-55.595212,-51.958748,-48.160727,-44.210351,-40.118004,-35.894304,-31.550893,-27.099671,-22.553587,-17.925851,-13.230821}, // NOLINT + {-13.197294,-17.894218,-22.523935,-27.072648,-31.526649,-35.873348,-40.100490,-44.196352,-48.150637,-51.952710,-55.593115,-59.063000,-62.354031,-65.458710,-68.369709,-71.080781,-73.585979,-75.879810,-77.957612,-79.815094,-81.448510,-82.854509,-84.030440,-84.973882,-85.683051,-86.156639,-86.393703,-86.393793,-86.156910,-85.683502,-84.974511,-84.031246,-82.855488,-81.449659,-79.816410,-77.959089,-75.881445,-73.587765,-71.082713,-68.371780,-65.460912,-62.356356,-59.065441,-55.595662,-51.955354,-48.153368,-44.199160,-40.103364,-35.876278,-31.529622,-27.075652,-22.526959,-17.897248,-13.200318}, // NOLINT + {-13.167013,-17.865511,-22.497397,-27.048534,-31.505424,-35.855210,-40.085697,-44.185404,-48.143232,-51.949153,-55.593496,-59.067179,-62.362367,-65.470902,-68.385720,-71.100422,-73.609044,-75.906206,-77.987083,-79.847342,-81.483211,-82.891416,-84.069180,-85.014119,-85.724422,-86.198773,-86.436220,-86.436310,-86.199045,-85.724874,-85.014749,-84.069987,-82.892396,-81.484362,-79.848660,-77.988563,-75.907843,-73.610833,-71.102356,-68.387793,-65.473107,-62.364695,-59.069623,-55.596046,-51.951800,-48.145966,-44.188214,-40.088573,-35.858141,-31.508398,-27.051539,-22.500421,-17.868541,-13.170036}, // NOLINT + {-13.136674,-17.836754,-22.470799,-27.024395,-31.484121,-35.837038,-40.070912,-44.174081,-48.135781,-51.945567,-55.593859,-59.071720,-62.370620,-65.482990,-68.401680,-71.120033,-73.632144,-75.932605,-78.016510,-79.879534,-81.517912,-82.928337,-84.107916,-85.054327,-85.765799,-86.240908,-86.478736,-86.478827,-86.241180,-85.766252,-85.054958,-84.108724,-82.929319,-81.519065,-79.880854,-78.017993,-75.934245,-73.633935,-71.121970,-68.403756,-65.485197,-62.372951,-59.074166,-55.596412,-51.948217,-48.138518,-44.176894,-40.073790,-35.839970,-31.487096,-27.027401,-22.473823,-17.839784,-13.139697}, // NOLINT + {-13.106018,-17.807918,-22.443852,-27.000169,-31.462719,-35.818830,-40.056097,-44.162836,-48.128306,-51.941926,-55.594108,-59.075946,-62.378770,-65.495146,-68.417593,-71.139626,-73.655223,-75.958989,-78.045916,-79.911746,-81.552615,-82.965186,-84.146648,-85.094569,-85.807145,-86.283040,-86.521253,-86.521343,-86.283312,-85.807598,-85.095202,-84.147458,-82.966170,-81.553770,-79.913068,-78.047401,-75.960631,-73.657017,-71.141566,-68.419672,-65.497356,-62.381104,-59.078395,-55.596663,-51.944578,-48.131044,-44.165651,-40.058977,-35.821765,-31.465695,-27.003176,-22.446877,-17.810948,-13.109040}, // NOLINT + {-13.075441,-17.779055,-22.417197,-26.975908,-31.441364,-35.800366,-40.041203,-44.151581,-48.120747,-51.938292,-55.594462,-59.080371,-62.387038,-65.507252,-68.433512,-71.159175,-73.678286,-75.985303,-78.075324,-79.943943,-81.587328,-83.002051,-84.185377,-85.134788,-85.848530,-86.325172,-86.563770,-86.563861,-86.325445,-85.848984,-85.135421,-84.186188,-83.003036,-81.588485,-79.945267,-78.076811,-75.986947,-73.680083,-71.161118,-68.435593,-65.509465,-62.389375,-59.082823,-55.597020,-51.940946,-48.123488,-44.154399,-40.044085,-35.803302,-31.444343,-26.978916,-22.420223,-17.782085,-13.078463}, // NOLINT + {-13.044821,-17.750135,-22.390516,-26.951693,-31.419900,-35.782160,-40.026279,-44.140287,-48.113196,-51.934593,-55.594721,-59.084355,-62.395239,-65.519332,-68.449363,-71.178748,-73.701330,-76.011638,-78.104704,-79.976123,-81.621994,-83.038925,-84.224101,-85.175015,-85.889900,-86.367304,-86.606286,-86.606377,-86.367577,-85.890355,-85.175650,-84.224913,-83.039912,-81.623153,-79.977449,-78.106193,-76.013285,-73.703130,-71.180693,-68.451448,-65.521548,-62.397579,-59.086809,-55.597282,-51.937250,-48.115940,-44.143106,-40.029163,-35.785098,-31.422880,-26.954702,-22.393542,-17.753164,-13.047842}, // NOLINT + {-13.014183,-17.721205,-22.363713,-26.927254,-31.398419,-35.763887,-40.011315,-44.128910,-48.105581,-51.930851,-55.594912,-59.088628,-62.403399,-65.531447,-68.465203,-71.198237,-73.724350,-76.037958,-78.134084,-80.008299,-81.656674,-83.075736,-84.262822,-85.215239,-85.931267,-86.409436,-86.648803,-86.648895,-86.409710,-85.931723,-85.215875,-84.263635,-83.076724,-81.657834,-80.009627,-78.135576,-76.039608,-73.726152,-71.200186,-68.467290,-65.533666,-62.405742,-59.091086,-55.597476,-51.933511,-48.108327,-44.131732,-40.014201,-35.766827,-31.401399,-26.930264,-22.366739,-17.724234,-13.017203}, // NOLINT + {-12.983553,-17.692220,-22.336821,-26.902874,-31.376910,-35.745351,-39.996305,-44.117505,-48.097974,-51.927076,-55.595091,-59.092749,-62.411516,-65.543372,-68.481019,-71.217761,-73.747351,-76.064260,-78.163458,-80.040386,-81.691321,-83.112647,-84.301538,-85.255470,-85.972631,-86.451567,-86.691319,-86.691411,-86.451842,-85.973087,-85.256107,-84.302353,-83.113637,-81.692483,-80.041716,-78.164952,-76.065912,-73.749156,-71.219712,-68.483109,-65.545594,-62.413861,-59.095209,-55.597657,-51.929739,-48.100723,-44.120329,-39.999193,-35.748292,-31.379892,-26.905884,-22.339848,-17.695249,-12.986573}, // NOLINT + {-12.952831,-17.663180,-22.309854,-26.878449,-31.355341,-35.727171,-39.981119,-44.105990,-48.090221,-51.923261,-55.595220,-59.096874,-62.419587,-65.555373,-68.496830,-71.237246,-73.770337,-76.090545,-78.192804,-80.072610,-81.725998,-83.149500,-84.340251,-85.295686,-86.013994,-86.493698,-86.733836,-86.733928,-86.493973,-86.014451,-85.296324,-84.341067,-83.150492,-81.727162,-80.073943,-78.194300,-76.092200,-73.772144,-71.239200,-68.498923,-65.557598,-62.421935,-59.099338,-55.597789,-51.925926,-48.092972,-44.108816,-39.984009,-35.730114,-31.358325,-26.881460,-22.312881,-17.666210,-12.955850}, // NOLINT + {-12.922048,-17.634142,-22.282954,-26.854012,-31.333659,-35.708536,-39.966130,-44.094536,-48.082496,-51.919260,-55.595369,-59.100957,-62.427650,-65.567336,-68.512748,-71.256685,-73.793304,-76.116814,-78.222153,-80.104727,-81.760661,-83.186347,-84.378959,-85.335901,-86.055355,-86.535828,-86.776353,-86.776445,-86.536104,-86.055813,-85.336540,-84.379777,-83.187341,-81.761827,-80.106062,-78.223651,-76.118472,-73.795114,-71.258641,-68.514843,-65.569563,-62.430001,-59.103424,-55.597940,-51.921928,-48.085250,-44.097364,-39.969022,-35.711480,-31.336644,-26.857024,-22.285981,-17.637171,-12.925066}, // NOLINT + {-12.891240,-17.605008,-22.255705,-26.829525,-31.311970,-35.690008,-39.950888,-44.082951,-48.074720,-51.915513,-55.595390,-59.104953,-62.435654,-65.579263,-68.528275,-71.276124,-73.816249,-76.143069,-78.251476,-80.136890,-81.795253,-83.223174,-84.417663,-85.376101,-86.096716,-86.577958,-86.818869,-86.818961,-86.578234,-86.097175,-85.376741,-84.418482,-83.224169,-81.796421,-80.138227,-78.252977,-76.144729,-73.818062,-71.278083,-68.530373,-65.581494,-62.438008,-59.107422,-55.597965,-51.918183,-48.077476,-44.085781,-39.953782,-35.692954,-31.314956,-26.832538,-22.258732,-17.608037,-12.894257}, // NOLINT + {-12.860500,-17.575808,-22.228747,-26.805022,-31.290247,-35.671404,-39.935797,-44.071330,-48.066903,-51.911591,-55.595415,-59.109026,-62.443654,-65.591166,-68.544106,-71.295506,-73.839172,-76.169411,-78.280777,-80.169002,-81.829911,-83.260028,-84.456364,-85.416316,-86.138067,-86.620088,-86.861385,-86.861477,-86.620364,-86.138526,-85.416957,-84.457184,-83.261024,-81.831081,-80.170341,-78.282280,-76.171073,-73.840988,-71.297468,-68.546207,-65.593399,-62.446011,-59.111498,-55.597992,-51.914264,-48.069661,-44.074163,-39.938693,-35.674352,-31.293234,-26.808036,-22.231775,-17.578837,-12.863517}, // NOLINT + {-12.829508,-17.546586,-22.201741,-26.780362,-31.268486,-35.652760,-39.920537,-44.059793,-48.058763,-51.907611,-55.595426,-59.113013,-62.451598,-65.603050,-68.559774,-71.314921,-73.862086,-76.195623,-78.310087,-80.201096,-81.864546,-83.296853,-84.495060,-85.456538,-86.179429,-86.662217,-86.903901,-86.903994,-86.662494,-86.179889,-85.457180,-84.495882,-83.297851,-81.865718,-80.202437,-78.311592,-76.197288,-73.863904,-71.316886,-68.561878,-65.605286,-62.453958,-59.115488,-55.598006,-51.910286,-48.061523,-44.062628,-39.923435,-35.655709,-31.271474,-26.783377,-22.204769,-17.549615,-12.832524}, // NOLINT + {-12.798581,-17.517329,-22.174574,-26.755714,-31.246695,-35.634139,-39.905216,-44.048124,-48.051140,-51.903609,-55.595358,-59.116943,-62.459529,-65.614892,-68.575458,-71.334296,-73.884982,-76.221680,-78.339365,-80.233206,-81.899165,-83.333677,-84.533753,-85.496745,-86.220790,-86.704345,-86.946418,-86.946510,-86.704623,-86.221251,-85.497388,-84.534576,-83.334677,-81.900339,-80.234550,-78.340873,-76.223347,-73.886803,-71.336264,-68.577565,-65.617131,-62.461892,-59.119420,-55.597941,-51.906288,-48.053903,-44.050961,-39.908116,-35.637090,-31.249684,-26.758729,-22.177602,-17.520357,-12.801596}, // NOLINT + {-12.098645,-16.753893,-21.346343,-25.861950,-30.287469,-34.609819,-38.816806,-42.896765,-46.838529,-50.631778,-54.266623,-57.733771,-61.024795,-64.131379,-67.046311,-69.762650,-72.274164,-74.575151,-76.660425,-78.525423,-80.166078,-81.578856,-82.760739,-83.709270,-84.422389,-84.898694,-85.137131,-85.137225,-84.898973,-84.422854,-83.709919,-82.761570,-81.579867,-80.167265,-78.526782,-76.661953,-74.576842,-72.276012,-69.764650,-67.048456,-64.133661,-61.027208,-57.736305,-54.269270,-50.634529,-46.841374,-42.899694,-38.819809,-34.612885,-30.290586,-25.865106,-21.349527,-16.757093,-12.101849}, // NOLINT + {-12.066012,-16.721582,-21.314744,-25.831498,-30.258360,-34.582406,-38.791341,-42.873399,-46.817615,-50.613368,-54.250837,-57.720669,-61.014328,-64.123663,-67.041245,-69.760192,-72.274150,-74.577528,-76.665025,-78.532057,-80.174530,-81.588913,-82.772128,-83.721796,-84.435778,-84.912627,-85.151346,-85.151440,-84.912908,-84.436244,-83.722446,-82.772960,-81.589926,-80.175719,-78.533419,-76.666555,-74.579221,-72.276000,-69.762195,-67.043392,-64.125948,-61.016743,-57.723206,-54.253487,-50.616122,-46.820462,-42.876331,-38.794346,-34.585474,-30.261479,-25.834656,-21.317929,-16.724782,-12.069215}, // NOLINT + {-12.033348,-16.689230,-21.283093,-25.800937,-30.229197,-34.554853,-38.765830,-42.850100,-46.796672,-50.594923,-54.234970,-57.707514,-61.003993,-64.115912,-67.036181,-69.757710,-72.274196,-74.579837,-76.669610,-78.538671,-80.182983,-81.598976,-82.783626,-83.734317,-84.449139,-84.926557,-85.165560,-85.165654,-84.926838,-84.449606,-83.734968,-82.784460,-81.599990,-80.184174,-78.540034,-76.671142,-74.581532,-72.276049,-69.759715,-67.038331,-64.118200,-61.006410,-57.710053,-54.237622,-50.597679,-46.799522,-42.853034,-38.768837,-34.557922,-30.232317,-25.804096,-21.286279,-16.692430,-12.036550}, // NOLINT + {-12.000514,-16.656820,-21.251399,-25.770316,-30.200023,-34.527366,-38.740210,-42.826772,-46.775669,-50.576422,-54.219098,-57.694311,-60.993383,-64.108145,-67.031062,-69.755258,-72.274205,-74.582286,-76.674206,-78.545302,-80.191463,-81.609021,-82.795009,-83.746811,-84.462509,-84.940479,-85.179774,-85.179868,-84.940760,-84.462977,-83.747463,-82.795844,-81.610037,-80.192655,-78.546668,-76.675740,-74.583984,-72.276061,-69.757266,-67.033215,-64.110435,-60.995803,-57.696853,-54.221753,-50.579181,-46.778522,-42.829708,-38.743219,-34.530437,-30.203144,-25.773476,-21.254586,-16.660021,-12.003717}, // NOLINT + {-11.967872,-16.624327,-21.219665,-25.739486,-30.170696,-34.499986,-38.714722,-42.803358,-46.754632,-50.557874,-54.203177,-57.681058,-60.982852,-64.100334,-67.025935,-69.752718,-72.274177,-74.584625,-76.678872,-78.551901,-80.199869,-81.619061,-82.806394,-83.759365,-84.475871,-84.954413,-85.193989,-85.194083,-84.954695,-84.476339,-83.760019,-82.807231,-81.620078,-80.201063,-78.553268,-76.680408,-74.586325,-72.276035,-69.754728,-67.028090,-64.102627,-60.985275,-57.683603,-54.205835,-50.560636,-46.757487,-42.806296,-38.717734,-34.503059,-30.173819,-25.742648,-21.222852,-16.627529,-11.971075}, // NOLINT + {-11.935045,-16.591849,-21.187837,-25.708926,-30.141420,-34.472283,-38.689086,-42.779911,-46.733548,-50.539320,-54.187241,-57.667789,-60.972333,-64.092526,-67.020782,-69.750158,-72.274145,-74.586965,-76.683334,-78.558505,-80.208294,-81.629092,-82.817780,-83.771874,-84.489230,-84.968344,-85.208204,-85.208298,-84.968626,-84.489699,-83.772529,-82.818618,-81.630110,-80.209490,-78.559874,-76.684872,-74.588667,-72.276005,-69.752170,-67.022940,-64.094822,-60.974759,-57.670336,-54.189902,-50.542084,-46.736405,-42.782852,-38.692099,-34.475358,-30.144545,-25.712088,-21.191025,-16.595051,-11.938247}, // NOLINT + {-11.902144,-16.559259,-21.156015,-25.678138,-30.111907,-34.444675,-38.663391,-42.756417,-46.712424,-50.520659,-54.171239,-57.654498,-60.961710,-64.084636,-67.015604,-69.747580,-72.274102,-74.589302,-76.687822,-78.565078,-80.216729,-81.639138,-82.829167,-83.784380,-84.502586,-84.982273,-85.222418,-85.222513,-84.982556,-84.503056,-83.785035,-82.830006,-81.640158,-80.217926,-78.566449,-76.689362,-74.591006,-72.275965,-69.749595,-67.017765,-64.086935,-60.964139,-57.657048,-54.173903,-50.523426,-46.715284,-42.759360,-38.666406,-34.447751,-30.115033,-25.681302,-21.159204,-16.562461,-11.905346}, // NOLINT + {-11.869257,-16.526624,-21.124082,-25.647323,-30.082646,-34.416964,-38.637654,-42.732881,-46.691257,-50.502031,-54.155213,-57.641165,-60.951081,-64.076777,-67.010404,-69.744987,-72.274026,-74.591633,-76.692422,-78.571651,-80.225132,-81.649150,-82.840681,-83.796938,-84.515948,-84.996201,-85.236632,-85.236726,-84.996484,-84.516418,-83.797595,-82.841521,-81.650171,-80.226331,-78.573025,-76.693965,-74.593340,-72.275892,-69.747005,-67.012567,-64.079078,-60.953512,-57.643718,-54.157879,-50.504800,-46.694120,-42.735826,-38.640672,-34.420042,-30.085773,-25.650487,-21.127272,-16.529826,-11.872459}, // NOLINT + {-11.836106,-16.493968,-21.092137,-25.616449,-30.053134,-34.389191,-38.612032,-42.709321,-46.670048,-50.483408,-54.139156,-57.627816,-60.940447,-64.068823,-67.005185,-69.742379,-72.273933,-74.593922,-76.696950,-78.578228,-80.233531,-81.659178,-82.852069,-83.809408,-84.529307,-85.010129,-85.250847,-85.250941,-85.010412,-84.529778,-83.810065,-82.852911,-81.660202,-80.234733,-78.579603,-76.698495,-74.595631,-72.275801,-69.744400,-67.007350,-64.071127,-60.942881,-57.630371,-54.141825,-50.486180,-46.672913,-42.712268,-38.615051,-34.392271,-30.056262,-25.619614,-21.095327,-16.497170,-11.839308}, // NOLINT + {-11.803039,-16.461256,-21.060135,-25.585519,-30.023686,-34.361378,-38.586070,-42.685664,-46.648873,-50.464659,-54.123056,-57.614389,-60.929782,-64.060901,-66.999949,-69.739751,-72.273827,-74.596182,-76.701450,-78.584780,-80.241936,-81.669199,-82.863455,-83.821914,-84.542661,-85.024057,-85.265061,-85.265156,-85.024340,-84.543132,-83.822573,-82.864298,-81.670224,-80.243139,-78.586158,-76.702998,-74.597894,-72.275698,-69.741774,-67.002117,-64.063207,-60.932219,-57.616947,-54.125727,-50.467433,-46.651740,-42.688614,-38.589091,-34.364459,-30.026816,-25.588686,-21.063326,-16.464459,-11.806240}, // NOLINT + {-11.770120,-16.428484,-21.028058,-25.554548,-29.994154,-34.333484,-38.560191,-42.662004,-46.627454,-50.445947,-54.106923,-57.600968,-60.919145,-64.052921,-66.994656,-69.737102,-72.273700,-74.598459,-76.705946,-78.591339,-80.250280,-81.679199,-82.874839,-83.834430,-84.556015,-85.037983,-85.279275,-85.279370,-85.038268,-84.556488,-83.835089,-82.875683,-81.680225,-80.251485,-78.592718,-76.707496,-74.600173,-72.275573,-69.739128,-66.996828,-64.055231,-60.921585,-57.603529,-54.109597,-50.448724,-46.630323,-42.664955,-38.563215,-34.336567,-29.997285,-25.557716,-21.031250,-16.431687,-11.773321}, // NOLINT + {-11.736828,-16.395572,-20.995972,-25.523526,-29.964503,-34.305667,-38.534288,-42.638286,-46.606122,-50.427189,-54.090762,-57.587507,-60.908377,-64.045088,-66.989371,-69.734454,-72.273554,-74.600714,-76.710424,-78.597865,-80.258711,-81.689195,-82.886219,-83.846936,-84.569373,-85.051910,-85.293490,-85.293585,-85.052194,-84.569847,-83.847596,-82.887065,-81.690223,-80.259918,-78.599246,-76.711976,-74.602431,-72.275430,-69.736483,-66.991545,-64.047400,-60.910819,-57.590071,-54.093438,-50.429968,-46.608994,-42.641240,-38.537313,-34.308752,-29.967636,-25.526695,-20.999164,-16.398775,-11.740029}, // NOLINT + {-11.703952,-16.362787,-20.963811,-25.492368,-29.934863,-34.277731,-38.508332,-42.614532,-46.584870,-50.408255,-54.074547,-57.574034,-60.897664,-64.036937,-66.984044,-69.731736,-72.273392,-74.602874,-76.714898,-78.604381,-80.267090,-81.699215,-82.897597,-83.859425,-84.582726,-85.065836,-85.307703,-85.307799,-85.066121,-84.583200,-83.860087,-82.898444,-81.700244,-80.268298,-78.605764,-76.716451,-74.604592,-72.275270,-69.733767,-66.986221,-64.039253,-60.900109,-57.576601,-54.077226,-50.411037,-46.587744,-42.617488,-38.511359,-34.280818,-29.937997,-25.495538,-20.967004,-16.365990,-11.707153}, // NOLINT + {-11.670589,-16.329878,-20.931594,-25.461334,-29.905182,-34.249664,-38.482331,-42.590730,-46.563352,-50.389374,-54.058319,-57.560516,-60.886953,-64.028889,-66.978704,-69.729035,-72.273208,-74.605236,-76.719291,-78.610889,-80.275449,-81.709208,-82.908972,-83.871901,-84.596079,-85.079762,-85.321917,-85.322012,-85.080047,-84.596554,-83.872564,-82.909820,-81.710239,-80.276659,-78.612274,-76.720847,-74.606957,-72.275088,-69.731069,-66.980883,-64.031207,-60.889401,-57.563085,-54.061001,-50.392158,-46.566229,-42.593688,-38.485360,-34.252752,-29.908317,-25.464505,-20.934788,-16.333081,-11.673789}, // NOLINT + {-11.637324,-16.296922,-20.899368,-25.430151,-29.875446,-34.221579,-38.456275,-42.566890,-46.541892,-50.370414,-54.042039,-57.546903,-60.876003,-64.020816,-66.973330,-69.726311,-72.273014,-74.607439,-76.723806,-78.617418,-80.283818,-81.719142,-82.920344,-83.884459,-84.609424,-85.093687,-85.336132,-85.336228,-85.093973,-84.609899,-83.885123,-82.921193,-81.720174,-80.285030,-78.618805,-76.725364,-74.609163,-72.274897,-69.728347,-66.975512,-64.023137,-60.878453,-57.549475,-54.044724,-50.373200,-46.544771,-42.569851,-38.459306,-34.224669,-29.878583,-25.433323,-20.902562,-16.300125,-11.640524}, // NOLINT + {-11.604052,-16.263886,-20.867031,-25.398939,-29.845720,-34.193698,-38.430186,-42.542999,-46.520497,-50.351485,-54.025717,-57.533290,-60.865170,-64.012771,-66.967992,-69.723574,-72.272790,-74.609542,-76.728240,-78.623898,-80.292179,-81.729173,-82.931712,-83.896951,-84.622783,-85.107612,-85.350346,-85.350442,-85.107898,-84.623260,-83.897615,-82.932563,-81.730207,-80.293392,-78.625287,-76.729800,-74.611268,-72.274675,-69.725613,-66.970177,-64.015095,-60.867624,-57.535865,-54.028404,-50.354274,-46.523378,-42.545962,-38.433219,-34.196790,-29.848858,-25.402111,-20.870226,-16.267090,-11.607251}, // NOLINT + {-11.570656,-16.230834,-20.834702,-25.367673,-29.815721,-34.165443,-38.404045,-42.519063,-46.498844,-50.332516,-54.009373,-57.519627,-60.854303,-64.004422,-66.962525,-69.720806,-72.272555,-74.611714,-76.732659,-78.630401,-80.300503,-81.739200,-82.943077,-83.909392,-84.636122,-85.121536,-85.364560,-85.364656,-85.121823,-84.636599,-83.910057,-82.943929,-81.740236,-80.301718,-78.631792,-76.734222,-74.613442,-72.274443,-69.722848,-66.964713,-64.006749,-60.856759,-57.522204,-54.012063,-50.335308,-46.501728,-42.522028,-38.407080,-34.168536,-29.818861,-25.370847,-20.837897,-16.234037,-11.573854}, // NOLINT + {-11.537255,-16.197725,-20.802282,-25.336354,-29.785840,-34.137339,-38.377863,-42.495098,-46.477270,-50.313457,-53.992979,-57.506147,-60.843414,-63.996429,-66.957057,-69.717962,-72.272303,-74.613874,-76.737074,-78.636877,-80.308858,-81.749148,-82.954438,-83.921902,-84.649471,-85.135460,-85.378773,-85.378869,-85.135747,-84.649948,-83.922569,-82.955292,-81.750185,-80.310075,-78.638270,-76.738639,-74.615605,-72.274194,-69.720006,-66.959247,-63.998757,-60.845874,-57.508727,-53.995672,-50.316252,-46.480156,-42.498066,-38.380900,-34.140434,-29.788981,-25.339529,-20.805478,-16.200929,-11.540454}, // NOLINT + {-11.503777,-16.164580,-20.769824,-25.304978,-29.755941,-34.109127,-38.351630,-42.471072,-46.455655,-50.294368,-53.976572,-57.492322,-60.832474,-63.988254,-66.951649,-69.715131,-72.272032,-74.616018,-76.741464,-78.643364,-80.317162,-81.759156,-82.965796,-83.934400,-84.662821,-85.149384,-85.392987,-85.393083,-85.149671,-84.663299,-83.935067,-82.966651,-81.760195,-80.318381,-78.644759,-76.743031,-74.617751,-72.273925,-69.717178,-66.953842,-63.990586,-60.834936,-57.494905,-53.979267,-50.297165,-46.458544,-42.474042,-38.354669,-34.112223,-29.759083,-25.308153,-20.773020,-16.167783,-11.506975}, // NOLINT + {-11.470258,-16.131357,-20.737327,-25.273580,-29.725950,-34.080792,-38.325445,-42.447020,-46.434050,-50.275271,-53.960111,-57.478638,-60.821511,-63.980049,-66.946134,-69.712298,-72.271744,-74.618147,-76.745851,-78.649884,-80.325540,-81.769055,-82.977151,-83.946883,-84.676165,-85.163307,-85.407201,-85.407297,-85.163595,-84.676644,-83.947552,-82.978007,-81.770095,-80.326761,-78.651282,-76.747421,-74.619882,-72.273640,-69.714347,-66.948330,-63.982384,-60.823975,-57.481224,-53.962809,-50.278071,-46.436941,-42.449992,-38.328486,-34.083890,-29.729094,-25.276756,-20.740524,-16.134561,-11.473455}, // NOLINT + {-11.436590,-16.098304,-20.704784,-25.242133,-29.695907,-34.052574,-38.299037,-42.422911,-46.412348,-50.256125,-53.943639,-57.464882,-60.810519,-63.971775,-66.940639,-69.709440,-72.271442,-74.620260,-76.750239,-78.656292,-80.333828,-81.779020,-82.988502,-83.959364,-84.689510,-85.177229,-85.421415,-85.421511,-85.177518,-84.689990,-83.960034,-82.989359,-81.780062,-80.335051,-78.657692,-76.751811,-74.621998,-72.273341,-69.711493,-66.942837,-63.974112,-60.812987,-57.467471,-53.946339,-50.258927,-46.415241,-42.425885,-38.302080,-34.055674,-29.699052,-25.245310,-20.707981,-16.101507,-11.439787}, // NOLINT + {-11.403121,-16.064802,-20.672210,-25.210615,-29.665838,-34.024208,-38.272672,-42.398765,-46.390603,-50.236940,-53.927108,-57.451114,-60.799491,-63.963513,-66.935088,-69.706571,-72.271118,-74.622358,-76.754588,-78.662684,-80.342129,-81.788979,-82.999849,-83.971845,-84.702857,-85.191152,-85.435629,-85.435725,-85.191441,-84.703338,-83.972515,-83.000707,-81.790023,-80.343353,-78.664085,-76.756162,-74.624098,-72.273019,-69.708625,-66.937290,-63.965853,-60.801961,-57.453705,-53.929811,-50.239745,-46.393499,-42.401741,-38.275717,-34.027310,-29.668985,-25.213793,-20.675407,-16.068006,-11.406317}, // NOLINT + {-11.369473,-16.031472,-20.639567,-25.179061,-29.635637,-33.995812,-38.246270,-42.374584,-46.368821,-50.217698,-53.910537,-57.437273,-60.788441,-63.955209,-66.929535,-69.703716,-72.270776,-74.624406,-76.758945,-78.669134,-80.350445,-81.798915,-83.011192,-83.984321,-84.716189,-85.205074,-85.449842,-85.449938,-85.205363,-84.716670,-83.984993,-83.012052,-81.799960,-80.351671,-78.670537,-76.760521,-74.626149,-72.272680,-69.705774,-66.931739,-63.957552,-60.790914,-57.439867,-53.913243,-50.220505,-46.371719,-42.377563,-38.249317,-33.998915,-29.638785,-25.182240,-20.642765,-16.034676,-11.372669}, // NOLINT + {-11.335790,-15.998041,-20.606892,-25.147461,-29.605499,-33.967222,-38.219831,-42.350309,-46.346995,-50.198457,-53.893942,-57.423390,-60.777353,-63.946928,-66.923797,-69.700688,-72.270419,-74.626483,-76.763281,-78.675521,-80.358724,-81.808855,-83.022532,-83.996806,-84.729565,-85.218996,-85.464056,-85.464152,-85.219286,-84.730047,-83.997479,-83.023393,-81.809901,-80.359952,-78.676927,-76.764859,-74.628228,-72.272325,-69.702748,-66.926004,-63.949273,-60.779829,-57.425987,-53.896650,-50.201267,-46.349896,-42.353290,-38.222880,-33.970327,-29.608648,-25.150642,-20.610090,-16.001244,-11.338985}, // NOLINT + {-11.302057,-15.964637,-20.574162,-25.115823,-29.575310,-33.938862,-38.193323,-42.326099,-46.325157,-50.179141,-53.877302,-57.409498,-60.766288,-63.938579,-66.918337,-69.697892,-72.270042,-74.628562,-76.767607,-78.681951,-80.367037,-81.818790,-83.033868,-84.009287,-84.742900,-85.232919,-85.478269,-85.478366,-85.233210,-84.743383,-84.009961,-83.034731,-81.819839,-80.368267,-78.683359,-76.769188,-74.630309,-72.271950,-69.699955,-66.920547,-63.940927,-60.768767,-57.412098,-53.880013,-50.181954,-46.328060,-42.329082,-38.196373,-33.941969,-29.578460,-25.119004,-20.577361,-15.967841,-11.305252}, // NOLINT + {-11.268265,-15.931125,-20.541378,-25.084134,-29.545040,-33.910451,-38.166746,-42.301771,-46.303254,-50.159803,-53.860681,-57.395584,-60.755085,-63.930226,-66.912715,-69.694871,-72.269697,-74.630620,-76.771926,-78.688366,-80.375376,-81.828709,-83.045201,-84.021755,-84.756212,-85.246837,-85.492483,-85.492580,-85.247128,-84.756696,-84.022430,-83.046065,-81.829759,-80.376608,-78.689776,-76.773508,-74.632370,-72.271608,-69.696936,-66.914927,-63.932577,-60.757567,-57.398186,-53.863395,-50.162618,-46.306159,-42.304755,-38.169799,-33.913559,-29.548192,-25.087316,-20.544577,-15.934328,-11.271459}, // NOLINT + {-11.234447,-15.897597,-20.508546,-25.052390,-29.514721,-33.881797,-38.140191,-42.277412,-46.281331,-50.140427,-53.843942,-57.381659,-60.743913,-63.921810,-66.907073,-69.691873,-72.269166,-74.632651,-76.776236,-78.694759,-80.383575,-81.838650,-83.056530,-84.034206,-84.769527,-85.260757,-85.506696,-85.506793,-85.261049,-84.770012,-84.034882,-83.057395,-81.839702,-80.384809,-78.696171,-76.777821,-74.634404,-72.271080,-69.693941,-66.909289,-63.924164,-60.746397,-57.384264,-53.846659,-50.143244,-46.284239,-42.280399,-38.143245,-33.884907,-29.517874,-25.055573,-20.511746,-15.900800,-11.237641}, // NOLINT + {-11.200701,-15.864016,-20.475677,-25.020601,-29.484378,-33.853105,-38.113587,-42.253017,-46.259400,-50.121027,-53.827202,-57.367643,-60.732718,-63.913396,-66.901385,-69.688902,-72.268802,-74.634647,-76.780510,-78.701131,-80.391894,-81.848564,-83.067855,-84.046682,-84.782872,-85.274677,-85.520909,-85.521007,-85.274969,-84.783358,-84.047359,-83.068721,-81.849617,-80.393130,-78.702545,-76.782097,-74.636402,-72.270718,-69.690973,-66.903603,-63.915753,-60.735205,-57.370252,-53.829921,-50.123847,-46.262310,-42.256006,-38.116644,-33.856217,-29.487532,-25.023784,-20.478877,-15.867219,-11.203894}, // NOLINT + {-11.166672,-15.830404,-20.442765,-24.988755,-29.453971,-33.824420,-38.086920,-42.228588,-46.237314,-50.101580,-53.810373,-57.353623,-60.721489,-63.904920,-66.895741,-69.685993,-72.268353,-74.636633,-76.784790,-78.707499,-80.400105,-81.858478,-83.079176,-84.059154,-84.796214,-85.288596,-85.535123,-85.535221,-85.288889,-84.796700,-84.059832,-83.080044,-81.859533,-80.401342,-78.708915,-76.786379,-74.638390,-72.270272,-69.688067,-66.897961,-63.907280,-60.723979,-57.356234,-53.813095,-50.104403,-46.240227,-42.231579,-38.089978,-33.827533,-29.457126,-24.991940,-20.445965,-15.833607,-11.169864}, // NOLINT + {-11.132718,-15.796832,-20.409817,-24.956881,-29.423527,-33.795748,-38.060296,-42.204123,-46.215314,-50.082073,-53.793609,-57.339586,-60.710195,-63.896477,-66.889971,-69.682837,-72.267852,-74.638635,-76.789056,-78.713856,-80.408354,-81.868313,-83.090494,-84.071618,-84.809553,-85.302516,-85.549336,-85.549434,-85.302809,-84.810040,-84.072297,-83.091363,-81.869369,-80.409593,-78.715274,-76.790648,-74.640395,-72.269774,-69.684914,-66.892195,-63.898840,-60.712687,-57.342200,-53.796333,-50.084898,-46.218229,-42.207117,-38.063356,-33.798863,-29.426683,-24.960066,-20.413017,-15.800034,-11.135910}, // NOLINT + {-11.098675,-15.763032,-20.376800,-24.924961,-29.393029,-33.767004,-38.033456,-42.179589,-46.193172,-50.062568,-53.776804,-57.325497,-60.698930,-63.888016,-66.884189,-69.679740,-72.267370,-74.640581,-76.793309,-78.720212,-80.416600,-81.878278,-83.101808,-84.084077,-84.822886,-85.316433,-85.563549,-85.563647,-85.316727,-84.823374,-84.084758,-83.102679,-81.879336,-80.417841,-78.721633,-76.794903,-74.642344,-72.269294,-69.681820,-66.886415,-63.890381,-60.701426,-57.328114,-53.779531,-50.065396,-46.196089,-42.182585,-38.036518,-33.770120,-29.396186,-24.928147,-20.380001,-15.766235,-11.101865}, // NOLINT + {-11.064678,-15.729276,-20.343737,-24.892998,-29.362503,-33.738197,-38.006652,-42.155042,-46.171059,-50.043020,-53.759905,-57.311376,-60.687573,-63.879482,-66.878433,-69.676677,-72.266919,-74.642500,-76.797550,-78.726632,-80.424836,-81.888189,-83.113119,-84.096534,-84.836214,-85.330354,-85.577763,-85.577861,-85.330648,-84.836703,-84.097216,-83.113991,-81.889248,-80.426080,-78.728054,-76.799146,-74.644265,-72.268846,-69.678759,-66.880662,-63.881850,-60.690071,-57.313995,-53.762635,-50.045851,-46.173979,-42.158040,-38.009716,-33.741315,-29.365662,-24.896185,-20.346938,-15.732478,-11.067868}, // NOLINT + {-10.198746,-14.798906,-19.346659,-23.827689,-28.227950,-32.534171,-36.733729,-40.813891,-44.763003,-48.569806,-52.223708,-55.714520,-59.032934,-62.169899,-65.117247,-67.867218,-70.412765,-72.747381,-74.865197,-76.761031,-78.430057,-79.868246,-81.072100,-82.038659,-82.765662,-83.251316,-83.494498,-83.494596,-83.251611,-82.766152,-82.039342,-81.072975,-79.869309,-78.431306,-76.762461,-74.866804,-72.749158,-70.414707,-67.869319,-65.119500,-62.172297,-59.035467,-55.717180,-52.226486,-48.572693,-44.765989,-40.816964,-36.736880,-32.537388,-28.231220,-23.831002,-19.350001,-14.802266,-10.202110}, // NOLINT + {-10.163058,-14.762143,-19.309200,-23.789854,-28.190152,-32.496686,-36.696816,-40.777766,-44.727885,-48.535985,-52.191094,-55.683412,-59.003152,-62.141778,-65.090708,-67.842250,-70.389339,-72.725473,-74.844714,-76.741789,-78.412018,-79.851246,-81.055976,-82.023300,-82.750850,-83.236878,-83.480253,-83.480351,-83.237173,-82.751340,-82.023985,-81.056852,-79.852311,-78.413269,-76.743221,-74.846323,-72.727252,-70.391284,-67.844354,-65.092963,-62.144177,-59.005688,-55.686076,-52.193875,-48.538875,-44.730873,-40.780842,-36.699969,-32.499904,-28.193424,-23.793168,-19.312543,-14.765503,-10.166422}, // NOLINT + {-10.127300,-14.725339,-19.271704,-23.752026,-28.152340,-32.459218,-36.659794,-40.741636,-44.692724,-48.501886,-52.158432,-55.652264,-58.973550,-62.113638,-65.064181,-67.817262,-70.365896,-72.703512,-74.824102,-76.722557,-78.393963,-79.834217,-81.039853,-82.007927,-82.736046,-83.222458,-83.466009,-83.466108,-83.222754,-82.736537,-82.008613,-81.040730,-79.835283,-78.395215,-76.723990,-74.825713,-72.705293,-70.367843,-67.819368,-65.066439,-62.116041,-58.976089,-55.654930,-52.161216,-48.504778,-44.695715,-40.744714,-36.662949,-32.462438,-28.155613,-23.755340,-19.275047,-14.728699,-10.130663}, // NOLINT + {-10.091504,-14.688478,-19.234154,-23.714118,-28.114501,-32.421656,-36.622824,-40.705396,-44.657537,-48.467864,-52.125745,-55.620944,-58.943815,-62.085463,-65.037552,-67.792256,-70.342436,-72.681537,-74.803629,-76.703311,-78.375916,-79.817246,-81.023730,-81.992554,-82.721229,-83.208024,-83.451765,-83.451864,-83.208320,-82.721721,-81.993240,-81.024609,-79.818314,-78.377170,-76.704746,-74.805242,-72.683321,-70.344385,-67.794365,-65.039812,-62.087868,-58.946357,-55.623612,-52.128531,-48.470759,-44.660530,-40.708476,-36.625981,-32.424878,-28.117775,-23.717434,-19.237498,-14.691838,-10.094868}, // NOLINT + {-10.055732,-14.651555,-19.196537,-23.676224,-28.076576,-32.384109,-36.585766,-40.669167,-44.622298,-48.433853,-52.093020,-55.589589,-58.914071,-62.057263,-65.010924,-67.767235,-70.318964,-72.659555,-74.783045,-76.684053,-78.357839,-79.800217,-81.007607,-81.977193,-82.706416,-83.193588,-83.437520,-83.437619,-83.193885,-82.706908,-81.977880,-81.008486,-79.801287,-78.359094,-76.685490,-74.784659,-72.661341,-70.320916,-67.769346,-65.013188,-62.059671,-58.916615,-55.592260,-52.095809,-48.436750,-44.625293,-40.672250,-36.588924,-32.387332,-28.079852,-23.679541,-19.199882,-14.654916,-10.059096}, // NOLINT + {-10.019732,-14.614569,-19.158888,-23.638246,-28.038597,-32.346327,-36.548681,-40.632876,-44.586994,-48.399909,-52.060263,-55.558314,-58.884391,-62.029065,-64.984223,-67.742193,-70.295466,-72.637574,-74.762472,-76.664798,-78.339771,-79.783213,-80.991613,-81.961828,-82.691601,-83.179153,-83.423276,-83.423375,-83.179450,-82.692094,-81.962516,-80.992494,-79.784284,-78.341028,-76.666238,-74.764089,-72.639362,-70.297420,-67.744307,-64.986489,-62.031475,-58.886937,-55.560987,-52.063054,-48.402808,-44.589992,-40.635961,-36.551841,-32.349552,-28.041875,-23.641564,-19.162234,-14.617930,-10.023096}, // NOLINT + {-9.983868,-14.577563,-19.121188,-23.600221,-28.000566,-32.308710,-36.511537,-40.596488,-44.551642,-48.365587,-52.027475,-55.526966,-58.854414,-62.000807,-64.957598,-67.717127,-70.271956,-72.615586,-74.741856,-76.645516,-78.321689,-79.766193,-80.975490,-81.946419,-82.676784,-83.164718,-83.409032,-83.409131,-83.165015,-82.677278,-81.947108,-80.976372,-79.767266,-78.322948,-76.646957,-74.743474,-72.617377,-70.273913,-67.719244,-64.959866,-62.003220,-58.856963,-55.529643,-52.030269,-48.368489,-44.554642,-40.599575,-36.514700,-32.311936,-28.003845,-23.603540,-19.124535,-14.580924,-9.987231}, // NOLINT + {-9.947839,-14.540496,-19.083438,-23.562172,-27.962510,-32.270955,-36.474351,-40.560135,-44.516322,-48.331418,-51.994633,-55.495575,-58.824522,-61.972530,-64.930978,-67.692038,-70.248430,-72.593453,-74.721276,-76.626241,-78.303603,-79.749164,-80.959365,-81.931038,-82.661967,-83.150282,-83.394787,-83.394886,-83.150579,-82.662461,-81.931728,-80.960249,-79.750238,-78.304863,-76.627684,-74.722896,-72.595246,-70.250390,-67.694157,-64.933249,-61.974945,-58.827074,-55.498253,-51.997429,-48.334323,-44.519324,-40.563224,-36.477515,-32.274184,-27.965791,-23.565492,-19.086785,-14.543858,-9.951202}, // NOLINT + {-9.911788,-14.503398,-19.045640,-23.524027,-27.924397,-32.233064,-36.437118,-40.523779,-44.480924,-48.297280,-51.961786,-55.464156,-58.794682,-61.944229,-64.904278,-67.667020,-70.224888,-72.571603,-74.700652,-76.606942,-78.285459,-79.732141,-80.943238,-81.915664,-82.647150,-83.135845,-83.380542,-83.380641,-83.136143,-82.647646,-81.916355,-80.944123,-79.733216,-78.286721,-76.608387,-74.702275,-72.573398,-70.226850,-67.669141,-64.906551,-61.946647,-58.797236,-55.466838,-51.964585,-48.300187,-44.483929,-40.526870,-36.440284,-32.236294,-27.927678,-23.527348,-19.048988,-14.506760,-9.915151}, // NOLINT + {-9.875683,-14.466223,-19.007792,-23.485856,-27.886231,-32.195283,-36.399838,-40.487279,-44.445507,-48.263023,-51.928881,-55.432717,-58.764764,-61.915899,-64.877544,-67.641841,-70.201333,-72.549528,-74.680010,-76.587576,-78.267409,-79.715073,-80.927108,-81.900284,-82.632333,-83.121408,-83.366298,-83.366397,-83.121707,-82.632829,-81.900976,-80.927994,-79.716150,-78.268673,-76.589023,-74.681635,-72.551325,-70.203297,-67.643965,-64.879821,-61.918319,-58.767321,-55.435401,-51.931683,-48.265933,-44.448514,-40.490372,-36.403007,-32.198515,-27.889514,-23.489179,-19.011141,-14.469585,-9.879045}, // NOLINT + {-9.839452,-14.429013,-18.969896,-23.447631,-27.848025,-32.157381,-36.362517,-40.450650,-44.410087,-48.228868,-51.895957,-55.401312,-58.734837,-61.887547,-64.850816,-67.616677,-70.177756,-72.527370,-74.659359,-76.568312,-78.249301,-79.698049,-80.910976,-81.884889,-82.617513,-83.106971,-83.352053,-83.352153,-83.107270,-82.618010,-81.885582,-80.911863,-79.699127,-78.250567,-76.569761,-74.660986,-72.529170,-70.179722,-67.618803,-64.853095,-61.889970,-58.737397,-55.403999,-51.898761,-48.231780,-44.413097,-40.453746,-36.365687,-32.160615,-27.851310,-23.450954,-18.973245,-14.432376,-9.842815}, // NOLINT + {-9.803331,-14.391734,-18.931950,-23.409370,-27.809760,-32.119358,-36.325157,-40.414231,-44.374556,-48.194442,-51.862982,-55.369658,-58.704847,-61.859163,-64.824035,-67.591534,-70.154163,-72.505288,-74.638745,-76.549010,-78.231186,-79.681006,-80.894841,-81.869482,-82.602692,-83.092533,-83.337808,-83.337908,-83.092832,-82.603189,-81.870176,-80.895729,-79.682086,-78.232453,-76.550461,-74.640374,-72.507090,-70.156132,-67.593663,-64.826316,-61.861589,-58.707409,-55.372348,-51.865789,-48.197357,-44.377568,-40.417328,-36.328329,-32.122593,-27.813046,-23.412695,-18.935300,-14.395096,-9.806693}, // NOLINT + {-9.767071,-14.354432,-18.893954,-23.371050,-27.771569,-32.081492,-36.287729,-40.377656,-44.338861,-48.160019,-51.829982,-55.338169,-58.674903,-61.830767,-64.797253,-67.566321,-70.130551,-72.483195,-74.618083,-76.529684,-78.213063,-79.663949,-80.878702,-81.854150,-82.587851,-83.078095,-83.323563,-83.323663,-83.078395,-82.588350,-81.854845,-80.879592,-79.665030,-78.214332,-76.531136,-74.619714,-72.484999,-70.132522,-67.568452,-64.799537,-61.833196,-58.677468,-55.340861,-51.832791,-48.162936,-44.341875,-40.380756,-36.290903,-32.084729,-27.774857,-23.374375,-18.897305,-14.357795,-9.770433}, // NOLINT + {-9.731005,-14.317161,-18.855908,-23.332685,-27.733104,-32.043326,-36.250295,-40.341009,-44.303431,-48.125699,-51.796946,-55.306659,-58.644787,-61.802312,-64.770435,-67.541109,-70.106925,-72.461087,-74.597408,-76.510329,-78.194926,-79.646912,-80.862561,-81.838747,-82.573048,-83.063657,-83.309319,-83.309419,-83.063957,-82.573546,-81.839443,-80.863451,-79.647994,-78.196197,-76.511784,-74.599041,-72.462894,-70.108898,-67.543243,-64.772721,-61.804744,-58.647354,-55.309354,-51.799758,-48.128619,-44.306447,-40.344111,-36.253471,-32.046564,-27.736393,-23.336011,-18.859259,-14.320524,-9.734366}, // NOLINT + {-9.694515,-14.279602,-18.817813,-23.294172,-27.694664,-32.005265,-36.212789,-40.304342,-44.267666,-48.091278,-51.763876,-55.275008,-58.614848,-61.773839,-64.743596,-67.515882,-70.083332,-72.438964,-74.576729,-76.490987,-78.176813,-79.629872,-80.846416,-81.823355,-82.558226,-83.049218,-83.295074,-83.295174,-83.049519,-82.558726,-81.824052,-80.847308,-79.630956,-78.178086,-76.492443,-74.578364,-72.440773,-70.085308,-67.518019,-64.745885,-61.776273,-58.617419,-55.277705,-51.766691,-48.094200,-44.270684,-40.307447,-36.215967,-32.008505,-27.697954,-23.297499,-18.821164,-14.282965,-9.697876}, // NOLINT + {-9.658002,-14.242193,-18.779668,-23.255803,-27.656343,-31.967104,-36.175247,-40.267618,-44.231996,-48.056901,-51.730771,-55.243377,-58.584690,-61.745358,-64.716733,-67.490641,-70.059550,-72.416827,-74.556021,-76.471645,-78.158664,-79.612780,-80.830268,-81.807918,-82.543394,-83.034779,-83.280829,-83.280930,-83.035080,-82.543894,-81.808616,-80.831162,-79.613866,-78.159938,-76.473104,-74.557659,-72.418638,-70.061528,-67.492780,-64.719025,-61.747795,-58.587263,-55.246077,-51.733589,-48.059826,-44.235017,-40.270724,-36.178427,-31.970346,-27.659634,-23.259131,-18.783020,-14.245557,-9.661363}, // NOLINT + {-9.621611,-14.204682,-18.741475,-23.217290,-27.617751,-31.929004,-36.137652,-40.230868,-44.196070,-48.022310,-51.697640,-55.211737,-58.554550,-61.717043,-64.689851,-67.465378,-70.035945,-72.394677,-74.535328,-76.452277,-78.140523,-79.595629,-80.814117,-81.792536,-82.528573,-83.020340,-83.266583,-83.266684,-83.020641,-82.529074,-81.793235,-80.815012,-79.596716,-78.141799,-76.453738,-74.536968,-72.396490,-70.037926,-67.467520,-64.692146,-61.719482,-58.557125,-55.214439,-51.700460,-48.025237,-44.199094,-40.233976,-36.140834,-31.932247,-27.621044,-23.220619,-18.744828,-14.208046,-9.624972}, // NOLINT + {-9.585195,-14.167142,-18.703235,-23.178736,-27.579178,-31.890775,-36.100017,-40.194164,-44.160576,-47.987774,-51.664459,-55.180070,-58.524433,-61.688267,-64.662953,-67.440124,-70.012250,-72.372512,-74.514604,-76.433002,-78.122355,-79.578612,-80.797963,-81.777114,-82.513746,-83.005900,-83.252338,-83.252439,-83.006201,-82.514248,-81.777814,-80.798859,-79.579700,-78.123633,-76.434465,-74.516245,-72.374328,-70.014233,-67.442268,-64.665250,-61.690709,-58.527011,-55.182775,-51.667282,-47.990703,-44.163602,-40.197274,-36.103201,-31.894021,-27.582472,-23.182067,-18.706589,-14.170505,-9.588555}, // NOLINT + {-9.548773,-14.129523,-18.664948,-23.140118,-27.540725,-31.852423,-36.062350,-40.157238,-44.124766,-47.953160,-51.631250,-55.148305,-58.494240,-61.659789,-64.636023,-67.414707,-69.988477,-72.350263,-74.493866,-76.413577,-78.104187,-79.561539,-80.781805,-81.761726,-82.498918,-82.991459,-83.238094,-83.238195,-82.991761,-82.499420,-81.762427,-80.782702,-79.562629,-78.105467,-76.415041,-74.495510,-72.352081,-69.990463,-67.416854,-64.638323,-61.662233,-58.496821,-55.151013,-51.634075,-47.956092,-44.127794,-40.160351,-36.065536,-31.855669,-27.544020,-23.143449,-18.668302,-14.132886,-9.552133}, // NOLINT + {-9.512089,-14.091873,-18.626611,-23.101473,-27.501903,-31.814041,-36.024627,-40.120347,-44.088959,-47.918537,-51.598008,-55.116508,-58.464162,-61.631203,-64.609066,-67.389362,-69.964811,-72.328057,-74.473141,-76.394124,-78.086032,-79.544458,-80.765644,-81.746325,-82.484088,-82.977018,-83.223849,-83.223950,-82.977320,-82.484591,-81.747027,-80.766542,-79.545549,-78.087313,-76.395590,-74.474788,-72.329877,-69.966800,-67.391511,-64.611369,-61.633650,-58.466745,-55.119219,-51.600836,-47.921471,-44.091990,-40.123462,-36.027814,-31.817290,-27.505200,-23.104806,-18.629966,-14.095236,-9.515449}, // NOLINT + {-9.475471,-14.054151,-18.588225,-23.062768,-27.463231,-31.775824,-35.986902,-40.083428,-44.053081,-47.883802,-51.564723,-55.084620,-58.433844,-61.602590,-64.582108,-67.364107,-69.941065,-72.305907,-74.452388,-76.374716,-78.067865,-79.527391,-80.749480,-81.730911,-82.469258,-82.962577,-83.209603,-83.209704,-82.962880,-82.469762,-81.731614,-80.750379,-79.528484,-78.069147,-76.376185,-74.454037,-72.307730,-69.943056,-67.366258,-64.584413,-61.605040,-58.436430,-55.087334,-51.567554,-47.886739,-44.056113,-40.086545,-35.990092,-31.779074,-27.466529,-23.066101,-18.591580,-14.057515,-9.478830}, // NOLINT + {-9.438801,-14.016424,-18.549812,-23.024004,-27.424592,-31.737340,-35.949068,-40.046471,-44.017225,-47.849212,-51.531414,-55.052918,-58.403555,-61.573908,-64.555105,-67.338758,-69.917305,-72.283716,-74.431626,-76.355314,-78.049676,-79.510265,-80.733312,-81.715481,-82.454428,-82.948135,-83.195358,-83.195460,-82.948439,-82.454932,-81.716185,-80.734212,-79.511359,-78.050961,-76.356784,-74.433276,-72.285541,-69.919298,-67.340912,-64.557413,-61.576361,-58.406144,-55.055634,-51.534247,-47.852151,-44.020260,-40.049590,-35.952260,-31.740592,-27.427891,-23.027338,-18.553167,-14.019788,-9.442160}, // NOLINT + {-9.402077,-13.978670,-18.511327,-22.985225,-27.385781,-31.698942,-35.911064,-40.009465,-43.981209,-47.814422,-51.497923,-55.021058,-58.373336,-61.545298,-64.528088,-67.313358,-69.893523,-72.261481,-74.410849,-76.335869,-78.031477,-79.493161,-80.717140,-81.700080,-82.439595,-82.933693,-83.181113,-83.181214,-82.933996,-82.440100,-81.700785,-80.718042,-79.494258,-78.032763,-76.337341,-74.412502,-72.263308,-69.895519,-67.315515,-64.530398,-61.547754,-58.375928,-55.023776,-51.500759,-47.817364,-43.984247,-40.012586,-35.914257,-31.702196,-27.389082,-22.988560,-18.514683,-13.982034,-9.405436}, // NOLINT + {-9.365353,-13.940783,-18.472803,-22.946388,-27.346959,-31.660409,-35.873308,-39.972407,-43.945220,-47.779775,-51.464695,-54.989162,-58.343000,-61.516586,-64.501047,-67.287999,-69.869727,-72.239234,-74.390068,-76.316456,-78.013276,-79.476056,-80.700965,-81.684662,-82.424767,-82.919248,-83.166868,-83.166969,-82.919552,-82.425273,-81.685368,-80.701869,-79.477154,-78.014564,-76.317930,-74.391723,-72.241064,-69.871725,-67.290159,-64.503360,-61.519044,-58.345595,-54.991883,-51.467533,-47.782719,-43.948259,-39.975530,-35.876503,-31.663664,-27.350261,-22.949724,-18.476160,-13.944147,-9.368711}, // NOLINT + {-9.328373,-13.902892,-18.434235,-22.907489,-27.308093,-31.621912,-35.835317,-39.935309,-43.909135,-47.744984,-51.431274,-54.957243,-58.312642,-61.487909,-64.473999,-67.262567,-69.845916,-72.216964,-74.369246,-76.297019,-77.995165,-79.458911,-80.684787,-81.669259,-82.409926,-82.904808,-83.152623,-83.152724,-82.905112,-82.410432,-81.669966,-80.685692,-79.460010,-77.996455,-76.298495,-74.370904,-72.218796,-69.847917,-67.264729,-64.476314,-61.490370,-58.315239,-54.959968,-51.434115,-47.747931,-43.912177,-39.938435,-35.838515,-31.625169,-27.311396,-22.910826,-18.437592,-13.906256,-9.331730}, // NOLINT + {-9.291552,-13.864979,-18.395612,-22.868542,-27.269173,-31.583436,-35.797392,-39.898191,-43.873116,-47.710156,-51.397840,-54.925267,-58.282281,-61.459151,-64.446906,-67.237114,-69.822080,-72.194689,-74.348457,-76.277555,-77.976855,-79.441825,-80.668605,-81.653850,-82.395090,-82.890365,-83.138377,-83.138479,-82.890671,-82.395597,-81.654558,-80.669511,-79.442926,-77.978147,-76.279033,-74.350116,-72.196523,-69.824083,-67.239279,-64.449225,-61.461615,-58.284881,-54.927994,-51.400684,-47.713105,-43.876161,-39.901318,-35.800592,-31.586694,-27.272478,-22.871880,-18.398970,-13.868343,-9.294908}, // NOLINT + {-9.254742,-13.826967,-18.356937,-22.829557,-27.230098,-31.544701,-35.759086,-39.861011,-43.837012,-47.675268,-51.364300,-54.893342,-58.251883,-61.430402,-64.419788,-67.211647,-69.798242,-72.172401,-74.327633,-76.258115,-77.958659,-79.424660,-80.652420,-81.638410,-82.380271,-82.875922,-83.124132,-83.124234,-82.876227,-82.380779,-81.639119,-80.653327,-79.425763,-77.959952,-76.259595,-74.329294,-72.174238,-69.800248,-67.213815,-64.422109,-61.432868,-58.254486,-54.896071,-51.367146,-47.678220,-43.840059,-39.864141,-35.762287,-31.547961,-27.233404,-22.832895,-18.360295,-13.830331,-9.258098}, // NOLINT + {-9.217784,-13.788768,-18.318214,-22.790525,-27.191205,-31.506033,-35.721281,-39.823795,-43.800847,-47.640362,-51.330822,-54.861298,-58.221459,-61.401569,-64.392653,-67.186160,-69.774368,-72.150105,-74.306795,-76.238647,-77.940428,-79.407575,-80.636231,-81.622997,-82.365405,-82.861478,-83.109887,-83.109989,-82.861784,-82.365914,-81.623707,-80.637140,-79.408679,-77.941723,-76.240129,-74.308458,-72.151944,-69.776376,-67.188330,-64.394977,-61.404039,-58.224064,-54.864030,-51.333671,-47.643317,-43.803896,-39.826927,-35.724484,-31.509294,-27.194512,-22.793864,-18.321573,-13.792132,-9.221140}, // NOLINT + {-9.180804,-13.750855,-18.279448,-22.751452,-27.152139,-31.467262,-35.683217,-39.786573,-43.764662,-47.605437,-51.297316,-54.829250,-58.190959,-61.372804,-64.365504,-67.160639,-69.750506,-72.127764,-74.285947,-76.219156,-77.922197,-79.390442,-80.620039,-81.607585,-82.350575,-82.847034,-83.095641,-83.095743,-82.847340,-82.351085,-81.608296,-80.620949,-79.391547,-77.923494,-76.220640,-74.287613,-72.129606,-69.752517,-67.162811,-64.367831,-61.375275,-58.193568,-54.831985,-51.300167,-47.608394,-43.767714,-39.789707,-35.686421,-31.470525,-27.155447,-22.754793,-18.282807,-13.754219,-9.184159}, // NOLINT + {-9.143763,-13.712737,-18.240639,-22.712332,-27.113054,-31.428531,-35.645054,-39.749238,-43.728437,-47.570448,-51.263693,-54.797184,-58.160517,-61.343953,-64.338289,-67.135193,-69.726595,-72.105412,-74.265099,-76.199675,-77.903941,-79.373278,-80.603843,-81.592152,-82.335734,-82.832589,-83.081395,-83.081498,-82.832896,-82.336244,-81.592864,-80.604754,-79.374385,-77.905240,-76.201161,-74.266767,-72.107256,-69.728608,-67.137368,-64.340618,-61.346428,-58.163128,-54.799922,-51.266547,-47.573408,-43.731490,-39.752375,-35.648261,-31.431796,-27.116363,-22.715673,-18.243998,-13.716101,-9.147117}, // NOLINT + {-9.106688,-13.674559,-18.201788,-22.673161,-27.073900,-31.389734,-35.606840,-39.711899,-43.692195,-47.535430,-51.230081,-54.765053,-58.130052,-61.315043,-64.311129,-67.109630,-69.702700,-72.083065,-74.244208,-76.180278,-77.885712,-79.356156,-80.587644,-81.576728,-82.320905,-82.818145,-83.067150,-83.067252,-82.818452,-82.321416,-81.577441,-80.588556,-79.357264,-77.887013,-76.181766,-74.245878,-72.084912,-69.704716,-67.111807,-64.313461,-61.317520,-58.132665,-54.767793,-51.232938,-47.538392,-43.695251,-39.715038,-35.610049,-31.393000,-27.077210,-22.676503,-18.205147,-13.677923,-9.110042}, // NOLINT + {-9.069563,-13.636355,-18.162896,-22.633938,-27.034738,-31.350939,-35.568491,-39.674522,-43.655974,-47.500374,-51.196380,-54.732954,-58.099457,-61.286179,-64.283884,-67.084069,-69.678762,-72.060712,-74.223369,-76.160649,-77.867455,-79.339016,-80.571441,-81.561291,-82.306058,-82.803699,-83.052904,-83.053007,-82.804007,-82.306570,-81.562005,-80.572355,-79.340126,-77.868758,-76.162139,-74.225042,-72.062560,-69.680781,-67.086249,-64.286219,-61.288660,-58.102074,-54.735697,-51.199239,-47.503339,-43.659033,-39.677663,-35.571702,-31.354207,-27.038050,-22.637280,-18.166256,-13.639718,-9.072916}, // NOLINT + {-8.053127,-12.556270,-17.015702,-21.417060,-25.746290,-29.989927,-34.134626,-38.167801,-42.077163,-45.851032,-49.478214,-52.948088,-56.250593,-59.376274,-62.316242,-65.062112,-67.606343,-69.941852,-72.062200,-73.961600,-75.634888,-77.077576,-78.285781,-79.256184,-79.986325,-80.474194,-80.718498,-80.718601,-80.474501,-79.986835,-79.256896,-78.286691,-77.078683,-75.636188,-73.963088,-72.063871,-69.943701,-67.608364,-65.064297,-62.318585,-59.378767,-56.253227,-52.950855,-49.481104,-45.854035,-42.080269,-38.170999,-34.137904,-29.993274,-25.749694,-21.420509,-17.019184,-12.559772,-8.056637}, // NOLINT + {-8.014395,-12.515136,-16.972520,-21.372160,-25.700084,-29.942407,-34.086456,-38.119055,-42.028076,-45.801844,-49.429011,-52.899080,-56.201892,-59.327967,-62.268407,-65.014890,-67.559673,-69.895778,-72.016654,-73.916693,-75.590521,-77.033699,-78.242307,-79.213100,-79.943503,-80.431549,-80.675951,-80.676054,-80.431855,-79.944014,-79.213813,-78.243218,-77.034807,-75.591822,-73.918182,-72.018328,-69.897630,-67.561696,-65.017078,-62.270753,-59.330463,-56.204530,-52.901850,-49.431904,-45.804850,-42.031184,-38.122254,-34.089736,-29.945756,-25.703490,-21.375611,-16.976003,-12.518639,-8.017904}, // NOLINT + {-7.975641,-12.473957,-16.929288,-21.327232,-25.653727,-29.895025,-34.038216,-38.070253,-41.978945,-45.752522,-49.379780,-52.849999,-56.153148,-59.279651,-62.220570,-64.967744,-67.512993,-69.849690,-71.971239,-73.871783,-75.546164,-76.989886,-78.198833,-79.170009,-79.900675,-80.388894,-80.633404,-80.633506,-80.389201,-79.901186,-79.170722,-78.199746,-76.990995,-75.547467,-73.873275,-71.972914,-69.851543,-67.515019,-64.969934,-62.222918,-59.282149,-56.155788,-52.852771,-49.382675,-45.755529,-41.982055,-38.073455,-34.041498,-29.898376,-25.657135,-21.330684,-16.932772,-12.477460,-7.979151}, // NOLINT + {-7.936831,-12.432727,-16.886013,-21.282245,-25.607415,-29.847640,-33.989955,-38.021375,-41.929835,-45.703264,-49.330511,-52.800951,-56.104374,-59.231310,-62.172706,-64.920195,-67.466289,-69.803629,-71.925724,-73.826865,-75.501799,-76.945929,-78.155360,-79.126901,-79.857846,-80.346269,-80.590857,-80.590959,-80.346576,-79.858357,-79.127615,-78.156274,-76.947040,-75.503104,-73.828358,-71.927401,-69.805484,-67.468317,-64.922388,-62.175056,-59.233811,-56.107016,-52.803725,-49.333409,-45.706274,-41.932948,-38.024579,-33.993239,-29.850993,-25.610824,-21.285698,-16.889497,-12.436231,-7.940341}, // NOLINT + {-7.898025,-12.391454,-16.842689,-21.237307,-25.560968,-29.800082,-33.941634,-37.972526,-41.880504,-45.653830,-49.281211,-52.751843,-56.055610,-59.182940,-62.124859,-64.872956,-67.419573,-69.757471,-71.880233,-73.781943,-75.457405,-76.902054,-78.111886,-79.083784,-79.815017,-80.303626,-80.548309,-80.548412,-80.303934,-79.815529,-79.084499,-78.112801,-76.903166,-75.458711,-73.783438,-71.881912,-69.759328,-67.421603,-64.875151,-62.127212,-59.185443,-56.058254,-52.754620,-49.284111,-45.656843,-41.883618,-37.975732,-33.944920,-29.803436,-25.564379,-21.240761,-16.846174,-12.394957,-7.901534}, // NOLINT + {-7.859047,-12.350134,-16.799315,-21.192121,-25.514419,-29.752626,-33.893273,-37.923661,-41.831257,-45.604517,-49.231872,-52.702706,-56.006729,-59.134552,-62.076969,-64.825589,-67.372838,-69.711303,-71.834710,-73.737009,-75.413013,-76.858136,-78.068411,-79.040698,-79.772189,-80.260984,-80.505762,-80.505865,-80.261293,-79.772702,-79.041413,-78.069327,-76.859250,-75.414320,-73.738505,-71.836391,-69.713163,-67.374870,-64.827786,-62.079325,-59.137058,-56.009376,-52.705485,-49.234774,-45.607532,-41.834374,-37.926869,-33.896561,-29.755982,-25.517831,-21.195576,-16.802801,-12.353639,-7.862556}, // NOLINT + {-7.820097,-12.308760,-16.755890,-21.147002,-25.467955,-29.705163,-33.844881,-37.874659,-41.781925,-45.555098,-49.182521,-52.653574,-55.957950,-59.085974,-62.029062,-64.778237,-67.326089,-69.665368,-71.789186,-73.692062,-75.368624,-76.814245,-78.025066,-78.997607,-79.729356,-80.218341,-80.463215,-80.463318,-80.218650,-79.729870,-78.998324,-78.025983,-76.815360,-75.369933,-73.693560,-71.790869,-69.667230,-67.328123,-64.780437,-62.031421,-59.088482,-55.960600,-52.656356,-49.185426,-45.558115,-41.785044,-37.877869,-33.848171,-29.708520,-25.471369,-21.150459,-16.759377,-12.312264,-7.823606}, // NOLINT + {-7.781080,-12.267324,-16.712412,-21.101797,-25.421337,-29.657382,-33.796442,-37.825679,-41.732719,-45.505624,-49.133113,-52.604384,-55.909080,-59.037713,-61.981128,-64.730874,-67.279326,-69.619172,-71.743634,-73.647092,-75.324217,-76.770386,-77.981591,-78.954469,-79.686526,-80.175698,-80.420666,-80.420770,-80.176007,-79.687040,-78.955186,-77.982510,-76.771502,-75.325528,-73.648592,-71.745318,-69.621036,-67.281363,-64.733076,-61.983489,-59.040223,-55.911732,-52.607169,-49.136020,-45.508644,-41.735841,-37.828892,-33.799733,-29.660741,-25.424751,-21.105254,-16.715900,-12.270829,-7.784590}, // NOLINT + {-7.742028,-12.225830,-16.668883,-21.056579,-25.374803,-29.609695,-33.747947,-37.776692,-41.683329,-45.456175,-49.083688,-52.555110,-55.860187,-58.989221,-61.933171,-64.683489,-67.232488,-69.572909,-71.698096,-73.602146,-75.279791,-76.726436,-77.938114,-78.911354,-79.643690,-80.133054,-80.378119,-80.378223,-80.133364,-79.644205,-78.912073,-77.939034,-76.727553,-75.281103,-73.603648,-71.699783,-69.574775,-67.234527,-64.685693,-61.935534,-58.991734,-55.862841,-52.557897,-49.086597,-45.459197,-41.686452,-37.779906,-33.751240,-29.613056,-25.378219,-21.060037,-16.672372,-12.229336,-7.745537}, // NOLINT + {-7.702897,-12.184309,-16.625303,-21.011308,-25.328132,-29.561892,-33.699410,-37.727505,-41.633918,-45.406621,-49.034219,-52.505836,-55.811217,-58.940714,-61.885208,-64.636086,-67.185749,-69.526730,-71.652506,-73.557205,-75.235390,-76.682528,-77.894635,-78.868248,-79.600862,-80.090411,-80.335572,-80.335675,-80.090721,-79.601377,-78.868968,-77.895556,-76.683647,-75.236704,-73.558709,-71.654195,-69.528598,-67.187790,-64.638293,-61.887573,-58.943229,-55.813874,-52.508625,-49.037131,-45.409645,-41.637044,-37.730722,-33.702705,-29.565255,-25.331550,-21.014767,-16.628792,-12.187815,-7.706406}, // NOLINT + {-7.663773,-12.142747,-16.581682,-20.965982,-25.281372,-29.514186,-33.650837,-37.678400,-41.584482,-45.357063,-48.984719,-52.456635,-55.762311,-58.892222,-61.837206,-64.588687,-67.138934,-69.480539,-71.606956,-73.512184,-75.190970,-76.638585,-77.851153,-78.825139,-79.558025,-80.047767,-80.293024,-80.293128,-80.048078,-79.558542,-78.825860,-77.852075,-76.639706,-75.192285,-73.513690,-71.608647,-69.482410,-67.140977,-64.590896,-61.839574,-58.894740,-55.764970,-52.459427,-48.987633,-45.360089,-41.587610,-37.681618,-33.654134,-29.517550,-25.284790,-20.969443,-16.585172,-12.146253,-7.667282}, // NOLINT + {-7.624562,-12.101137,-16.538014,-20.920616,-25.234680,-29.466361,-33.602218,-37.629260,-41.535011,-45.307459,-48.935178,-52.407197,-55.713333,-58.843647,-61.789194,-64.541261,-67.092050,-69.434336,-71.561363,-73.467214,-75.146540,-76.594680,-77.807669,-78.782020,-79.515193,-80.005122,-80.250476,-80.250580,-80.005433,-79.515710,-78.782742,-77.808592,-76.595802,-75.147857,-73.468722,-71.563056,-69.436208,-67.094095,-64.543473,-61.791564,-58.846167,-55.715996,-52.409992,-48.938095,-45.310488,-41.538142,-37.632480,-33.605517,-29.469727,-25.238100,-20.924077,-16.541504,-12.104643,-7.628070}, // NOLINT + {-7.585321,-12.059478,-16.494294,-20.875182,-25.187880,-29.418419,-33.553552,-37.580059,-41.485447,-45.257831,-48.885562,-52.357886,-55.664320,-58.795138,-61.741146,-64.494064,-67.045256,-69.388118,-71.515745,-73.422207,-75.102109,-76.550758,-77.764182,-78.738889,-79.472353,-79.962478,-80.207929,-80.208033,-79.962789,-79.472870,-78.739611,-77.765106,-76.551881,-75.103428,-73.423716,-71.517439,-69.389992,-67.047304,-64.496279,-61.743519,-58.797661,-55.666985,-52.360683,-48.888481,-45.260862,-41.488580,-37.583282,-33.556853,-29.421787,-25.191301,-20.878645,-16.497785,-12.062985,-7.588829}, // NOLINT + {-7.546004,-12.017735,-16.450506,-20.829719,-25.141045,-29.370548,-33.504834,-37.530805,-41.435968,-45.208166,-48.835980,-52.308508,-55.615248,-58.746539,-61.693090,-64.446333,-66.998395,-69.341885,-71.470160,-73.377235,-75.057671,-76.506808,-77.720692,-78.695749,-79.429515,-79.919832,-80.165381,-80.165485,-79.920144,-79.430034,-78.696472,-77.721617,-76.507933,-75.058991,-73.378746,-71.471857,-69.343762,-67.000445,-64.448549,-61.695466,-58.749064,-55.617915,-52.311308,-48.838902,-45.211200,-41.439103,-37.534030,-33.508136,-29.373917,-25.144467,-20.833183,-16.453998,-12.021242,-7.549512}, // NOLINT + {-7.506659,-11.975955,-16.406688,-20.784202,-25.094159,-29.322560,-33.456105,-37.481525,-41.386309,-45.158461,-48.786377,-52.259073,-55.566222,-58.697931,-61.644991,-64.398835,-66.951513,-69.295640,-71.424542,-73.332188,-75.013209,-76.462849,-77.677199,-78.652689,-79.386683,-79.877187,-80.122833,-80.122937,-79.877499,-79.387202,-78.653413,-77.678126,-76.463975,-75.014531,-73.333701,-71.426241,-69.297519,-66.953566,-64.401054,-61.647369,-58.700459,-55.568892,-52.261876,-48.789301,-45.161497,-41.389446,-37.484752,-33.459410,-29.325931,-25.097583,-20.787667,-16.410181,-11.979462,-7.510168}, // NOLINT + {-7.467266,-11.934144,-16.362822,-20.738636,-25.047437,-29.274730,-33.407304,-37.432169,-41.336634,-45.108709,-48.736706,-52.209658,-55.517130,-58.649295,-61.596905,-64.351319,-66.904622,-69.249380,-71.378917,-73.287163,-74.968751,-76.418916,-77.633703,-78.609556,-79.343835,-79.834541,-80.080285,-80.080389,-79.834853,-79.344355,-78.610281,-77.634631,-76.420044,-74.970074,-73.288678,-71.380618,-69.251261,-66.906677,-64.353540,-61.599285,-58.651825,-55.519803,-52.212463,-48.739633,-45.111747,-41.339773,-37.435398,-33.410611,-29.278102,-25.050863,-20.742102,-16.366315,-11.937651,-7.470774}, // NOLINT + {-7.427649,-11.892277,-16.318907,-20.693033,-25.000226,-29.226478,-33.358459,-37.382815,-41.286998,-45.058934,-48.686997,-52.160167,-55.468067,-58.600627,-61.548753,-64.303783,-66.857709,-69.203109,-71.333258,-73.242138,-74.924295,-76.375033,-77.590204,-78.566434,-79.300998,-79.791895,-80.037738,-80.037843,-79.792208,-79.301518,-78.567160,-77.591133,-76.376162,-74.925620,-73.243655,-71.334961,-69.204993,-66.859766,-64.306007,-61.551135,-58.603161,-55.470742,-52.162974,-48.689926,-45.061975,-41.290140,-37.386046,-33.361767,-29.229851,-25.003652,-20.696499,-16.322400,-11.895785,-7.431157}, // NOLINT + {-7.388266,-11.850271,-16.274943,-20.647364,-24.953204,-29.178415,-33.309582,-37.333361,-41.237301,-45.008935,-48.637256,-52.110625,-55.418873,-58.551934,-61.500623,-64.256229,-66.810786,-69.156733,-71.287619,-73.197101,-74.879836,-76.331013,-77.546702,-78.523263,-79.258149,-79.749248,-79.995190,-79.995295,-79.749561,-79.258670,-78.523990,-77.547632,-76.332144,-74.881163,-73.198620,-71.289324,-69.158618,-66.812845,-64.258455,-61.503008,-58.554470,-55.421550,-52.113435,-48.640188,-45.011978,-41.240445,-37.336594,-33.312892,-29.181791,-24.956632,-20.650832,-16.278437,-11.853779,-7.391774}, // NOLINT + {-7.348762,-11.808367,-16.230930,-20.601575,-24.906068,-29.130320,-33.260675,-37.283944,-41.187544,-44.959094,-48.587495,-52.061087,-55.369669,-58.503227,-61.452390,-64.208655,-66.763845,-69.110421,-71.241956,-73.152059,-74.835336,-76.287076,-77.503197,-78.480141,-79.215308,-79.706601,-79.952642,-79.952747,-79.706914,-79.215830,-78.480869,-77.504128,-76.288208,-74.836664,-73.153579,-71.243663,-69.112309,-66.765907,-64.210884,-61.454778,-58.505766,-55.372349,-52.063900,-48.590429,-44.962140,-41.190690,-37.287179,-33.263988,-29.133697,-24.909497,-20.605044,-16.234425,-11.811875,-7.352270}, // NOLINT + {-7.309325,-11.766284,-16.186869,-20.555922,-24.859008,-29.082139,-33.211679,-37.234451,-41.137706,-44.909345,-48.537694,-52.011581,-55.320482,-58.454492,-61.404263,-64.161064,-66.716878,-69.064187,-71.196305,-73.106994,-74.790887,-76.243109,-77.459688,-78.437008,-79.172471,-79.663954,-79.910093,-79.910198,-79.664268,-79.172993,-78.437737,-77.460621,-76.244243,-74.792217,-73.108516,-71.198014,-69.066076,-66.718942,-64.163295,-61.406654,-58.457033,-55.323164,-52.014396,-48.540631,-44.912393,-41.140854,-37.237688,-33.214993,-29.085517,-24.862438,-20.559392,-16.190365,-11.769792,-7.312833}, // NOLINT + {-7.269575,-11.724324,-16.142759,-20.510003,-24.811860,-29.033817,-33.162660,-37.184922,-41.087918,-44.859409,-48.487857,-51.961965,-55.271147,-58.405726,-61.356051,-64.113454,-66.669870,-69.017858,-71.150605,-73.061887,-74.746370,-76.199155,-77.416177,-78.393875,-79.129599,-79.621306,-79.867546,-79.867651,-79.621620,-79.130122,-78.394605,-77.417111,-76.200290,-74.747701,-73.063411,-71.152316,-69.019751,-66.671936,-64.115688,-61.358444,-58.408270,-55.273833,-51.964782,-48.490797,-44.862460,-41.091069,-37.188161,-33.165976,-29.037197,-24.815292,-20.513474,-16.146255,-11.727833,-7.273082}, // NOLINT + {-7.229688,-11.682207,-16.098601,-20.464234,-24.764526,-28.985627,-33.113605,-37.135332,-41.037986,-44.809510,-48.437981,-51.912341,-55.221942,-58.356949,-61.307811,-64.065827,-66.622915,-68.971530,-71.104901,-73.016879,-74.701881,-76.155184,-77.372662,-78.350723,-79.086776,-79.578658,-79.824997,-79.825102,-79.578973,-79.087300,-78.351454,-77.373597,-76.156320,-74.703214,-73.018405,-71.106614,-68.973425,-66.624984,-64.068063,-61.310207,-58.359495,-55.224630,-51.915161,-48.440923,-44.812563,-41.041139,-37.138574,-33.116923,-28.989009,-24.767959,-20.467705,-16.102098,-11.685715,-7.233195}, // NOLINT + {-7.190162,-11.640050,-16.054413,-20.418334,-24.717341,-28.937298,-33.064498,-37.085721,-40.988102,-44.759640,-48.388074,-51.862680,-55.172734,-58.308145,-61.259552,-64.018117,-66.575896,-68.925181,-71.059204,-72.971772,-74.657403,-76.111163,-77.329144,-78.307601,-79.043938,-79.536009,-79.782449,-79.782555,-79.536324,-79.044462,-78.308333,-77.330080,-76.112301,-74.658738,-72.973300,-71.060919,-68.927077,-66.577967,-64.020355,-61.261950,-58.310694,-55.175424,-51.865502,-48.391018,-44.762696,-40.991257,-37.088965,-33.067818,-28.940682,-24.720776,-20.421807,-16.057911,-11.643559,-7.193668}, // NOLINT + {-7.150330,-11.597853,-16.010158,-20.372379,-24.670138,-28.888913,-33.015360,-37.036043,-40.938177,-44.709461,-48.338134,-51.813012,-55.123329,-58.259306,-61.211267,-63.970453,-66.528879,-68.878821,-71.013486,-72.926703,-74.612888,-76.067224,-77.285622,-78.264438,-79.001082,-79.493360,-79.739901,-79.740006,-79.493676,-79.001607,-78.265171,-77.286559,-76.068363,-74.614224,-72.928233,-71.015203,-68.880720,-66.530952,-63.972694,-61.213668,-58.261857,-55.126022,-51.815837,-48.341081,-44.712519,-40.941334,-37.039288,-33.018681,-28.892298,-24.673574,-20.375853,-16.013656,-11.601362,-7.153836}, // NOLINT + {-7.110518,-11.555565,-15.965851,-20.326376,-24.622532,-28.840519,-32.966173,-36.986328,-40.888186,-44.659389,-48.288155,-51.763265,-55.074044,-58.210393,-61.162967,-63.922783,-66.481834,-68.832438,-70.967758,-72.881585,-74.568340,-76.023237,-77.242097,-78.221311,-78.958231,-79.450711,-79.697353,-79.697458,-79.451027,-78.958756,-78.222045,-77.243036,-76.024378,-74.569678,-72.883117,-70.969477,-68.834339,-66.483910,-63.925026,-61.165370,-58.212947,-55.076740,-51.766093,-48.291105,-44.662450,-40.891346,-36.989575,-32.969496,-28.843905,-24.625969,-20.329851,-15.969349,-11.559074,-7.114023}, // NOLINT + {-7.070573,-11.513281,-15.921498,-20.280362,-24.575189,-28.791922,-32.916937,-36.936595,-40.838129,-44.609287,-48.238171,-51.713503,-55.024632,-58.161535,-61.114641,-63.875112,-66.434776,-68.786045,-70.922015,-72.836461,-74.523846,-75.979247,-77.198569,-78.178187,-78.915392,-79.408060,-79.654804,-79.654910,-79.408377,-78.915918,-78.178922,-77.199509,-75.980389,-74.525186,-72.837994,-70.923736,-68.787948,-66.436855,-63.877358,-61.117046,-58.164091,-55.027330,-51.716334,-48.241122,-44.612350,-40.841291,-36.939845,-32.920263,-28.795310,-24.578627,-20.283838,-15.924997,-11.516790,-7.074078}, // NOLINT + {-7.030714,-11.470955,-15.877105,-20.234246,-24.527786,-28.743500,-32.867607,-36.886791,-40.787753,-44.559142,-48.188061,-51.663691,-54.975266,-58.112543,-61.066292,-63.827397,-66.387703,-68.739646,-70.876261,-72.791345,-74.479320,-75.935251,-77.155037,-78.135054,-78.872548,-79.365417,-79.612256,-79.612362,-79.365734,-78.873075,-78.135789,-77.155978,-75.936395,-74.480662,-72.792880,-70.877985,-68.741551,-66.389783,-63.829646,-61.068700,-58.115103,-54.977967,-51.666524,-48.191015,-44.562207,-40.790917,-36.890043,-32.870934,-28.746890,-24.531226,-20.237723,-15.880605,-11.474465,-7.034219}, // NOLINT + {-6.990692,-11.428534,-15.832661,-20.188119,-24.480296,-28.694893,-32.818332,-36.836958,-40.738065,-44.508940,-48.138026,-51.613901,-54.925776,-58.063703,-61.017913,-63.779646,-66.340569,-68.693157,-70.830517,-72.746194,-74.434762,-75.891238,-77.111502,-78.091872,-78.829679,-79.322763,-79.569708,-79.569814,-79.323080,-78.830206,-78.092609,-77.112444,-75.892383,-74.436105,-72.747732,-70.832243,-68.695064,-66.342652,-63.781897,-61.020324,-58.066265,-54.928479,-51.616736,-48.140983,-44.512007,-40.741232,-36.840212,-32.821661,-28.698285,-24.483737,-20.191596,-15.836161,-11.432043,-6.994197}, // NOLINT + {-6.950676,-11.386105,-15.788166,-20.141903,-24.432717,-28.646505,-32.768959,-36.787084,-40.687820,-44.458717,-48.087937,-51.564049,-54.876375,-58.014711,-60.969521,-63.731931,-66.293503,-68.646801,-70.784723,-72.701074,-74.390217,-75.847253,-77.067964,-78.048714,-78.786825,-79.280110,-79.527159,-79.527266,-79.280428,-78.787354,-78.049451,-77.068907,-75.848399,-74.391562,-72.702614,-70.786451,-68.648711,-66.295589,-63.734185,-60.971934,-58.017276,-54.879081,-51.566888,-48.090896,-44.461787,-40.690989,-36.790340,-32.772290,-28.649898,-24.436159,-20.145381,-15.791667,-11.389615,-6.954181}, // NOLINT + {-6.910652,-11.343602,-15.743620,-20.095680,-24.385152,-28.597732,-32.719531,-36.737200,-40.637617,-44.408734,-48.037770,-51.514173,-54.826876,-57.965724,-60.921108,-63.684064,-66.246375,-68.600289,-70.738937,-72.655938,-74.345643,-75.803299,-77.024422,-78.005555,-78.743949,-79.237459,-79.484611,-79.484717,-79.237777,-78.744478,-78.006293,-77.025367,-75.804446,-74.346990,-72.657479,-70.740667,-68.602201,-66.248463,-63.686320,-60.923524,-57.968292,-54.829585,-51.517013,-48.040732,-44.411807,-40.640788,-36.740458,-32.722863,-28.601126,-24.388595,-20.099159,-15.747121,-11.347112,-6.914156}, // NOLINT + {-6.870528,-11.301061,-15.699024,-20.049407,-24.337508,-28.549042,-32.670230,-36.687252,-40.587400,-44.358173,-47.987575,-51.464247,-54.777378,-57.916706,-60.872662,-63.636332,-66.199228,-68.553839,-70.693139,-72.610756,-74.301112,-75.759217,-76.980876,-77.962404,-78.701108,-79.194808,-79.442062,-79.442169,-79.195126,-78.701638,-77.963143,-76.981822,-75.760366,-74.302460,-72.612299,-70.694871,-68.555754,-66.201318,-63.638591,-60.875081,-57.919276,-54.780090,-51.467091,-47.990540,-44.361248,-40.590574,-36.690512,-32.673564,-28.552438,-24.340952,-20.052887,-15.702525,-11.304571,-6.874031}, // NOLINT + {-6.830312,-11.258489,-15.654379,-20.003070,-24.289828,-28.500260,-32.620599,-36.637215,-40.537125,-44.307839,-47.937347,-51.414331,-54.727841,-57.867643,-60.824198,-63.588459,-66.152074,-68.507357,-70.647330,-72.565590,-74.256545,-75.715195,-76.937328,-77.919251,-78.658254,-79.152156,-79.399514,-79.399620,-79.152475,-78.658785,-77.919992,-76.938275,-75.716346,-74.257896,-72.567135,-70.649064,-68.509274,-66.154167,-63.590720,-60.826619,-57.870215,-54.730555,-51.417177,-47.940314,-44.310916,-40.540301,-36.640478,-32.623936,-28.503658,-24.293274,-20.006551,-15.657881,-11.261999,-6.833815}, // NOLINT +}}; // NOLINT + +static const double robinW_kInnoPs2Nps[3][192][55] = {{ + {18.664550,18.453424,18.248632,18.050365,17.858816,17.674173,17.496620,17.326321,17.163441,17.008139,16.860572,16.720873,16.589183,16.465626,16.350323,16.243384,16.144915,16.055009,15.973751,15.901223,15.837493,15.782622,15.736666,15.699669,15.671661,15.652676,15.642729,15.641833,15.649986,15.667183,15.693406,15.728632,15.772827,15.825949,15.887947,15.958763,16.038330,16.126572,16.223402,16.328727,16.442455,16.564469,16.694653,16.832884,16.979029,17.132947,17.294492,17.463508,17.639832,17.823295,18.013720,18.210923,18.414716,18.624901,18.841276,}, // NOLINT + {18.824968,18.609644,18.400483,18.197691,18.001462,17.811981,17.629437,17.453999,17.285838,17.125113,16.971980,16.826584,16.689063,16.559554,16.438172,16.325035,16.220265,16.123944,16.036168,15.957024,15.886585,15.824919,15.772083,15.728129,15.693096,15.667022,15.649925,15.641824,15.642727,15.652632,15.671529,15.699400,15.736218,15.781945,15.836541,15.899951,15.972110,16.052961,16.142413,16.240385,16.346783,16.461505,16.584439,16.715470,16.854466,17.001299,17.155824,17.317894,17.487351,17.664037,17.847766,18.038372,18.235682,18.439486,18.649595,}, // NOLINT + {18.415125,18.204684,18.000560,17.802952,17.612050,17.428039,17.251094,17.081387,16.919083,16.764335,16.617293,16.478097,16.346881,16.223772,16.108885,16.002338,15.904224,15.814643,15.733676,15.661409,15.597903,15.543221,15.497418,15.460534,15.432609,15.413667,15.403728,15.402802,15.410888,15.427981,15.454065,15.489115,15.533096,15.585972,15.647688,15.718188,15.797403,15.885263,15.981679,16.086563,16.199814,16.321324,16.450979,16.588654,16.734218,16.887534,17.048455,17.216826,17.392492,17.575272,17.765008,17.961503,18.164577,18.374040,18.589684,}, // NOLINT + {18.574144,18.359498,18.151012,17.948883,17.753318,17.564487,17.382576,17.207758,17.040201,16.880063,16.727497,16.582650,16.445650,16.316640,16.195730,16.083046,15.978692,15.882756,15.795343,15.716529,15.646390,15.584989,15.532386,15.488635,15.453771,15.427828,15.410830,15.402794,15.403726,15.413626,15.432483,15.460279,15.496988,15.542572,15.596992,15.660192,15.732113,15.812686,15.901838,15.999473,16.105506,16.219838,16.342352,16.472938,16.611464,16.757803,16.911813,17.073347,17.242251,17.418360,17.601508,17.791518,17.988209,18.191393,18.400869,}, // NOLINT + {18.166880,17.957034,17.753497,17.556471,17.366140,17.182685,17.006284,16.837102,16.675309,16.521051,16.374477,16.235727,16.104938,15.982228,15.867717,15.761515,15.663722,15.574431,15.493727,15.421688,15.358382,15.303869,15.258200,15.221421,15.193566,15.174662,15.164727,15.163771,15.171796,15.188794,15.214749,15.249638,15.293427,15.346078,15.407534,15.477750,15.556647,15.644162,15.740203,15.844684,15.957507,16.078565,16.207742,16.344916,16.489961,16.642734,16.803095,16.970890,17.145960,17.328139,17.517255,17.713126,17.915574,18.124387,18.339386,}, // NOLINT + {18.324551,18.110497,17.902616,17.701078,17.506096,17.317839,17.136493,16.962230,16.795212,16.635598,16.483539,16.339181,16.202651,16.074086,15.953607,15.841324,15.737345,15.641767,15.554679,15.476166,15.406296,15.345139,15.292751,15.249180,15.214469,15.188647,15.171741,15.163764,15.164725,15.174622,15.193445,15.221176,15.257788,15.303247,15.357509,15.420523,15.492230,15.572558,15.661435,15.758774,15.864483,15.978465,16.100606,16.230795,16.368905,16.514805,16.668359,16.829418,16.997831,17.173436,17.356067,17.545548,17.741701,17.944338,18.153265,}, // NOLINT + {17.919718,17.710383,17.507357,17.310847,17.121012,16.938052,16.762128,16.593410,16.432070,16.278246,16.132089,15.993738,15.863324,15.740971,15.626793,15.520900,15.423390,15.334359,15.253886,15.182053,15.118924,15.064560,15.019013,14.982325,14.954531,14.935659,14.925726,14.924742,14.932709,14.949619,14.975457,15.010198,15.053812,15.106256,15.167484,15.237438,15.316049,15.403248,15.498952,15.603071,15.715508,15.836158,15.964906,16.101631,16.246208,16.398497,16.558358,16.725639,16.900182,17.081822,17.270394,17.465707,17.667588,17.875844,18.090276,}, // NOLINT + {18.076092,17.862569,17.655200,17.454188,17.259717,17.071971,16.891127,16.717355,16.550818,16.391671,16.240065,16.096141,15.960035,15.831874,15.711777,15.599857,15.496218,15.400958,15.314165,15.235922,15.166298,15.105361,15.053165,15.009761,14.975188,14.949479,14.932656,14.924736,14.925724,14.935620,14.954415,14.982089,15.018617,15.063964,15.118087,15.180938,15.252450,15.332563,15.421198,15.518272,15.623694,15.737364,15.859175,15.989013,16.126753,16.272266,16.425415,16.586062,16.754038,16.929199,17.111375,17.300387,17.496078,17.698239,17.906690,}, // NOLINT + {17.673538,17.464658,17.262082,17.066018,16.876614,16.694079,16.518580,16.350272,16.189324,16.035883,15.890094,15.752094,15.622014,15.499975,15.386092,15.280474,15.183216,15.094414,15.014149,14.942497,14.879525,14.825294,14.779851,14.743244,14.715504,14.696658,14.686725,14.685714,14.693626,14.710455,14.736186,14.770793,14.814247,14.866505,14.927523,14.997240,15.075593,15.162509,15.257909,15.361702,15.473790,15.594072,15.722439,15.858765,16.002921,16.154786,16.314195,16.481018,16.655093,16.836259,17.024343,17.219170,17.420559,17.628323,17.842266,}, // NOLINT + {17.828675,17.615607,17.408691,17.208137,17.014115,16.826822,16.646420,16.473080,16.306970,16.148238,15.997037,15.853504,15.717773,15.589971,15.470217,15.358622,15.255290,15.160317,15.073789,14.995787,14.926387,14.865647,14.813627,14.770375,14.735929,14.710322,14.693576,14.685708,14.686723,14.696620,14.715391,14.743017,14.779471,14.824721,14.878722,14.941424,15.012770,15.092690,15.181112,15.277952,15.383120,15.496515,15.618034,15.747560,15.884975,16.030148,16.182943,16.343217,16.510820,16.685594,16.867378,17.055992,17.251269,17.453020,17.661057,}, // NOLINT + {17.428269,17.219776,17.017588,16.821898,16.632878,16.450717,16.275580,16.107632,15.947031,15.793921,15.648460,15.510771,15.380982,15.259221,15.145600,15.040222,14.943185,14.854588,14.774505,14.703014,14.640180,14.586064,14.540715,14.504177,14.476483,14.457659,14.447724,14.446686,14.454548,14.471302,14.496934,14.531422,14.574727,14.626820,14.687645,14.757150,14.835270,14.921934,15.017058,15.120558,15.232336,15.352293,15.480313,15.616279,15.760066,15.911539,16.070559,16.236972,16.410640,16.591385,16.779045,16.973445,17.174405,17.381736,17.595246,}, // NOLINT + {17.582217,17.369544,17.163027,16.962864,16.769240,16.582331,16.402320,16.229365,16.063629,15.905260,15.754422,15.611232,15.475836,15.348355,15.228907,15.117603,15.014544,14.919829,14.833539,14.755758,14.686556,14.625997,14.574135,14.531021,14.496689,14.471175,14.454500,14.446680,14.447721,14.457623,14.476374,14.503958,14.540351,14.585513,14.639408,14.701980,14.773178,14.852931,14.941166,15.037799,15.142740,15.255897,15.377159,15.506414,15.643542,15.788418,15.940903,16.100858,16.268133,16.442571,16.624010,16.812281,17.007209,17.208611,17.416293,}, // NOLINT + {17.183838,16.975677,16.773816,16.578448,16.389757,16.207916,16.033095,15.865457,15.705157,15.552341,15.407159,15.269739,15.140209,15.018691,14.905297,14.800132,14.703293,14.614872,14.534948,14.463599,14.400887,14.346870,14.301605,14.265124,14.237468,14.218662,14.208722,14.207659,14.215474,14.232160,14.257701,14.292077,14.335253,14.387192,14.447846,14.517161,14.595069,14.681503,14.776383,14.879622,14.991123,15.110787,15.238502,15.374150,15.517607,15.668741,15.827412,15.993474,16.166774,16.347152,16.534442,16.728471,16.929061,17.136020,17.349164,}, // NOLINT + {17.336659,17.124312,16.918129,16.718308,16.525024,16.338458,16.158782,15.986163,15.820754,15.662711,15.512182,15.369301,15.234200,15.107004,14.987831,14.876783,14.773969,14.679481,14.593403,14.515823,14.446800,14.386402,14.334683,14.291692,14.257466,14.232037,14.215428,14.207653,14.208720,14.218626,14.237363,14.264913,14.301249,14.346339,14.400141,14.462604,14.533671,14.613277,14.701347,14.797800,14.902548,15.015493,15.136531,15.265550,15.402431,15.547050,15.699265,15.858944,16.025936,16.200085,16.381239,16.569210,16.763838,16.964949,17.172345,}, // NOLINT + {16.940198,16.732299,16.530712,16.335619,16.147200,15.965635,15.791084,15.623711,15.463673,15.311109,15.166167,15.028980,14.899674,14.778367,14.665171,14.560191,14.463523,14.375256,14.295472,14.224243,14.161636,14.107709,14.062510,14.026082,13.998459,13.979666,13.969721,13.968633,13.976403,13.993026,14.018485,14.052760,14.095817,14.147619,14.208119,14.277260,14.354986,14.441212,14.535871,14.638878,14.750136,14.869538,14.996982,15.132349,15.275516,15.426350,15.584716,15.750467,15.923452,16.103512,16.290482,16.484195,16.684460,16.891107,17.103941,}, // NOLINT + {17.091918,16.879849,16.673958,16.474417,16.281427,16.095148,15.915764,15.743433,15.578312,15.420552,15.270297,15.127684,14.992841,14.865899,14.746963,14.636148,14.533553,14.439268,14.353383,14.275974,14.207109,14.146860,14.095267,14.052391,14.018260,13.992909,13.976359,13.968627,13.969719,13.979632,13.998358,14.025879,14.062170,14.107196,14.160918,14.223285,14.294241,14.373719,14.461647,14.557944,14.662522,14.775286,14.896132,15.024946,15.161612,15.306009,15.457997,15.617441,15.784192,15.958098,16.138999,16.326729,16.521115,16.721980,16.929133,}, // NOLINT + {16.697265,16.489589,16.288227,16.093367,15.905171,15.723835,15.549511,15.382362,15.222541,15.070194,14.925461,14.788475,14.659360,14.538234,14.425210,14.320388,14.223867,14.135734,14.056070,13.984945,13.922430,13.868577,13.823438,13.787053,13.759456,13.740672,13.730719,13.729607,13.737336,13.753901,13.779286,13.813468,13.856418,13.908097,13.968458,14.037446,14.114998,14.201048,14.295516,14.398313,14.509350,14.628526,14.755732,14.890852,15.033764,15.184337,15.342438,15.507920,15.680632,15.860419,16.047116,16.240549,16.440554,16.646937,16.859513,}, // NOLINT + {16.847941,16.636098,16.430440,16.231142,16.038394,15.852367,15.673230,15.501146,15.336271,15.178751,15.028738,14.886360,14.751747,14.625021,14.506298,14.395684,14.293278,14.199176,14.113458,14.036208,13.967490,13.907366,13.855892,13.813113,13.779069,13.753788,13.737294,13.729602,13.730717,13.740639,13.759358,13.786856,13.823109,13.868083,13.921737,13.984021,14.054881,14.134251,14.222057,14.318221,14.422656,14.535262,14.655942,14.784584,14.921071,15.065277,15.217073,15.376318,15.542867,15.716571,15.897268,16.084796,16.278978,16.479646,16.686609,}, // NOLINT + {16.455000,16.247499,16.046314,15.851631,15.663632,15.482480,15.308344,15.141381,14.981744,14.829578,14.685020,14.548203,14.419253,14.298279,14.185399,14.080715,13.984316,13.896299,13.816737,13.745703,13.683264,13.629474,13.584383,13.548033,13.520457,13.501679,13.491718,13.490581,13.498272,13.514783,13.540100,13.574200,13.617054,13.668622,13.728859,13.797711,13.875116,13.961003,14.055297,14.157913,14.268759,14.387734,14.514732,14.649637,14.792329,14.942681,15.100549,15.265800,15.438280,15.617833,15.804307,15.997512,16.197289,16.403455,16.615829,}, // NOLINT + {16.604666,16.393008,16.187538,15.988440,15.795895,15.610071,15.431143,15.259269,15.094603,14.937296,14.787483,14.645306,14.510890,14.384355,14.265815,14.155379,14.053143,13.959193,13.873631,13.796518,13.727925,13.667918,13.616547,13.573858,13.539891,13.514674,13.498232,13.490577,13.491715,13.501647,13.520362,13.547843,13.584065,13.628995,13.682595,13.744810,13.815588,13.894868,13.982569,14.078621,14.182933,14.295409,14.415953,14.544447,14.680781,14.824832,14.976466,15.135549,15.301934,15.475472,15.656005,15.843370,16.037396,16.237908,16.444724,}, // NOLINT + {16.213353,16.005972,15.804935,15.610401,15.422538,15.241540,15.067554,14.900743,14.741256,14.589238,14.444825,14.308147,14.179328,14.058488,13.945730,13.841159,13.744869,13.656945,13.577468,13.506507,13.444134,13.390396,13.345346,13.309024,13.281463,13.262688,13.252716,13.251557,13.259211,13.275673,13.300928,13.334955,13.377721,13.429192,13.489317,13.558048,13.635321,13.721070,13.815212,13.917669,14.028348,14.147148,14.273965,14.408686,14.551188,14.701345,14.859021,15.024075,15.196362,15.375723,15.561997,15.755023,15.954621,16.160607,16.372819,}, // NOLINT + {16.362051,16.150533,15.945217,15.746268,15.553884,15.368232,15.189474,15.017774,14.853283,14.696149,14.546510,14.404504,14.270255,14.143886,14.025506,13.915222,13.813131,13.719326,13.633890,13.556896,13.488419,13.428513,13.377232,13.334624,13.300727,13.275569,13.259173,13.251552,13.252714,13.262656,13.281370,13.308839,13.345038,13.389933,13.443484,13.505646,13.576357,13.655558,13.743176,13.839134,13.943345,14.055713,14.176140,14.304517,14.440728,14.584651,14.736157,14.895106,15.061362,15.234770,15.415176,15.602416,15.796322,15.996725,16.203431,}, // NOLINT + {15.972279,15.764990,15.564050,15.369616,15.181872,15.000984,14.827116,14.660422,14.501055,14.349155,14.204853,14.068294,13.939586,13.818850,13.706191,13.601715,13.505510,13.417665,13.338259,13.267361,13.205039,13.151343,13.106324,13.070024,13.042474,13.023698,13.013714,13.012532,13.020153,13.036570,13.061769,13.095729,13.138418,13.189800,13.249831,13.318455,13.395613,13.481236,13.575248,13.677567,13.788101,13.906752,14.033416,14.167978,14.310320,14.460315,14.617828,14.782722,14.954847,15.134051,15.320183,15.513051,15.712508,15.918367,16.130448,}, // NOLINT + {16.120049,15.908631,15.703417,15.504592,15.312337,15.126813,14.948191,14.776630,14.612282,14.455292,14.305800,14.163938,14.029831,13.903601,13.785356,13.675202,13.573238,13.479553,13.394230,13.317343,13.248963,13.189144,13.137946,13.095411,13.061576,13.036470,13.020116,13.012528,13.013712,13.023667,13.042383,13.069844,13.106025,13.150893,13.204408,13.266524,13.337183,13.416322,13.503876,13.599755,13.703883,13.816165,13.936499,14.064782,14.200895,14.344717,14.496109,14.654978,14.821124,14.994437,15.174749,15.361904,15.555724,15.756044,15.962689,}, // NOLINT + {15.731739,15.524511,15.323625,15.129263,14.941594,14.760788,14.587003,14.420399,14.261123,14.109311,13.965105,13.828628,13.700007,13.579355,13.466775,13.362373,13.266236,13.178456,13.099103,13.028259,12.965975,12.912311,12.867317,12.831032,12.803487,12.784709,12.774712,12.773508,12.781097,12.797472,12.822622,12.856522,12.899143,12.950448,13.010394,13.078925,13.155983,13.241499,13.335401,13.437600,13.548011,13.666537,13.793069,13.927498,14.069707,14.219566,14.376950,14.541712,14.713709,14.892790,15.078795,15.271559,15.470909,15.676679,15.888673,}, // NOLINT + {15.878617,15.667257,15.462122,15.263375,15.071206,14.885788,14.707271,14.535819,14.371584,14.214709,14.065334,13.923590,13.789601,13.663485,13.545352,13.435312,13.333454,13.239871,13.154643,13.077851,13.009553,12.949815,12.898687,12.856215,12.822435,12.797377,12.781061,12.773504,12.774710,12.784678,12.803400,12.830857,12.867027,12.911875,12.965363,13.027444,13.098063,13.177154,13.264650,13.360474,13.464539,13.576753,13.697019,13.825226,13.961268,14.105014,14.256343,14.415121,14.581204,14.754449,14.934698,15.121795,15.315567,15.515849,15.722460,}, // NOLINT + {15.491698,15.284484,15.083629,14.889303,14.701679,14.520923,14.347199,14.180651,14.021435,13.869690,13.725549,13.589143,13.460585,13.339992,13.227474,13.123128,13.027043,12.939311,12.860003,12.789188,12.726937,12.673301,12.628324,12.592047,12.564506,12.545720,12.535711,12.534485,12.542044,12.558382,12.583487,12.617333,12.659894,12.711133,12.771003,12.839454,12.916426,13.001851,13.095655,13.197756,13.308065,13.426483,13.552909,13.687239,13.829331,13.979086,14.136362,14.301022,14.472922,14.651910,14.837827,15.030517,15.229798,15.435505,15.647453,}, // NOLINT + {15.637717,15.426387,15.221286,15.022594,14.830489,14.645130,14.466687,14.295317,14.131167,13.974382,13.825097,13.683446,13.549554,13.423530,13.305493,13.195542,13.093772,13.000275,12.915131,12.838413,12.770188,12.710518,12.659453,12.617036,12.583305,12.558288,12.542010,12.534481,12.535708,12.545691,12.564420,12.591878,12.628041,12.672877,12.726349,12.788402,12.858991,12.938048,13.025505,13.121285,13.225304,13.337470,13.457683,13.585841,13.721827,13.865524,14.016804,14.175535,14.341574,14.514781,14.694997,14.882066,15.075824,15.276096,15.482708,}, // NOLINT + {15.252120,15.044894,14.844033,14.649713,14.462103,14.281370,14.107671,13.941158,13.781977,13.630277,13.486179,13.349814,13.221301,13.100754,12.988278,12.883972,12.787927,12.700227,12.620949,12.550164,12.487934,12.434310,12.389342,12.353071,12.325526,12.306733,12.296709,12.295461,12.302993,12.319297,12.344360,12.378160,12.420669,12.471848,12.531658,12.600039,12.676938,12.762286,12.856010,12.958029,13.068250,13.186586,13.312925,13.447163,13.589179,13.738851,13.896047,14.060633,14.232463,14.411387,14.597250,14.789888,14.989139,15.194813,15.406747,}, // NOLINT + {15.397316,15.185975,14.980885,14.782213,14.590134,14.404816,14.226422,14.055104,13.891011,13.734291,13.585071,13.443498,13.309672,13.183725,13.065761,12.955883,12.854187,12.760760,12.675683,12.599031,12.530869,12.471256,12.420242,12.377873,12.344185,12.319206,12.302960,12.295458,12.296706,12.306705,12.325443,12.352905,12.389068,12.433898,12.487359,12.549398,12.619966,12.699000,12.786431,12.882183,12.986171,13.098305,13.218484,13.346612,13.482567,13.626233,13.777489,13.936197,14.102219,14.275412,14.455623,14.642695,14.836473,15.036756,15.243403,}, // NOLINT + {15.012975,14.805700,14.604802,14.410473,14.222846,14.042108,13.868411,13.701907,13.542744,13.391058,13.246982,13.110640,12.982153,12.861631,12.749181,12.644899,12.548878,12.461199,12.381939,12.311171,12.248954,12.195337,12.150374,12.114101,12.086550,12.067747,12.057707,12.056439,12.063944,12.080217,12.105244,12.139004,12.181467,12.232597,12.292352,12.360676,12.437515,12.522801,12.616460,12.718412,12.828570,12.946835,13.073108,13.207282,13.349232,13.498846,13.655988,13.820523,13.992308,14.171198,14.357038,14.549657,14.748890,14.954568,15.166524,}, // NOLINT + {15.157377,14.946005,14.740889,14.542206,14.350129,14.164825,13.986448,13.815157,13.651101,13.494421,13.345253,13.203721,13.069951,12.944058,12.826151,12.716330,12.614689,12.521320,12.436298,12.359699,12.291585,12.232019,12.181053,12.138725,12.105075,12.080130,12.063912,12.056435,12.057704,12.067719,12.086469,12.113939,12.150106,12.194936,12.248389,12.310426,12.380987,12.460007,12.547424,12.643160,12.747133,12.859251,12.979418,13.107531,13.243470,13.387132,13.538382,13.697089,13.863117,14.036323,14.216556,14.403656,14.597458,14.797802,15.004516,}, // NOLINT + {14.774233,14.566891,14.365935,14.171545,13.983885,13.803117,13.629400,13.462883,13.303713,13.152021,13.007946,12.871609,12.743129,12.622617,12.510176,12.405905,12.309894,12.222225,12.142975,12.072211,12.009993,11.956381,11.911415,11.875138,11.847578,11.828762,11.818705,11.817416,11.824897,11.841142,11.866136,11.899861,11.942286,11.993376,12.053083,12.121362,12.198152,12.283393,12.376999,12.478897,12.589003,12.707219,12.833442,12.967570,13.109477,13.259057,13.416165,13.580679,13.752445,13.931320,14.117153,14.309781,14.509040,14.714756,14.926753,}, // NOLINT + {14.917873,14.706442,14.501272,14.302554,14.110451,13.925131,13.746752,13.575464,13.411423,13.254762,13.105615,12.964112,12.830378,12.704523,12.586652,12.476875,12.375278,12.281950,12.196970,12.120413,12.052342,11.992816,11.941884,11.899591,11.865973,11.841058,11.824867,11.817413,11.818702,11.828734,11.847499,11.874980,11.911155,11.955990,12.009449,12.071485,12.142043,12.221064,12.308480,12.404214,12.508182,12.620302,12.740470,12.868584,13.004535,13.148205,13.299466,13.458198,13.624246,13.797495,13.977770,14.164924,14.358796,14.559219,14.766016,}, // NOLINT + {14.535871,14.328430,14.127388,13.932924,13.745201,13.564379,13.390620,13.224067,13.064866,12.913154,12.769062,12.632712,12.504222,12.383704,12.271258,12.166984,12.070971,11.983299,11.904047,11.833281,11.771062,11.717440,11.672466,11.636179,11.608609,11.589777,11.579703,11.578394,11.585852,11.602071,11.627039,11.660732,11.703124,11.754178,11.813852,11.882093,11.958846,12.044043,12.137613,12.239477,12.349548,12.467730,12.593925,12.728024,12.869912,13.019470,13.176557,13.341076,13.512845,13.691735,13.877591,14.070253,14.269558,14.475331,14.687403,}, // NOLINT + {14.678777,14.467251,14.262008,14.063229,13.871074,13.685720,13.507316,13.336013,13.171959,13.015296,12.866156,12.724666,12.590946,12.465110,12.347265,12.237512,12.135948,12.042646,11.957698,11.881171,11.813132,11.753635,11.702734,11.660471,11.626880,11.601990,11.585823,11.578391,11.579700,11.589750,11.608531,11.636026,11.672213,11.717060,11.770528,11.832573,11.903137,11.982170,12.069594,12.165337,12.269319,12.381450,12.501634,12.629768,12.765742,12.909440,13.060737,13.219507,13.385614,13.558911,13.739253,13.926487,14.120429,14.320967,14.527882,}, // NOLINT + {14.297861,14.090293,13.889147,13.694585,13.506777,13.325881,13.152056,12.985447,12.826198,12.674446,12.530318,12.393939,12.265424,12.144885,12.032421,11.928132,11.832106,11.744420,11.665155,11.594378,11.532146,11.478515,11.433529,11.397227,11.369641,11.350793,11.340700,11.339372,11.346809,11.363006,11.387949,11.421617,11.463982,11.515007,11.574654,11.642868,11.719592,11.804763,11.898306,12.000148,12.110196,12.228361,12.354541,12.488628,12.630513,12.780074,12.937180,13.101704,13.273500,13.452423,13.638326,13.831045,14.030409,14.236288,14.448452,}, // NOLINT + {14.440062,14.228421,14.023077,13.824212,13.631991,13.446574,13.268119,13.096782,12.932697,12.776013,12.626864,12.485366,12.351643,12.225812,12.107977,11.998237,11.896683,11.803404,11.718475,11.641972,11.573954,11.514480,11.463603,11.421362,11.387794,11.362926,11.346780,11.339369,11.340698,11.350766,11.369565,11.397077,11.433281,11.478143,11.531629,11.593689,11.664271,11.743319,11.830762,11.926527,12.030532,12.142689,12.262902,12.391072,12.527085,12.670828,12.822179,12.981009,13.147182,13.320557,13.500986,13.688319,13.882385,14.083038,14.290087,}, // NOLINT + {14.060187,13.852478,13.651190,13.456512,13.268594,13.087605,12.913695,12.746999,12.587698,12.435887,12.291708,12.155283,12.026729,11.906154,11.793661,11.689344,11.593292,11.505587,11.426300,11.355505,11.293252,11.239603,11.194600,11.158280,11.130675,11.111809,11.101698,11.100350,11.107768,11.123943,11.148865,11.182513,11.224857,11.275862,11.335488,11.403682,11.480388,11.565543,11.659073,11.760902,11.870943,11.989102,12.115284,12.249371,12.391275,12.540855,12.698000,12.862546,13.034388,13.213369,13.399339,13.592140,13.791605,13.997576,14.209871,}, // NOLINT + {14.201705,13.989917,13.784463,13.585490,13.393173,13.207675,13.029152,12.857753,12.693625,12.536903,12.387720,12.246199,12.112462,11.986623,11.868783,11.759042,11.657492,11.564220,11.479302,11.402813,11.334807,11.275350,11.224488,11.182266,11.148716,11.123867,11.107740,11.100347,11.101696,11.111783,11.130601,11.158133,11.194358,11.239240,11.292748,11.354830,11.425437,11.504511,11.591983,11.687778,11.791818,11.904014,12.024272,12.152488,12.288556,12.432360,12.583780,12.742686,12.908946,13.082416,13.262953,13.450403,13.644601,13.845399,14.052612,}, // NOLINT + {13.822820,13.614939,13.413503,13.218683,13.030641,12.849538,12.675525,12.508750,12.349349,12.197462,12.053221,11.916737,11.788130,11.667507,11.554971,11.450615,11.354529,11.266790,11.187473,11.116651,11.054378,11.000704,10.955678,10.919338,10.891712,10.872827,10.862696,10.861329,10.868727,10.884885,10.909790,10.943420,10.985748,11.036739,11.096352,11.164535,11.241228,11.326379,11.419906,11.521736,11.631781,11.749951,11.876145,12.010263,12.152185,12.301803,12.458980,12.623593,12.795501,12.974556,13.160614,13.353515,13.553096,13.759192,13.971639,}, // NOLINT + {13.963684,13.751744,13.546139,13.347038,13.154608,12.969009,12.790398,12.618924,12.454729,12.297952,12.148723,12.007164,11.873399,11.747535,11.629677,11.519923,11.418367,11.325091,11.240174,11.163685,11.095690,11.036239,10.985390,10.943180,10.909644,10.884811,10.868701,10.861326,10.862693,10.872801,10.891640,10.919194,10.955441,11.000350,11.053883,11.115998,11.186637,11.265741,11.353251,11.449087,11.553173,11.665415,11.785731,11.914010,12.050146,12.194027,12.345531,12.504529,12.670893,12.844479,13.025141,13.212725,13.407084,13.608041,13.815438,}, // NOLINT + {13.585746,13.377675,13.176068,12.981089,12.792901,12.611666,12.437533,12.270647,12.111149,11.959178,11.814851,11.678294,11.549621,11.428938,11.316348,11.211943,11.115811,11.028034,10.948686,10.877827,10.815520,10.761817,10.716765,10.680400,10.652752,10.633845,10.623693,10.622308,10.629689,10.645831,10.670721,10.704338,10.746656,10.797639,10.857244,10.925423,11.002119,11.087269,11.180803,11.282643,11.392705,11.510898,11.637122,11.771274,11.913242,12.062911,12.220147,12.384831,12.556819,12.735966,12.922134,13.115161,13.314874,13.521124,13.733732,}, // NOLINT + {13.725980,13.513860,13.308090,13.108843,12.916278,12.730562,12.551845,12.380278,12.216000,12.059154,11.909863,11.768254,11.634443,11.508542,11.390652,11.280877,11.179303,11.086014,11.001088,10.924595,10.856598,10.797152,10.746307,10.704105,10.670580,10.645759,10.629663,10.622305,10.623691,10.633819,10.652680,10.680259,10.716533,10.761471,10.815036,10.877179,10.947862,11.027011,11.114563,11.210451,11.314592,11.426896,11.547278,11.675631,11.811848,11.955820,12.107423,12.266529,12.433017,12.606728,12.787533,12.975277,13.169797,13.370947,13.578543,}, // NOLINT + {13.348935,13.140667,12.938863,12.743710,12.555362,12.373978,12.199709,12.032700,11.873089,11.721011,11.576590,11.439947,11.311196,11.190440,11.077785,10.973324,10.877139,10.789313,10.709917,10.639018,10.576677,10.522942,10.477861,10.441466,10.413793,10.394862,10.384691,10.383287,10.390652,10.406780,10.431658,10.465267,10.507578,10.558556,10.618162,10.686344,10.763046,10.848209,10.941759,11.043621,11.153711,11.271937,11.398202,11.532403,11.674430,11.824161,11.981478,12.146247,12.318334,12.497596,12.683885,12.877048,13.076917,13.283339,13.496131,}, // NOLINT + {13.488569,13.276254,13.070300,12.870887,12.678173,12.492319,12.313482,12.141806,11.977432,11.820498,11.671132,11.529456,11.395588,11.269639,11.151709,11.041899,10.940295,10.846987,10.762042,10.685536,10.617532,10.558082,10.507238,10.465039,10.431520,10.406710,10.390627,10.383284,10.384688,10.394837,10.413722,10.441328,10.477631,10.522603,10.576204,10.638391,10.709111,10.788310,10.875918,10.971865,11.076069,11.188449,11.308908,11.437345,11.573657,11.717730,11.869447,12.028677,12.195295,12.369156,12.550125,12.738036,12.932747,13.134097,13.341918,}, // NOLINT + {13.112399,12.903897,12.701889,12.506538,12.318011,12.136462,11.962042,11.794894,11.635156,11.482960,11.338430,11.201691,11.072851,10.952017,10.839285,10.734754,10.638509,10.550625,10.471179,10.400233,10.337850,10.284077,10.238960,10.202536,10.174835,10.155881,10.145688,10.144266,10.151616,10.167732,10.192602,10.226205,10.268513,10.319493,10.379104,10.447297,10.524019,10.609197,10.702772,10.804665,10.914792,11.033063,11.159382,11.293644,11.435740,11.585553,11.742959,11.907832,12.080034,12.259423,12.445853,12.639169,12.839211,13.045821,13.258825,}, // NOLINT + {13.251442,13.038905,12.832754,12.633153,12.440275,12.254272,12.075296,11.903495,11.739010,11.581977,11.432521,11.290766,11.156830,11.030820,10.912838,10.802983,10.701343,10.608001,10.523033,10.446509,10.378490,10.319030,10.268182,10.225982,10.192467,10.167664,10.151592,10.144264,10.145686,10.155856,10.174766,10.202401,10.238735,10.283745,10.337387,10.399618,10.470391,10.549644,10.637316,10.733328,10.837606,10.950061,11.070612,11.199146,11.335565,11.479753,11.631594,11.790962,11.957726,12.131749,12.312888,12.500993,12.695915,12.897476,13.105530,}, // NOLINT + {8.043648,7.397306,6.770988,6.165243,5.580595,5.017552,4.476592,3.958179,3.462753,2.990727,2.542507,2.118435,1.718892,1.344193,0.994648,0.670529,0.372112,0.099630,-0.146699,-0.366697,-0.560162,-0.726958,-0.866957,-0.980036,-1.066125,-1.125150,-1.157072,-1.161869,-1.139540,-1.090107,-1.013613,-0.910121,-0.779714,-0.622518,-0.438643,-0.228245,0.008502,0.271406,0.560245,0.874787,1.214769,1.579912,1.969910,2.384439,2.823148,3.285667,3.771634,4.280595,4.812131,5.365788,5.941115,6.537523,7.154567,7.791696,8.448346,}, // NOLINT + {8.381690,7.729504,7.096713,6.483863,5.891520,5.320170,4.770318,4.242451,3.737017,3.254436,2.795110,2.359453,1.947825,1.560550,1.197967,0.860371,0.548046,0.261238,0.000194,-0.234879,-0.443789,-0.626362,-0.782445,-0.911921,-1.014676,-1.090627,-1.139709,-1.161879,-1.157116,-1.125421,-1.066815,-0.981341,-0.869063,-0.730065,-0.564456,-0.372365,-0.153933,0.090645,0.361199,0.657506,0.979331,1.326407,1.698465,2.095192,2.516271,2.961333,3.430070,3.922029,4.436822,4.974002,5.533134,6.113720,6.715267,7.337255,7.979123,}, // NOLINT + {7.668273,7.026706,6.405032,5.803795,5.223509,4.664672,4.127777,3.613263,3.121581,2.653130,2.208303,1.787468,1.390975,1.019135,0.672258,0.350631,0.054501,-0.215893,-0.460335,-0.678634,-0.870618,-1.036138,-1.175065,-1.287293,-1.372734,-1.431331,-1.463034,-1.467825,-1.445702,-1.396688,-1.320825,-1.218175,-1.088824,-0.932871,-0.750463,-0.541731,-0.306850,-0.046008,0.240576,0.552671,0.890022,1.252354,1.639358,2.050716,2.486094,2.945132,3.427397,3.932565,4.460134,5.009685,5.580736,6.172807,6.785346,7.417871,8.069762,}, // NOLINT + {8.005394,7.357799,6.729480,6.120993,5.532869,4.965632,4.419763,3.895726,3.393976,2.914938,2.459011,2.026589,1.618018,1.233644,0.873797,0.538752,0.228796,-0.055819,-0.314872,-0.548138,-0.755432,-0.936588,-1.091456,-1.219913,-1.321852,-1.397191,-1.445865,-1.467834,-1.463077,-1.431594,-1.373402,-1.288555,-1.177102,-1.039147,-0.874766,-0.684111,-0.467322,-0.224568,0.043960,0.338049,0.657470,1.001954,1.371239,1.765017,2.182973,2.624761,3.090019,3.578359,4.089375,4.622601,5.177694,5.754074,6.351239,6.968741,7.606002,}, // NOLINT + {7.296512,6.659464,6.042179,5.445199,4.869044,4.314202,3.781152,3.270341,2.782202,2.317140,1.875541,1.457768,1.064162,0.695040,0.350711,0.031436,-0.262521,-0.530937,-0.773574,-0.990269,-1.180845,-1.345153,-1.483068,-1.594482,-1.679309,-1.737498,-1.768994,-1.773780,-1.751855,-1.703239,-1.627976,-1.526127,-1.397773,-1.243023,-1.061998,-0.854849,-0.621738,-0.362860,-0.078417,0.231354,0.566210,0.925863,1.310017,1.718372,2.150584,2.606296,3.085105,3.586630,4.110448,4.656101,5.223134,5.811036,6.419321,7.047440,7.694856,}, // NOLINT + {7.632662,6.989411,6.365330,5.760971,5.176887,4.613524,4.071419,3.551027,3.052826,2.577108,2.124404,1.695049,1.289395,0.907781,0.550523,0.217898,-0.089803,-0.372347,-0.629495,-0.861041,-1.066800,-1.246610,-1.400313,-1.527805,-1.628969,-1.703724,-1.752011,-1.773789,-1.769036,-1.737753,-1.679967,-1.595704,-1.485041,-1.348059,-1.184859,-0.995569,-0.780332,-0.539316,-0.272717,0.019267,0.336399,0.678429,1.045074,1.436061,1.851047,2.289712,2.751693,3.236601,3.744033,4.273573,4.824763,5.397138,5.990208,6.603472,7.236362,}, // NOLINT + {6.928139,6.295361,5.682233,5.089289,4.517051,3.965980,3.436579,2.929280,2.444503,1.982674,1.544117,1.129250,0.738391,0.371849,0.029928,-0.287103,-0.579008,-0.845512,-1.086452,-1.301623,-1.490860,-1.654017,-1.790967,-1.901609,-1.985863,-2.043654,-2.074953,-2.079734,-2.057996,-2.009761,-1.935069,-1.833981,-1.706571,-1.552966,-1.373266,-1.167622,-0.936200,-0.679180,-0.396778,-0.089223,0.243251,0.600356,0.981815,1.387306,1.816510,2.269068,2.744576,3.242663,3.762912,4.304877,4.868060,5.452063,6.056298,6.680271,7.323430,}, // NOLINT + {7.263250,6.624111,6.004084,5.403628,4.823330,4.263683,3.725157,3.208220,2.713304,2.240828,1.791180,1.364746,0.961866,0.582870,0.228075,-0.102241,-0.407802,-0.688359,-0.943702,-1.173612,-1.377911,-1.556440,-1.709045,-1.835607,-1.936025,-2.010230,-2.058148,-2.079742,-2.074993,-2.043902,-1.986492,-1.902794,-1.792879,-1.656829,-1.494748,-1.306755,-1.092997,-0.853638,-0.588863,-0.298885,0.016074,0.355768,0.719919,1.108241,1.520417,1.956128,2.414979,2.896631,3.400669,3.926677,4.474210,5.042803,5.631975,6.241205,6.869974,}, // NOLINT + {6.562937,5.934196,5.324994,4.735896,4.167341,3.619864,3.093920,2.589948,2.108360,1.649570,1.213942,0.801835,0.413583,0.049498,-0.290141,-0.605031,-0.894965,-1.159680,-1.398994,-1.612715,-1.800674,-1.962739,-2.098772,-2.208678,-2.292378,-2.349799,-2.380910,-2.385687,-2.364130,-2.316257,-2.242110,-2.141748,-2.015252,-1.862726,-1.684283,-1.480074,-1.250258,-0.995018,-0.714559,-0.409103,-0.078896,0.275792,0.654676,1.057457,1.483792,1.933338,2.405724,2.900548,3.417401,3.955853,4.515441,5.095662,5.696085,6.316122,6.955250,}, // NOLINT + {6.897023,6.261772,5.645516,5.048787,4.472102,3.915962,3.380840,2.867187,2.375437,1.905998,1.459264,1.035595,0.635364,0.258854,-0.093595,-0.421712,-0.725230,-1.003908,-1.257525,-1.485876,-1.688782,-1.866076,-2.017634,-2.143318,-2.243038,-2.316710,-2.364275,-2.385695,-2.380950,-2.350039,-2.292988,-2.209827,-2.100626,-1.965467,-1.804446,-1.617689,-1.405338,-1.167553,-0.904514,-0.616446,-0.303551,0.033917,0.395691,0.781483,1.190987,1.623865,2.079777,2.558330,3.059147,3.581806,4.125870,4.690876,5.276350,5.881774,6.506640,}, // NOLINT + {6.200689,5.575782,4.970318,4.384816,3.819792,3.275718,2.753060,2.252237,1.773681,1.317799,0.884934,0.475454,0.089683,-0.272067,-0.609522,-0.922386,-1.210441,-1.473454,-1.711210,-1.923561,-2.110302,-2.271319,-2.406488,-2.515690,-2.598864,-2.655932,-2.686865,-2.691639,-2.670254,-2.622729,-2.549100,-2.449431,-2.323796,-2.172303,-1.995066,-1.792225,-1.563940,-1.310393,-1.031786,-0.728334,-0.400270,-0.047898,0.328537,0.728726,1.152339,1.599024,2.068414,2.560155,3.073783,3.608896,4.165044,4.741750,5.338508,5.954808,6.590121,}, // NOLINT + {6.533696,5.902145,5.289500,4.696295,4.123044,3.570237,3.038344,2.527813,2.039073,1.572543,1.128562,0.707541,0.309817,-0.064320,-0.414535,-0.740556,-1.042126,-1.319004,-1.570983,-1.797847,-1.999424,-2.175558,-2.326107,-2.450952,-2.549999,-2.623166,-2.670395,-2.691647,-2.686904,-2.656166,-2.599457,-2.516807,-2.408287,-2.273972,-2.113966,-1.928387,-1.717376,-1.481093,-1.219734,-0.933460,-0.622526,-0.287179,0.072334,0.455720,0.862676,1.292878,1.745973,2.221598,2.719350,3.238834,3.779601,4.341208,4.923174,5.524989,6.146150,}, // NOLINT + {5.841225,5.219941,4.618008,4.035950,3.474228,2.933413,2.413867,1.916076,1.440390,0.987254,0.557024,0.150039,-0.233369,-0.592899,-0.928265,-1.239205,-1.525480,-1.786862,-2.023156,-2.234177,-2.419768,-2.579786,-2.714118,-2.822655,-2.905324,-2.962057,-2.992820,-2.997591,-2.976370,-2.929173,-2.856044,-2.757035,-2.632232,-2.481720,-2.305629,-2.104094,-1.877272,-1.625335,-1.348486,-1.046955,-0.720962,-0.370774,0.003319,0.401054,0.822069,1.266048,1.732591,2.221389,2.731936,3.263881,3.816754,4.390081,4.983394,5.596153,6.227845,}, // NOLINT + {6.173131,5.545083,4.935867,4.346021,3.776017,3.226378,2.697573,2.189968,1.704119,1.240327,0.799001,0.380496,-0.014845,-0.386705,-0.734790,-1.058815,-1.358530,-1.633702,-1.884104,-2.109548,-2.309858,-2.484877,-2.634460,-2.758512,-2.856910,-2.929597,-2.976506,-2.997599,-2.992858,-2.962284,-2.905901,-2.823739,-2.715867,-2.582358,-2.423321,-2.238865,-2.029129,-1.794283,-1.534492,-1.249955,-0.940901,-0.607566,-0.250196,0.130887,0.535422,0.963085,1.413495,1.886331,2.381169,2.897630,3.435276,3.993652,4.572283,5.170689,5.788342,}, // NOLINT + {5.484365,4.866512,4.267935,3.689136,3.130614,2.592832,2.076254,1.581295,1.108365,0.657878,0.230134,-0.174470,-0.555625,-0.913041,-1.246427,-1.555522,-1.840090,-2.099925,-2.334813,-2.544579,-2.729066,-2.888136,-3.021673,-3.129570,-3.211760,-3.268171,-3.298773,-3.303543,-3.282478,-3.235599,-3.162940,-3.064565,-2.940547,-2.790982,-2.615987,-2.415699,-2.190268,-1.939878,-1.664719,-1.365006,-1.040977,-0.692883,-0.321004,0.074366,0.492911,0.934289,1.398151,1.884101,2.391753,2.920682,3.470447,4.040583,4.630603,5.240006,5.868259,}, // NOLINT + {5.815169,5.190430,4.584468,3.997792,3.430896,2.884271,2.358375,1.853650,1.370499,0.909324,0.470508,0.054398,-0.338654,-0.708354,-1.054406,-1.376526,-1.674465,-1.947998,-2.196906,-2.420995,-2.620093,-2.794048,-2.942719,-3.065999,-3.163788,-3.236009,-3.282611,-3.303550,-3.298810,-3.268393,-3.212321,-3.130624,-3.023372,-2.890636,-2.732519,-2.549135,-2.340604,-2.107146,-1.848852,-1.565969,-1.258703,-0.927290,-0.571988,-0.193076,0.209153,0.634377,1.082249,1.552420,2.044504,2.558093,3.092766,3.648075,4.223553,4.818715,5.433049,}, // NOLINT + {5.129950,4.515364,3.919957,3.344254,2.788737,2.253876,1.740113,1.247871,0.777564,0.329529,-0.095795,-0.498134,-0.877141,-1.232539,-1.564035,-1.871375,-2.154326,-2.412671,-2.646205,-2.854780,-3.038212,-3.196374,-3.329150,-3.436441,-3.518173,-3.574278,-3.604726,-3.609493,-3.588580,-3.542003,-3.469800,-3.372029,-3.248769,-3.100100,-2.926154,-2.727056,-2.502954,-2.254042,-1.980487,-1.682524,-1.360359,-1.014273,-0.644518,-0.251390,0.164793,0.603700,1.064987,1.548259,2.053134,2.579188,3.125997,3.693096,4.279986,4.886204,5.511189,}, // NOLINT + {5.459609,4.838035,4.235170,3.651514,3.087568,2.543812,2.020698,1.518683,1.038108,0.579440,0.143023,-0.270791,-0.661672,-1.029313,-1.373417,-1.693716,-1.989966,-2.261934,-2.509411,-2.732203,-2.930142,-3.103077,-3.250875,-3.373420,-3.470621,-3.542402,-3.588708,-3.609500,-3.604762,-3.574494,-3.518719,-3.437467,-3.330805,-3.198808,-3.041572,-2.859212,-2.651864,-2.419682,-2.162840,-1.881532,-1.575972,-1.246394,-0.893051,-0.516219,-0.116191,0.306716,0.752163,1.219808,1.709258,2.220116,2.751965,3.304365,3.876844,4.468930,5.080110,}, // NOLINT + {4.777830,4.166326,3.573944,3.001182,2.448522,1.916433,1.405354,0.915692,0.447844,0.002261,-0.420823,-0.820998,-1.197967,-1.551432,-1.881122,-2.186785,-2.468186,-2.725114,-2.957375,-3.164793,-3.347216,-3.504511,-3.636560,-3.743270,-3.824564,-3.880376,-3.910677,-3.915443,-3.894674,-3.848387,-3.776619,-3.679423,-3.556884,-3.409082,-3.236137,-3.038180,-2.815362,-2.567853,-2.295837,-1.999537,-1.679166,-1.334989,-0.967261,-0.576278,-0.162345,0.274207,0.733028,1.213748,1.715977,2.239302,2.783290,3.347473,3.931422,4.534595,5.156484,}, // NOLINT + {5.106347,4.487785,3.887849,3.307068,2.745925,2.204901,1.684439,1.184976,0.706894,0.250607,-0.183519,-0.595147,-0.983945,-1.349614,-1.691866,-2.010424,-2.305054,-2.575526,-2.821633,-3.043186,-3.240017,-3.411977,-3.558926,-3.680779,-3.777416,-3.848773,-3.894798,-3.915450,-3.910713,-3.880587,-3.825097,-3.744270,-3.638175,-3.506883,-3.350489,-3.169108,-2.962881,-2.731938,-2.476467,-2.196670,-1.892740,-1.564915,-1.213443,-0.838597,-0.440667,-0.019974,0.423180,0.888403,1.375346,1.883604,2.412766,2.962390,3.532031,4.121194,4.729381,}, // NOLINT + {4.427861,3.819301,3.229776,2.659810,2.109872,1.580425,1.071894,0.584705,0.119228,-0.324111,-0.745008,-1.143114,-1.518123,-1.869752,-2.197723,-2.501782,-2.781703,-3.037274,-3.268307,-3.474629,-3.656089,-3.812552,-3.943907,-4.050060,-4.130935,-4.186467,-4.216627,-4.221393,-4.200762,-4.154753,-4.083404,-3.986763,-3.864910,-3.717938,-3.545952,-3.349087,-3.127489,-2.881328,-2.610785,-2.316080,-1.997427,-1.655071,-1.289283,-0.900344,-0.488563,-0.054253,0.402208,0.880506,1.380202,1.900921,2.442223,3.003669,3.584782,4.185068,4.804020,}, // NOLINT + {4.755243,4.139521,3.542375,2.964332,2.405868,1.867442,1.349507,0.852483,0.376784,-0.077212,-0.509173,-0.918711,-1.305516,-1.669307,-2.009778,-2.326680,-2.619757,-2.888796,-3.133593,-3.353959,-3.549728,-3.720752,-3.866906,-3.988077,-4.084176,-4.155130,-4.200883,-4.221399,-4.216662,-4.186673,-4.131455,-4.051035,-3.945478,-3.814864,-3.659277,-3.478834,-3.273665,-3.043923,-2.789776,-2.511411,-2.209040,-1.882888,-1.533202,-1.160251,-0.764308,-0.345733,0.095202,0.558133,1.042681,1.548472,2.075073,2.622067,3.188995,3.775385,4.380735,}, // NOLINT + {4.079924,3.474136,2.887364,2.320037,1.772688,1.245756,0.739654,0.254813,-0.208385,-0.649572,-1.068399,-1.464537,-1.837684,-2.187549,-2.513864,-2.816393,-3.094895,-3.349170,-3.579027,-3.784299,-3.964836,-4.120506,-4.251195,-4.356815,-4.437284,-4.492550,-4.522577,-4.527342,-4.506844,-4.461100,-4.390150,-4.294043,-4.172852,-4.026676,-3.855611,-3.659787,-3.439359,-3.194486,-2.925360,-2.632177,-2.315162,-1.974557,-1.610621,-1.223643,-0.813917,-0.381757,0.072447,0.548427,1.045722,1.563954,2.102705,2.661527,3.239949,3.837493,4.453649,}, // NOLINT + {4.406160,3.793146,3.198622,2.623211,2.067298,1.531353,1.015823,0.521138,0.047667,-0.404130,-0.833993,-1.241535,-1.626445,-1.988426,-2.327197,-2.642502,-2.934098,-3.201765,-3.445306,-3.664533,-3.859285,-4.029415,-4.174798,-4.295324,-4.390903,-4.461469,-4.506961,-4.527348,-4.522611,-4.492753,-4.437791,-4.357765,-4.252729,-4.122757,-3.967943,-3.788400,-3.584250,-3.355654,-3.102765,-2.825775,-2.524897,-2.200352,-1.852373,-1.481234,-1.087223,-0.670641,-0.231808,0.228928,0.711201,1.214599,1.738795,2.283283,2.847634,3.431386,4.034042,}, // NOLINT + {3.733889,3.130746,2.546541,1.981765,1.436879,0.912342,0.408560,-0.074039,-0.535079,-0.974195,-1.391042,-1.785296,-2.156664,-2.504841,-2.829581,-3.130644,-3.407784,-3.660814,-3.889548,-4.093814,-4.273467,-4.428370,-4.558425,-4.663532,-4.743618,-4.798630,-4.828525,-4.833290,-4.812921,-4.767435,-4.696868,-4.601270,-4.480714,-4.335294,-4.165111,-3.970294,-3.750988,-3.507376,-3.239569,-2.947858,-2.632416,-2.293483,-1.931325,-1.546215,-1.138457,-0.708370,-0.256266,0.217467,0.712461,1.228330,1.764637,2.320957,2.896836,3.491755,4.105253,}, // NOLINT + {4.058985,3.448547,2.856596,2.283636,1.730153,1.196556,0.683344,0.190871,-0.280418,-0.730170,-1.158028,-1.563668,-1.946756,-2.306998,-2.644145,-2.957923,-3.248097,-3.514452,-3.756786,-3.974921,-4.168696,-4.337966,-4.482610,-4.602522,-4.697602,-4.767792,-4.813034,-4.833296,-4.828559,-4.798826,-4.744114,-4.664462,-4.559924,-4.430571,-4.276502,-4.097816,-3.894647,-3.667136,-3.415462,-3.139798,-2.840342,-2.517325,-2.170985,-1.801584,-1.409402,-0.994739,-0.557918,-0.099277,0.380822,0.882008,1.403854,1.945940,2.507850,3.089090,3.689185,}, // NOLINT + {3.389641,2.789018,2.207278,1.644908,1.102369,0.580107,0.078544,-0.401917,-0.860896,-1.298032,-1.712985,-2.105440,-2.475092,-2.821662,-3.144893,-3.444541,-3.720388,-3.972232,-4.199881,-4.403177,-4.581985,-4.736158,-4.865603,-4.970219,-5.049936,-5.104700,-5.134474,-5.139238,-5.118992,-5.073751,-5.003554,-4.908447,-4.788502,-4.643808,-4.474474,-4.280620,-4.062391,-3.819946,-3.553465,-3.263146,-2.949206,-2.611880,-2.251422,-1.868110,-1.462233,-1.034105,-0.584055,-0.112448,0.380354,0.893958,1.427936,1.981875,2.555302,3.147748,3.758717,}, // NOLINT + {3.713631,3.105617,2.516077,1.945476,1.394287,0.862938,0.351932,-0.138395,-0.607615,-1.055375,-1.481324,-1.885125,-2.266470,-2.625071,-2.960653,-3.272965,-3.561775,-3.826865,-4.068046,-4.285134,-4.477973,-4.646417,-4.790347,-4.909664,-5.004269,-5.074099,-5.119102,-5.139244,-5.134507,-5.104892,-5.050421,-4.971128,-4.867066,-4.738309,-4.584945,-4.407088,-4.204861,-3.978404,-3.727884,-3.453481,-3.155395,-2.833853,-2.489075,-2.121330,-1.730910,-1.318079,-0.883177,-0.426538,0.051485,0.550517,1.070149,1.609972,2.169538,2.748396,3.346058,}, // NOLINT + {3.047080,2.448849,1.869454,1.309380,0.769076,0.248981,-0.250457,-0.728874,-1.185882,-1.621142,-2.034271,-2.424997,-2.793015,-3.138042,-3.459824,-3.758124,-4.032722,-4.283421,-4.510040,-4.712413,-4.890401,-5.043875,-5.172731,-5.276875,-5.356238,-5.410766,-5.440421,-5.445186,-5.425058,-5.380053,-5.310212,-5.215572,-5.096216,-4.952225,-4.783703,-4.590777,-4.373579,-4.132272,-3.867038,-3.578075,-3.265570,-2.929773,-2.570956,-2.189360,-1.785286,-1.359040,-0.910951,-0.441375,0.049326,0.560770,1.092528,1.644187,2.215293,2.805368,3.413935,}, // NOLINT + {3.369926,2.764266,2.177019,1.608669,1.059674,0.530522,0.021588,-0.466699,-0.933957,-1.379807,-1.803922,-2.205974,-2.585639,-2.942659,-3.276744,-3.587649,-3.875151,-4.139032,-4.379099,-4.595194,-4.787116,-4.954771,-5.098020,-5.216761,-5.310903,-5.380395,-5.425165,-5.445191,-5.440454,-5.410955,-5.356713,-5.277765,-5.174162,-5.045977,-4.893299,-4.716231,-4.514904,-4.289455,-4.040047,-3.766864,-3.470084,-3.149945,-2.806674,-2.440522,-2.051768,-1.640703,-1.207642,-0.752913,-0.276872,0.220086,0.737628,1.275281,1.832631,2.409220,3.004561,}, // NOLINT + {2.706109,2.110152,1.532990,0.975096,0.436934,-0.081071,-0.578503,-1.054967,-1.510096,-1.943527,-2.354936,-2.744011,-3.110457,-3.454006,-3.774404,-4.071403,-4.344805,-4.594409,-4.820030,-5.021515,-5.198721,-5.351521,-5.479812,-5.583503,-5.662526,-5.716826,-5.746368,-5.751133,-5.731119,-5.686344,-5.616844,-5.522653,-5.403864,-5.260547,-5.092804,-4.900768,-4.684571,-4.444361,-4.180316,-3.892644,-3.581525,-3.247216,-2.889954,-2.509993,-2.107660,-1.683220,-1.237011,-0.769376,-0.280683,0.228692,0.758331,1.307827,1.876709,2.464539,3.070802,}, // NOLINT + {3.027836,2.424396,1.839335,1.273170,0.726259,0.199149,-0.307773,-0.794107,-1.259472,-1.703494,-2.125866,-2.526233,-2.904303,-3.259795,-3.592443,-3.902003,-4.188242,-4.450960,-4.689959,-4.905070,-5.096141,-5.263033,-5.405624,-5.523813,-5.617520,-5.686674,-5.731224,-5.751138,-5.746400,-5.717011,-5.662990,-5.584373,-5.481213,-5.353577,-5.201554,-5.025251,-4.824789,-4.600308,-4.351967,-4.079942,-3.784428,-3.465644,-3.123808,-2.759185,-2.372035,-1.962658,-1.531352,-1.078462,-0.604310,-0.109291,0.406215,0.941799,1.497028,2.071467,2.664598,}, // NOLINT + {2.366632,1.772822,1.197807,0.642002,0.105870,-0.410150,-0.905665,-1.380251,-1.833571,-2.265271,-2.675017,-3.062509,-3.427450,-3.769574,-4.088637,-4.384399,-4.656651,-4.905194,-5.129866,-5.330494,-5.506947,-5.659101,-5.786850,-5.890102,-5.968801,-6.022882,-6.052314,-6.057080,-6.037176,-5.992619,-5.923444,-5.829698,-5.711448,-5.568778,-5.401793,-5.210609,-4.995363,-4.756208,-4.493317,-4.206877,-3.897098,-3.564209,-3.208447,-2.830081,-2.429395,-2.006662,-1.562275,-1.096501,-0.609729,-0.102333,0.425280,0.972725,1.539470,2.125152,2.729229,}, // NOLINT + {2.687255,2.085937,1.502953,0.938811,0.393938,-0.131211,-0.636204,-1.120673,-1.584235,-2.026517,-2.447190,-2.845943,-3.222477,-3.576506,-3.907790,-4.216033,-4.501064,-4.762663,-5.000635,-5.214817,-5.405054,-5.571212,-5.713169,-5.830829,-5.924110,-5.992942,-6.037278,-6.057085,-6.052346,-6.023064,-5.969256,-5.890956,-5.788219,-5.661112,-5.509722,-5.334152,-5.134532,-4.910979,-4.663653,-4.392752,-4.098448,-3.780953,-3.440506,-3.077342,-2.691738,-2.283971,-1.854350,-1.403210,-0.930880,-0.437734,0.075847,0.609468,1.162659,1.735025,2.326074,}, // NOLINT + {2.028567,1.436836,0.863828,0.310010,-0.224174,-0.738297,-1.231953,-1.704766,-2.156358,-2.586409,-2.994543,-3.380530,-3.744017,-4.084780,-4.402560,-4.697127,-4.968274,-5.215807,-5.439556,-5.639363,-5.815091,-5.966618,-6.093844,-6.196681,-6.275061,-6.328933,-6.358260,-6.363025,-6.343229,-6.298884,-6.230022,-6.136698,-6.018972,-5.876933,-5.710667,-5.520302,-5.305981,-5.067840,-4.806054,-4.520809,-4.212315,-3.880785,-3.526470,-3.149626,-2.750524,-2.329474,-1.886788,-1.422801,-0.937867,-0.432356,0.093307,0.638702,1.203484,1.787116,2.389124,}, // NOLINT + {2.348089,1.748777,1.167791,0.605599,0.062659,-0.460600,-0.963766,-1.446443,-1.908259,-2.348868,-2.767952,-3.165138,-3.540189,-3.892814,-4.222753,-4.529766,-4.813634,-5.074152,-5.311139,-5.524419,-5.713856,-5.879302,-6.020655,-6.137805,-6.230674,-6.299199,-6.343328,-6.363031,-6.358291,-6.329111,-6.275508,-6.197516,-6.095188,-5.968587,-5.817806,-5.642942,-5.444115,-5.221458,-4.975133,-4.705308,-4.412166,-4.095913,-3.756796,-3.395034,-3.010911,-2.604696,-2.176694,-1.727235,-1.256638,-0.765278,-0.253524,0.278180,0.829463,1.399862,1.988913,}, // NOLINT + {1.691827,1.102061,0.530988,-0.020935,-0.553260,-1.065568,-1.557463,-2.028554,-2.478494,-2.906937,-3.313563,-3.698074,-4.060185,-4.399640,-4.716184,-5.009603,-5.279686,-5.526242,-5.749108,-5.948122,-6.123152,-6.274076,-6.400802,-6.503234,-6.581311,-6.634979,-6.664206,-6.668972,-6.649277,-6.605136,-6.536581,-6.443662,-6.326439,-6.184995,-6.019437,-5.829871,-5.616430,-5.379265,-5.118544,-4.834452,-4.527184,-4.196970,-3.844041,-3.468656,-3.071087,-2.651630,-2.210600,-1.748326,-1.265156,-0.761487,-0.237648,0.305892,0.868716,1.450380,2.050407,}, // NOLINT + {2.010269,1.412876,0.833788,0.273468,-0.267635,-0.789092,-1.290496,-1.771459,-2.231607,-2.670612,-3.088124,-3.483826,-3.857473,-4.208746,-4.537404,-4.843217,-5.125963,-5.385446,-5.621478,-5.833896,-6.022556,-6.187323,-6.328086,-6.444744,-6.537217,-6.605444,-6.649374,-6.668976,-6.664236,-6.635153,-6.581749,-6.504053,-6.402118,-6.276011,-6.125815,-5.951627,-5.753574,-5.531782,-5.286406,-5.017613,-4.725591,-4.410558,-4.072698,-3.712292,-3.329585,-2.924857,-2.498408,-2.050545,-1.581613,-1.091975,-0.581999,-0.052067,0.497352,1.065883,1.653035,}, // NOLINT + {1.356335,0.768443,0.199211,-0.350879,-0.881445,-1.392012,-1.882215,-2.351668,-2.800020,-3.226932,-3.632083,-4.015198,-4.375975,-4.714166,-5.029530,-5.321841,-5.590901,-5.836521,-6.058528,-6.256784,-6.431138,-6.581484,-6.707721,-6.809762,-6.887549,-6.941022,-6.970150,-6.974917,-6.955321,-6.911378,-6.843118,-6.750588,-6.633854,-6.492994,-6.328107,-6.139306,-5.926720,-5.690494,-5.430802,-5.147816,-4.841739,-4.512785,-4.161192,-3.787213,-3.391113,-2.973188,-2.533747,-2.073112,-1.591638,-1.089683,-0.567641,-0.025915,0.535068,1.114859,1.712997,}, // NOLINT + {1.673708,1.078151,0.500880,-0.057665,-0.597003,-1.116733,-1.616447,-2.095755,-2.554325,-2.991786,-3.407798,-3.802096,-4.174347,-4.524318,-4.851748,-5.156402,-5.438069,-5.696549,-5.931663,-6.143257,-6.331162,-6.495271,-6.635464,-6.751647,-6.843740,-6.911679,-6.955416,-6.974922,-6.970181,-6.941194,-6.887979,-6.810569,-6.709015,-6.583379,-6.433749,-6.260219,-6.062911,-5.841948,-5.597491,-5.329693,-5.038749,-4.724857,-4.388239,-4.029131,-3.647790,-3.244489,-2.819525,-2.373210,-1.905877,-1.417877,-0.909569,-0.381395,0.166295,0.733028,1.318360,}, // NOLINT + {1.022029,0.435922,-0.131550,-0.679931,-1.208764,-1.717682,-2.206268,-2.674141,-3.120966,-3.546411,-3.950150,-4.331914,-4.691408,-5.028390,-5.342610,-5.633858,-5.901929,-6.146642,-6.367830,-6.565343,-6.739052,-6.888839,-7.014607,-7.116276,-7.193776,-7.247062,-7.276095,-7.280863,-7.261363,-7.217609,-7.149636,-7.057481,-6.941217,-6.800919,-6.636683,-6.448620,-6.236860,-6.001552,-5.742839,-5.460923,-5.155989,-4.828253,-4.477945,-4.105311,-3.710632,-3.294169,-2.856265,-2.397210,-1.917354,-1.417068,-0.896728,-0.356723,0.202482,0.780489,1.376820,}, // NOLINT + {1.338344,0.744528,0.168987,-0.387834,-0.925493,-1.443569,-1.941664,-2.419407,-2.876432,-3.312394,-3.726974,-4.119891,-4.490837,-4.839555,-5.165794,-5.469338,-5.749962,-6.007476,-6.241704,-6.452486,-6.639685,-6.803150,-6.942798,-7.058520,-7.150243,-7.217903,-7.261455,-7.280867,-7.276125,-7.247229,-7.194198,-7.117064,-7.015875,-6.890699,-6.741614,-6.568714,-6.372126,-6.151964,-5.908390,-5.641557,-5.351652,-5.038874,-4.703431,-4.345573,-3.965549,-3.563623,-3.140090,-2.695256,-2.229452,-1.743029,-1.236316,-0.709805,-0.163795,0.401221,0.984832,}, // NOLINT + {0.688831,0.104426,-0.461363,-1.008080,-1.535300,-2.042617,-2.529642,-2.996011,-3.441374,-3.865405,-4.267795,-4.648254,-5.006515,-5.342333,-5.655444,-5.945659,-6.212784,-6.456618,-6.677015,-6.873815,-7.046899,-7.196146,-7.321461,-7.422765,-7.499993,-7.553095,-7.582039,-7.586808,-7.567400,-7.523830,-7.456129,-7.364343,-7.248533,-7.108778,-6.945171,-6.757822,-6.546858,-6.312418,-6.054671,-5.773793,-5.469954,-5.143382,-4.794323,-4.422995,-4.029677,-3.614639,-3.178187,-2.720650,-2.242359,-1.743667,-1.224959,-0.686634,-0.129111,0.447201,1.041809,}, // NOLINT + {1.004103,0.411962,-0.161929,-0.717117,-1.253167,-1.769646,-2.266192,-2.742415,-3.197961,-3.632495,-4.045700,-4.437287,-4.806963,-5.154470,-5.479572,-5.782035,-6.061653,-6.318235,-6.551608,-6.761610,-6.948105,-7.110964,-7.250085,-7.365361,-7.456728,-7.524120,-7.567491,-7.586812,-7.582069,-7.553262,-7.500409,-7.423541,-7.322704,-7.197972,-7.049415,-6.877132,-6.681231,-6.461847,-6.219121,-5.953219,-5.664316,-5.352609,-5.018311,-4.661656,-4.282892,-3.882287,-3.460127,-3.016718,-2.552385,-2.067470,-1.562341,-1.037374,-0.493022,0.070413,0.652374,}, // NOLINT + {0.356679,-0.226102,-0.790272,-1.335411,-1.861052,-2.366862,-2.852396,-3.317311,-3.761280,-4.183942,-4.585019,-4.964234,-5.321300,-5.655983,-5.968044,-6.257272,-6.523470,-6.766470,-6.986091,-7.182205,-7.354684,-7.503405,-7.628282,-7.729238,-7.806202,-7.859126,-7.887983,-7.892752,-7.873434,-7.830043,-7.762608,-7.671176,-7.555804,-7.416579,-7.253573,-7.066917,-6.856719,-6.623133,-6.366306,-6.086415,-5.783652,-5.458218,-5.110346,-4.740275,-4.348271,-3.934594,-3.499561,-3.043479,-2.566685,-2.069529,-1.552385,-1.015667,-0.459732,0.114934,0.707901,}, // NOLINT + {0.670920,0.080380,-0.491907,-1.045544,-1.580074,-2.095010,-2.590062,-3.064836,-3.518956,-3.952115,-4.363993,-4.754297,-5.122751,-5.469092,-5.793087,-6.094510,-6.373155,-6.628838,-6.861382,-7.070631,-7.256450,-7.418718,-7.557322,-7.672176,-7.763193,-7.830325,-7.873523,-7.892756,-7.888012,-7.859291,-7.806610,-7.730002,-7.629506,-7.505199,-7.357155,-7.185462,-6.990233,-6.771598,-6.529698,-6.264692,-5.976751,-5.666082,-5.332883,-4.977387,-4.599851,-4.200509,-3.779673,-3.337632,-2.874713,-2.391251,-1.887600,-1.364152,-0.821290,-0.259459,0.320925,}, // NOLINT + {0.025517,-0.555716,-1.118343,-1.661965,-2.186132,-2.690457,-3.174557,-3.638078,-4.080673,-4.502044,-4.901870,-5.279876,-5.635795,-5.969388,-6.280424,-6.568693,-6.834005,-7.076185,-7.295068,-7.490519,-7.662408,-7.810626,-7.935078,-8.035697,-8.112401,-8.165155,-8.193927,-8.198697,-8.179465,-8.136246,-8.069069,-7.977978,-7.863034,-7.724309,-7.561900,-7.375909,-7.166460,-6.933691,-6.677756,-6.398827,-6.097096,-5.772754,-5.426036,-5.057175,-4.666430,-4.254075,-3.820403,-3.365725,-2.890372,-2.394690,-1.879037,-1.343843,-0.789472,-0.216366,0.375027,}, // NOLINT + {0.338751,-0.250272,-0.821024,-1.373179,-1.906190,-2.419702,-2.913315,-3.386678,-3.839440,-4.271271,-4.681869,-5.070938,-5.438210,-5.783428,-6.106356,-6.406774,-6.684482,-6.939291,-7.171034,-7.379557,-7.564724,-7.726415,-7.864522,-7.978957,-8.069643,-8.136522,-8.179552,-8.198701,-8.193956,-8.165317,-8.112804,-8.036443,-7.936282,-7.812392,-7.664837,-7.493717,-7.299141,-7.081227,-6.840122,-6.575983,-6.288981,-5.979308,-5.647159,-5.292796,-4.916425,-4.518316,-4.098754,-3.658031,-3.196467,-2.714397,-2.212174,-1.690175,-1.148794,-0.588449,-0.009599,}, // NOLINT + {-5.518289,-6.617390,-7.680134,-8.705793,-9.693695,-10.643273,-11.553853,-12.424894,-13.255868,-14.046282,-14.795671,-15.503607,-16.169688,-16.793547,-17.374843,-17.913259,-18.408536,-18.860394,-19.268611,-19.632989,-19.953332,-20.229531,-20.461400,-20.648891,-20.791880,-20.890321,-20.944184,-20.953449,-20.918128,-20.838254,-20.713878,-20.545073,-20.331953,-20.074626,-19.773248,-19.427984,-19.039019,-18.606581,-18.130915,-17.612287,-17.050982,-16.447337,-15.801698,-15.114444,-14.385980,-13.616755,-12.807231,-11.957911,-11.069327,-10.142059,-9.176697,-8.173897,-7.134292,-6.058633,-4.947659,}, // NOLINT + {-5.065671,-6.168966,-7.237036,-8.269274,-9.264934,-10.223359,-11.143893,-12.026027,-12.869102,-13.672653,-14.436166,-15.159159,-15.841261,-16.482010,-17.081076,-17.638101,-18.152758,-18.624774,-19.053877,-19.439824,-19.782423,-20.081463,-20.336782,-20.548251,-20.715737,-20.839149,-20.918405,-20.953461,-20.944280,-20.890856,-20.793201,-20.651348,-20.465348,-20.235322,-19.961299,-19.643460,-19.281931,-18.876908,-18.428561,-17.937141,-17.402877,-16.826044,-16.206976,-15.545974,-14.843412,-14.099680,-13.315199,-12.490425,-11.625847,-10.721984,-9.779387,-8.798647,-7.780385,-6.725256,-5.633987,}, // NOLINT + {-5.994097,-7.084564,-8.138844,-9.156233,-10.136103,-11.077813,-11.980781,-12.844479,-13.668367,-14.451989,-15.194860,-15.896595,-16.556793,-17.175097,-17.751205,-18.284761,-18.775548,-19.223271,-19.627751,-19.988785,-20.306187,-20.579818,-20.809541,-20.995286,-21.136946,-21.234480,-21.287846,-21.297035,-21.262054,-21.182937,-21.059732,-20.892513,-20.681385,-20.426454,-20.127864,-19.785778,-19.400376,-18.971888,-18.500526,-17.986562,-17.430295,-16.831975,-16.192013,-15.510743,-14.788574,-14.025907,-13.223215,-12.380985,-11.499738,-10.580019,-9.622421,-8.627564,-7.596112,-6.528737,-5.426204,}, // NOLINT + {-5.541338,-6.636339,-7.696330,-8.720611,-9.708465,-10.659306,-11.572478,-12.447374,-13.283531,-14.080386,-14.837470,-15.554333,-16.230567,-16.865775,-17.459604,-18.011720,-18.521813,-18.989608,-19.414854,-19.797294,-20.136799,-20.433105,-20.686092,-20.895607,-21.061542,-21.183807,-21.262324,-21.297046,-21.287940,-21.234999,-21.138232,-20.997681,-20.813382,-20.585443,-20.313935,-19.998984,-19.640738,-19.239369,-18.795054,-18.308022,-17.778506,-17.206764,-16.593135,-15.937878,-15.241363,-14.504015,-13.726188,-12.908350,-12.050946,-11.154530,-10.219612,-9.246765,-8.236571,-7.189761,-6.106935,}, // NOLINT + {-6.465694,-7.547811,-8.593861,-9.603245,-10.575298,-11.509409,-12.405006,-13.261603,-14.078637,-14.855645,-15.592259,-16.287972,-16.942483,-17.555423,-18.126474,-18.655346,-19.141789,-19.585533,-19.986401,-20.344175,-20.658726,-20.929882,-21.157522,-21.341589,-21.481966,-21.578618,-21.631505,-21.640619,-21.605969,-21.527582,-21.405514,-21.239825,-21.030630,-20.778002,-20.482119,-20.143109,-19.761165,-19.336488,-18.869289,-18.359848,-17.808414,-17.215296,-16.580821,-15.905345,-15.189259,-14.432951,-13.636884,-12.801528,-11.927386,-11.014991,-10.064918,-9.077778,-8.054201,-6.994863,-5.900464,}, // NOLINT + {-6.012927,-7.099900,-8.152029,-9.168587,-10.148893,-11.092346,-11.998369,-12.866306,-13.695722,-14.486089,-15.236947,-15.947857,-16.618460,-17.248238,-17.837009,-18.384361,-18.890046,-19.353767,-19.775282,-20.154364,-20.490828,-20.784504,-21.035217,-21.242840,-21.407278,-21.528433,-21.606232,-21.640630,-21.631597,-21.579124,-21.483223,-21.343924,-21.161291,-20.935371,-20.666279,-20.354135,-19.999057,-19.601220,-19.160811,-18.678025,-18.153105,-17.586296,-16.977910,-16.328230,-15.637601,-14.906403,-14.135021,-13.323893,-12.473473,-11.584247,-10.656757,-9.691559,-8.689231,-7.650422,-6.575796,}, // NOLINT + {-6.933278,-8.007241,-9.045378,-10.046977,-11.011476,-11.938233,-12.826711,-13.676388,-14.486785,-15.257432,-15.987903,-16.677836,-17.326835,-17.934563,-18.500739,-19.025075,-19.507302,-19.947199,-20.344559,-20.699200,-21.010980,-21.279742,-21.505383,-21.687808,-21.826942,-21.922737,-21.975161,-21.984204,-21.949872,-21.872199,-21.751223,-21.587023,-21.379687,-21.129308,-20.836034,-20.500010,-20.121411,-19.700421,-19.237271,-18.732196,-18.185463,-17.597357,-16.968207,-16.298345,-15.588146,-14.838046,-14.048364,-13.219668,-12.352406,-11.447124,-10.504356,-9.524695,-8.508774,-7.457261,-6.370816,}, // NOLINT + {-6.480590,-7.559833,-8.604302,-9.613355,-10.586338,-11.522640,-12.421672,-13.282895,-14.105788,-14.889869,-15.634690,-16.339830,-17.004891,-17.629523,-18.213362,-18.756123,-19.257520,-19.717276,-20.135166,-20.510985,-20.844525,-21.135634,-21.384156,-21.589956,-21.752940,-21.873026,-21.950128,-21.984214,-21.975251,-21.923229,-21.828167,-21.690085,-21.509041,-21.285105,-21.018351,-20.708907,-20.356914,-19.962502,-19.525855,-19.047201,-18.526731,-17.964706,-17.361399,-16.717114,-16.032178,-15.306946,-14.541806,-13.737172,-12.893555,-12.011264,-11.090974,-10.133183,-9.138457,-8.107433,-7.040781,}, // NOLINT + {-7.397068,-8.463141,-9.493549,-10.487650,-11.444804,-12.364415,-13.245980,-14.088979,-14.892936,-15.657404,-16.381987,-17.066257,-17.709930,-18.312627,-18.874069,-19.393995,-19.872146,-20.308304,-20.702273,-21.053880,-21.362969,-21.629413,-21.853096,-22.033942,-22.171872,-22.266840,-22.318815,-22.327787,-22.293765,-22.216779,-22.096863,-21.934095,-21.728572,-21.480369,-21.189617,-20.856486,-20.481129,-20.063725,-19.604494,-19.103660,-18.561480,-17.978225,-17.354278,-16.689830,-15.985324,-15.241180,-14.457764,-13.635527,-12.774957,-11.876560,-10.940871,-9.968485,-8.959982,-7.916044,-6.837341,}, // NOLINT + {-6.944644,-8.016278,-9.053290,-10.055104,-11.020963,-11.950321,-12.842606,-13.697279,-14.513831,-15.291822,-16.030793,-16.730331,-17.390060,-18.009615,-18.588719,-19.127019,-19.624250,-20.080182,-20.494571,-20.867202,-21.197918,-21.486543,-21.732933,-21.936965,-22.098542,-22.217580,-22.294014,-22.327797,-22.318903,-22.267324,-22.173070,-22.036167,-21.856671,-21.634639,-21.370164,-21.063354,-20.714331,-20.323245,-19.890264,-19.415597,-18.899446,-18.342045,-17.743675,-17.104615,-16.425192,-15.705748,-14.946658,-14.148331,-13.311200,-12.435744,-11.522432,-10.571824,-9.584467,-8.560998,-7.502035,}, // NOLINT + {-7.857202,-8.915654,-9.938579,-10.925365,-11.875383,-12.788099,-13.662963,-14.499482,-15.297196,-16.055665,-16.774496,-17.453345,-18.091820,-18.689646,-19.246513,-19.762154,-20.236352,-20.668885,-21.059562,-21.408218,-21.714705,-21.978902,-22.200698,-22.380004,-22.516765,-22.610926,-22.662466,-22.671370,-22.637647,-22.561324,-22.442443,-22.281076,-22.077296,-21.831204,-21.542921,-21.212597,-20.840374,-20.426443,-19.970989,-19.474284,-18.936531,-18.357995,-17.739013,-17.079879,-16.380964,-15.642581,-14.865207,-14.049238,-13.195145,-12.303454,-11.374640,-10.409295,-9.408019,-8.371439,-7.300223,}, // NOLINT + {-7.405125,-8.469418,-9.499246,-10.493947,-11.452884,-12.375531,-13.261260,-14.109582,-14.919988,-15.692069,-16.425350,-17.119454,-17.774009,-18.388676,-18.963146,-19.497104,-19.990310,-20.442513,-20.853497,-21.223047,-21.551022,-21.837233,-22.081562,-22.283872,-22.444084,-22.562110,-22.637890,-22.671379,-22.662552,-22.611401,-22.517935,-22.382177,-22.204173,-21.984006,-21.721735,-21.417475,-21.071327,-20.683480,-20.254076,-19.783257,-19.271289,-18.718381,-18.124778,-17.490809,-16.816728,-16.102904,-15.349686,-14.557468,-13.726681,-12.857777,-11.951255,-11.007596,-10.027416,-9.011268,-7.959833,}, // NOLINT + {-8.313881,-9.364920,-10.380615,-11.360291,-12.303418,-13.209420,-14.077777,-14.908018,-15.699668,-16.452336,-17.165614,-17.839148,-18.472598,-19.065681,-19.618094,-20.129595,-20.599956,-21.028968,-21.416452,-21.762233,-22.066204,-22.328211,-22.548161,-22.725993,-22.861619,-22.955000,-23.006115,-23.014952,-22.981521,-22.905842,-22.787966,-22.627948,-22.425884,-22.181825,-21.895933,-21.568320,-21.199155,-20.788598,-20.336848,-19.844122,-19.310664,-18.736717,-18.122597,-17.468576,-16.775010,-16.042297,-15.270781,-14.460903,-13.613114,-12.727902,-11.805766,-10.847280,-9.853009,-8.823600,-7.759651,}, // NOLINT + {-7.862261,-8.919419,-9.942232,-10.930068,-11.882313,-12.798394,-13.677751,-14.519902,-15.324356,-16.090638,-16.818437,-17.507263,-18.156794,-18.766696,-19.336661,-19.866427,-20.355708,-20.804305,-21.211951,-21.578552,-21.903846,-22.187719,-22.430022,-22.630683,-22.789572,-22.906609,-22.981757,-23.014962,-23.006200,-22.955463,-22.862760,-22.728114,-22.551572,-22.333207,-22.073078,-21.771286,-21.427967,-21.043239,-20.617266,-20.150234,-19.642312,-19.093772,-18.504822,-17.875770,-17.206883,-16.498504,-15.750981,-14.964695,-14.140069,-13.277524,-12.377571,-11.440703,-10.467445,-9.458410,-8.414171,}, // NOLINT + {-8.767290,-9.811133,-10.819769,-11.792587,-12.729009,-13.628496,-14.490546,-15.314678,-16.100439,-16.847489,-17.555354,-18.223742,-18.852322,-19.440788,-19.988876,-20.496359,-20.962993,-21.388586,-21.772964,-22.115975,-22.417481,-22.677361,-22.895542,-23.071911,-23.206429,-23.299059,-23.349762,-23.358534,-23.325382,-23.250334,-23.133429,-22.974726,-22.774293,-22.532245,-22.248673,-21.923710,-21.557507,-21.150225,-20.702060,-20.213212,-19.683936,-19.114428,-18.505019,-17.855981,-17.167669,-16.440413,-15.674595,-14.870629,-14.028963,-13.150035,-12.234415,-11.282579,-10.295160,-9.272636,-8.215779,}, // NOLINT + {-8.316198,-9.366406,-10.382417,-11.363581,-12.309306,-13.219018,-14.092201,-14.928355,-15.727010,-16.487716,-17.210138,-17.893832,-18.538482,-19.143750,-19.709361,-20.235028,-20.720509,-21.165586,-21.570051,-21.933710,-22.256412,-22.538009,-22.778365,-22.977399,-23.134994,-23.251086,-23.325616,-23.358543,-23.349845,-23.299512,-23.207558,-23.073993,-22.898870,-22.682254,-22.424206,-22.124827,-21.784231,-21.402541,-20.979926,-20.516537,-20.012580,-19.468269,-18.883849,-18.259562,-17.595723,-16.892641,-16.150661,-15.370125,-14.551466,-13.695120,-12.801546,-11.871234,-10.904726,-9.902582,-8.865430,}, // NOLINT + {-9.217584,-10.254451,-11.256243,-12.222374,-13.152289,-14.045450,-14.901364,-15.719570,-16.499640,-17.241152,-17.943817,-18.607197,-19.231080,-19.815037,-20.358920,-20.862481,-21.325483,-21.747757,-22.129124,-22.469427,-22.768547,-23.026369,-23.242808,-23.417770,-23.551219,-23.643105,-23.693407,-23.702116,-23.669239,-23.594798,-23.478842,-23.321415,-23.122586,-22.882475,-22.601159,-22.278769,-21.915445,-21.511353,-21.066670,-20.581598,-20.056358,-19.491195,-18.886379,-18.242200,-17.558959,-16.837019,-16.076724,-15.278529,-14.442805,-13.570031,-12.660698,-11.715329,-10.734484,-9.718757,-8.668776,}, // NOLINT + {-8.767066,-9.810564,-10.819947,-11.794626,-12.733999,-13.637539,-14.504703,-15.335021,-16.128044,-16.883340,-17.600522,-18.279229,-18.919119,-19.519897,-20.081255,-20.602947,-21.084729,-21.526387,-21.927719,-22.288542,-22.608730,-22.888114,-23.126596,-23.324029,-23.480371,-23.595532,-23.669465,-23.702124,-23.693488,-23.643549,-23.552312,-23.419805,-23.246065,-23.031151,-22.775130,-22.478087,-22.140150,-21.761419,-21.342057,-20.882232,-20.382114,-19.841922,-19.261884,-18.642266,-17.983317,-17.285372,-16.548758,-15.773835,-14.960993,-14.110657,-13.223279,-12.299356,-11.339377,-10.343936,-9.313614,}, // NOLINT + {-9.664909,-10.694988,-11.690136,-12.649788,-13.573378,-14.460400,-15.310349,-16.122794,-16.897314,-17.633518,-18.331050,-18.989575,-19.608800,-20.188440,-20.728213,-21.227988,-21.687480,-22.106519,-22.484948,-22.822633,-23.119417,-23.375229,-23.589967,-23.763564,-23.895966,-23.987140,-24.037050,-24.045696,-24.013086,-23.939241,-23.824204,-23.668020,-23.470774,-23.232537,-22.953407,-22.633513,-22.273002,-21.872012,-21.430717,-20.949318,-20.428024,-19.867072,-19.266717,-18.627245,-17.948961,-17.232195,-16.477307,-15.684687,-14.854747,-13.987938,-13.084737,-12.145659,-11.171255,-10.162081,-9.118782,}, // NOLINT + {-9.215078,-10.251998,-11.254946,-12.223317,-13.156535,-14.054059,-14.915371,-15.740017,-16.527553,-17.277553,-17.989666,-18.663516,-19.298781,-19.895173,-20.452397,-20.970222,-21.448401,-21.886728,-22.285017,-22.643100,-22.960818,-23.238047,-23.474669,-23.670579,-23.825699,-23.939959,-24.013307,-24.045705,-24.037130,-23.987574,-23.897039,-23.765564,-23.593167,-23.379909,-23.125863,-22.831111,-22.495749,-22.119904,-21.703726,-21.247344,-20.750962,-20.214779,-19.639011,-19.023906,-18.369737,-17.676769,-16.945410,-16.175935,-15.368737,-14.524244,-13.642838,-12.725156,-11.771550,-10.782619,-9.758932,}, // NOLINT + {-10.109419,-11.132900,-12.121600,-13.074939,-13.992397,-14.873432,-15.717593,-16.524437,-17.293546,-18.024571,-18.717139,-19.370950,-19.985691,-20.561078,-21.096916,-21.592953,-22.048998,-22.464882,-22.840461,-23.175565,-23.470097,-23.723941,-23.937044,-24.109309,-24.240701,-24.331160,-24.380692,-24.389277,-24.356925,-24.283658,-24.169514,-24.014544,-23.818817,-23.582400,-23.305426,-22.987975,-22.630190,-22.232222,-21.794230,-21.316406,-20.798969,-20.242104,-19.646100,-19.011214,-18.337745,-17.626043,-16.876378,-16.089197,-15.264887,-14.403883,-13.506647,-12.573698,-11.605532,-10.602749,-9.565918,}, // NOLINT + {-9.660317,-10.690871,-11.687560,-12.649783,-13.577005,-14.468668,-15.324291,-16.143415,-16.925605,-17.670468,-18.377631,-19.046755,-19.677513,-20.269651,-20.822856,-21.336889,-21.811555,-22.246637,-22.641962,-22.997360,-23.312683,-23.587819,-23.822631,-24.017049,-24.170981,-24.284361,-24.357141,-24.389285,-24.380770,-24.331589,-24.241754,-24.111269,-23.940183,-23.728548,-23.476416,-23.183882,-22.851040,-22.478018,-22.064905,-21.611922,-21.119165,-20.586886,-20.015264,-19.404576,-18.755046,-18.066975,-17.340679,-16.576496,-15.774798,-14.935987,-14.060445,-13.148787,-12.201367,-11.218756,-10.201549,}, // NOLINT + {-10.551267,-11.568332,-12.550759,-13.497971,-14.409440,-15.284670,-16.123194,-16.924580,-17.688443,-18.414424,-19.102144,-19.751335,-20.361732,-20.932932,-21.464936,-21.957364,-22.410072,-22.822890,-23.195668,-23.528276,-23.820601,-24.072548,-24.284034,-24.454999,-24.585395,-24.675174,-24.724332,-24.732856,-24.700757,-24.628050,-24.514782,-24.360995,-24.166752,-23.932130,-23.657230,-23.342157,-22.987036,-22.592002,-22.157239,-21.682898,-21.169186,-20.616338,-20.024571,-19.394156,-18.725386,-18.018561,-17.274033,-16.492149,-15.673319,-14.817965,-13.926558,-12.999537,-12.037476,-11.040912,-10.010452,}, // NOLINT + {-10.102951,-11.127300,-12.117887,-13.074149,-13.995509,-14.881477,-15.731559,-16.545298,-17.322294,-18.062149,-18.764486,-19.428998,-20.055373,-20.643332,-21.192612,-21.702980,-22.174221,-22.606136,-22.998578,-23.351357,-23.664349,-23.937428,-24.170501,-24.363448,-24.516221,-24.628743,-24.700969,-24.732865,-24.724409,-24.675593,-24.586428,-24.456919,-24.287114,-24.077049,-23.826799,-23.536432,-23.206029,-22.835747,-22.425665,-21.975947,-21.486756,-20.958279,-20.390722,-19.784311,-19.139306,-18.455972,-17.734622,-16.975612,-16.179262,-15.345988,-14.476192,-13.570341,-12.628937,-11.652486,-10.641544,}, // NOLINT + {-10.990571,-12.001403,-12.977726,-13.918974,-14.824625,-15.694193,-16.527228,-17.323307,-18.082063,-18.803111,-19.486125,-20.130825,-20.736929,-21.304166,-21.832365,-22.321269,-22.770714,-23.180540,-23.550597,-23.880768,-24.170941,-24.421021,-24.630943,-24.800632,-24.930064,-25.019176,-25.067970,-25.076436,-25.044582,-24.972427,-24.860015,-24.707371,-24.514568,-24.281701,-24.008834,-23.696079,-23.343556,-22.951398,-22.519770,-22.048816,-21.538778,-20.989817,-20.402184,-19.776128,-19.111929,-18.409889,-17.670336,-16.893622,-16.080129,-15.230284,-14.344572,-13.423313,-12.467179,-11.476672,-10.452358,}, // NOLINT + {-10.543097,-11.561363,-12.546062,-13.496493,-14.412175,-15.292589,-16.137262,-16.945743,-17.717668,-18.452620,-19.150284,-19.810301,-20.432424,-21.016294,-21.561744,-22.068527,-22.536414,-22.965266,-23.354873,-23.705101,-24.015815,-24.286897,-24.518248,-24.709778,-24.861416,-24.973101,-25.044789,-25.076444,-25.068046,-25.019587,-24.931078,-24.802521,-24.633958,-24.425443,-24.177021,-23.888770,-23.560778,-23.193151,-22.786007,-22.339496,-21.853770,-21.328997,-20.765396,-20.163176,-19.522575,-18.843873,-18.127393,-17.373358,-16.582227,-15.754333,-14.890092,-13.989955,-13.054384,-12.083929,-11.079107,}, // NOLINT + {-11.427448,-12.432223,-13.402622,-14.338078,-15.238043,-16.102099,-16.929785,-17.720693,-18.474445,-19.190698,-19.869135,-20.509467,-21.111391,-21.674733,-22.199239,-22.684696,-23.130954,-23.537859,-23.905265,-24.233053,-24.521124,-24.769389,-24.977776,-25.146229,-25.274708,-25.363168,-25.411607,-25.420015,-25.388400,-25.316782,-25.205193,-25.053679,-24.862293,-24.631128,-24.360246,-24.049754,-23.699767,-23.310417,-22.881843,-22.414231,-21.907743,-21.362585,-20.778981,-20.157180,-19.497444,-18.800072,-18.065372,-17.293695,-16.485413,-15.640926,-14.760678,-13.845104,-12.894774,-11.910147,-10.891838,}, // NOLINT + {-10.980882,-11.993347,-12.972178,-13.916948,-14.827071,-15.702073,-16.541470,-17.344859,-18.111823,-18.842004,-19.535082,-20.190716,-20.808631,-21.388566,-21.930281,-22.433581,-22.898192,-23.324048,-23.710875,-24.058608,-24.367095,-24.636226,-24.865910,-25.056044,-25.206576,-25.317443,-25.388603,-25.420023,-25.411682,-25.363573,-25.275704,-25.148079,-24.980738,-24.773727,-24.527093,-24.240908,-23.915258,-23.550237,-23.145971,-22.702584,-22.220240,-21.699093,-21.139331,-20.541203,-19.904876,-19.230714,-18.518919,-17.769809,-16.983755,-16.161110,-15.302279,-14.407704,-13.477841,-12.513196,-11.514319,}, // NOLINT + {-11.862058,-12.860941,-13.825538,-14.755365,-15.649788,-16.508474,-17.330951,-18.116796,-18.865702,-19.577257,-20.251233,-20.887268,-21.485166,-22.044665,-22.565562,-23.047670,-23.490832,-23.894875,-24.259679,-24.585143,-24.871159,-25.117647,-25.324537,-25.491777,-25.619329,-25.707152,-25.755243,-25.763594,-25.732212,-25.661117,-25.550341,-25.399926,-25.209934,-24.980419,-24.711471,-24.403197,-24.055689,-23.669078,-23.243504,-22.779128,-22.276118,-21.734675,-21.155011,-20.537360,-19.881981,-19.189182,-18.459203,-17.692425,-16.889240,-16.049991,-15.175119,-14.265064,-13.320350,-12.341466,-11.328999,}, // NOLINT + {-11.416418,-12.423109,-13.396349,-14.335580,-15.240304,-16.110022,-16.944283,-17.742673,-18.504843,-19.230360,-19.918941,-20.570288,-21.184123,-21.760188,-22.298254,-22.798103,-23.259554,-23.682436,-24.066594,-24.411889,-24.718202,-24.985415,-25.213468,-25.402250,-25.551696,-25.661766,-25.732411,-25.763601,-25.755316,-25.707549,-25.620308,-25.493594,-25.327448,-25.121908,-24.877022,-24.592858,-24.269496,-23.907031,-23.505568,-23.065242,-22.586193,-22.068587,-21.512600,-20.918441,-20.286352,-19.616561,-18.909356,-18.165036,-17.383932,-16.566408,-15.712854,-14.823694,-13.899362,-12.940415,-11.947318,}, // NOLINT + {-12.294495,-13.287633,-14.246597,-15.170875,-16.059958,-16.913403,-17.730792,-18.511773,-19.255873,-19.962877,-20.632458,-21.264332,-21.858244,-22.414006,-22.931399,-23.410218,-23.850317,-24.251586,-24.613861,-24.937049,-25.221055,-25.465804,-25.671228,-25.837283,-25.963929,-26.051127,-26.098878,-26.107172,-26.076018,-26.005435,-25.895453,-25.746114,-25.557462,-25.329582,-25.062536,-24.756420,-24.411333,-24.027403,-23.604756,-23.143548,-22.643942,-22.106101,-21.530311,-20.916717,-20.265595,-19.577225,-18.851892,-18.089933,-17.291667,-16.457551,-15.587928,-14.683254,-13.744025,-12.770741,-11.763952,}, // NOLINT + {-11.849823,-12.850929,-13.818667,-14.752557,-15.651956,-16.516519,-17.345763,-18.139306,-18.896694,-19.617684,-20.301901,-20.949066,-21.558897,-22.131191,-22.665683,-23.162181,-23.620524,-24.040525,-24.422046,-24.764958,-25.069142,-25.334493,-25.560939,-25.748389,-25.896783,-26.006072,-26.076213,-26.107179,-26.098950,-26.051518,-25.964892,-25.839070,-25.674093,-25.469992,-25.226817,-24.944630,-24.623505,-24.263535,-23.864822,-23.427487,-22.951661,-22.437511,-21.885212,-21.294955,-20.666960,-20.001469,-19.298754,-18.559083,-17.782842,-16.970307,-16.121891,-15.238020,-14.319110,-13.365684,-12.378227,}, // NOLINT + {-12.724869,-13.712423,-14.665889,-15.584784,-16.468623,-17.316958,-18.129382,-18.905516,-19.645015,-20.347567,-21.012865,-21.640661,-22.230714,-22.782807,-23.296747,-23.772357,-24.209501,-24.608026,-24.967820,-25.288781,-25.570819,-25.813866,-26.017859,-26.182750,-26.308508,-26.395094,-26.442511,-26.450749,-26.419818,-26.349736,-26.240529,-26.092240,-25.904919,-25.678630,-25.413435,-25.109434,-24.766710,-24.385392,-23.965628,-23.507517,-23.011241,-22.476978,-21.904909,-21.295292,-20.648344,-19.964313,-19.243518,-18.486225,-17.692837,-16.863685,-15.999181,-15.099749,-14.165888,-13.198065,-12.196838,}, // NOLINT + {-12.281210,-13.276863,-14.239253,-15.167830,-16.062117,-16.921637,-17.745979,-18.534712,-19.287548,-20.004077,-20.684019,-21.327095,-21.933027,-22.501581,-23.032610,-23.525824,-23.981116,-24.398308,-24.777249,-25.117826,-25.419927,-25.683443,-25.908331,-26.094478,-26.241835,-26.350360,-26.420010,-26.450757,-26.442582,-26.395480,-26.309455,-26.184507,-26.020667,-25.817984,-25.576487,-25.296235,-24.977301,-24.619773,-24.223746,-23.789336,-23.316675,-22.805920,-22.257209,-21.670762,-21.046779,-20.385495,-19.687163,-18.952073,-18.180528,-17.372874,-16.529494,-15.650764,-14.737154,-13.789095,-12.807177,}, // NOLINT + {-13.153316,-14.135398,-15.083531,-15.997159,-16.875868,-17.719222,-18.526791,-19.298243,-20.033223,-20.731380,-21.392502,-22.016310,-22.602571,-23.151096,-23.661656,-24.134129,-24.568356,-24.964206,-25.321569,-25.640349,-25.920466,-26.161841,-26.364427,-26.528180,-26.653068,-26.739055,-26.786144,-26.794327,-26.763613,-26.694021,-26.585576,-26.438315,-26.252288,-26.027553,-25.764181,-25.462253,-25.121864,-24.743111,-24.326123,-23.871063,-23.378045,-22.847256,-22.278877,-21.673142,-21.030247,-20.350482,-19.634099,-18.881439,-18.092746,-17.268474,-16.408977,-15.514695,-14.586036,-13.623544,-12.627728,}, // NOLINT + {-12.710721,-13.701014,-14.658171,-15.581604,-16.470853,-17.325457,-18.144999,-18.929100,-19.677405,-20.389581,-21.065335,-21.704405,-22.306511,-22.871478,-23.399071,-23.889077,-24.341376,-24.755793,-25.132213,-25.470504,-25.770564,-26.032308,-26.255643,-26.440514,-26.586858,-26.694635,-26.763802,-26.794334,-26.786214,-26.739434,-26.654000,-26.529910,-26.367198,-26.165893,-25.926036,-25.647682,-25.330901,-24.975762,-24.582379,-24.150833,-23.681255,-23.173809,-22.628628,-22.045912,-21.425855,-20.768680,-20.074621,-19.344006,-18.577083,-17.774197,-16.935715,-16.062032,-15.153556,-14.210772,-13.234176,}, // NOLINT + {-13.579901,-14.556653,-15.499535,-16.408070,-17.281782,-18.120251,-18.923087,-19.689905,-20.420449,-21.114379,-21.771409,-22.391310,-22.973865,-23.518865,-24.026141,-24.495538,-24.926912,-25.320139,-25.675122,-25.991778,-26.269989,-26.509731,-26.710942,-26.873576,-26.997610,-27.083009,-27.129776,-27.137905,-27.107403,-27.038289,-26.930582,-26.784337,-26.599582,-26.376357,-26.114783,-25.814885,-25.476769,-25.100541,-24.686303,-24.234207,-23.744382,-23.216997,-22.652232,-22.050288,-21.411390,-20.735774,-20.023728,-19.275529,-18.491502,-17.671988,-16.817382,-15.928086,-15.004559,-14.047269,-13.056730,}, // NOLINT + {-13.138326,-14.123471,-15.075503,-15.993920,-16.878244,-17.728043,-18.542895,-19.322440,-20.066328,-20.774248,-21.445908,-22.081047,-22.679426,-23.240827,-23.765054,-24.251932,-24.701299,-25.113015,-25.486954,-25.823002,-26.121063,-26.381047,-26.602877,-26.786501,-26.931858,-27.038894,-27.107589,-27.137911,-27.129845,-27.083382,-26.998528,-26.875275,-26.713668,-26.513734,-26.275474,-25.998975,-25.684303,-25.331508,-24.940704,-24.511968,-24.045427,-23.541210,-22.999502,-22.420444,-21.804223,-21.151075,-20.461234,-19.734960,-18.972555,-18.174333,-17.340640,-16.471871,-15.568426,-14.630795,-13.659426,}, // NOLINT + {-14.004745,-14.976287,-15.914082,-16.817608,-17.686423,-18.520127,-19.318323,-20.080676,-20.806868,-21.496607,-22.149629,-22.765697,-23.344621,-23.886184,-24.390232,-24.856610,-25.285185,-25.675846,-26.028492,-26.343033,-26.619406,-26.857544,-27.057402,-27.218941,-27.342136,-27.426956,-27.473406,-27.481481,-27.451188,-27.382545,-27.275575,-27.130314,-26.946802,-26.725092,-26.465248,-26.167342,-25.831458,-25.457694,-25.046142,-24.596985,-24.110276,-23.586227,-23.024999,-22.426781,-21.791788,-21.120254,-20.412446,-19.668630,-18.889129,-18.074292,-17.224471,-16.340076,-15.421543,-14.469346,-13.483983,}, // NOLINT + {-13.564249,-14.544320,-15.491359,-16.404858,-17.284369,-18.129455,-18.939720,-19.714802,-20.454363,-21.158118,-21.825770,-22.457059,-23.051765,-23.609678,-24.130626,-24.614402,-25.060913,-25.469974,-25.841481,-26.175332,-26.471428,-26.729688,-26.950043,-27.132440,-27.276816,-27.383139,-27.451371,-27.481488,-27.473475,-27.427324,-27.343040,-27.220616,-27.060086,-26.861471,-26.624807,-26.350138,-26.037528,-25.687042,-25.298786,-24.872781,-24.409217,-23.908189,-23.369863,-22.794378,-22.181931,-21.532726,-20.846997,-20.124991,-19.367007,-18.573341,-17.744344,-16.880385,-15.981860,-15.049244,-14.082978,}, // NOLINT + {-14.427939,-15.394414,-16.327206,-17.225839,-18.089870,-18.918906,-19.712568,-20.470523,-21.192461,-21.878105,-22.527173,-23.139523,-23.714878,-24.253088,-24.753947,-25.217365,-25.643193,-26.031331,-26.381685,-26.694168,-26.968720,-27.205282,-27.403812,-27.564271,-27.686645,-27.770898,-27.817036,-27.825058,-27.794969,-27.726784,-27.620527,-27.476244,-27.293952,-27.073714,-26.815585,-26.519635,-26.185941,-25.814597,-25.405701,-24.959370,-24.475757,-23.954979,-23.397216,-22.802652,-22.171487,-21.503950,-20.800261,-20.060785,-19.285728,-18.475455,-17.630318,-16.750717,-15.837066,-14.889829,-13.909516,}, // NOLINT + {-13.988546,-14.963635,-15.905784,-16.814498,-17.689291,-18.529772,-19.335539,-20.106235,-20.841579,-21.541231,-22.204942,-22.832468,-23.423575,-23.978080,-24.495791,-24.976559,-25.420237,-25.826692,-26.195813,-26.527502,-26.821671,-27.078243,-27.297150,-27.478325,-27.621750,-27.727371,-27.795148,-27.825064,-27.817104,-27.771260,-27.687536,-27.565922,-27.406458,-27.209152,-26.974041,-26.701172,-26.390582,-26.042360,-25.656565,-25.233288,-24.772646,-24.274748,-23.739734,-23.167764,-22.559010,-21.913675,-21.231975,-20.514161,-19.760502,-18.971300,-18.146895,-17.287643,-16.393933,-15.466220,-14.504936,}, // NOLINT + {-14.849561,-15.811078,-16.738982,-17.632837,-18.492189,-19.316654,-20.105869,-20.859511,-21.577298,-22.258918,-22.904155,-23.512810,-24.084665,-24.619552,-25.117311,-25.577823,-26.000952,-26.386613,-26.734712,-27.045175,-27.317941,-27.552943,-27.750175,-27.909576,-28.031134,-28.114833,-28.160665,-28.168634,-28.138745,-28.071014,-27.965474,-27.822127,-27.641039,-27.422244,-27.165812,-26.871771,-26.540230,-26.171257,-25.764970,-25.321450,-24.840838,-24.323270,-23.768920,-23.177937,-22.550531,-21.886915,-21.187330,-20.452035,-19.681335,-18.875535,-18.034991,-17.160078,-16.251219,-15.308855,-14.333470,}, // NOLINT + {-14.411296,-15.381556,-16.318911,-17.222904,-18.093081,-18.929042,-19.730400,-20.496821,-21.228002,-21.923644,-22.583487,-23.207295,-23.794887,-24.346027,-24.860581,-25.338373,-25.779280,-26.183172,-26.549954,-26.879522,-27.171798,-27.426705,-27.644187,-27.824192,-27.966679,-28.071588,-28.138921,-28.168640,-28.160733,-28.115190,-28.032014,-27.911205,-27.752787,-27.556764,-27.323188,-27.052074,-26.743484,-26.397472,-26.014130,-25.593510,-25.135743,-24.640905,-24.109153,-23.540631,-22.935503,-22.293960,-21.616214,-20.902503,-20.153090,-19.368266,-18.548353,-17.693706,-16.804703,-15.881784,-14.925383,}, // NOLINT + {-15.269710,-16.226372,-17.149504,-18.038669,-18.893440,-19.713392,-20.498286,-21.247701,-21.961392,-22.639082,-23.280544,-23.885585,-24.454003,-24.985636,-25.480342,-25.937993,-26.358480,-26.741696,-27.087586,-27.396059,-27.667064,-27.900554,-28.096496,-28.254859,-28.375616,-28.458764,-28.504294,-28.512210,-28.482517,-28.415232,-28.310376,-28.167973,-27.988064,-27.770683,-27.515902,-27.223756,-26.894330,-26.527698,-26.123956,-25.683201,-25.205553,-24.691146,-24.140131,-23.552661,-22.928949,-22.269183,-21.573591,-20.842451,-20.076012,-19.274603,-18.438557,-17.568248,-16.664064,-15.726460,-14.755875,}, // NOLINT + {-14.832581,-15.798088,-16.730765,-17.630141,-18.495797,-19.327332,-20.124366,-20.886580,-21.613685,-22.305381,-22.961432,-23.581612,-24.165724,-24.713578,-25.225012,-25.699883,-26.138066,-26.539451,-26.903917,-27.231397,-27.521802,-27.775086,-27.991169,-28.170006,-28.311558,-28.415799,-28.482690,-28.512216,-28.504361,-28.459118,-28.376483,-28.256464,-28.099068,-27.904316,-27.672239,-27.402863,-27.096239,-26.752415,-26.371470,-25.953469,-25.498507,-25.006693,-24.478144,-23.913005,-23.311440,-22.673624,-21.999761,-21.290082,-20.544824,-19.764275,-18.948762,-18.098645,-17.214262,-16.296030,-15.344406,}, // NOLINT + {-15.688478,-16.640365,-17.558843,-18.443411,-19.293656,-20.109290,-20.889873,-21.635139,-22.344814,-23.018639,-23.656396,-24.257886,-24.822926,-25.351359,-25.843062,-26.297905,-26.715787,-27.096612,-27.440319,-27.746829,-28.016108,-28.248098,-28.442773,-28.600108,-28.720084,-28.802690,-28.847923,-28.855785,-28.826285,-28.759436,-28.655259,-28.513780,-28.335031,-28.119055,-27.865899,-27.575609,-27.248265,-26.883930,-26.482694,-26.044653,-25.569923,-25.058615,-24.510885,-23.926875,-23.306794,-22.650803,-21.959150,-21.232057,-20.469812,-19.672708,-18.841074,-17.975269,-17.075680,-16.142743,-15.176914,}, // NOLINT + {-15.252487,-16.213324,-17.141423,-18.036257,-18.897504,-19.724682,-20.517485,-21.275573,-21.998664,-22.686490,-23.338817,-23.955421,-24.536116,-25.080729,-25.589103,-26.061103,-26.496608,-26.895510,-27.257719,-27.583136,-27.871722,-28.123389,-28.338092,-28.515785,-28.656430,-28.759996,-28.826455,-28.855791,-28.847988,-28.803039,-28.720940,-28.601696,-28.445313,-28.251809,-28.021211,-27.753543,-27.448857,-27.107183,-26.728598,-26.313159,-25.860979,-25.372127,-24.846733,-24.284909,-23.686856,-23.052697,-22.382644,-21.676916,-20.935749,-20.159425,-19.348243,-18.502535,-17.622660,-16.709033,-15.762084,}, // NOLINT + {-24.010165,-25.462359,-26.863274,-28.212173,-29.508538,-30.751709,-31.941276,-33.076764,-34.157760,-35.183917,-36.154935,-37.070513,-37.930468,-38.734538,-39.482564,-40.174392,-40.809892,-41.388961,-41.911516,-42.377488,-42.786813,-43.139459,-43.435398,-43.674610,-43.857091,-43.982843,-44.051877,-44.064211,-44.019871,-43.918890,-43.761308,-43.547174,-43.276545,-42.949487,-42.566066,-42.126382,-41.630529,-41.078621,-40.470784,-39.807160,-39.087920,-38.313246,-37.483352,-36.598455,-35.658888,-34.664869,-33.616767,-32.514960,-31.359849,-30.151894,-28.891600,-27.579521,-26.216270,-24.802464,-23.338980,}, // NOLINT + {-23.498229,-24.951818,-26.355766,-27.709372,-29.012029,-30.263113,-31.462105,-32.608509,-33.701905,-34.741893,-35.728125,-36.660278,-37.538076,-38.361258,-39.129613,-39.842947,-40.501074,-41.103841,-41.651124,-42.142797,-42.578759,-42.958914,-43.283194,-43.551532,-43.763835,-43.920085,-44.020226,-44.064220,-44.052033,-43.983641,-43.859024,-43.678171,-43.441077,-43.147738,-42.798171,-42.392404,-41.930453,-41.412384,-40.838244,-40.208112,-39.522086,-38.780280,-37.982834,-37.129902,-36.221713,-35.258447,-34.240381,-33.167810,-32.041066,-30.860521,-29.626616,-28.339822,-27.000602,-25.609629,-24.167596,}, // NOLINT + {-24.544707,-25.985824,-27.375709,-28.713696,-29.999210,-31.231750,-32.410849,-33.536112,-34.607165,-35.623705,-36.585424,-37.492122,-38.343542,-39.139530,-39.879949,-40.564636,-41.193496,-41.766458,-42.283440,-42.744366,-43.149275,-43.498075,-43.790757,-44.027316,-44.207766,-44.332108,-44.400356,-44.412532,-44.368659,-44.268773,-44.112902,-43.901086,-43.633404,-43.309882,-42.930585,-42.495589,-42.005000,-41.458899,-40.857356,-40.200561,-39.488599,-38.721697,-37.899986,-37.023693,-36.093048,-35.108342,-34.069862,-32.977932,-31.832943,-30.635366,-29.385509,-28.084061,-26.731477,-25.328454,-23.875640,}, // NOLINT + {-24.032271,-25.475263,-26.868592,-28.211643,-29.503783,-30.744538,-31.933292,-33.069775,-34.153416,-35.183929,-36.160991,-37.084330,-37.953655,-38.768783,-39.529502,-40.235642,-40.887045,-41.483605,-42.025180,-42.511678,-42.943022,-43.319124,-43.639920,-43.905358,-44.115378,-44.269942,-44.369007,-44.412539,-44.400509,-44.332890,-44.209662,-44.030806,-43.796330,-43.506179,-43.160410,-42.759027,-42.302000,-41.789401,-41.221296,-40.597695,-39.918696,-39.184382,-38.394905,-37.550351,-36.650934,-35.696815,-34.688241,-33.625464,-32.508789,-31.338565,-30.115178,-28.839047,-27.510681,-26.130616,-24.699449,}, // NOLINT + {-25.075822,-26.506064,-27.885079,-29.212273,-30.487129,-31.709185,-32.878006,-33.993236,-35.054535,-36.061618,-37.014289,-37.912192,-38.755278,-39.543348,-40.276300,-40.953994,-41.576358,-42.143335,-42.654854,-43.110888,-43.511437,-43.856458,-44.145972,-44.379930,-44.558391,-44.681354,-44.748832,-44.760852,-44.717436,-44.618618,-44.464426,-44.254898,-43.990083,-43.670008,-43.294754,-42.864359,-42.378908,-41.838462,-41.243137,-40.592990,-39.888211,-39.128891,-38.315203,-37.447335,-36.525425,-35.549900,-34.520857,-33.438642,-32.303611,-31.116151,-29.876682,-28.585670,-27.243662,-25.851236,-24.409029,}, // NOLINT + {-24.563111,-25.995594,-27.378453,-28.711082,-29.992913,-31.223439,-32.402226,-33.528817,-34.602888,-35.624098,-36.592166,-37.506822,-38.367865,-39.175085,-39.928318,-40.627414,-41.272246,-41.862698,-42.398687,-42.880124,-43.306943,-43.679066,-43.996466,-44.259072,-44.466852,-44.619761,-44.717776,-44.760859,-44.748982,-44.682122,-44.560248,-44.383354,-44.151427,-43.864418,-43.522357,-43.125232,-42.673058,-42.165842,-41.603616,-40.986422,-40.314304,-39.587365,-38.805662,-37.969343,-37.078524,-36.133382,-35.134117,-34.080960,-32.974180,-31.814091,-30.601047,-29.335452,-28.017768,-26.648404,-25.228054,}, // NOLINT + {-25.603779,-27.023208,-28.391495,-29.708056,-30.972423,-32.184098,-33.342873,-34.448240,-35.499951,-36.497764,-37.441425,-38.330821,-39.165738,-39.946054,-40.671667,-41.342512,-41.958508,-42.519612,-43.025796,-43.477029,-43.873312,-44.214639,-44.501025,-44.732456,-44.908975,-45.030579,-45.097304,-45.109170,-45.066202,-44.968426,-44.815878,-44.608592,-44.346584,-44.029896,-43.658586,-43.232685,-42.752268,-42.217382,-41.628111,-40.984540,-40.286759,-39.534877,-38.729057,-37.869466,-36.956291,-35.989629,-34.969854,-33.897200,-32.771964,-31.594497,-30.365185,-29.084509,-27.752893,-26.370917,-24.939253,}, // NOLINT + {-25.090856,-26.512957,-27.885484,-29.207764,-30.479459,-31.699942,-32.868823,-33.985772,-35.050432,-36.062495,-37.021718,-37.927875,-38.780793,-39.580217,-40.326120,-41.018308,-41.656699,-42.241174,-42.771693,-43.248175,-43.670542,-44.038781,-44.352848,-44.612673,-44.818255,-44.969551,-45.066535,-45.109178,-45.097452,-45.031335,-44.910790,-44.735815,-44.506374,-44.222458,-43.884027,-43.491097,-43.043644,-42.541698,-41.985256,-41.374336,-40.708984,-39.989241,-39.215215,-38.386918,-37.504555,-36.568224,-35.578105,-34.534348,-33.437313,-32.287227,-31.084360,-29.829101,-28.521888,-27.163183,-25.753478,}, // NOLINT + {-26.128661,-27.537403,-28.895078,-30.201161,-31.455193,-32.656769,-33.805540,-34.901213,-35.943511,-36.932213,-37.867122,-38.748086,-39.574972,-40.347677,-41.066110,-41.730235,-42.339986,-42.895340,-43.396283,-43.842805,-44.234918,-44.572624,-44.855948,-45.084900,-45.259504,-45.379787,-45.445774,-45.457489,-45.414958,-45.318208,-45.167262,-44.962153,-44.702910,-44.389540,-44.022104,-43.600617,-43.125137,-42.595706,-42.012372,-41.375217,-40.684311,-39.939759,-39.141664,-38.290170,-37.385419,-36.427620,-35.416960,-34.353686,-33.238087,-32.070477,-30.851201,-29.580672,-28.259370,-26.887775,-25.466439,}, // NOLINT + {-25.615642,-27.027477,-28.389734,-29.701962,-30.963591,-32.174143,-33.333283,-34.440741,-35.496127,-36.499209,-37.449737,-38.347527,-39.192432,-39.984281,-40.722966,-41.408368,-42.040423,-42.619043,-43.144190,-43.615801,-44.033833,-44.398259,-44.709047,-44.966158,-45.169592,-45.319314,-45.415284,-45.457496,-45.445919,-45.380526,-45.261296,-45.088197,-44.861209,-44.580288,-44.245449,-43.856603,-43.413816,-42.917037,-42.366241,-41.761479,-41.102746,-40.390081,-39.623533,-38.803183,-37.929117,-37.001430,-36.020291,-34.985877,-33.898387,-32.758067,-31.565227,-30.320186,-29.023306,-27.675044,-26.275893,}, // NOLINT + {-26.650448,-28.048655,-29.395940,-30.691702,-31.935554,-33.127139,-34.266113,-35.352273,-36.385305,-37.365061,-38.291346,-39.164046,-39.983053,-40.748284,-41.459678,-42.117182,-42.720827,-43.270542,-43.766340,-44.208257,-44.596268,-44.930429,-45.210753,-45.437263,-45.609995,-45.728977,-45.794240,-45.805807,-45.763705,-45.667952,-45.518591,-45.315621,-45.059065,-44.748960,-44.385314,-43.968162,-43.497521,-42.973441,-42.395926,-41.765079,-41.080918,-40.343549,-39.553025,-38.709519,-37.813062,-36.863946,-35.862247,-34.808209,-33.702102,-32.544178,-31.334761,-30.074296,-28.763116,-27.401764,-25.990658,}, // NOLINT + {-26.137547,-27.539236,-28.891424,-30.193593,-31.445289,-32.646179,-33.795688,-34.893804,-35.940071,-36.934336,-37.876289,-38.765908,-39.602920,-40.387288,-41.118882,-41.797641,-42.423487,-42.996358,-43.516230,-43.983066,-44.396834,-44.757533,-45.065103,-45.319560,-45.520879,-45.669038,-45.764024,-45.805814,-45.794383,-45.729706,-45.611755,-45.440501,-45.215922,-44.937952,-44.606591,-44.221811,-43.783575,-43.291840,-42.746620,-42.147894,-41.495649,-40.789945,-40.030765,-39.218180,-38.352263,-37.433063,-36.460769,-35.435478,-34.357400,-33.226740,-32.043754,-30.808768,-29.522099,-28.184145,-26.795388,}, // NOLINT + {-27.169407,-28.557271,-29.894213,-31.179793,-32.413617,-33.595347,-34.724729,-35.801487,-36.825425,-37.796370,-38.714189,-39.578770,-40.390040,-41.147944,-41.852411,-42.503457,-43.101067,-43.645243,-44.135990,-44.573372,-44.957377,-45.288052,-45.565422,-45.789552,-45.960449,-46.078157,-46.142705,-46.154125,-46.112441,-46.017677,-45.869853,-45.668983,-45.415084,-45.108182,-44.748247,-44.335332,-43.869456,-43.350637,-42.778830,-42.154167,-41.476643,-40.746319,-39.963264,-39.127567,-38.239330,-37.298695,-36.305816,-35.260863,-34.164083,-33.015709,-31.816062,-30.565455,-29.264287,-27.913001,-26.512074,}, // NOLINT + {-26.656695,-28.048372,-29.390573,-30.682868,-31.924791,-33.116010,-34.256182,-35.345041,-36.382343,-37.367873,-38.301441,-39.182978,-40.012283,-40.789309,-41.513951,-42.186156,-42.805903,-43.373134,-43.887828,-44.349967,-44.759563,-45.116574,-45.421017,-45.672851,-45.872099,-46.018737,-46.112757,-46.154131,-46.142846,-46.078871,-45.962176,-45.792735,-45.570496,-45.295448,-44.967527,-44.586699,-44.152904,-43.666177,-43.126411,-42.533619,-41.887794,-41.188877,-40.436938,-39.631988,-38.774061,-37.863273,-36.899617,-35.883314,-34.814488,-33.693320,-32.520050,-31.294948,-30.018332,-28.690571,-27.312073,}, // NOLINT + {-27.685609,-29.063209,-30.389989,-31.665525,-32.889476,-34.061528,-35.181434,-36.248961,-37.263938,-38.226231,-39.135722,-39.992308,-40.795986,-41.546667,-42.244341,-42.889036,-43.480738,-44.019474,-44.505290,-44.938196,-45.318256,-45.645512,-45.920008,-46.141765,-46.310864,-46.427317,-46.491167,-46.502442,-46.461169,-46.367367,-46.221067,-46.022252,-45.770971,-45.467174,-45.110908,-44.702149,-44.240948,-43.727273,-43.161113,-42.542522,-41.871513,-41.148119,-40.372371,-39.544394,-38.664209,-37.731941,-36.747734,-35.711735,-34.624143,-33.485184,-32.295124,-31.054270,-29.762977,-28.421651,-27.030694,}, // NOLINT + {-27.173135,-28.554951,-29.887307,-31.169837,-32.402136,-33.583880,-34.714772,-35.794552,-36.823016,-37.799968,-38.725314,-39.598884,-40.420586,-41.190385,-41.908178,-42.573979,-43.187719,-43.749401,-44.259011,-44.716556,-45.122028,-45.475423,-45.776792,-46.026053,-46.223268,-46.368412,-46.461479,-46.502448,-46.491305,-46.428022,-46.312559,-46.144903,-45.924990,-45.652783,-45.328235,-44.951297,-44.521918,-44.040054,-43.505655,-42.918690,-42.279090,-41.586927,-40.842104,-40.044645,-39.194606,-38.292003,-37.336919,-36.329454,-35.269726,-34.157899,-32.994213,-31.778862,-30.512148,-29.194422,-27.826071,}, // NOLINT + {-28.199139,-29.566649,-30.883375,-32.149002,-33.363238,-34.525740,-35.636318,-36.694771,-37.700940,-38.654689,-39.556009,-40.404763,-41.200949,-41.944539,-42.635543,-43.273974,-43.859852,-44.393261,-44.874197,-45.302735,-45.678922,-46.002815,-46.274464,-46.493925,-46.661249,-46.776465,-46.839626,-46.850759,-46.809890,-46.717035,-46.572218,-46.375431,-46.126702,-45.825996,-45.473315,-45.068668,-44.612033,-44.103412,-43.542798,-42.930185,-42.265577,-41.548996,-40.780472,-39.960048,-39.087782,-38.163794,-37.188089,-36.160907,-35.082368,-33.952700,-32.772076,-31.540837,-30.259270,-28.927792,-27.546810,}, // NOLINT + {-27.687122,-29.059103,-30.381742,-31.654639,-32.877443,-34.049839,-35.171569,-36.242415,-37.262174,-38.230716,-39.147895,-40.013659,-40.827898,-41.590573,-42.301670,-42.961119,-43.568964,-44.125189,-44.629797,-45.082818,-45.484248,-45.834108,-46.132415,-46.379167,-46.574385,-46.718060,-46.810191,-46.850765,-46.839762,-46.777157,-46.662917,-46.497005,-46.279370,-46.009964,-45.688736,-45.315622,-44.890559,-44.413501,-43.884382,-43.303141,-42.669743,-41.984130,-41.246284,-40.456236,-39.613944,-38.719430,-37.772744,-36.773977,-35.723218,-34.620624,-33.466340,-32.260604,-31.003671,-29.695835,-28.337479,}, // NOLINT + {-28.710115,-30.067642,-31.374493,-32.630385,-33.835005,-34.988180,-36.089497,-37.138995,-38.136492,-39.081860,-39.975122,-40.816157,-41.604988,-42.341592,-43.026024,-43.658302,-44.238484,-44.766624,-45.242775,-45.667007,-46.039383,-46.359974,-46.628830,-46.846028,-47.011586,-47.125601,-47.188084,-47.199075,-47.158599,-47.066679,-46.923319,-46.728527,-46.482300,-46.184609,-45.835469,-45.434861,-44.982706,-44.479100,-43.923918,-43.317181,-42.658830,-41.949002,-41.187568,-40.374597,-39.510127,-38.594196,-37.626958,-36.608454,-35.538838,-34.418295,-33.247000,-32.025237,-30.753326,-29.431559,-28.060342,}, // NOLINT + {-28.198651,-29.560929,-30.873953,-32.137359,-33.350791,-34.513975,-35.626676,-36.688703,-37.699899,-38.660134,-39.569316,-40.427363,-41.234246,-41.989917,-42.694359,-43.347622,-43.949649,-44.500521,-45.000205,-45.448779,-45.846243,-46.192609,-46.487923,-46.732201,-46.925453,-47.067685,-47.158898,-47.199081,-47.188218,-47.126282,-47.013231,-46.849047,-46.633653,-46.367000,-46.049039,-45.679686,-45.258910,-44.786540,-44.262607,-43.687024,-43.059681,-42.380568,-41.649627,-40.866817,-40.032145,-39.145575,-38.207183,-37.216979,-36.175048,-35.081521,-33.936529,-32.740272,-31.492975,-30.194915,-28.846424,}, // NOLINT + {-29.218683,-30.566326,-31.863434,-33.109704,-34.304867,-35.448706,-36.541034,-37.581731,-38.570695,-39.507853,-40.393115,-41.226548,-42.008121,-42.737873,-43.415835,-44.042064,-44.616623,-45.139589,-45.611021,-46.031024,-46.399651,-46.716978,-46.983094,-47.198043,-47.361916,-47.474723,-47.536539,-47.547391,-47.507305,-47.416302,-47.274377,-47.081542,-46.837781,-46.543078,-46.197416,-45.800759,-45.353074,-44.854340,-44.304501,-43.703556,-43.051453,-42.348180,-41.593726,-40.788099,-39.931306,-39.023394,-38.064418,-37.054462,-35.993642,-34.882116,-33.720022,-32.507632,-31.245200,-29.933027,-28.571449,}, // NOLINT + {-28.707788,-30.060524,-31.364075,-32.618088,-33.822267,-34.976364,-36.080161,-37.133501,-38.136268,-39.088298,-39.989586,-40.840051,-41.639670,-42.388447,-43.086403,-43.733522,-44.329833,-44.875397,-45.370278,-45.814457,-46.207999,-46.550953,-46.843325,-47.085158,-47.276475,-47.417288,-47.507597,-47.547397,-47.536671,-47.475395,-47.363538,-47.201033,-46.987845,-46.723914,-46.409158,-46.043507,-45.626884,-45.159191,-44.640372,-44.070321,-43.448970,-42.776246,-42.052085,-41.276435,-40.449262,-39.570525,-38.640291,-37.658525,-36.625303,-35.540688,-34.404877,-33.217961,-31.980163,-30.691747,-29.352991,}, // NOLINT + {-29.724907,-31.062798,-32.350299,-33.587080,-34.772916,-35.907613,-36.991026,-38.023032,-39.003528,-39.932577,-40.810049,-41.636004,-42.410433,-43.133431,-43.805015,-44.425294,-44.994309,-45.512185,-45.978977,-46.394803,-46.759727,-47.073867,-47.337272,-47.550028,-47.712201,-47.823834,-47.884993,-47.895707,-47.856002,-47.765893,-47.625388,-47.434477,-47.193140,-46.901386,-46.559136,-46.166384,-45.723073,-45.229156,-44.684596,-44.089339,-43.443345,-42.746574,-41.998998,-41.200600,-40.351375,-39.451354,-38.500527,-37.499008,-36.446863,-35.344206,-34.191204,-32.988050,-31.734973,-30.432285,-29.080256,}, // NOLINT + {-29.214703,-30.557992,-31.852174,-33.096927,-34.291964,-35.437100,-36.532125,-37.576891,-38.571287,-39.515328,-40.408777,-41.251822,-42.044259,-42.786246,-43.477762,-44.118833,-44.709546,-45.249916,-45.740000,-46.179851,-46.569555,-46.909117,-47.198590,-47.438035,-47.627447,-47.766867,-47.856289,-47.895712,-47.885124,-47.824496,-47.713799,-47.552965,-47.341968,-47.080690,-46.769101,-46.407096,-45.994590,-45.531488,-45.017693,-44.453118,-43.837647,-43.171214,-42.453731,-41.685115,-40.865356,-39.994354,-39.072140,-38.098693,-37.074052,-35.998273,-34.871465,-33.693771,-32.465276,-31.186438,-29.857314,}, // NOLINT + {-30.228907,-31.557223,-32.835178,-34.062607,-35.239239,-36.364856,-37.439539,-38.462988,-39.435215,-40.356211,-41.225991,-42.044541,-42.811953,-43.528247,-44.193590,-44.807977,-45.371559,-45.884410,-46.346637,-46.758355,-47.119645,-47.430625,-47.691366,-47.901951,-48.062460,-48.172935,-48.233445,-48.244022,-48.204692,-48.115471,-47.976358,-47.787347,-47.548400,-47.259526,-46.920651,-46.531728,-46.092733,-45.603574,-45.064205,-44.474567,-43.834590,-43.144224,-42.403426,-41.612177,-40.770392,-39.878112,-38.935370,-37.942163,-36.898573,-35.804683,-34.660636,-33.466610,-32.222768,-30.929452,-29.586907,}, // NOLINT + {-29.719475,-31.053415,-32.338351,-33.573956,-34.759993,-35.896264,-36.982620,-38.018932,-39.005089,-39.941147,-40.826959,-41.662583,-42.448020,-43.183312,-43.868495,-44.503627,-45.088787,-45.624024,-46.109413,-46.545016,-46.930913,-47.267137,-47.553781,-47.790848,-47.978390,-48.116428,-48.204974,-48.244027,-48.233574,-48.173587,-48.064035,-47.904847,-47.695979,-47.437351,-47.128878,-46.770468,-46.362023,-45.903438,-45.394630,-44.835406,-44.225751,-43.565513,-42.854615,-42.092959,-41.280477,-40.417116,-39.502776,-38.537554,-37.521373,-36.454284,-35.336372,-34.167776,-32.948603,-31.679089,-30.359443,}, // NOLINT + {-30.730788,-32.049580,-33.318189,-34.536371,-35.703910,-36.820724,-37.886654,-38.901650,-39.865675,-40.778789,-41.640938,-42.452242,-43.212722,-43.922450,-44.581600,-45.190205,-45.748371,-46.256305,-46.714032,-47.121695,-47.479406,-47.787268,-48.045377,-48.253827,-48.412693,-48.522026,-48.581895,-48.592337,-48.553375,-48.465021,-48.327284,-48.140140,-47.903570,-47.617523,-47.281973,-46.896844,-46.462081,-45.977603,-45.443353,-44.859252,-44.225213,-43.541162,-42.807058,-42.022823,-41.188412,-40.303808,-39.369014,-38.383998,-37.348852,-36.263621,-35.128416,-33.943385,-32.708795,-31.424616,-30.091405,}, // NOLINT + {-30.222218,-31.546924,-32.822696,-34.049273,-35.226393,-36.353927,-37.431729,-38.459701,-39.437769,-40.365921,-41.244178,-42.072533,-42.851019,-43.579698,-44.258637,-44.887907,-45.467589,-45.997768,-46.478524,-46.909930,-47.292084,-47.625038,-47.908849,-48.143585,-48.329286,-48.465965,-48.553653,-48.592342,-48.582023,-48.522669,-48.414246,-48.256682,-48.049928,-47.793897,-47.488500,-47.133635,-46.729193,-46.275046,-45.771113,-45.217233,-44.613296,-43.959183,-43.254778,-42.499968,-41.694685,-40.838825,-39.932331,-38.975168,-37.967340,-36.908839,-35.799724,-34.640086,-33.430056,-32.169808,-30.859559,}, // NOLINT + {-31.230654,-32.540049,-33.799410,-35.008455,-36.167058,-37.275076,-38.332440,-39.339109,-40.295078,-41.200371,-42.055037,-42.859149,-43.612780,-44.316044,-44.969074,-45.571969,-46.124850,-46.627872,-47.081168,-47.484834,-47.839008,-48.143800,-48.399319,-48.605656,-48.762902,-48.871107,-48.930345,-48.940651,-48.902052,-48.814561,-48.678173,-48.492868,-48.258623,-47.975393,-47.643111,-47.261721,-46.831148,-46.351299,-45.822095,-45.243473,-44.615262,-43.937453,-43.209939,-42.432615,-41.605471,-40.728447,-39.801480,-38.824582,-37.797773,-36.721089,-35.594586,-34.418485,-33.192835,-31.917888,-30.593895,}, // NOLINT + {-30.722971,-32.038583,-33.305317,-34.522951,-35.691288,-36.810175,-37.879528,-38.899277,-39.869315,-40.789724,-41.660486,-42.481663,-43.253290,-43.975446,-44.648218,-45.271736,-45.845979,-46.371167,-46.847348,-47.274624,-47.653078,-47.982793,-48.263836,-48.496277,-48.680151,-48.815491,-48.902326,-48.940657,-48.930470,-48.871741,-48.764434,-48.608472,-48.403802,-48.150337,-47.847975,-47.496607,-47.096117,-46.646374,-46.147260,-45.598622,-45.000333,-44.352253,-43.654269,-42.906219,-42.108016,-41.259541,-40.360805,-39.411622,-38.412023,-37.361996,-36.261554,-35.110798,-33.909774,-32.658689,-31.357693,}, // NOLINT + {-31.728543,-33.028701,-34.278926,-35.478969,-36.628714,-37.728070,-38.776974,-39.775417,-40.723408,-41.621003,-42.468265,-43.265286,-44.012178,-44.709046,-45.356045,-45.953304,-46.500961,-46.999162,-47.448060,-47.847770,-48.198465,-48.500225,-48.753187,-48.957442,-49.113087,-49.220179,-49.278792,-49.288965,-49.250724,-49.164080,-49.029030,-48.845542,-48.613591,-48.333126,-48.004076,-47.626371,-47.199924,-46.724642,-46.200456,-45.627164,-45.004762,-44.333105,-43.612099,-42.841649,-42.021647,-41.152107,-40.232878,-39.263980,-38.245400,-37.177160,-36.059328,-34.891962,-33.675246,-32.409338,-31.094468,}, // NOLINT + {-31.221881,-32.528472,-33.786283,-34.995071,-36.154737,-37.265089,-38.326080,-39.337653,-40.299814,-41.212554,-42.075940,-42.890013,-43.654863,-44.370578,-45.037268,-45.655030,-46.223950,-46.744246,-47.215908,-47.639096,-48.013906,-48.340426,-48.618731,-48.848892,-49.030974,-49.164996,-49.250993,-49.288970,-49.278916,-49.220805,-49.114599,-48.960221,-48.757613,-48.506677,-48.207311,-47.859399,-47.462807,-47.017411,-46.523054,-45.979595,-45.386877,-44.744767,-44.053092,-43.311728,-42.520547,-41.679423,-40.788247,-39.846967,-38.855504,-37.813836,-36.721966,-35.579941,-34.387833,-33.145786,-31.853969,}, // NOLINT + {-32.224580,-33.515662,-34.756836,-35.947960,-37.088976,-38.179774,-39.220321,-40.210649,-41.150740,-42.040747,-42.880694,-43.670716,-44.410936,-45.101496,-45.742539,-46.334217,-46.876717,-47.370154,-47.814728,-48.210555,-48.557798,-48.856559,-49.106988,-49.309197,-49.463252,-49.569242,-49.627239,-49.637278,-49.599390,-49.513581,-49.379841,-49.198155,-48.968474,-48.690736,-48.364869,-47.990812,-47.568445,-47.097657,-46.578370,-46.010435,-45.393744,-44.728144,-44.013589,-43.249903,-42.436988,-41.574815,-40.663247,-39.702255,-38.691817,-37.631918,-36.522601,-35.363943,-34.156051,-32.899066,-31.593213,}, // NOLINT + {-31.719044,-33.016720,-34.265667,-35.465743,-36.616792,-37.718715,-38.771449,-39.775000,-40.729261,-41.634493,-42.490567,-43.297614,-44.055800,-44.765141,-45.425816,-46.037929,-46.601605,-47.116987,-47.584213,-48.003367,-48.374575,-48.697937,-48.973540,-49.201462,-49.381772,-49.514488,-49.599655,-49.637283,-49.627361,-49.569861,-49.464744,-49.311925,-49.111356,-48.862923,-48.566518,-48.222022,-47.829284,-47.388170,-46.898523,-46.360178,-45.772973,-45.136741,-44.451323,-43.716554,-42.932294,-42.098407,-41.214762,-40.281262,-39.297838,-38.264435,-37.181028,-36.047648,-34.864350,-33.631198,-32.348454,}, // NOLINT + {-32.718976,-34.000933,-35.233209,-36.415569,-37.547919,-38.630255,-39.662566,-40.644832,-41.577170,-42.459644,-43.292370,-44.075474,-44.809105,-45.493420,-46.128585,-46.714772,-47.252153,-47.740901,-48.181180,-48.573151,-48.916983,-49.212797,-49.460728,-49.660893,-49.813396,-49.918299,-49.975684,-49.985593,-49.948051,-49.863067,-49.730632,-49.550714,-49.323275,-49.048232,-48.725525,-48.355056,-47.936718,-47.470405,-46.955960,-46.393284,-45.782230,-45.122660,-44.414442,-43.657442,-42.851553,-41.996649,-41.092647,-40.139470,-39.137096,-38.085428,-36.984540,-35.834464,-34.635303,-33.387151,-32.090219,}, // NOLINT + {-32.214522,-33.503350,-34.743571,-35.935021,-37.077563,-38.171143,-39.215713,-40.211244,-41.157861,-42.055555,-42.904431,-43.704572,-44.456108,-45.159172,-45.813877,-46.420426,-46.978910,-47.489474,-47.952280,-48.367447,-48.735096,-49.055338,-49.328262,-49.553976,-49.732519,-49.863957,-49.948312,-49.985597,-49.975805,-49.918909,-49.814870,-49.663605,-49.465042,-49.219084,-48.925604,-48.584476,-48.195552,-47.758676,-47.273679,-46.740358,-46.158631,-45.528219,-44.848978,-44.120731,-43.343297,-42.516573,-41.640369,-40.714543,-39.739090,-38.713849,-37.638816,-36.513942,-35.339378,-34.115101,-32.841265,}, // NOLINT + {-33.211676,-34.484724,-35.708098,-36.881789,-38.005606,-39.079582,-40.103719,-41.078034,-42.002739,-42.877751,-43.703333,-44.479600,-45.206717,-45.884849,-46.514214,-47.094959,-47.627288,-48.111386,-48.547437,-48.935606,-49.276057,-49.568950,-49.814411,-50.012565,-50.163521,-50.267347,-50.324128,-50.333905,-50.296706,-50.212533,-50.081378,-49.903210,-49.677987,-49.405618,-49.086028,-48.719114,-48.304758,-47.842838,-47.333210,-46.775734,-46.170258,-45.516633,-44.814702,-44.064324,-43.265342,-42.417672,-41.521132,-40.575683,-39.581242,-38.537753,-37.445216,-36.303627,-35.113085,-33.873696,-32.585593,}, // NOLINT + {-32.708405,-33.988499,-35.220066,-36.402953,-37.537109,-38.622426,-39.658966,-40.646610,-41.585561,-42.475843,-43.317569,-44.110855,-44.855843,-45.552685,-46.201540,-46.802537,-47.355869,-47.861687,-48.320126,-48.731333,-49.095475,-49.412636,-49.682923,-49.906441,-50.083264,-50.213415,-50.296964,-50.333910,-50.324248,-50.267951,-50.164977,-50.015242,-49.818668,-49.575156,-49.284569,-48.946783,-48.561627,-48.128943,-47.648557,-47.120257,-46.543885,-45.919228,-45.246092,-44.524307,-43.753605,-42.933988,-42.065123,-41.146945,-40.179316,-39.162158,-38.095401,-36.979021,-35.813028,-34.597493,-33.332491,}, // NOLINT + {-33.702818,-34.967029,-36.181704,-37.346750,-38.462131,-39.527824,-40.543890,-41.510380,-42.427408,-43.295162,-44.113626,-44.883130,-45.603803,-46.275841,-46.899428,-47.474806,-48.002123,-48.481647,-48.913502,-49.297905,-49.635023,-49.925025,-50.168037,-50.364203,-50.513628,-50.616389,-50.672571,-50.682219,-50.645357,-50.561990,-50.432122,-50.255677,-50.032635,-49.762903,-49.446394,-49.082992,-48.672581,-48.215023,-47.710142,-47.157805,-46.557852,-45.910098,-45.214386,-44.470539,-43.678424,-42.837869,-41.948733,-41.010967,-40.024377,-38.988965,-37.904675,-36.771501,-35.589516,-34.358760,-33.079385,}, // NOLINT + {-33.200786,-34.472233,-35.695236,-36.869674,-37.995491,-39.072635,-40.101146,-41.081038,-42.012408,-42.895358,-43.730024,-44.516531,-45.255040,-45.945720,-46.588749,-47.184289,-47.732548,-48.233629,-48.687763,-49.095082,-49.455726,-49.769833,-50.037507,-50.258858,-50.433965,-50.562861,-50.645611,-50.682223,-50.672690,-50.616986,-50.515068,-50.366846,-50.172247,-49.931154,-49.643440,-49.308948,-48.927523,-48.498975,-48.023177,-47.499791,-46.928758,-46.309799,-45.642713,-44.927295,-44.163361,-43.350659,-42.489085,-41.578444,-40.618585,-39.609422,-38.550862,-37.442829,-36.285355,-35.078454,-33.822210,}, // NOLINT + {-34.192463,-35.447939,-36.653980,-37.810524,-38.917534,-39.975019,-40.983120,-41.941814,-42.851340,-43.711767,-44.523273,-45.286101,-46.000423,-46.666391,-47.284306,-47.854341,-48.376727,-48.851674,-49.279390,-49.660066,-49.993885,-50.281018,-50.521614,-50.715808,-50.863719,-50.965425,-51.021014,-51.030531,-50.994003,-50.911435,-50.782819,-50.608089,-50.387217,-50.120094,-49.806631,-49.446709,-49.040202,-48.586941,-48.086776,-47.539517,-46.945039,-46.303101,-45.613544,-44.876169,-44.090838,-43.257346,-42.375554,-41.445325,-40.466549,-39.439123,-38.363012,-37.238174,-36.064620,-34.842447,-33.571729,}, // NOLINT + {-33.691749,-34.954626,-36.169148,-37.335235,-38.452785,-39.521846,-40.542429,-41.514606,-42.438490,-43.314177,-44.141817,-44.921629,-45.653727,-46.338316,-46.975569,-47.565703,-48.108890,-48.605336,-49.055201,-49.458683,-49.815851,-50.126936,-50.392027,-50.611232,-50.784640,-50.912292,-50.994254,-51.030535,-51.021131,-50.966015,-50.865142,-50.718421,-50.525767,-50.287080,-50.002200,-49.670982,-49.293250,-48.868814,-48.397483,-47.879041,-47.313307,-46.699960,-46.038857,-45.329755,-44.572435,-43.766675,-42.912302,-42.009089,-41.056960,-40.055713,-39.005241,-37.905493,-36.756441,-35.558096,-34.310510,}, // NOLINT + {-34.680761,-35.927575,-37.125045,-38.273157,-39.371898,-40.421338,-41.421470,-42.372501,-43.274543,-44.127751,-44.932374,-45.688548,-46.396537,-47.056538,-47.668797,-48.233573,-48.751063,-49.221502,-49.645114,-50.022098,-50.352647,-50.636944,-50.875143,-51.067385,-51.213795,-51.314455,-51.369455,-51.378843,-51.342645,-51.260866,-51.133491,-50.960458,-50.741723,-50.477188,-50.166748,-49.810274,-49.407623,-48.958631,-48.463126,-47.920933,-47.331843,-46.695667,-46.012203,-45.281254,-44.502627,-43.676133,-42.801595,-41.878868,-40.907800,-39.888301,-38.820281,-37.703686,-36.538520,-35.324833,-34.062666,}, // NOLINT + {-34.181352,-35.435739,-36.641859,-37.799674,-38.909055,-39.970098,-40.982837,-41.947352,-42.863820,-43.732323,-44.553053,-45.326190,-46.051928,-46.730469,-47.362025,-47.946798,-48.485002,-48.976815,-49.422448,-49.822076,-50.175857,-50.483953,-50.746483,-50.963564,-51.135291,-51.261712,-51.342892,-51.378847,-51.369572,-51.315039,-51.215203,-51.069970,-50.879257,-50.642937,-50.360891,-50.032891,-49.658818,-49.238447,-48.771591,-48.258012,-47.697443,-47.089722,-46.434554,-45.731709,-44.980945,-44.182053,-43.334820,-42.439022,-41.494483,-40.501065,-39.458621,-38.367066,-37.226367,-36.036481,-34.797465,}, // NOLINT + {-35.167729,-36.405946,-37.595031,-38.734740,-39.825288,-40.866664,-41.859000,-42.802416,-43.697061,-44.543147,-45.340893,-46.090505,-46.792230,-47.446310,-48.052995,-48.612555,-49.125169,-49.591150,-50.010685,-50.384010,-50.711321,-50.992803,-51.228626,-51.418934,-51.563857,-51.663480,-51.717896,-51.727155,-51.691283,-51.610283,-51.484140,-51.312787,-51.096173,-50.834200,-50.526755,-50.173691,-49.774862,-49.330102,-48.839218,-48.302015,-47.718287,-47.087819,-46.410398,-45.685806,-44.913827,-44.094264,-43.226920,-42.311634,-41.348202,-40.336544,-39.276544,-38.168132,-37.011254,-35.805959,-34.552290,}, // NOLINT + {-34.669720,-35.915703,-37.113557,-38.263063,-39.364362,-40.417458,-41.422424,-42.379380,-43.288464,-44.149844,-44.963712,-45.730242,-46.449683,-47.122239,-47.748137,-48.327597,-48.860834,-49.348072,-49.789527,-50.185361,-50.535758,-50.840889,-51.100881,-51.315856,-51.485919,-51.611119,-51.691527,-51.727158,-51.718011,-51.664058,-51.565251,-51.421492,-51.232694,-50.998735,-50.719454,-50.394686,-50.024240,-49.607902,-49.145465,-48.636699,-48.081330,-47.479134,-46.829829,-46.133198,-45.388971,-44.596849,-43.756682,-42.868200,-41.931216,-40.945551,-39.911067,-38.827629,-37.695190,-36.513696,-35.283173,}, // NOLINT + {-35.653459,-36.883207,-38.063865,-39.195328,-40.277753,-41.311186,-42.295751,-43.231609,-44.118939,-44.957968,-45.748906,-46.492007,-47.187519,-47.835730,-48.436879,-48.991234,-49.499062,-49.960605,-50.376112,-50.745810,-51.069909,-51.348601,-51.582069,-51.770459,-51.913907,-52.012499,-52.066337,-52.075466,-52.039916,-51.959688,-51.834766,-51.665075,-51.450568,-51.191132,-50.886634,-50.536971,-50.141938,-49.701363,-49.215047,-48.682811,-48.104395,-47.479586,-46.808145,-46.089860,-45.324493,-44.511770,-43.651573,-42.743645,-41.787810,-40.783926,-39.731874,-38.631552,-37.482910,-36.285947,-35.040688,}, // NOLINT + {-35.156903,-36.394548,-37.584030,-38.725489,-39.818769,-40.863987,-41.861247,-42.810709,-43.712471,-44.566768,-45.373819,-46.133830,-46.847021,-47.513639,-48.133923,-48.708117,-49.236448,-49.719149,-50.156442,-50.548515,-50.895561,-51.197748,-51.455224,-51.668110,-51.836525,-51.960516,-52.040158,-52.075470,-52.066451,-52.013071,-51.915279,-51.772988,-51.586101,-51.354473,-51.077954,-50.756372,-50.389524,-49.977195,-49.519149,-49.015133,-48.464918,-47.868218,-47.224741,-46.534248,-45.796456,-45.011101,-44.177936,-43.296710,-42.367207,-41.389250,-40.362655,-39.287249,-38.162992,-36.989823,-35.767705,}, // NOLINT +}, // NOLINT +{ + {31.715736,32.118091,32.369887,32.471214,32.422725,32.225649,31.881803,31.393539,30.763777,29.995974,29.094169,28.062825,26.906972,25.632085,24.244118,22.749446,21.154859,19.467547,17.694989,15.845087,13.925978,11.946061,9.914070,7.838906,5.729213,3.594544,1.444020,-0.713055,-2.867338,-5.009508,-7.130281,-9.220486,-11.271001,-13.272916,-15.217429,-17.096116,-18.900657,-20.623045,-22.255585,-23.790938,-25.222243,-26.542840,-27.746593,-28.827834,-29.781338,-30.602363,-31.286690,-31.830620,-32.230982,-32.485168,-32.591125,-32.547368,-32.352989,-32.007654,-31.511606,}, // NOLINT + {31.553689,32.037395,32.371203,32.554898,32.588843,32.473970,32.211786,31.804349,31.254279,30.564740,29.739424,28.782548,27.698814,26.493457,25.172082,23.740784,22.206284,20.575293,18.855106,17.053422,15.178149,13.237522,11.239965,9.194208,7.109015,4.993727,2.856915,0.708233,-1.443207,-3.588140,-5.717304,-7.821583,-9.891808,-11.919069,-13.894628,-15.809819,-17.656249,-19.426056,-21.111158,-22.704208,-24.198072,-25.585995,-26.861628,-28.019097,-29.052892,-29.958059,-30.730098,-31.365025,-31.859381,-32.210248,-32.415234,-32.472547,-32.380927,-32.139695,-31.748737,}, // NOLINT + {32.050386,32.430799,32.661297,32.742018,32.673672,32.457536,32.095446,31.589801,30.943552,30.160161,29.243638,28.198487,27.029686,25.742729,24.343495,22.838426,21.234140,19.537868,17.756970,15.899474,13.973229,11.986648,9.948412,7.867143,5.751948,3.611780,1.455861,-0.706479,-2.866169,-5.013846,-7.140421,-9.236677,-11.293583,-13.302413,-15.254350,-17.141000,-18.954098,-20.685827,-22.328445,-23.874702,-25.317673,-26.650834,-27.868065,-28.963690,-29.932500,-30.769779,-31.471277,-32.033286,-32.452631,-32.726648,-32.853269,-32.830954,-32.658744,-32.336234,-31.863609,}, // NOLINT + {31.902178,32.363111,32.674698,32.836796,32.849823,32.714773,32.433189,32.007171,31.439369,30.732973,29.891678,28.919738,27.821779,26.603097,25.269233,23.826358,22.280989,20.639799,18.910291,17.099908,15.216577,13.268359,11.263720,9.211443,7.120090,4.998636,2.856214,0.701884,-1.455135,-3.605642,-5.740506,-7.850621,-9.926964,-11.960630,-13.943021,-15.865498,-17.719796,-19.497891,-21.192088,-22.794780,-24.299055,-25.698192,-26.985804,-28.156079,-29.203514,-30.123179,-30.910567,-31.561689,-32.073081,-32.441788,-32.665417,-32.742114,-32.670585,-32.450093,-32.080476,}, // NOLINT + {32.379524,32.739033,32.949193,33.010197,32.922812,32.688357,32.308708,31.786277,31.124063,30.325521,29.394656,28.335976,27.154500,25.855638,24.445281,22.929801,21.315855,19.610542,17.821271,15.955854,14.022273,12.028846,9.984012,7.896563,5.775393,3.629449,1.467830,-0.700273,-2.865703,-5.019303,-7.151908,-9.254526,-11.318146,-13.334119,-15.293542,-17.188388,-19.010202,-20.751337,-22.403999,-23.961065,-25.415626,-26.761176,-27.991624,-29.101303,-30.085048,-30.938089,-31.656214,-32.235687,-32.673307,-32.966402,-33.112846,-33.111063,-32.960032,-32.659316,-32.209004,}, // NOLINT + {32.244410,32.683633,32.973978,33.115408,33.108387,32.953955,32.653701,32.209769,31.624826,30.902079,30.045250,29.058583,27.946727,26.714921,25.368785,23.914367,22.358140,20.706943,18.967969,17.148828,15.257220,13.301345,11.289502,9.230269,7.132364,5.004661,2.856157,0.695909,-1.466958,-3.623444,-5.764318,-7.880614,-9.963337,-12.003742,-13.993114,-15.923102,-17.785382,-19.571953,-21.275185,-22.887632,-24.402301,-25.812524,-27.111979,-28.294829,-29.355635,-30.289435,-31.091751,-31.758575,-32.286430,-32.672349,-32.913903,-33.009206,-32.956921,-32.756262,-32.407001,}, // NOLINT + {32.703689,33.043244,33.233939,33.276036,33.170356,32.918266,32.521662,31.982994,31.305291,30.492000,29.547151,28.475247,27.281267,25.970650,24.549269,23.023405,21.399729,19.685345,17.887513,16.014102,14.072960,12.072366,10.020810,7.926885,5.799404,3.647409,1.479719,-0.694316,-2.865915,-5.025740,-7.164685,-9.273896,-11.344497,-13.367699,-15.335042,-17.238124,-19.068792,-20.819279,-22.482060,-24.049881,-25.515924,-26.873701,-28.117136,-29.240589,-30.238885,-31.107273,-31.841531,-32.437909,-32.893177,-33.204643,-33.370146,-33.388063,-33.257333,-32.977441,-32.548430,}, // NOLINT + {32.580979,32.999430,33.269470,33.391079,33.364799,33.191716,32.873463,32.412209,31.810659,31.072038,30.200079,29.199014,28.073554,26.828871,25.470584,24.004739,22.437750,20.776443,19.027998,17.199957,15.299974,13.336211,11.316872,9.250558,7.145849,5.011616,2.856737,0.690294,-1.478888,-3.641538,-5.788719,-7.911443,-10.000837,-12.048182,-14.044819,-15.982516,-17.852844,-19.648051,-21.360426,-22.982626,-24.507656,-25.928877,-27.240024,-28.435263,-29.509167,-30.456787,-31.273635,-31.955731,-32.499512,-32.902057,-33.160889,-33.274087,-33.240273,-33.058613,-32.728819,}, // NOLINT + {33.023383,33.343815,33.515844,33.539785,33.416495,33.147383,32.734403,32.180005,31.487220,30.659553,29.701025,28.616132,27.409857,26.087617,24.655266,23.119074,21.485659,19.762087,17.955678,16.074073,14.125202,12.117306,10.058670,7.958018,5.824000,3.665575,1.491569,-0.688846,-2.866718,-5.032959,-7.178610,-9.294697,-11.372476,-13.403213,-15.378509,-17.289987,-19.129595,-20.889569,-22.562439,-24.140988,-25.618387,-26.988226,-28.244479,-29.381455,-30.393958,-31.277348,-32.027250,-32.640011,-33.112354,-33.441556,-33.625413,-33.662272,-33.551019,-33.291080,-32.882434,}, // NOLINT + {32.912418,33.310987,33.561540,33.664108,33.619290,33.428226,33.092577,32.614547,31.996888,31.242814,30.356110,29.340978,28.202142,26.944781,25.574478,24.097281,22.519585,20.848198,19.090222,17.253106,15.344670,13.372807,11.345823,9.272206,7.160471,5.019410,2.857912,0.684891,-1.490727,-3.659864,-5.813619,-7.943060,-10.039381,-12.093884,-14.098038,-16.043498,-17.922123,-19.726018,-21.447623,-23.079590,-24.614964,-26.047103,-27.369817,-28.577253,-29.664023,-30.625170,-31.456201,-32.153110,-32.712386,-33.131026,-33.406550,-33.536990,-33.520940,-33.357515,-33.046381,}, // NOLINT + {33.339008,33.641102,33.795196,33.801655,33.661380,33.375820,32.946950,32.377278,31.669827,30.828098,29.856197,28.758562,27.540145,26.206404,24.763177,23.216653,21.573455,19.840694,18.025536,16.135628,14.178867,12.163399,10.097558,7.989887,5.849079,3.683950,1.503395,-0.683599,-2.868091,-5.041062,-7.193588,-9.316920,-11.401943,-13.440504,-15.423845,-17.343872,-19.192508,-20.962055,-22.644984,-24.234216,-25.722921,-27.104728,-28.373543,-29.523770,-30.550224,-31.448178,-32.213378,-32.842037,-33.330944,-33.677291,-33.878866,-33.933971,-33.841445,-33.600668,-33.211564,}, // NOLINT + {33.239188,33.618682,33.850506,33.934754,33.872068,33.663624,33.311144,32.816857,32.183522,31.414379,30.513283,29.484352,28.332383,27.062513,25.680332,24.191863,22.603475,20.921992,19.154424,17.308264,15.391163,13.411132,11.376287,9.295212,7.176129,5.028018,2.859611,0.679786,-1.502543,-3.678474,-5.839030,-7.975420,-10.078977,-12.140765,-14.152607,-16.105966,-17.993029,-19.805773,-21.536658,-23.178381,-24.724037,-26.167081,-27.501238,-28.720715,-29.820124,-30.794530,-31.639415,-32.350787,-32.925108,-33.359353,-33.651019,-33.798114,-33.799180,-33.653293,-33.360074,}, // NOLINT + {33.650933,33.935405,34.072238,34.061836,33.905149,33.603660,33.159381,32.574841,31.853085,30.997639,30.012590,28.902391,27.672023,26.326889,24.872809,23.316015,21.663086,19.920988,18.096986,16.198693,14.233900,12.210655,10.137499,8.022491,5.874655,3.702580,1.515201,-0.678642,-2.869994,-5.049956,-7.209592,-9.340173,-11.432905,-13.479321,-15.470947,-17.399649,-19.257369,-21.036481,-22.729540,-24.329433,-25.829360,-27.222983,-28.504220,-29.667485,-30.707601,-31.619839,-32.399923,-33.044085,-33.549034,-33.911989,-34.130693,-34.203404,-34.128916,-33.906562,-33.536206,}, // NOLINT + {33.561680,33.922863,34.136667,34.203246,34.123300,33.898049,33.529243,33.019159,32.370560,31.586746,30.671506,29.629073,28.464170,27.181958,25.788052,24.288353,22.689317,20.997677,19.220427,17.365170,15.439323,13.450931,11.408081,9.319190,7.192715,5.037326,2.861833,0.674965,-1.514341,-3.697246,-5.864877,-8.008456,-10.119261,-12.188715,-14.208384,-16.169985,-18.065503,-19.887136,-21.627340,-23.278880,-24.834859,-26.288678,-27.634180,-28.865549,-29.977412,-30.964834,-31.823266,-32.548748,-33.137714,-33.587120,-33.894442,-34.057634,-34.075224,-33.946232,-33.670223,}, // NOLINT + {33.959459,34.226995,34.347184,34.320494,34.147917,33.830982,33.371722,32.772697,32.036989,31.168104,30.170130,29.047568,27.805381,26.448953,24.984098,23.417026,21.754305,20.002857,18.169931,16.263063,14.290054,12.258964,10.178030,8.055733,5.900632,3.721446,1.526977,-0.673928,-2.872409,-5.059532,-7.226521,-9.364627,-11.465156,-13.519629,-15.519664,-17.457109,-19.324133,-21.112801,-22.815946,-24.426486,-25.937624,-27.342906,-28.636414,-29.812516,-30.866045,-31.792254,-32.586883,-33.246133,-33.766697,-34.145770,-34.381059,-34.470787,-34.413705,-34.209095,-33.856766,}, // NOLINT + {33.880290,34.223839,34.420263,34.469787,34.373145,34.131596,33.746940,33.221474,32.558007,31.759838,30.830766,29.775052,28.597389,27.303008,25.897401,24.386619,22.776995,21.075196,19.288335,17.423735,15.488947,13.492162,11.441026,9.344393,7.210229,5.047396,2.864503,0.670417,-1.526109,-3.716232,-5.891183,-8.042108,-10.160473,-12.237674,-14.265337,-16.235243,-18.139387,-19.970005,-21.719598,-23.380953,-24.947195,-26.411793,-27.768552,-29.011665,-30.135778,-31.135976,-32.007723,-32.746996,-33.350244,-33.814400,-34.136905,-34.315706,-34.349269,-34.236582,-33.977165,}, // NOLINT + {34.264919,34.516108,34.620223,34.577778,34.389795,34.057851,33.584006,32.970847,32.221456,31.339406,30.328750,29.194001,27.940118,26.572490,25.096917,23.519578,21.847041,20.086193,18.244251,16.328679,14.347384,12.308241,10.219501,8.089589,5.927056,3.740494,1.538725,-0.669533,-2.875226,-5.069862,-7.244357,-9.390156,-11.498643,-13.561329,-15.569889,-17.516220,-19.392392,-21.190859,-22.904193,-24.525282,-26.047483,-27.464395,-28.770028,-29.958781,-31.025485,-31.965393,-32.774253,-33.448228,-33.983996,-34.378731,-34.630105,-34.736307,-34.696048,-34.508557,-34.173596,}, // NOLINT + {34.195331,34.521884,34.701533,34.734553,34.621730,34.364372,33.964299,33.423848,32.745849,31.933615,30.990997,29.922223,28.732025,27.425561,26.008412,24.486542,22.866276,21.154365,19.357737,17.483874,15.540234,13.534727,11.475412,9.370534,7.228600,5.058066,2.867648,0.666070,-1.537851,-3.735464,-5.917880,-8.076341,-10.202450,-12.287574,-14.323388,-16.301695,-18.214590,-20.054279,-21.813316,-23.484527,-25.061044,-26.536314,-27.904223,-29.158980,-30.295208,-31.307964,-32.192754,-32.945530,-33.562719,-34.041250,-34.378524,-34.572463,-34.621498,-34.524574,-34.281161,}, // NOLINT + {34.567548,34.802957,34.891524,34.833802,34.630871,34.284321,33.796257,33.169285,32.406514,31.511525,30.488382,29.341606,28.076189,26.697406,25.211151,23.623576,21.941156,20.170891,18.319858,16.395567,14.405770,12.358425,10.261705,8.124005,5.953808,3.759712,1.550451,-0.665255,-2.878541,-5.080621,-7.262959,-9.416672,-11.533270,-13.604325,-15.621521,-17.576839,-19.462391,-21.270546,-22.993986,-24.625682,-26.158918,-27.587350,-28.904974,-30.106209,-31.185880,-32.139269,-32.962031,-33.650390,-34.200986,-34.610957,-34.877965,-35.000136,-34.976157,-34.805211,-34.486991,}, // NOLINT + {34.507113,34.817243,34.980668,34.997703,34.869183,34.596447,34.181365,33.626292,32.934087,32.108110,31.152146,30.070509,28.867917,27.549525,26.120889,24.588018,22.957197,21.234994,19.428748,17.545457,15.592731,13.578536,11.510749,9.397628,7.247699,5.069273,2.871201,0.662031,-1.549558,-3.754742,-5.944811,-8.111127,-10.245134,-12.338344,-14.382498,-16.369319,-18.291021,-20.139913,-21.908373,-23.589456,-25.176225,-26.662164,-28.041187,-29.307424,-30.455594,-31.480736,-32.378336,-33.144344,-33.775174,-34.267722,-34.619377,-34.828026,-34.892064,-34.810400,-34.582455,}, // NOLINT + {34.867582,35.087738,35.161235,35.088694,34.871211,34.510441,34.008491,33.368012,32.592116,31.684416,30.648968,29.490304,28.213372,26.823607,25.326717,23.728896,22.036667,20.256872,18.396662,16.463449,14.465133,12.409459,10.304608,8.158959,5.980908,3.779099,1.562138,-0.661272,-2.882234,-5.092167,-7.282334,-9.444132,-11.568972,-13.648531,-15.674453,-17.638861,-19.533811,-21.351782,-23.085351,-24.727610,-26.271845,-27.711684,-29.041177,-30.254736,-31.347180,-32.313772,-33.150202,-33.852633,-34.417708,-34.842535,-35.124729,-35.262419,-35.254223,-35.099293,-34.797261,}, // NOLINT + {34.815877,35.110135,35.257845,35.259376,35.115599,34.827905,34.398181,33.828824,33.122715,32.283222,31.314159,30.219849,29.004998,27.674811,26.234803,24.690946,23.049552,21.317289,19.501150,17.608362,15.646593,13.623505,11.547105,9.425644,7.267555,5.081173,2.875149,0.657979,-1.561263,-3.774233,-5.972105,-8.146428,-10.288476,-12.389920,-14.442416,-16.438011,-18.368603,-20.226657,-22.004699,-23.695669,-25.292674,-26.789239,-28.179242,-29.456910,-30.616896,-31.654244,-32.564445,-33.343425,-33.987614,-34.493861,-34.859537,-35.082499,-35.161111,-35.094237,-34.881266,}, // NOLINT + {35.165228,35.370603,35.429487,35.342538,35.110905,34.736248,34.220734,33.567010,32.778239,31.858025,30.810402,29.640032,28.351751,26.951005,25.443496,23.835472,22.133349,20.344007,18.474577,16.532459,14.525432,12.461276,10.348143,8.194399,6.008401,3.798629,1.573813,-0.657269,-2.886302,-5.104181,-7.302424,-9.472406,-11.605664,-13.693799,-15.728703,-17.702220,-19.606635,-21.434374,-23.178136,-24.830946,-26.386111,-27.837302,-29.178557,-30.404291,-31.509330,-32.488923,-33.338756,-34.054979,-34.634200,-35.073521,-35.370532,-35.523289,-35.530412,-35.390990,-35.104632,}, // NOLINT + {35.121865,35.400753,35.533228,35.519696,35.361081,35.058797,34.614775,34.031438,33.311698,32.458934,31.476994,30.370185,29.143243,27.801338,26.350024,24.795231,23.143298,21.400848,19.574884,17.672586,15.701598,13.669483,11.584437,9.454566,7.288103,5.093534,2.879437,0.654315,-1.572924,-3.793808,-5.999761,-8.182110,-10.332440,-12.442224,-14.503289,-16.507604,-18.447248,-20.314583,-22.102293,-23.803082,-25.410327,-26.917468,-28.318395,-29.607397,-30.779056,-31.828445,-32.750981,-33.542817,-34.200047,-34.719700,-35.099064,-35.335978,-35.428760,-35.376253,-35.177788,}, // NOLINT + {35.460670,35.651708,35.696400,35.595433,35.349994,34.961784,34.432982,33.766286,32.964862,32.032311,30.972765,29.790724,28.491185,27.079527,25.561463,23.943210,22.231171,20.432267,18.553475,16.602473,14.586579,12.513789,10.392281,8.230233,6.036091,3.818286,1.585455,-0.653722,-2.890704,-5.116604,-7.323172,-9.501534,-11.643286,-13.740164,-15.784025,-17.766797,-19.680749,-21.518326,-23.272301,-24.935614,-26.501677,-27.964162,-29.317057,-30.554821,-31.672289,-32.664673,-33.527686,-34.257426,-34.850501,-35.303978,-35.615416,-35.782864,-35.804876,-35.680506,-35.409325,}, // NOLINT + {35.425290,35.689281,35.806955,35.778772,35.605688,35.289181,34.831186,34.234164,33.501047,32.635237,31.640601,30.521453,29.282539,27.929019,26.466431,24.900787,23.238320,21.485678,19.649785,17.738017,15.757637,13.716586,11.622689,9.484148,7.309238,5.106374,2.884012,0.650871,-1.584553,-3.813609,-6.027723,-8.218331,-10.376947,-12.495230,-14.564967,-16.578151,-18.526916,-20.403575,-22.200846,-23.911614,-25.529074,-27.046778,-28.458604,-29.758791,-30.942042,-32.003306,-32.938126,-33.742404,-34.412506,-34.945275,-35.338017,-35.588538,-35.695125,-35.656579,-35.472195,}, // NOLINT + {35.754074,35.931197,35.962078,35.847449,35.588535,35.187063,34.645268,33.965815,33.151928,32.207245,31.135863,29.942358,28.631638,27.209094,25.680520,24.052037,22.330080,20.521544,18.633455,16.673098,14.648364,12.567000,10.436963,8.266489,6.064150,3.838049,1.597078,-0.650302,-2.895455,-5.129713,-7.344593,-9.531373,-11.681820,-13.787563,-15.840436,-17.832532,-19.756058,-21.603518,-23.367650,-25.041512,-26.618435,-28.092103,-29.456573,-30.706335,-31.836004,-32.841016,-33.716971,-34.459984,-35.066630,-35.533955,-35.859486,-36.041249,-36.077748,-35.968007,-35.711544,}, // NOLINT + {35.726339,35.975864,36.079154,36.036708,35.849529,35.519103,35.047429,34.436996,33.690740,32.812099,31.804940,30.673602,29.422853,28.057798,26.584056,25.007554,23.334543,21.571702,19.725935,17.804461,15.814725,13.764543,11.661772,9.514523,7.331007,5.119606,2.889023,0.647539,-1.596158,-3.833506,-6.055928,-8.254920,-10.422007,-12.548895,-14.627500,-16.649508,-18.607456,-20.493548,-22.300483,-24.021183,-25.648869,-27.177089,-28.599736,-29.911079,-31.105738,-32.178775,-33.125648,-33.942267,-34.624975,-35.170611,-35.576445,-35.840254,-35.960303,-35.935348,-35.764647,}, // NOLINT + {36.045592,36.209182,36.226616,36.098658,35.826575,35.412123,34.857553,34.165584,33.339421,32.382780,31.299706,30.094780,28.772966,27.339644,25.800577,24.161878,22.430026,20.611780,18.714268,16.744833,14.711149,12.620845,10.482130,8.303223,6.092344,3.857991,1.608670,-0.646976,-2.900520,-5.143191,-7.366508,-9.561942,-11.721157,-13.835789,-15.897920,-17.899351,-19.832510,-21.689863,-23.464200,-25.148570,-26.736276,-28.221134,-29.597073,-30.858580,-32.000442,-33.017901,-33.906599,-34.662654,-35.282612,-35.763496,-36.102808,-36.298533,-36.349151,-36.253641,-36.011476,}, // NOLINT + {36.025185,36.260657,36.349940,36.293585,36.092630,35.748608,35.263546,34.639937,33.880761,32.989478,31.969948,30.826613,29.564069,28.187604,26.702740,25.115419,23.431919,21.658849,19.803144,17.871995,15.872886,13.813495,11.701638,9.545538,7.353331,5.133306,2.894309,0.644471,-1.607739,-3.853501,-6.084361,-8.291822,-10.467547,-12.603165,-14.690630,-16.721732,-18.688881,-20.584443,-22.401074,-24.131723,-25.769625,-27.308339,-28.741729,-30.064159,-31.270160,-32.354810,-33.313591,-34.142369,-34.837479,-35.395732,-35.814391,-36.091197,-36.224387,-36.212674,-36.055284,}, // NOLINT + {36.335359,36.485778,36.490093,36.349128,36.064154,35.636981,35.069880,34.365595,33.527369,32.558879,31.464245,30.248013,28.915180,27.471111,25.921562,24.272659,22.530850,20.702919,18.795879,16.817246,14.774492,12.675278,10.527850,8.340260,6.120800,3.877982,1.620216,-0.643987,-2.905890,-5.157082,-7.389026,-9.593184,-11.761267,-13.884975,-15.956304,-17.967171,-19.910022,-21.777330,-23.561876,-25.256734,-26.855275,-28.351175,-29.738508,-31.011723,-32.165543,-33.195296,-34.096558,-34.865438,-35.498462,-35.992639,-36.345442,-36.554807,-36.619193,-36.537546,-36.309283,}, // NOLINT + {36.321989,36.543777,36.619415,36.549486,36.335068,35.977733,35.479521,34.842972,34.071093,33.167350,32.135660,30.980338,29.706189,28.318366,26.822443,25.224345,23.530317,21.747053,19.881373,17.940524,15.931823,13.863092,11.742247,9.577197,7.376221,5.147620,2.899841,0.641322,-1.619291,-3.873589,-6.112973,-8.329085,-10.513553,-12.657997,-14.754278,-16.794662,-18.771192,-20.676202,-22.502555,-24.243172,-25.891290,-27.440470,-28.884624,-30.218019,-31.435227,-32.531413,-33.501938,-34.342686,-35.050002,-35.620656,-36.051893,-36.341421,-36.487446,-36.488661,-36.344236,}, // NOLINT + {36.623498,36.761078,36.752595,36.598895,36.301307,35.861655,35.282240,34.565841,33.715712,32.735511,31.629419,30.401988,29.058204,27.603434,26.043434,24.384333,22.632559,20.794891,18.878407,16.890370,14.838340,12.730257,10.573963,8.377659,6.149543,3.898118,1.631745,-0.640972,-2.911505,-5.171341,-7.411933,-9.625041,-11.802086,-13.935012,-16.015521,-18.035950,-19.988533,-21.865910,-23.660635,-25.365913,-26.975211,-28.482148,-29.880780,-31.165582,-32.331270,-33.373175,-34.286820,-35.068346,-35.714212,-36.221419,-36.587419,-36.810134,-36.887972,-36.819834,-36.605111,}, // NOLINT + {36.616887,36.825347,36.887673,36.804481,36.576888,36.206497,35.695392,35.046120,34.261739,33.345704,32.301935,31.134811,29.849127,28.450033,26.943057,25.334253,23.629763,21.836248,19.960557,18.009915,15.991725,13.913687,11.783554,9.609425,7.399565,5.162193,2.905671,0.638482,-1.630796,-3.893728,-6.141877,-8.366727,-10.559981,-12.713355,-14.818780,-16.868282,-18.854123,-20.768754,-22.604885,-24.355479,-26.013759,-27.573421,-29.028252,-30.372555,-31.600960,-32.708514,-33.690625,-34.543220,-35.262523,-35.845401,-36.288975,-36.590974,-36.749564,-36.763398,-36.631620,}, // NOLINT + {36.910120,37.035174,37.014182,36.848024,36.538065,36.086154,35.494632,34.766287,33.904384,32.912641,31.795209,30.556660,29.201982,27.736566,26.166140,24.496827,22.735083,20.887634,18.961575,16.964167,14.903015,12.785747,10.620444,8.415326,6.178523,3.918265,1.643248,-0.638174,-2.917417,-5.185965,-7.435529,-9.657483,-11.843596,-13.985647,-16.075618,-18.105616,-20.067972,-21.955242,-23.760243,-25.476067,-27.096084,-28.614010,-30.023908,-31.320189,-32.497655,-33.551522,-34.477336,-35.271349,-35.929845,-36.449861,-36.828812,-37.064592,-37.155576,-37.100629,-36.899101,}, // NOLINT + {36.910011,37.105478,37.154797,37.058632,36.818129,36.434941,35.911169,35.249392,34.452662,33.524492,32.468816,31.290016,29.992864,28.582553,27.064642,25.445082,23.730188,21.926343,20.040648,18.080191,16.052392,13.964850,11.825503,9.642295,7.423397,5.177074,2.911725,0.635764,-1.642332,-3.914039,-6.171016,-8.404613,-10.606802,-12.769201,-14.883729,-16.942558,-18.937745,-20.862060,-22.707986,-24.468573,-26.137102,-27.707141,-29.172616,-30.527770,-31.767254,-32.886083,-33.879694,-34.743948,-35.475133,-36.069976,-36.525679,-36.839911,-37.010791,-37.036975,-36.917540,}, // NOLINT + {37.195327,37.308147,37.274918,37.096554,36.774457,36.310503,35.707052,34.966928,34.093412,33.090236,31.961562,30.711978,29.346472,27.870443,26.289605,24.610106,22.838390,20.981116,19.045401,17.038578,14.968082,12.841713,10.667429,8.453291,6.207564,3.938557,1.654736,-0.635460,-2.923539,-5.201048,-7.459505,-9.690476,-11.885735,-14.037038,-16.136500,-18.176130,-20.148294,-22.045592,-23.860802,-25.587117,-27.217833,-28.746705,-30.167771,-31.475449,-32.664568,-33.730305,-34.668251,-35.474463,-36.145399,-36.677996,-37.069657,-37.318237,-37.422082,-37.380020,-37.191368,}, // NOLINT + {37.201476,37.384257,37.420863,37.311996,37.058849,36.663084,36.126846,35.452760,34.643856,33.703697,32.636259,31.445865,30.137325,28.715872,27.187053,25.556797,23.831333,22.017325,20.121557,18.151292,16.113807,14.016764,11.868087,9.675653,7.447642,5.192241,2.918025,0.633172,-1.653781,-3.934369,-6.200183,-8.442837,-10.654031,-12.825508,-14.949310,-17.017410,-19.022139,-20.956064,-22.811816,-24.582414,-26.261142,-27.841582,-29.317642,-30.683609,-31.934087,-33.064104,-34.069085,-34.944872,-35.687737,-36.294398,-36.762025,-37.088263,-37.271209,-37.309465,-37.202094,}, // NOLINT + {37.479206,37.580067,37.534855,37.344526,37.010501,36.534700,35.919503,35.167691,34.282763,33.268272,32.128447,30.867898,29.491623,28.005007,26.413802,24.724116,22.942364,21.075330,19.129931,17.113660,15.033697,12.898137,10.714718,8.491541,6.236838,3.958930,1.666188,-0.632928,-2.930025,-5.216371,-7.483845,-9.723991,-11.928466,-14.089179,-16.198116,-18.247410,-20.229429,-22.136779,-23.962270,-25.699009,-27.340409,-28.880153,-30.312353,-31.631299,-32.832022,-33.909498,-34.859433,-35.677673,-36.360862,-36.905843,-37.309986,-37.571126,-37.687569,-37.658114,-37.482031,}, // NOLINT + {37.491389,37.661778,37.685940,37.564630,37.299065,36.890946,36.342445,35.656199,34.835306,33.883299,32.804161,31.602276,30.282459,28.849938,27.310245,25.669301,23.933383,22.109102,20.203303,18.223188,16.175932,14.069377,11.911227,9.709518,7.472304,5.207906,2.924559,0.630712,-1.665206,-3.954773,-6.229585,-8.481271,-10.701594,-12.882235,-15.015336,-17.092825,-19.107124,-21.050722,-22.916345,-24.696930,-26.385870,-27.976689,-29.463333,-30.840021,-32.101424,-33.242537,-34.258773,-35.145964,-35.900366,-36.518670,-36.998035,-37.336068,-37.530847,-37.580939,-37.485368,}, // NOLINT + {37.761847,37.851003,37.794048,37.591967,37.246223,36.758760,36.131979,35.368756,34.472392,33.446672,32.295825,31.024388,29.637389,28.140231,26.538657,24.838775,23.047027,21.170085,19.214952,17.189093,15.099874,12.954956,10.762326,8.530032,6.266267,3.979335,1.677598,-0.630499,-2.936549,-5.232045,-7.508652,-9.757977,-11.971773,-14.141920,-16.260424,-18.319459,-20.311266,-22.228769,-24.064510,-25.811715,-27.463751,-29.014370,-30.457592,-31.787882,-32.999951,-34.089071,-35.050731,-35.880987,-36.576257,-37.133422,-37.549837,-37.823302,-37.952097,-37.934984,-37.771188,}, // NOLINT + {37.779849,37.938108,37.950090,37.816574,37.538816,37.118546,36.557968,35.859742,35.026981,34.063260,32.972557,31.759270,30.428268,28.984708,27.434174,25.782590,24.036233,22.201676,20.285772,18.295661,16.238776,14.122502,11.954934,9.743823,7.497385,5.223772,2.931307,0.628398,-1.676617,-3.975290,-6.259135,-8.519948,-10.749415,-12.939370,-15.081787,-17.168888,-19.192756,-21.145989,-23.021471,-24.812119,-26.511245,-28.112380,-29.609581,-30.996979,-32.269230,-33.421358,-34.448748,-35.347211,-36.113013,-36.742808,-37.233729,-37.583360,-37.789767,-37.851459,-37.767441,}, // NOLINT + {38.043322,38.121013,38.052539,37.838916,37.481641,36.982683,36.344477,35.569905,34.662314,33.625518,32.463668,31.181407,29.783739,28.276066,26.664144,24.954071,23.152260,21.265491,19.300775,17.265261,15.166472,13.012163,10.810259,8.568753,6.295845,3.999862,1.688989,-0.628186,-2.943362,-5.248023,-7.533818,-9.792425,-12.015642,-14.195290,-16.323421,-18.392175,-20.394002,-22.321494,-24.167513,-25.925151,-27.587826,-29.149260,-30.603494,-31.944952,-33.168404,-34.269029,-35.242339,-36.084393,-36.791573,-37.360740,-37.789236,-38.074819,-38.215728,-38.210702,-38.058937,}, // NOLINT + {38.066942,38.213331,38.213369,38.067873,37.778127,37.345900,36.773417,36.063369,35.218883,34.243572,33.141412,31.916837,30.574675,29.120137,27.558768,25.896601,24.139794,22.294955,20.368943,18.368878,16.302164,14.176308,11.999151,9.778616,7.522824,5.239942,2.938239,0.626078,-1.687965,-3.995786,-6.288827,-8.558844,-10.797573,-12.996861,-15.148694,-17.245105,-19.278816,-21.241868,-23.127204,-24.927907,-26.637218,-28.248713,-29.756399,-31.154441,-32.437481,-33.600545,-34.638990,-35.548613,-36.325698,-36.966808,-37.469123,-37.830179,-38.047997,-38.121081,-38.048388,}, // NOLINT + {38.323709,38.390153,38.310364,38.085395,37.716768,37.206480,36.556990,35.771216,34.852511,33.804682,32.631939,31.338911,29.930624,28.412444,26.790186,25.069965,23.258131,21.361431,19.386865,17.341688,15.233435,13.069731,10.858598,8.607693,6.325558,4.020360,1.700327,-0.625989,-2.950391,-5.264269,-7.559334,-9.827318,-12.059977,-14.249134,-16.386963,-18.465542,-20.477311,-22.414937,-24.271206,-26.039293,-27.712579,-29.284786,-30.749976,-32.102548,-33.337276,-34.449289,-35.434174,-36.287884,-37.006826,-37.587838,-38.028214,-38.325703,-38.478514,-38.485346,-38.345362,}, // NOLINT + {38.352754,38.487509,38.475829,38.318561,38.017027,37.573017,36.988799,36.267080,35.411012,34.424206,33.310686,32.074883,30.721642,29.256185,27.684078,26.011278,24.244022,22.388949,20.452771,18.442718,16.366146,14.230590,12.043823,9.813800,7.548575,5.256368,2.945403,0.624022,-1.699319,-4.016371,-6.318649,-8.597934,-10.845982,-13.054704,-15.216011,-17.322103,-19.365284,-21.338192,-23.233480,-25.044250,-26.763732,-28.385608,-29.903739,-31.312369,-32.606153,-33.780055,-34.829469,-35.750159,-36.538360,-37.190686,-37.704246,-38.076538,-38.305591,-38.389859,-38.328270,}, // NOLINT + {38.603053,38.658471,38.567572,38.331434,37.951621,37.430154,36.769519,35.972652,35.042935,33.984171,32.800591,31.496878,30.078020,28.549434,26.916835,25.186395,23.364536,21.457892,19.473537,17.418650,15.300826,13.127625,10.906964,8.646824,6.355397,4.040931,1.711650,-0.624163,-2.957561,-5.280776,-7.585223,-9.862628,-12.104761,-14.303559,-16.451092,-18.539535,-20.561404,-22.509045,-24.375588,-26.154092,-27.837969,-29.420921,-30.897009,-32.260631,-33.506544,-34.629882,-35.626199,-36.491453,-37.222014,-37.814706,-38.266792,-38.575996,-38.740504,-38.758976,-38.630533,}, // NOLINT + {38.637354,38.760705,38.737517,38.568672,38.255534,37.799919,37.204112,36.470853,35.603321,34.605149,33.480354,32.233401,30.869149,29.392814,27.809975,26.126587,24.348902,22.483498,20.537207,18.517157,16.430698,14.285342,12.088969,9.849346,7.574621,5.273045,2.952750,0.622058,-1.710623,-4.036872,-6.348588,-8.637239,-10.894599,-13.112861,-15.283700,-17.399383,-19.452361,-21.435055,-23.340340,-25.161130,-26.890807,-28.522924,-30.051543,-31.470740,-32.775200,-33.959881,-35.020167,-35.951821,-36.751038,-37.414435,-37.939074,-38.322465,-38.562581,-38.657840,-38.607157,}, // NOLINT + {44.880919,45.466016,45.839312,46.000390,45.949749,45.688784,45.219770,44.545851,43.671006,42.600033,41.338553,39.892818,38.270007,36.477849,34.524806,32.419866,30.172758,27.793631,25.293179,22.682346,19.973010,17.176921,14.306247,11.373835,8.392059,5.374156,2.332990,-0.718189,-3.766235,-6.797987,-9.800317,-12.760295,-15.665113,-18.501773,-21.258346,-23.922614,-26.482856,-28.927760,-31.246401,-33.428417,-35.463904,-37.343559,-39.058656,-40.601129,-41.963573,-43.139304,-44.122438,-44.907719,-45.490810,-45.868169,-46.037097,-45.995753,-45.743209,-45.279403,-44.605189,}, // NOLINT + {44.682183,45.333225,45.775402,46.007931,46.030915,45.845351,45.453098,44.856889,44.060283,43.067632,41.884059,40.515553,38.968766,37.250956,35.370216,33.335171,31.155083,28.839686,26.399371,23.844866,21.187390,18.438568,15.610438,12.715044,9.765040,6.773006,3.751868,0.714597,-2.325665,-5.356048,-8.363479,-11.335000,-14.257811,-17.119380,-19.907210,-22.609210,-25.213652,-27.708853,-30.084017,-32.328482,-34.432167,-36.385464,-38.179458,-39.805734,-41.256600,-42.524965,-43.604666,-44.489980,-45.176178,-45.659262,-45.936098,-46.004367,-45.862641,-45.510368,-44.947911,}, // NOLINT + {45.214382,45.760802,46.097357,46.223752,46.140586,45.849329,45.352329,44.652754,43.754635,42.662753,41.382692,39.920771,38.284039,36.480152,34.517496,32.405080,30.152375,27.769462,25.266893,22.655664,19.947195,17.153208,14.285818,11.357377,8.380513,5.367727,2.332146,-0.713339,-3.755761,-6.782121,-9.779525,-12.735158,-15.636380,-18.470846,-21.226029,-23.890317,-26.452085,-28.900171,-31.223769,-33.412630,-35.456972,-37.347601,-39.075825,-40.633662,-42.013795,-43.209570,-44.214963,-45.024966,-45.635058,-46.041703,-46.242138,-46.234452,-46.017612,-45.591430,-44.956675,}, // NOLINT + {45.027671,45.640216,46.045660,46.243338,46.233467,46.017136,45.596284,44.973681,44.152926,43.138411,41.935277,40.549467,38.987547,37.256832,35.365354,33.321557,31.134672,28.814377,26.370774,23.814629,21.156984,18.409286,15.583333,12.691181,9.745178,6.757798,3.741837,0.709943,-2.324982,-5.350057,-8.352668,-11.319586,-14.238699,-17.097120,-19.883176,-22.584448,-25.189453,-27.686879,-30.065838,-32.315858,-34.426999,-36.389723,-38.195236,-39.835194,-41.301961,-42.588541,-43.688647,-44.596722,-45.307978,-45.818378,-46.124806,-46.224815,-46.116930,-45.800496,-45.275757,}, // NOLINT + {45.538123,46.047452,46.348770,46.441891,46.327506,46.007168,45.483274,44.759047,43.838518,42.726495,41.428541,39.950950,38.300704,36.485440,34.513493,32.393660,30.135415,27.748616,25.243958,22.632017,19.924148,17.131973,14.267377,11.342575,8.370121,5.362033,2.331579,-0.708723,-3.745906,-6.767433,-9.760328,-12.712089,-15.610257,-18.442448,-21.196733,-23.861288,-26.424774,-28.876063,-31.204622,-33.400217,-35.453254,-37.354502,-39.095430,-40.668162,-42.065363,-43.280414,-44.307357,-45.141070,-45.777138,-46.211923,-46.442624,-46.467257,-46.284692,-45.894662,-45.297759,}, // NOLINT + {45.363194,45.938774,46.308937,46.473138,46.431703,46.185794,45.737429,45.089440,44.245533,43.209866,41.987852,40.585299,39.008785,37.265574,35.363583,33.311211,31.117637,28.792342,26.345470,23.787556,21.129522,18.382631,15.558723,12.669355,9.726949,6.743846,3.732464,0.705391,-2.324540,-5.344827,-8.342569,-11.305778,-14.221448,-17.077452,-19.861778,-22.562609,-25.168460,-27.668173,-30.050923,-32.306475,-34.424914,-36.396896,-38.213577,-39.866835,-41.348962,-42.653082,-43.772922,-44.702918,-45.438280,-45.974991,-46.309804,-46.440304,-46.364905,-46.082862,-45.594321,}, // NOLINT + {45.852911,46.326635,46.594114,46.655271,46.510890,46.162582,45.612819,44.864858,43.922737,42.791329,41.476028,39.983267,38.319936,36.493591,34.512488,32.385406,30.121548,27.731124,25.224052,22.611221,19.903720,17.113011,14.250896,11.329333,8.360409,5.357034,2.331204,-0.704248,-3.736923,-6.753895,-9.742733,-12.691001,-15.586586,-18.416812,-21.170316,-23.835351,-26.400636,-28.855296,-31.188766,-33.390975,-35.452461,-37.364075,-39.117406,-40.704530,-42.118240,-43.351923,-44.399616,-45.256213,-45.917283,-46.379156,-46.638957,-46.694668,-46.545049,-46.189734,-45.629208,}, // NOLINT + {45.689539,46.229579,46.565796,46.697806,46.625995,46.351628,45.876774,45.204319,44.337918,43.282007,42.041727,40.622992,39.032326,37.276935,35.364689,33.303943,31.103729,28.773572,26.323308,23.763476,21.104833,18.358474,15.536049,12.649324,9.710380,6.730918,3.723699,0.701158,-2.324341,-5.340252,-8.333929,-11.293459,-14.206127,-17.059908,-19.842910,-22.543525,-25.150385,-27.652468,-30.039151,-32.300164,-34.425797,-36.406819,-38.234443,-39.900559,-41.397603,-42.718712,-43.857551,-44.808691,-45.567288,-46.129301,-46.491455,-46.651274,-46.607102,-46.358119,-45.904344,}, // NOLINT + {46.159449,46.598954,46.833899,46.864312,46.691056,46.315828,45.741136,44.970278,44.007309,42.857079,41.525103,40.017628,38.341558,36.504432,34.514324,32.380148,30.110866,27.716486,25.207011,22.593095,19.885778,17.096199,14.236217,11.317549,8.352145,5.352683,2.331079,-0.700094,-3.728367,-6.741326,-9.726529,-12.671713,-15.564709,-18.393548,-21.146614,-23.812309,-26.379550,-28.837557,-31.175936,-33.384758,-35.454532,-37.376294,-39.141640,-40.742782,-42.172451,-43.424109,-44.491878,-45.370559,-46.055723,-46.543686,-46.831531,-46.917144,-46.799229,-46.477316,-45.951778,}, // NOLINT + {46.007331,46.513188,46.816771,46.917772,46.816706,46.514907,46.014515,45.318456,44.430425,43.354855,42.096921,40.662460,39.058090,37.290815,35.368550,33.299594,31.092854,28.757723,26.304053,23.742175,21.082740,18.336907,15.515751,12.631197,9.694924,6.718983,3.715677,0.697070,-2.324351,-5.336296,-8.326304,-11.282540,-14.192549,-17.044371,-19.826388,-22.527027,-25.135071,-27.639664,-30.030324,-32.296761,-34.429519,-36.419362,-38.257645,-39.936281,-41.447792,-42.785287,-43.942592,-44.914138,-45.695157,-46.281568,-46.670063,-46.858116,-46.844002,-46.626818,-46.206481,}, // NOLINT + {46.458387,46.864951,47.068576,47.069379,46.868310,46.467126,45.868390,45.075411,44.092295,42.923907,41.575710,40.053958,38.365501,36.517837,34.518972,32.377715,30.103053,27.704675,25.192783,22.577489,19.870136,17.081578,14.223225,11.307205,8.344869,5.348964,2.331190,-0.696084,-3.720466,-6.729707,-9.711712,-12.654130,-15.545127,-18.372717,-21.125460,-23.791998,-26.361325,-28.822776,-31.166063,-33.381382,-35.459407,-37.390999,-39.168061,-40.782777,-42.227947,-43.497028,-44.584154,-45.484215,-46.192644,-46.705776,-47.020653,-47.135093,-47.047722,-46.757981,-46.266128,}, // NOLINT + {46.317292,46.790197,47.062311,47.133424,47.004143,46.675878,46.150828,45.431965,44.523013,43.428470,42.153376,40.703698,39.085947,37.307103,35.375041,33.298015,31.084831,28.744807,26.287590,23.723536,21.063168,18.317342,15.497329,12.614648,9.680915,6.708045,3.708075,0.693172,-2.324560,-5.332939,-8.319633,-11.272982,-14.180619,-17.030881,-19.812088,-22.512952,-25.122362,-27.629553,-30.024012,-32.296073,-34.435893,-36.434387,-38.283085,-39.973925,-41.499471,-42.852910,-44.028036,-45.019356,-45.822032,-46.432001,-46.845906,-47.061181,-47.076033,-46.889482,-46.501351,}, // NOLINT + {46.750287,47.125124,47.298561,47.270815,47.042892,46.616669,45.994694,45.180395,44.177766,42.991739,41.627818,40.092164,38.391637,36.533656,34.526244,32.377959,30.097844,27.695490,25.180815,22.564248,19.856490,17.068638,14.211892,11.298010,8.338524,5.345775,2.331426,-0.692265,-3.713175,-6.719239,-9.698119,-12.638163,-15.527255,-18.353997,-21.106714,-23.774262,-26.345784,-28.810781,-31.159036,-33.380719,-35.466681,-37.408048,-39.196502,-40.824487,-42.284696,-43.570717,-44.676594,-45.597312,-46.328207,-46.865658,-47.206628,-47.348885,-47.290977,-47.032257,-46.572878,}, // NOLINT + {46.619962,47.061089,47.302840,47.345110,47.188585,46.834753,46.285889,45.544899,44.615740,43.502724,42.211061,40.746575,39.115757,37.325688,35.384031,33.299046,31.079437,28.734407,26.273718,23.707379,21.045860,18.299949,15.480896,12.599606,9.668293,6.698100,3.701124,0.689457,-2.324986,-5.330127,-8.313861,-11.264643,-14.170249,-17.019206,-19.799865,-22.501167,-25.112123,-27.621962,-30.020565,-32.297997,-34.444717,-36.451768,-38.310712,-40.013395,-41.552618,-42.921561,-44.113951,-45.124410,-45.948036,-46.580773,-47.019230,-47.260783,-47.303585,-47.146572,-46.789486,}, // NOLINT + {47.035681,47.379915,47.524223,47.468915,47.215092,46.764628,46.120189,45.285155,44.263657,43.060607,41.681336,40.132172,38.419874,36.551780,34.535901,32.380733,30.095261,27.688810,25.171388,22.553235,19.844964,17.057511,14.201993,11.290086,8.333053,5.343155,2.331926,-0.688617,-3.706383,-6.709447,-9.685911,-12.623747,-15.511401,-18.337336,-21.090207,-23.758954,-26.332839,-28.801363,-31.154501,-33.382612,-35.476458,-37.427336,-39.227010,-40.867816,-42.342671,-43.645076,-44.769212,-45.709859,-46.462561,-47.023530,-47.389725,-47.558852,-47.529394,-47.300613,-46.872570,}, // NOLINT + {46.915859,47.326316,47.538742,47.553140,47.370282,46.991723,46.419775,45.657505,44.708667,43.577750,42.269938,40.791027,39.147536,37.346441,35.395366,33.302536,31.076606,28.726655,26.262319,23.693574,21.030759,18.284522,15.465941,12.586104,9.656530,6.688865,3.694635,0.685902,-2.325580,-5.327841,-8.308933,-11.257462,-14.161337,-17.009191,-19.789597,-22.491532,-25.104336,-27.616746,-30.019524,-32.302348,-34.455935,-36.471379,-38.340237,-40.054604,-41.607157,-42.991116,-44.200325,-45.229324,-46.073279,-46.728054,-47.190253,-47.457205,-47.527004,-47.398514,-47.071385,}, // NOLINT + {47.315043,47.629722,47.745897,47.663951,47.385059,46.911164,46.244959,45.389873,44.350074,43.130287,41.736237,40.173878,38.450076,36.572078,34.547863,32.385848,30.094909,27.684422,25.164280,22.544314,19.835354,17.048111,14.193640,11.283298,8.328404,5.341031,2.332536,-0.685142,-3.700095,-6.700550,-9.674648,-12.610702,-15.497056,-18.322612,-21.075833,-23.745930,-26.322311,-28.794415,-31.152528,-33.386907,-35.488595,-37.448754,-39.259348,-40.912728,-42.401823,-43.720183,-44.861998,-45.822040,-46.595837,-47.179573,-47.570177,-47.765295,-47.763338,-47.563487,-47.165721,}, // NOLINT + {47.205499,47.586290,47.770361,47.757800,47.549459,47.146959,46.552662,45.769708,44.801775,43.653495,42.329986,40.837062,39.181148,37.369243,35.408959,33.308405,31.076145,28.721255,26.253219,23.681968,21.017710,18.271016,15.452716,12.573975,9.646052,6.680412,3.688667,0.682524,-2.326315,-5.326023,-8.304798,-11.251377,-14.153826,-17.000816,-19.781174,-22.483921,-25.098319,-27.613961,-30.020755,-32.308995,-34.469390,-36.493095,-38.371749,-40.097494,-41.663031,-43.061636,-44.287177,-45.334202,-46.197851,-46.873984,-47.359172,-47.650704,-47.746610,-47.645688,-47.347505,}, // NOLINT + {47.588807,47.874923,47.963883,47.856163,47.553001,47.056399,46.369097,45.494533,44.436854,43.201107,41.792451,40.217233,38.482126,36.594443,34.562026,32.393226,30.096886,27.682269,25.159059,22.537361,19.827538,17.040279,14.186586,11.277566,8.324528,5.339391,2.333317,-0.681811,-3.694291,-6.692416,-9.664544,-12.599129,-15.484500,-18.309696,-21.063493,-23.735073,-26.313909,-28.789768,-31.152833,-33.393505,-35.502861,-37.472192,-39.293487,-40.959131,-42.462122,-43.796016,-44.954994,-45.933874,-46.728138,-47.333954,-47.748200,-47.968476,-47.993138,-47.821281,-47.452788,}, // NOLINT + {47.489285,47.841377,47.998009,47.959346,47.726317,47.300611,46.684641,45.881554,44.895135,43.729940,42.391148,40.884531,39.216514,37.394046,35.424658,33.316481,31.077958,28.718112,26.246346,23.672461,21.006609,18.259235,15.441264,12.563140,9.636604,6.672841,3.683153,0.679289,-2.327181,-5.324678,-8.301409,-11.246314,-14.147534,-16.993949,-19.774468,-22.478209,-25.094479,-27.613205,-30.024221,-32.317821,-34.484962,-36.516813,-38.405082,-40.141960,-41.720196,-43.133060,-44.374547,-45.439060,-46.321833,-47.018688,-47.526162,-47.841501,-47.962687,-47.888442,-47.618256,}, // NOLINT + {47.857370,48.115839,48.178457,48.045769,47.719086,47.200466,46.492677,45.599221,44.524224,43.272669,41.849923,40.262149,38.516032,36.618788,34.578248,32.402732,30.100977,27.682193,25.155967,22.532274,19.821390,17.033938,14.180747,11.272836,8.321378,5.338167,2.334248,-0.678646,-3.688935,-6.685037,-9.655365,-12.588663,-15.473403,-18.298482,-21.053034,-23.726252,-26.307734,-28.787355,-31.155365,-33.402259,-35.519171,-37.497551,-39.329327,-41.006983,-42.523525,-43.872578,-45.048236,-46.045449,-46.859571,-47.486809,-47.923984,-48.168653,-48.219095,-48.074342,-47.734179,}, // NOLINT + {47.767622,48.091930,48.221973,48.158005,47.901039,47.452810,46.815791,45.993149,44.988761,43.807152,42.453394,40.933407,39.253558,37.420690,35.442409,33.326624,31.081907,28.717110,26.241532,23.664925,20.997340,18.249148,15.430925,12.553590,9.628181,6.665830,3.678037,0.676205,-2.328213,-5.323714,-8.298720,-11.242216,-14.142569,-16.988545,-19.769397,-22.474293,-25.092719,-27.614456,-30.029621,-32.328695,-34.502529,-36.542427,-38.440155,-40.187956,-41.778662,-43.205419,-44.462354,-45.543928,-46.445288,-47.162279,-47.691378,-48.029810,-48.175495,-48.127091,-47.884011,}, // NOLINT + {48.121085,48.352781,48.389866,48.232966,47.883461,47.343461,46.615763,45.703911,44.612095,43.345161,41.908602,40.308509,38.551541,36.644932,34.596437,32.414225,30.107079,27.684073,25.154734,22.528923,19.816827,17.028943,14.176063,11.268996,8.319065,5.337414,2.335328,-0.675624,-3.683968,-6.678443,-9.647290,-12.579453,-15.463706,-18.288859,-21.044293,-23.719359,-26.303585,-28.787040,-31.159952,-33.413082,-35.537497,-37.524734,-39.366805,-41.056201,-42.585988,-43.949803,-45.141708,-46.156757,-46.990217,-47.638265,-48.097705,-48.366037,-48.441482,-48.323000,-48.010291,}, // NOLINT + {48.040884,48.338252,48.442508,48.353988,48.073782,47.603681,46.946196,46.104547,45.082553,43.884955,42.516670,40.983608,39.292114,37.449098,35.462018,33.338801,31.087873,28.718096,26.238664,23.659255,20.989804,18.240570,15.422079,12.545093,9.620618,6.659569,3.673374,0.673267,-2.329331,-5.323188,-8.296856,-11.239023,-14.138589,-16.984525,-19.765894,-22.472052,-25.092708,-27.617581,-30.037026,-32.341534,-34.521986,-36.569801,-38.476844,-40.235361,-41.838153,-43.278604,-44.550655,-45.648833,-46.568292,-47.304810,-47.854961,-48.215812,-48.385266,-48.361922,-48.145113,}, // NOLINT + {48.380286,48.586017,48.598329,48.417929,48.046254,47.485469,46.738409,45.808648,44.700390,43.418492,41.968435,40.356295,38.588663,36.672842,34.616432,32.427574,30.115071,27.687828,25.155260,22.527215,19.813754,17.025376,14.172515,11.266130,8.317222,5.336826,2.336536,-0.672742,-3.679466,-6.672265,-9.639954,-12.571388,-15.455341,-18.280884,-21.037381,-23.714278,-26.301341,-28.788436,-31.166620,-33.425837,-35.557650,-37.553638,-39.405809,-41.106734,-42.649470,-44.027648,-45.235543,-46.267887,-47.120151,-47.788446,-48.269515,-48.560828,-48.660546,-48.567554,-48.281472,}, // NOLINT + {48.309399,48.580626,48.659850,48.547492,48.244711,47.753330,47.075966,46.215780,45.176758,43.963419,42.580939,41.035052,39.332174,37.479217,35.483442,33.352840,31.095757,28.720959,26.237642,23.655333,20.983899,18.233526,15.414573,12.537634,9.613868,6.653940,3.669075,0.670452,-2.330648,-5.323035,-8.295426,-11.236680,-14.135748,-16.981735,-19.763734,-22.471419,-25.094353,-27.622577,-30.046250,-32.356119,-34.543221,-36.598915,-38.515101,-40.284120,-41.898824,-43.352607,-44.639414,-45.753785,-46.690878,-47.446492,-48.017041,-48.399668,-48.592213,-48.593193,-48.401874,}, // NOLINT + {48.635273,48.815799,48.804055,48.600819,48.207587,47.626569,46.860661,45.913442,44.789138,43.492620,42.029354,40.405389,38.627357,36.702406,34.638177,32.442801,30.124835,27.693233,25.157452,22.527140,19.812135,17.022997,14.169997,11.264058,8.315986,5.336887,2.337819,-0.669990,-3.675299,-6.666947,-9.633555,-12.564336,-15.448217,-18.274324,-21.031997,-23.710912,-26.300890,-28.792097,-31.174993,-33.440422,-35.579599,-37.584188,-39.446298,-41.158497,-42.713921,-44.106211,-45.329593,-46.378853,-47.249447,-47.937440,-48.439552,-48.753210,-48.876511,-48.808275,-48.548042,}, // NOLINT + {48.573462,48.819312,48.874213,48.738674,48.413911,47.901809,47.205059,46.326849,45.271168,44.042547,42.646156,41.087777,39.373728,37.510863,35.506555,33.368656,31.105440,28.725672,26.238378,23.653076,20.979510,18.227840,15.408334,12.531383,9.607999,6.648919,3.665153,0.667775,-2.332033,-5.323250,-8.294601,-11.235114,-14.133935,-16.980114,-19.763103,-22.472310,-25.097626,-27.629142,-30.057197,-32.372504,-34.566148,-36.629579,-38.554820,-40.334197,-41.960535,-43.427386,-44.728626,-45.858809,-46.813096,-47.587260,-48.177707,-48.581540,-48.796526,-48.821143,-48.654578,}, // NOLINT + {48.886317,49.042353,49.007224,48.781777,48.367564,47.766832,46.982562,46.018310,44.878341,43.567465,42.091306,40.455766,38.667459,36.733529,34.661571,32.459650,30.136290,27.700379,25.161188,22.528369,19.811795,17.021702,14.168444,11.262768,8.315336,5.337147,2.339172,-0.667376,-3.671503,-6.662155,-9.627936,-12.558432,-15.442314,-18.269064,-21.028117,-23.709132,-26.302149,-28.797340,-31.185209,-33.456666,-35.603191,-37.616336,-39.488162,-41.211459,-42.779309,-44.185385,-45.423914,-46.489690,-47.378149,-48.085342,-48.607945,-48.943343,-49.089582,-49.045413,-48.810296,}, // NOLINT + {48.833391,49.054546,49.085790,48.927696,48.581533,48.049309,47.333626,46.437817,45.365828,44.122273,42.712279,41.141602,39.416625,37.544041,35.531290,33.386157,31.116834,28.732020,26.240750,23.652203,20.976649,18.223465,15.403138,12.526067,9.603121,6.644354,3.661604,0.665242,-2.333547,-5.323700,-8.294290,-11.234328,-14.133014,-16.979612,-19.763567,-22.474561,-25.102415,-27.637341,-30.069770,-32.390436,-34.590653,-36.661803,-38.595923,-40.385455,-42.023306,-43.502916,-44.818264,-45.963907,-46.934982,-47.727212,-48.337079,-48.761552,-48.998384,-49.045987,-48.903484,}, // NOLINT + {49.133666,49.265889,49.208004,48.960928,48.526281,47.906361,47.104142,46.123255,44.967950,43.643134,42.154244,40.507313,38.708919,36.766118,34.686471,32.478094,30.149324,27.709015,25.166428,22.531052,19.812704,17.021538,14.167846,11.262189,8.315198,5.337743,2.340744,-0.664874,-3.668051,-6.657800,-9.623034,-12.553464,-15.437540,-18.265107,-21.025703,-23.708939,-26.304951,-28.804150,-31.197088,-33.474632,-35.628366,-37.649850,-39.531354,-41.265598,-42.845580,-44.265152,-45.518491,-46.600411,-47.506309,-48.232224,-48.774802,-49.131381,-49.299946,-49.279190,-49.068505,}, // NOLINT + {49.089408,49.286545,49.294759,49.114714,48.747700,48.195795,47.461674,46.548680,45.460787,44.202624,42.779260,41.196547,39.460745,37.578639,35.557545,33.405190,31.129832,28.739979,26.244669,23.653185,20.975117,18.220359,15.399110,12.521726,9.598637,6.640548,3.658316,0.662748,-2.335094,-5.324523,-8.294565,-11.234253,-14.132992,-16.980179,-19.765308,-22.478116,-25.108612,-27.647017,-30.083857,-32.410000,-34.616657,-36.695404,-38.638343,-40.437872,-42.086998,-43.579140,-44.908324,-46.069066,-47.056558,-47.866486,-48.495239,-48.939831,-49.197939,-49.267922,-49.148832,}, // NOLINT + {49.377553,49.486593,49.406548,49.138401,48.683818,48.045157,47.225401,46.228270,45.057989,43.719443,42.218112,40.559988,38.751641,36.800120,34.712908,32.498024,30.163837,27.719182,25.173036,22.535032,19.814812,17.022408,14.168068,11.262364,8.315536,5.338619,2.342326,-0.662429,-3.664929,-6.654088,-9.619088,-12.549221,-15.433831,-18.262394,-21.024532,-23.710167,-26.309385,-28.812618,-31.210533,-33.494210,-35.655034,-37.684801,-39.575801,-41.320703,-42.912691,-44.345565,-45.613334,-46.711037,-47.633974,-48.378162,-48.940225,-49.317463,-49.507772,-49.509821,-49.322916,}, // NOLINT + {49.341758,49.515504,49.501281,49.299808,48.912477,48.341369,47.589247,46.659446,45.555965,44.283448,42.847061,41.252520,39.506090,37.614582,35.585120,33.425784,31.144350,28.749453,26.250061,23.655329,20.974832,18.218377,15.396084,12.518119,9.594931,6.637184,3.655377,0.660439,-2.336783,-5.325608,-8.295200,-11.234850,-14.133853,-16.981761,-19.768182,-22.482956,-25.116050,-27.658033,-30.099437,-32.430958,-34.644072,-36.730414,-38.681998,-40.491417,-42.151595,-43.656062,-44.998798,-46.174337,-47.177854,-48.005048,-48.652266,-49.116495,-49.395337,-49.487128,-49.390841,}, // NOLINT + {49.618185,49.704639,49.602991,49.314287,48.840253,48.183288,47.346438,46.333369,45.148405,43.796363,42.282882,40.613682,38.795576,36.835394,34.740676,32.519355,30.179757,27.730606,25.180946,22.540184,19.817978,17.024263,14.169166,11.263046,8.316376,5.339793,2.344016,-0.660374,-3.662086,-6.650791,-9.615716,-12.545948,-15.431124,-18.260712,-21.024681,-23.712810,-26.315197,-28.822518,-31.225476,-33.515182,-35.683071,-37.721071,-39.621409,-41.376841,-42.980611,-44.426387,-45.708439,-46.821575,-47.761179,-48.523234,-49.104304,-49.501651,-49.713212,-49.737494,-49.573756,}, // NOLINT + {49.590663,49.741609,49.705502,49.483129,49.075957,48.486111,47.716365,46.770132,45.651434,44.364869,42.915558,41.309451,39.552593,37.651795,35.614296,33.447768,31.160302,28.760380,26.256826,23.658870,20.975837,18.217638,15.394035,12.515389,9.591974,6.634214,3.652773,0.658351,-2.338507,-5.326966,-8.296351,-11.236020,-14.135456,-16.984292,-19.772123,-22.488963,-25.124968,-27.670538,-30.116285,-32.453234,-34.672789,-36.766649,-38.726810,-40.545972,-42.217038,-43.733585,-45.089610,-46.279650,-47.298879,-48.142967,-48.808245,-49.291614,-49.590712,-49.703769,-49.629708,}, // NOLINT + {49.855755,49.920185,49.797460,49.488687,48.995651,48.320793,47.467186,46.438557,45.239193,43.874001,42.348432,40.668475,38.840641,36.871895,34.769745,32.542009,30.196998,27.743383,25.190080,22.546506,19.822191,17.027064,14.170964,11.264402,8.317629,5.341205,2.345758,-0.658057,-3.659535,-6.648033,-9.612887,-12.543443,-15.429378,-18.260338,-21.025998,-23.716588,-26.322350,-28.833817,-31.241818,-33.537520,-35.712492,-37.758578,-39.668152,-41.433968,-43.049272,-44.507792,-45.803775,-46.932034,-47.887941,-48.667419,-49.267121,-49.684164,-49.916415,-49.962380,-49.821234,}, // NOLINT + {49.836316,49.965021,49.907557,49.664782,49.238218,48.630043,47.843074,46.880747,45.747122,44.446769,42.984934,41.367381,39.600159,37.690197,35.644637,33.471088,31.177619,28.772616,26.264909,23.663587,20.977986,18.217820,15.392927,12.513437,9.589622,6.631753,3.650435,0.656195,-2.340343,-5.328636,-8.297895,-11.237793,-14.137817,-16.987610,-19.777016,-22.496096,-25.134951,-27.684161,-30.134436,-32.476855,-34.702796,-36.803953,-38.772723,-40.601455,-42.283278,-43.811715,-45.180786,-46.385077,-47.419684,-48.280284,-48.963191,-49.465318,-49.784175,-49.917994,-49.865617,}, // NOLINT + {50.090440,50.133374,49.990064,49.661697,49.150068,48.457708,47.587705,46.543801,45.330317,43.952161,42.414809,40.724155,38.886773,36.909590,34.800018,32.565916,30.215468,27.757302,25.200400,22.553838,19.827374,17.030604,14.173543,11.266432,8.319279,5.342876,2.347591,-0.656003,-3.657310,-6.645702,-9.610641,-12.541741,-15.428519,-18.260787,-21.028460,-23.721670,-26.330786,-28.846452,-31.259471,-33.561177,-35.743115,-37.797252,-39.715936,-41.491974,-43.118647,-44.589680,-45.899338,-47.042431,-48.014298,-48.810897,-49.428749,-49.865020,-50.117503,-50.184641,-50.065544,}, // NOLINT + {50.078906,50.185894,50.107570,49.844849,49.399327,48.773220,47.969389,46.991318,45.842997,44.529112,43.054918,41.425990,39.648747,37.729735,35.676176,33.495666,31.196194,28.786146,26.274223,23.669368,20.981198,18.219015,15.392705,12.512253,9.587794,6.629703,3.648344,0.654203,-2.342223,-5.330360,-8.299852,-11.240109,-14.140812,-16.991803,-19.782878,-22.504215,-25.146021,-27.698975,-30.153761,-32.501636,-34.733953,-36.842561,-38.819650,-40.657863,-42.350261,-43.890401,-45.272306,-46.490544,-47.540225,-48.417024,-49.117224,-49.637643,-49.975846,-50.129941,-50.098738,}, // NOLINT + {50.322401,50.344338,50.180913,49.833354,49.303575,48.594058,47.707974,46.649109,45.421770,44.030865,42.481893,40.780727,38.933924,36.948346,34.831444,32.590963,30.235109,27.772415,25.211744,22.562288,19.833472,17.034998,14.176754,11.268762,8.321335,5.344668,2.349470,-0.654053,-3.655304,-6.643777,-9.608965,-12.540751,-15.428509,-18.262263,-21.031980,-23.727901,-26.340415,-28.860185,-31.278377,-33.586047,-35.774934,-37.837017,-39.764714,-41.550864,-43.188693,-44.672068,-45.995117,-47.152748,-48.140278,-48.953607,-49.589254,-50.044344,-50.316595,-50.404423,-50.306861,}, // NOLINT + {50.318599,50.404367,50.305647,50.023429,49.559348,48.915682,48.095325,47.101762,45.939083,44.611959,43.125586,41.485592,39.698285,37.770331,35.708883,33.521415,31.215977,28.800851,26.284693,23.676464,20.985330,18.221134,15.393206,12.511683,9.586559,6.628119,3.646541,0.652311,-2.344163,-5.332467,-8.302173,-11.242952,-14.144559,-16.996755,-19.789616,-22.513356,-25.158178,-27.714904,-30.174267,-32.527543,-34.766208,-36.882119,-38.867573,-40.715143,-42.417957,-43.969606,-45.364117,-46.596068,-47.660550,-48.553218,-49.270364,-49.808700,-50.165811,-50.339733,-50.329222,}, // NOLINT + {50.551787,50.553197,50.370095,50.003777,49.456180,48.729874,47.828044,46.754464,45.513503,44.110068,42.549613,40.838098,38.981960,36.988059,34.863922,32.617156,30.255830,27.788603,25.224124,22.571653,19.840418,17.040133,14.180602,11.271780,8.323749,5.346887,2.351426,-0.652199,-3.653573,-6.642306,-9.608019,-12.540395,-15.429311,-18.264640,-21.036505,-23.735180,-26.351175,-28.875282,-31.298431,-33.612008,-35.807855,-37.877875,-39.814416,-41.610500,-43.259357,-44.754809,-46.091102,-47.263006,-48.265878,-49.095618,-49.748694,-50.222185,-50.513794,-50.621860,-50.545348,}, // NOLINT + {50.555551,50.620567,50.501895,50.200584,49.718324,49.057463,48.220893,47.212164,46.035374,44.695191,43.196812,41.545907,39.748729,37.811946,35.742609,33.548296,31.236897,28.816683,26.296248,23.684535,20.990674,18.224170,15.394491,12.511821,9.585844,6.626797,3.644946,0.650512,-2.346153,-5.334706,-8.304805,-11.246274,-14.148901,-17.002418,-19.797168,-22.523284,-25.171300,-27.731812,-30.195814,-32.554504,-34.799490,-36.922677,-38.916342,-40.773173,-42.486298,-44.049292,-45.456219,-46.701640,-47.780650,-48.688894,-49.422583,-49.978536,-50.354134,-50.547487,-50.557212,}, // NOLINT + {50.778735,50.760060,50.557702,50.172999,49.607982,48.865174,47.947874,46.859865,45.605473,44.189731,42.618020,40.896243,39.030913,37.028849,34.897409,32.644287,30.277599,27.805673,25.237482,22.581872,19.848154,17.046031,14.185098,11.275154,8.326460,5.349240,2.353382,-0.650437,-3.652060,-6.641154,-9.607436,-12.540682,-15.430869,-18.267785,-21.041993,-23.743476,-26.363032,-28.891338,-31.319600,-33.639183,-35.841806,-37.919598,-39.864995,-41.670895,-43.330604,-44.837987,-46.187239,-47.373180,-48.391124,-49.236954,-49.907118,-50.398638,-50.709211,-50.837074,-50.781154,}, // NOLINT + {50.789906,50.834613,50.696414,50.376398,49.876300,49.198588,48.346120,47.322468,46.131818,44.778787,43.268588,41.606930,39.799992,37.854454,35.777357,33.576211,31.258878,28.833556,26.308841,23.693575,20.996866,18.227994,15.396647,12.512464,9.585655,6.625980,3.643585,0.648809,-2.348186,-5.337131,-8.307793,-11.249975,-14.153761,-17.008824,-19.805492,-22.534164,-25.185330,-27.749688,-30.218296,-32.582434,-34.833764,-36.964138,-38.965975,-40.831969,-42.555209,-44.129426,-45.548569,-46.807245,-47.900525,-48.824056,-49.574031,-50.147205,-50.540972,-50.753305,-50.782839,}, // NOLINT + {51.003369,50.965027,50.743802,50.341084,49.758928,48.999976,48.067488,46.965284,45.697781,44.269838,42.686971,40.955094,39.080650,37.070460,34.931827,32.672425,30.300287,27.823792,25.251677,22.592880,19.856653,17.052488,14.190060,11.278887,8.329499,5.351647,2.355446,-0.648768,-3.650786,-6.640411,-9.607365,-12.541601,-15.433086,-18.271946,-21.048317,-23.752737,-26.375824,-28.908458,-31.341804,-33.667310,-35.876729,-37.962279,-39.916381,-41.731990,-43.402437,-44.921528,-46.283548,-47.483277,-48.516026,-49.377653,-50.064589,-50.573793,-50.902921,-51.050179,-51.014419,}, // NOLINT + {51.021793,51.046611,50.889280,50.550923,50.033395,49.339081,48.471005,47.432732,46.228417,44.862749,43.340912,41.668632,39.852067,37.897859,35.813050,33.605104,31.281835,28.851437,26.322385,23.703499,21.003810,18.232611,15.399410,12.513890,9.585913,6.625466,3.642470,0.647191,-2.350261,-5.339772,-8.311059,-11.254194,-14.159134,-17.015720,-19.814536,-22.545824,-25.200157,-27.768469,-30.241722,-32.611301,-34.868883,-37.006454,-39.016454,-40.891423,-42.624745,-44.209964,-45.641141,-46.912860,-48.020188,-48.958741,-49.724689,-50.314771,-50.726322,-50.957283,-51.006223,}, // NOLINT + {53.426391,53.969855,54.270842,54.329676,54.147748,53.727432,53.072138,52.186192,51.074833,49.744164,48.201117,46.453400,44.509470,42.378467,40.070195,37.595090,34.963992,32.188513,29.280572,26.252508,23.117267,19.887474,16.577203,13.199268,9.768169,6.297798,2.801929,-0.704924,-4.208661,-7.695028,-11.150003,-14.559594,-17.909647,-21.186722,-24.377236,-27.468055,-30.446393,-33.299652,-36.015767,-38.583116,-40.990619,-43.227611,-45.284106,-47.150724,-48.818763,-50.280204,-51.527817,-52.555158,-53.356615,-53.927445,-54.263840,-54.362927,-54.222826,-53.842678,-53.222681,}, // NOLINT + {53.298846,53.892007,54.246993,54.363777,54.243292,53.887495,53.299331,52.482595,51.442134,50.183502,48.713165,47.038403,45.167030,43.107870,40.870107,38.463721,35.899259,33.187682,30.340556,27.369882,24.287851,21.107352,17.841432,14.503202,11.106369,7.664544,4.191787,0.701836,-2.791191,-6.273242,-9.730323,-13.148516,-16.514057,-19.812713,-23.032005,-26.157963,-29.177896,-32.079007,-34.849260,-37.476646,-39.949917,-42.258196,-44.391061,-46.338900,-48.092593,-49.643735,-50.984649,-52.108416,-53.008931,-53.680943,-54.120089,-54.322934,-54.287009,-54.010847,-53.494034,}, // NOLINT + {53.685496,54.185313,54.444994,54.465052,54.247029,53.793461,53.107843,52.194566,51.058946,49.707073,48.145944,46.383183,44.427218,42.287132,39.972512,37.493885,34.861820,32.087909,29.183699,26.161390,23.033660,19.813326,16.513749,13.147868,9.729743,6.272783,2.791126,-0.701469,-4.191014,-7.663545,-11.105211,-14.502281,-17.840917,-21.107892,-24.289882,-27.373937,-30.347442,-33.197950,-35.913718,-38.483192,-40.895331,-43.139905,-45.206724,-47.086610,-48.770879,-50.251613,-51.521543,-52.574205,-53.403951,-54.005983,-54.376384,-54.512165,-54.411300,-54.072749,-53.496515,}, // NOLINT + {53.566807,54.117015,54.431218,54.509535,54.353090,53.963969,53.345223,52.500844,51.435575,50.155130,48.665950,46.975256,45.090951,43.021665,40.776607,38.365624,35.799117,33.087963,30.243500,27.277748,24.202235,21.030180,17.774030,14.447053,11.062489,7.633720,4.174508,0.698462,-2.780584,-6.248856,-9.692697,-13.098105,-16.451956,-19.740255,-22.950202,-26.068651,-29.082829,-31.980287,-34.749053,-37.377374,-39.854087,-42.168479,-44.310192,-46.269817,-48.038254,-49.607048,-50.968679,-52.116178,-53.043450,-53.745145,-54.216859,-54.455052,-54.457124,-54.221465,-53.747454,}, // NOLINT + {53.935362,54.392875,54.612536,54.595061,54.342136,53.856420,53.141512,52.201841,51.042803,49.670563,48.091906,46.314714,44.347164,42.198315,39.877775,37.395720,34.762771,31.990294,29.089686,26.073184,22.952830,19.741580,16.452487,13.098093,9.692445,6.248663,2.780633,-0.698157,-4.173974,-7.633118,-11.061849,-14.446857,-17.774357,-21.031699,-24.205317,-27.282780,-30.251499,-33.099384,-35.814778,-38.386198,-40.802938,-43.054595,-45.131360,-47.024012,-48.723935,-50.223252,-51.514695,-52.591798,-53.448876,-54.081067,-54.484367,-54.655671,-54.592814,-54.294588,-53.760781,}, // NOLINT + {53.825579,54.334107,54.608745,54.649782,54.458507,54.037150,53.388837,52.517686,51.428499,50.126997,48.619639,46.913628,45.016720,42.937903,40.685810,38.270495,35.702010,32.991237,30.149376,27.188104,24.119318,20.955264,17.708773,14.392731,11.019975,7.603811,4.157819,0.695237,-2.770280,-6.225213,-9.656027,-13.049319,-16.391506,-19.669836,-22.870935,-25.981997,-28.990667,-31.884574,-34.651839,-37.281028,-39.761014,-42.081247,-44.231534,-46.202443,-47.985007,-49.570892,-50.952504,-52.122919,-53.076001,-53.806408,-54.309622,-54.582019,-54.620889,-54.424462,-53.991960,}, // NOLINT + {54.176528,54.592993,54.773888,54.720064,54.433351,53.916533,53.173283,52.208150,51.026500,49.634518,48.039139,46.247917,44.269228,42.112024,39.785721,37.300406,34.666711,31.895631,28.998631,25.987577,22.874476,19.672013,16.392795,13.049814,9.656232,6.225320,2.770433,-0.694998,-4.157510,-7.603475,-11.019903,-14.393109,-17.709990,-20.957776,-24.123387,-27.194383,-30.158469,-33.003795,-35.718685,-38.292022,-40.713076,-42.971636,-45.057938,-46.962881,-48.677914,-50.195076,-51.507359,-52.608081,-53.491591,-54.152950,-54.588095,-54.793812,-54.767800,-54.508705,-54.016130,}, // NOLINT + {54.075661,54.543744,54.779982,54.784872,54.559847,54.107267,53.430388,52.533316,51.420995,50.099148,48.574241,46.853456,44.944661,42.856303,40.597558,38.177974,35.607701,32.897443,30.058220,27.101422,24.039001,20.882943,17.645735,14.340154,10.978926,7.574867,4.141689,0.692153,-2.760261,-6.202393,-9.620578,-13.001982,-16.333268,-19.601505,-22.794063,-25.898112,-28.901265,-31.791691,-34.557585,-37.187458,-39.670573,-41.996390,-44.154924,-46.136729,-47.932933,-49.535293,-50.936200,-52.128763,-53.106755,-53.864965,-54.398661,-54.704178,-54.778694,-54.620304,-54.228081,}, // NOLINT + {54.409511,54.786147,54.929435,54.840378,54.520940,53.974019,53.203361,52.213575,51.010076,49.599054,47.987381,46.182776,44.193306,42.027979,39.696182,37.207814,34.573375,31.803751,28.910223,25.904444,22.798453,19.604473,16.335150,13.003051,9.621201,6.202626,2.760520,-0.691971,-4.141556,-7.574930,-10.979362,-14.341284,-17.647658,-20.886191,-24.044089,-27.108770,-30.068323,-32.911038,-35.625426,-38.200524,-40.625727,-42.890941,-44.986293,-46.903181,-48.632829,-50.167335,-51.499622,-52.623182,-53.532251,-54.221861,-54.687858,-54.926927,-54.936652,-54.715527,-54.263003,}, // NOLINT + {54.317610,54.746347,54.945304,54.915123,54.657375,54.174539,53.469961,52.547831,51.413149,50.071619,48.529747,46.794711,44.874322,42.777056,40.511745,38.088120,35.516201,32.806376,29.969640,27.017393,23.961068,20.812717,17.584589,14.289185,10.939061,7.547078,4.126082,0.689204,-2.750523,-6.179955,-9.586138,-12.956050,-16.276668,-19.535372,-22.719464,-25.816556,-28.814522,-31.701495,-34.465922,-37.096531,-39.582616,-41.913848,-44.080282,-46.072608,-47.881994,-49.500253,-50.919813,-52.133780,-53.135985,-53.921000,-54.484222,-54.821834,-54.930911,-54.809423,-54.456279,}, // NOLINT + {54.634760,54.972739,55.079535,54.956313,54.605166,54.029066,53.231864,52.218221,50.993584,49.564164,47.936852,46.119142,44.119369,41.946201,39.609046,37.117801,34.482682,31.714488,28.824372,25.823812,22.724651,19.538912,16.279003,12.957551,9.587075,6.180612,2.750852,-0.689219,-4.126186,-7.547421,-10.939975,-14.290758,-17.587218,-20.816753,-23.966929,-27.025499,-29.980722,-32.820920,-35.534924,-38.111603,-40.540733,-42.812313,-44.916653,-46.844872,-48.588489,-50.139819,-51.491528,-52.637196,-53.571032,-54.287995,-54.783902,-55.055328,-55.099737,-54.915491,-54.501875,}, // NOLINT + {54.551807,54.942324,55.105069,55.040839,54.751348,54.239157,53.507736,52.561321,51.404971,50.044387,48.486125,46.737304,44.805713,42.699713,40.428216,38.000770,35.427203,32.717922,29.883690,26.935786,23.885401,20.744580,17.525177,14.239728,10.900409,7.519933,4.110990,0.686494,-2.741036,-6.158282,-9.552657,-12.911428,-16.221837,-19.471033,-22.647017,-25.737379,-28.730354,-31.613854,-34.376707,-37.008111,-39.497072,-41.833484,-44.007611,-46.010019,-47.832158,-49.465778,-50.903376,-52.138074,-53.163671,-53.974723,-54.566545,-54.935282,-55.077882,-54.992211,-54.677047,}, // NOLINT + {54.852725,55.153146,55.224516,55.068140,54.686222,54.081842,53.258920,52.222154,50.977059,49.529791,47.887274,46.057035,44.047247,41.866564,39.524323,37.030232,34.394488,31.627727,28.740933,25.745559,22.652946,19.475328,16.224804,12.913371,9.553932,6.159100,2.741399,-0.686347,-4.111197,-7.520694,-10.901739,-14.241908,-17.528349,-20.749364,-23.892078,-26.944803,-29.895664,-32.733367,-35.446755,-38.025094,-40.458011,-42.735688,-44.848577,-46.787894,-48.545196,-50.112632,-51.483156,-52.650228,-53.608053,-54.351563,-54.876480,-55.179301,-55.257392,-55.108984,-54.733196,}, // NOLINT + {54.778706,55.132049,55.259595,55.162287,54.841958,54.301299,53.543844,52.573887,51.396515,50.017585,48.443375,46.681222,44.738797,42.624430,40.346996,37.915780,35.340735,32.631937,29.800393,26.856395,23.811960,20.678410,17.467834,14.191731,10.862808,7.493744,4.096362,0.683583,-2.731715,-6.137240,-9.520214,-12.868124,-16.168392,-19.408513,-22.576583,-25.660498,-28.648284,-31.528606,-34.290161,-36.922018,-39.413814,-41.755191,-43.936656,-45.948895,-47.783350,-49.431860,-50.886937,-52.141711,-53.189973,-54.026273,-54.645845,-55.044767,-55.219920,-55.169036,-54.890736,}, // NOLINT + {55.063819,55.327732,55.364683,55.176108,54.764326,54.132505,53.284627,52.225462,50.960546,49.495962,47.838772,45.996370,43.976869,41.788965,39.441818,36.944981,34.308658,31.543310,28.659789,25.669256,22.583209,19.413461,16.171662,12.870484,9.521951,6.138209,2.732176,-0.683651,-4.096899,-7.494714,-10.864707,-14.194452,-17.471699,-20.683907,-23.819398,-26.866268,-29.812958,-32.648228,-35.361064,-37.940904,-40.377418,-42.661054,-44.782236,-46.732228,-48.502640,-50.085790,-51.474534,-52.662364,-53.643454,-54.412731,-54.965792,-55.299112,-55.409932,-55.296355,-54.957372,}, // NOLINT + {54.998695,55.315864,55.409182,55.279723,54.929442,54.361134,53.578393,52.585592,51.387851,49.991025,48.401458,46.626399,44.673490,42.551045,40.267782,37.833037,35.256510,32.548294,29.718918,26.779314,23.740562,20.614130,17.411833,14.145169,10.826585,7.468151,4.082152,0.681147,-2.722658,-6.116708,-9.488406,-12.825845,-16.116340,-19.347670,-22.508069,-25.585559,-28.568539,-31.445687,-34.205806,-36.838283,-39.332634,-41.678869,-43.867397,-45.889188,-47.735559,-49.398479,-50.870474,-52.144736,-53.215006,-54.075780,-54.722295,-55.150543,-55.357314,-55.340238,-55.097820,}, // NOLINT + {55.268419,55.496825,55.500313,55.280451,54.839658,54.181191,53.309100,52.228191,50.943996,49.462784,47.791240,45.937077,43.908049,41.713231,39.361343,36.861945,34.225142,31.461167,28.580780,25.595099,22.515343,19.353139,16.120144,12.828658,9.490423,6.117878,2.723198,-0.681141,-4.082824,-7.469547,-10.828682,-14.148348,-17.416361,-20.620283,-23.748716,-26.789929,-29.732538,-32.565379,-35.277666,-37.858908,-40.299014,-42.588274,-44.717433,-46.677726,-48.460930,-50.059289,-51.465728,-52.673660,-53.677345,-54.471609,-55.052042,-55.415003,-55.557645,-55.477957,-55.174791,}, // NOLINT + {55.212134,55.494100,55.554107,55.393377,55.013980,54.418791,53.611501,52.596526,51.379009,49.964795,48.360358,46.572784,44.609759,42.479441,40.190624,37.752436,35.174517,32.466862,29.639902,26.704415,23.671141,20.551630,17.357092,14.099897,10.791251,7.443495,4.068511,0.678637,-2.713807,-6.096692,-9.457786,-12.784789,-16.065702,-19.288482,-22.441370,-25.512726,-28.490897,-31.364922,-34.123705,-36.756632,-39.253525,-41.604418,-43.799858,-45.830783,-47.688749,-49.365664,-50.854105,-52.147231,-53.238839,-54.123395,-54.796080,-55.252819,-55.490332,-55.506133,-55.298605,}, // NOLINT + {55.466875,55.660726,55.631666,55.381377,54.912385,54.228018,53.332405,52.230382,50.927501,49.429991,47.744700,45.879092,43.841147,41.639410,39.283049,36.781061,34.143677,31.381083,28.503828,25.522709,22.449225,19.294439,16.070121,12.788015,9.460025,6.097986,2.714380,-0.678735,-4.069219,-7.444987,-10.793680,-14.103523,-17.362230,-20.558250,-23.679940,-26.715691,-29.654217,-32.484689,-35.196412,-37.778998,-40.222475,-42.517247,-44.654152,-46.624477,-48.420021,-50.033125,-51.456681,-52.684193,-53.709820,-54.528380,-55.135412,-55.527197,-55.700800,-55.654097,-55.385808,}, // NOLINT + {55.419391,55.667050,55.694627,55.503463,55.095731,54.474405,53.643244,52.606713,51.369992,49.938957,48.320029,46.520323,44.547472,42.409584,40.115377,37.673858,35.094621,32.387569,29.562933,26.631284,23.603558,20.490805,17.304363,14.055856,10.756904,7.419360,4.055139,0.676322,-2.705161,-6.077186,-9.427857,-12.744688,-16.016372,-19.230826,-22.376382,-25.441586,-28.415213,-31.286139,-34.043502,-36.677009,-39.176349,-41.531747,-43.733854,-45.773722,-47.642869,-49.333413,-50.837743,-52.149211,-53.261565,-54.169231,-54.867391,-55.351808,-55.619216,-55.667011,-55.493450,}, // NOLINT + {55.659514,55.819719,55.758976,55.479085,54.982654,54.273115,53.354625,52.232077,50.911063,49.397760,47.699054,45.822308,43.775534,41.567267,39.206258,36.702002,34.064232,31.303040,28.428762,25.452407,22.384808,19.237396,16.021199,12.748211,9.429853,6.078704,2.705800,-0.676460,-4.056104,-7.421194,-10.759745,-14.059916,-17.309880,-20.498217,-23.612986,-26.643296,-29.577942,-32.406073,-35.117208,-37.701073,-40.147742,-42.447896,-44.592284,-46.572329,-48.379877,-50.007236,-51.447497,-52.694015,-53.740971,-54.583156,-55.216062,-55.635895,-55.839644,-55.825065,-55.590748,}, // NOLINT + {55.620765,55.834996,55.830976,55.610174,55.174860,54.528106,53.673718,52.616224,51.360843,49.913426,48.280448,46.468957,44.486578,42.341284,40.041817,37.597199,35.016726,32.310278,29.487926,26.560168,23.537766,20.431528,17.252931,14.013010,10.723483,7.395996,4.042240,0.674087,-2.696668,-6.058067,-9.398132,-12.705572,-15.968216,-19.174460,-22.313007,-25.372358,-28.341428,-31.209232,-33.965435,-36.599213,-39.100984,-41.460743,-43.669360,-45.717832,-47.597876,-49.301539,-50.821427,-52.150736,-53.283249,-54.213392,-54.936299,-55.447680,-55.744193,-55.823142,-55.682674,}, // NOLINT + {55.846646,55.974065,55.882461,55.573740,55.050611,54.316560,53.375815,52.233312,50.894631,49.365976,47.654265,45.766792,43.711375,41.496965,39.131486,36.624894,33.986653,31.226777,28.355587,25.383695,22.321958,19.181448,15.973485,12.709445,9.400789,6.059682,2.697311,-0.674295,-4.043318,-7.398166,-10.726640,-14.017411,-17.258813,-20.439402,-23.547743,-26.572771,-29.503562,-32.329467,-35.039934,-37.625027,-40.074919,-42.380135,-44.531780,-46.521253,-48.340436,-49.981771,-51.438162,-52.703165,-53.770872,-54.636050,-55.294132,-55.741296,-55.974403,-55.991134,-55.789964,}, // NOLINT + {55.816566,55.998195,55.963375,55.713685,55.251512,54.579987,53.702987,52.625102,51.351545,49.888196,48.241570,46.418641,44.426978,42.274625,39.970108,37.522357,34.940707,32.234897,29.414741,26.490803,23.473550,20.373858,17.202555,13.971254,10.690894,7.373201,4.029670,0.671963,-2.688329,-6.039415,-9.369515,-12.667468,-15.921245,-19.119643,-22.251154,-25.304747,-28.269528,-31.134351,-33.889105,-36.523408,-39.027351,-41.391344,-43.606187,-45.663105,-47.553723,-49.270212,-50.805189,-52.151815,-53.303952,-54.255965,-55.002937,-55.540613,-55.865474,-55.974776,-55.866554,}, // NOLINT + {56.028548,56.124005,56.002323,55.665512,55.116371,54.358457,53.396048,52.234113,50.878232,49.334684,47.610287,45.712346,43.648744,41.427897,39.058361,36.549538,33.910910,31.152357,28.284110,25.316601,22.260576,19.127013,15.926891,12.671725,9.372373,6.041123,2.689033,-0.672196,-4.030893,-7.375514,-10.694217,-13.976058,-17.209210,-20.382149,-23.484105,-26.503979,-29.430988,-32.254610,-34.964497,-37.550809,-40.003624,-42.313878,-44.472558,-46.471187,-48.301706,-49.956558,-51.428710,-52.711687,-53.799597,-54.687161,-55.369754,-55.843562,-56.105291,-56.152548,-55.983694,}, // NOLINT + {56.007068,56.156883,56.092020,55.814170,55.325799,54.630135,53.731116,52.633385,51.342146,49.863344,48.203369,46.369312,44.368552,42.209383,39.899969,37.449235,34.866536,32.161193,29.343354,26.423117,23.410952,20.317521,17.153706,13.930564,10.659247,7.351141,4.017489,0.669871,-2.680160,-6.021174,-9.341529,-12.630223,-15.875506,-19.065980,-22.190741,-25.238704,-28.199033,-31.061104,-33.814565,-36.449233,-38.955347,-41.323462,-43.544379,-45.609437,-47.510361,-49.239293,-50.788862,-52.152477,-53.323710,-54.297039,-55.067483,-55.630745,-55.983248,-56.122141,-56.045374,}, // NOLINT + {56.205481,56.269762,56.118744,55.754536,55.180050,54.398879,53.415363,52.234496,50.861917,49.303848,47.567077,45.658920,43.587326,41.360335,38.986780,36.475841,33.836870,31.079618,28.214226,25.251034,22.200594,19.073712,15.881353,12.634608,9.344574,6.023051,2.680908,-0.670227,-4.018830,-7.353558,-10.662961,-13.935725,-17.160659,-20.326296,-23.421999,-26.436822,-29.360130,-32.181505,-34.890830,-37.478119,-39.933936,-42.249031,-44.414562,-46.422084,-48.263617,-49.931625,-51.419119,-52.719607,-53.827191,-54.736584,-55.443126,-55.942863,-56.232499,-56.309542,-56.172231,}, // NOLINT + {56.192529,56.311288,56.217100,55.911767,55.397856,54.678653,53.758171,52.641049,51.332604,49.838720,48.165806,46.320913,44.311504,42.145519,39.831339,37.377622,34.793916,32.089074,29.273592,26.357020,23.349835,20.262563,17.105829,13.890822,10.628303,7.329507,4.005642,0.667981,-2.672105,-6.003294,-9.314141,-12.593787,-15.830623,-19.013539,-22.131674,-25.174137,-28.130221,-30.989480,-33.741604,-36.376656,-38.884868,-41.256945,-43.483851,-45.556812,-47.467824,-49.208809,-50.772715,-52.152735,-53.342591,-54.336688,-55.130017,-55.718229,-56.097683,-56.265452,-56.219376,}, // NOLINT + {56.377694,56.411539,56.231896,55.840953,55.241746,54.437893,53.433788,52.234504,50.845586,49.273410,47.524572,45.606576,43.527016,41.294215,38.916776,36.403710,33.764316,31.008402,28.145893,25.186901,22.141941,19.021635,15.836812,12.598410,9.317357,6.005260,2.672900,-0.668310,-4.007096,-7.332173,-10.632306,-13.896324,-17.113071,-20.271754,-23.361397,-26.371208,-29.290874,-32.110052,-34.818721,-37.407089,-39.865749,-42.185536,-44.357703,-46.373890,-48.226144,-49.906926,-51.409401,-52.726978,-53.853721,-54.784387,-55.514261,-56.039320,-56.356209,-56.462329,-56.355821,}, // NOLINT + {56.373188,56.461608,56.338785,56.006627,55.467777,54.725609,53.784177,52.648183,51.322878,49.814300,48.128821,46.273395,44.255467,42.082944,39.764136,37.307785,34.722905,32.018882,29.205405,26.292415,23.290107,20.208987,17.059237,13.851982,10.598163,7.308461,3.994080,0.666050,-2.664210,-5.985794,-9.287317,-12.558122,-15.786727,-18.962235,-22.073891,-25.110958,-28.062887,-30.919324,-33.670197,-36.305557,-38.815851,-41.191772,-43.424405,-45.505158,-47.425813,-49.178710,-50.756555,-52.152598,-53.360618,-54.374971,-55.190624,-55.803187,-56.208954,-56.404903,-56.388797,}, // NOLINT + {56.545410,56.549528,56.341930,55.924918,55.301545,54.475558,53.451375,52.233993,50.829272,49.243258,47.482756,45.555058,43.467932,41.229407,38.848094,36.333049,33.693487,30.938766,28.078972,25.124120,22.084515,18.970653,15.793234,12.562963,9.290690,5.987847,2.665014,-0.666439,-3.995639,-7.311299,-10.602348,-13.857807,-17.066904,-20.218456,-23.302045,-26.307056,-29.223167,-32.040156,-34.748185,-37.337558,-39.798949,-42.123409,-44.301933,-46.326543,-48.189239,-49.882554,-51.399552,-52.733742,-53.879256,-54.830654,-55.583298,-56.133081,-56.476582,-56.611107,-56.534697,}, // NOLINT + {56.549269,56.608036,56.457232,56.098840,55.535660,54.771067,53.809187,52.654723,51.313148,49.790194,48.092401,46.226688,44.200520,42.021593,39.698321,37.239301,34.653405,31.950027,29.138695,26.229227,23.231704,20.156448,17.013692,13.814204,10.568688,7.287926,3.982860,0.664410,-2.656437,-5.968608,-9.261023,-12.523176,-15.743706,-18.911992,-22.017299,-25.049084,-27.996953,-30.850661,-33.600227,-36.235887,-38.748181,-41.127867,-43.366080,-45.454343,-47.384534,-49.148964,-50.740386,-52.152111,-53.377808,-54.411944,-55.249399,-55.885733,-56.317191,-56.540677,-56.553853,}, // NOLINT + {56.708838,56.683902,56.448990,56.006495,55.359538,54.511933,53.468144,52.233264,50.812965,49.213465,47.441556,45.504439,43.409802,41.165759,38.780801,36.263805,33.623837,30.870475,28.013413,25.062612,22.028279,18.920712,15.750481,12.528219,9.264540,5.970759,2.657267,-0.664936,-3.984524,-7.290917,-10.573141,-13.820258,-17.021533,-20.166264,-23.244036,-26.244282,-29.156947,-31.971846,-34.679092,-37.269433,-39.733464,-42.062243,-44.247216,-46.279998,-48.152838,-49.858357,-51.389535,-52.740008,-53.903744,-54.875448,-55.650335,-56.224274,-56.593771,-56.756061,-56.709080,}, // NOLINT + {56.720982,56.750746,56.572579,56.188589,55.601588,54.815091,53.833238,52.660859,51.303191,49.766269,48.056482,46.180736,44.146474,41.961515,39.633761,37.172185,34.585361,31.882570,29.073363,26.167370,23.174544,20.105191,16.969071,13.777172,10.539955,7.267939,3.971894,0.662568,-2.648774,-5.951722,-9.235228,-12.488912,-15.701703,-18.862753,-21.961814,-24.988437,-27.932312,-30.783330,-33.531641,-36.167586,-38.681764,-41.065051,-43.308779,-45.404382,-47.343844,-49.119516,-50.724205,-52.151174,-53.394222,-54.447664,-55.306401,-55.965976,-56.422534,-56.672940,-56.714745,}, // NOLINT + {56.868173,56.814824,56.553196,56.085795,55.415795,54.547056,53.484118,52.232051,50.796562,49.183989,47.400919,45.454605,43.352707,41.103197,38.714694,36.195777,33.555585,30.803492,27.949116,25.002296,21.973045,18.871727,15.708586,12.494136,9.238874,5.953951,2.649620,-0.663169,-3.973667,-7.271008,-10.544478,-13.783472,-16.977228,-20.115293,-23.187233,-26.182803,-29.091898,-31.904704,-34.611470,-37.202622,-39.669217,-42.002307,-44.193375,-46.234156,-48.116974,-49.834345,-51.379414,-52.745664,-53.927312,-54.918819,-55.715441,-56.312980,-56.707917,-56.897360,-56.879166,}, // NOLINT + {56.888522,56.889901,56.684967,56.275918,55.665647,54.857724,53.856361,52.666359,51.293100,49.742520,48.021037,46.135514,44.093399,41.902263,39.570331,37.106232,34.518546,31.816501,29.009344,26.106769,23.118561,20.054664,16.925403,13.740925,10.511773,7.248276,3.961216,0.661286,-2.641152,-5.935131,-9.209901,-12.455285,-15.660253,-18.814414,-21.907414,-24.928942,-27.868850,-30.717251,-33.464236,-36.100450,-38.616546,-41.003391,-43.252422,-45.355179,-47.303689,-49.090355,-50.708030,-52.149893,-53.409840,-54.482158,-55.361717,-56.043998,-56.525119,-56.801844,-56.871652,}, // NOLINT + {57.023593,56.942444,56.654698,56.162916,55.470368,54.580982,53.499307,52.230539,50.780260,49.154759,47.360798,45.405520,43.296515,41.041811,38.649746,36.128992,33.488566,30.737753,27.885997,24.942955,21.918935,18.823651,15.667413,12.460670,9.213661,5.937420,2.642044,-0.661560,-3.963083,-7.251603,-10.516730,-13.747466,-16.933813,-20.065518,-23.131570,-26.122547,-29.028261,-31.838894,-34.544979,-37.137047,-39.606123,-41.943396,-44.140400,-46.189019,-48.081494,-49.810507,-51.369106,-52.750896,-53.949931,-54.960819,-55.778699,-56.399347,-56.819145,-57.035160,-57.045143,}, // NOLINT + {57.052054,57.025651,56.794518,56.360943,55.727901,54.899020,53.878567,52.671370,51.282846,49.718903,47.985975,46.090931,44.041077,41.844122,39.508137,37.041525,34.453014,31.751604,28.946552,26.047348,23.063671,20.005426,16.882677,13.705437,10.484017,7.229114,3.950800,0.659651,-2.633697,-5.918821,-9.185009,-12.422330,-15.619641,-18.766775,-21.853981,-24.870585,-27.806593,-30.652392,-33.398140,-36.034572,-38.552430,-40.942810,-43.196939,-45.306662,-47.264038,-49.061432,-50.691722,-52.148222,-53.424700,-54.515474,-55.415400,-56.119904,-56.625051,-56.927532,-57.024753,}, // NOLINT + {57.175264,57.066897,56.753566,56.237932,55.523330,54.613727,53.513737,52.228512,50.763771,49.125742,47.321143,45.357128,43.241183,40.981346,38.585846,36.063325,33.422701,30.673112,27.823968,24.884943,21.865737,18.776408,15.627000,12.427747,9.188871,5.921143,2.634573,-0.660231,-3.952751,-7.232534,-10.489139,-13.712159,-16.891286,-20.016281,-23.076991,-26.063438,-28.965787,-31.774359,-34.479811,-37.072554,-39.544110,-41.885457,-44.088268,-46.144493,-48.046429,-49.786769,-51.358614,-52.755573,-53.971677,-55.001494,-55.840175,-56.483425,-56.927574,-57.169606,-57.207188,}, // NOLINT + {57.211759,57.158134,56.901336,56.443747,55.788411,54.939023,53.899886,52.675874,51.272418,49.695407,47.951281,46.046926,43.989589,41.786933,39.446910,36.978029,34.388636,31.687908,28.884922,25.989025,23.009832,19.957114,16.840752,13.670662,10.457203,7.210370,3.940627,0.658288,-2.626295,-5.902748,-9.160524,-12.389796,-15.579745,-18.720340,-21.801466,-24.813131,-27.745380,-30.588559,-33.332962,-35.969761,-38.489335,-40.883047,-43.142253,-45.258827,-47.224814,-49.032705,-50.675372,-52.146153,-53.438806,-54.547650,-55.467498,-56.193756,-56.722426,-57.050134,-57.174203,}, // NOLINT + {57.323339,57.188302,56.849919,56.310923,55.574720,54.645333,53.527402,52.226118,50.747212,49.096907,47.281982,45.309305,43.186611,40.921680,38.522941,35.998702,33.357902,30.609567,27.762990,24.827737,21.813447,18.729965,15.587265,12.395461,9.164475,5.905096,2.627189,-0.658853,-3.942658,-7.213974,-10.462445,-13.677534,-16.849582,-19.968187,-23.023412,-26.005395,-28.904428,-31.710936,-34.415625,-37.009335,-39.483083,-41.828398,-44.036885,-46.100538,-48.011717,-49.763143,-51.348011,-52.759718,-53.992510,-55.040877,-55.899924,-56.565310,-57.033313,-57.300836,-57.365456,}, // NOLINT + {57.367785,57.287480,57.005535,56.524406,55.847233,54.977751,53.920323,52.679872,51.261760,49.672002,47.916963,46.003473,43.938814,41.730540,39.386663,36.915399,34.325321,31.625283,28.824342,25.931739,22.956955,19.909610,16.799501,13.636753,10.430844,7.191998,3.930692,0.656965,-2.618984,-5.886896,-9.136417,-12.357896,-15.540466,-18.674467,-21.749815,-24.756590,-27.685193,-30.525796,-33.269128,-35.905955,-38.427185,-40.824147,-43.088330,-45.211556,-47.185988,-49.004132,-50.658914,-52.143655,-53.452156,-54.578693,-55.518058,-56.265623,-56.817339,-57.169768,-57.320149,}, // NOLINT + {57.467961,57.306783,56.943848,56.381955,55.624583,54.675813,53.540320,52.223316,50.730505,49.068205,47.243037,45.262029,43.132733,40.862972,38.460941,35.935039,33.294094,30.546998,27.702985,24.771445,21.761930,18.684377,15.548142,12.363595,9.140609,5.889336,2.620037,-0.657568,-3.932795,-7.195661,-10.435729,-13.643631,-16.808602,-19.920960,-22.970654,-25.948358,-28.844104,-31.648609,-34.352500,-36.946938,-39.423010,-41.772196,-43.986173,-46.057095,-47.977303,-49.739569,-51.337050,-52.763343,-54.012474,-55.079008,-55.957999,-56.645079,-57.136453,-57.428964,-57.520100,}, // NOLINT + {57.520275,57.413794,57.107186,56.602993,55.904413,55.015247,53.939901,52.683304,51.250891,49.648624,47.882905,45.960557,43.888683,41.675006,39.327285,36.853821,34.263041,31.563738,28.764782,25.875422,22.904966,19.862993,16.759089,13.602997,10.404447,7.174093,3.920979,0.655723,-2.611727,-5.871324,-9.112814,-12.326362,-15.501754,-18.629327,-21.698892,-24.701007,-27.625869,-30.464043,-33.206071,-35.843052,-38.365869,-40.766056,-43.035064,-45.164800,-47.147491,-48.975683,-50.642321,-52.140748,-53.464760,-54.608626,-55.567125,-56.335576,-56.909885,-57.286548,-57.462726,}, // NOLINT + {57.609259,57.422443,57.035424,56.451087,55.672962,54.705239,53.552482,52.220071,50.713693,49.039601,47.204452,45.215260,43.079510,40.804988,38.399789,35.872305,33.231183,30.485404,27.643862,24.716017,21.711279,18.639255,15.509580,12.332092,9.116902,5.873712,2.612691,-0.656358,-3.923164,-7.177704,-10.410039,-13.610273,-16.768366,-19.874608,-22.919026,-25.892299,-28.784792,-31.587228,-34.290440,-36.885532,-39.363775,-41.716696,-43.936099,-46.014136,-47.943162,-49.716032,-51.325931,-52.766406,-54.031564,-55.115896,-56.014445,-56.722787,-57.237091,-57.554110,-57.671257,}, // NOLINT + {57.669361,57.537200,57.206393,56.679574,55.959997,55.051525,53.958611,52.686212,51.239767,49.625272,47.849083,45.917996,43.839158,41.620122,39.268732,36.793118,34.201677,31.503016,28.706160,25.820026,22.853970,19.817130,16.719305,13.570079,10.379228,7.156288,3.911477,0.654552,-2.604542,-5.855798,-9.089378,-12.295270,-15.463698,-18.584801,-21.648814,-24.646199,-27.567385,-30.403051,-33.143889,-35.780962,-38.305423,-40.708672,-42.982394,-45.118515,-47.109278,-48.947305,-50.625550,-52.137379,-53.476614,-54.637493,-55.614751,-56.403667,-57.000128,-57.400569,-57.602059,}, // NOLINT + {57.747353,57.535380,57.124723,56.518365,55.719918,54.733471,53.563881,52.216367,50.696678,49.011050,47.166113,45.168903,43.026845,40.747681,38.339399,35.810360,33.169124,30.424547,27.585525,24.661381,21.661276,18.594841,15.471602,12.301229,9.093508,5.858280,2.605419,-0.655224,-3.913734,-7.160161,-10.384707,-13.577491,-16.728782,-19.828834,-22.868056,-25.837063,-28.726316,-31.526740,-34.229235,-36.824975,-39.305309,-41.661907,-43.886575,-45.971546,-47.909196,-49.692473,-51.314500,-52.768937,-54.049788,-55.151575,-56.069303,-56.798511,-57.335304,-57.676375,-57.819053,}, // NOLINT + {57.815164,57.657792,57.303230,56.754218,56.014019,55.086623,53.976461,52.688557,51.228383,49.601891,47.815440,45.875824,43.790166,41.565938,39.210940,36.733241,34.141170,31.443292,28.648366,25.765500,22.803535,19.771989,16.680199,13.537692,10.354033,7.138918,3.902186,0.653462,-2.597400,-5.840536,-9.066234,-12.264632,-15.426102,-18.540886,-21.599385,-24.592141,-27.509671,-30.342877,-33.082507,-35.719735,-38.245666,-40.651955,-42.930261,-45.072668,-47.071301,-48.918970,-50.608605,-52.133584,-53.487723,-54.665249,-55.660902,-56.469935,-57.088150,-57.511924,-57.738262,}, // NOLINT + {61.401032,61.601496,61.554224,61.261269,60.725673,59.951503,58.943636,57.707848,56.250713,54.579507,52.702176,50.627358,48.364082,45.922170,43.311747,40.543426,37.628222,34.577480,31.402860,28.116291,24.730045,21.256485,17.708181,14.097919,10.438505,6.742898,3.024091,-0.704848,-4.430902,-8.140990,-11.822167,-15.461463,-19.046075,-22.563278,-26.000603,-29.345536,-32.585957,-35.709933,-38.705822,-41.562284,-44.268277,-46.813192,-49.186807,-51.379413,-53.381612,-55.184876,-56.781019,-58.162566,-59.322753,-60.255540,-60.955682,-61.418786,-61.641355,-61.620849,-61.355755,}, // NOLINT + {61.395902,61.634360,61.629922,61.384260,60.900020,60.180803,59.231078,58.056159,56.662105,55.055719,53.244465,51.236446,49.040322,46.665315,44.121086,41.417745,38.565870,35.576373,32.460432,29.229611,25.895688,22.470724,18.966839,15.396341,11.772253,8.106734,4.412689,0.702889,-3.009784,-6.712432,-10.392237,-14.036338,-17.631989,-21.166575,-24.627467,-28.002204,-31.278651,-34.444631,-37.488418,-40.398443,-43.163457,-45.772565,-48.215243,-50.481427,-52.561397,-54.446138,-56.127046,-57.596169,-58.846221,-59.870626,-60.663554,-61.220022,-61.535929,-61.608067,-61.434278,}, // NOLINT + {61.523751,61.681431,61.593843,61.263279,60.693024,59.887278,58.851117,57.590405,56.111785,54.422558,52.530749,50.444836,48.174038,45.727912,43.116462,40.350287,37.440215,34.397357,31.233253,27.959844,24.588503,21.131856,17.602219,14.012095,10.373832,6.700206,3.003948,-0.702242,-4.405621,-8.093305,-11.752853,-15.371567,-18.936486,-22.435615,-25.856622,-29.187309,-32.415601,-35.529921,-38.518990,-41.371307,-44.076279,-46.623174,-49.002085,-51.203287,-53.217599,-55.036307,-56.651334,-58.055197,-59.241037,-60.202689,-60.934894,-61.432985,-61.693325,-61.713131,-61.490622,}, // NOLINT + {61.525785,61.722262,61.678128,61.395306,60.876684,60.126001,59.147965,57.947842,56.531961,54.907105,53.080772,51.061019,48.856577,46.476488,43.930390,41.228297,38.380644,35.398062,32.291722,29.072933,25.753184,22.344346,18.858404,15.307388,11.703721,8.059633,4.387717,0.700496,-2.989772,-6.670166,-10.328210,-13.951407,-17.527027,-21.043325,-24.487304,-27.846965,-31.110655,-34.266231,-37.301990,-40.206853,-42.969617,-45.579578,-48.026223,-50.299735,-52.390418,-54.289291,-55.987774,-57.477924,-58.752403,-59.804553,-60.628460,-61.219000,-61.571875,-61.683704,-61.552058,}, // NOLINT + {61.638896,61.754767,61.627832,61.260630,60.656646,59.820244,58.756638,57.471788,55.972404,54.265851,52.359996,50.263692,47.985713,45.535706,42.923538,40.159685,37.254813,34.219880,31.066296,27.805567,24.449228,21.009430,17.497960,13.927682,10.310233,6.658156,2.984073,-0.699666,-4.380854,-8.046598,-11.684772,-15.282935,-18.828725,-22.310203,-25.715030,-29.031544,-32.247909,-35.352748,-38.334667,-41.182895,-43.886443,-46.435153,-48.818990,-51.028364,-53.054295,-54.887758,-56.521008,-57.946433,-59.157120,-60.146856,-60.910162,-61.442340,-61.739508,-61.798693,-61.617858,}, // NOLINT + {61.648225,61.803623,61.720709,61.401643,60.849505,60.068252,59.062632,57.838219,56.401215,54.758541,52.917702,50.886809,48.674416,46.289628,43.741948,41.041282,38.197897,35.222406,32.125630,28.918726,25.613030,22.220237,18.751825,15.219910,11.636390,8.013540,4.363246,0.697971,-2.970076,-6.628540,-10.265317,-13.867839,-17.423934,-20.921973,-24.349380,-27.694403,-30.945209,-34.090272,-37.118165,-40.017724,-42.778084,-45.388537,-47.838942,-50.119310,-52.220232,-54.132665,-55.848095,-57.358556,-58.656684,-59.735757,-60.589763,-61.213443,-61.602351,-61.752920,-61.662477,}, // NOLINT + {61.746796,61.821783,61.656438,61.253524,60.616707,59.750567,58.660282,57.352058,55.832624,54.109350,52.190291,50.083813,47.799047,45.345446,42.732873,39.971494,37.071921,34.044994,30.901775,27.653681,24.312147,20.888892,17.395630,13.844648,10.247525,6.616878,2.964456,-0.697428,-4.356579,-8.000854,-11.617966,-15.195864,-18.722803,-22.186761,-25.575760,-28.878327,-32.082826,-35.178091,-38.153003,-40.996752,-43.698847,-46.249084,-48.637490,-50.854576,-52.891287,-54.739242,-56.390078,-57.836341,-59.071110,-60.088092,-60.881693,-61.447052,-61.780157,-61.877810,-61.737755,}, // NOLINT + {61.763508,61.878709,61.757900,61.403489,60.818694,60.007684,58.975362,57.727316,56.269881,54.610027,52.755262,50.713657,48.493710,46.104679,43.555637,40.856590,38.017580,35.049177,31.961899,28.766760,25.475102,22.097999,18.646929,15.133908,11.570311,7.968141,4.339253,0.695596,-2.950653,-6.587557,-10.203392,-13.785606,-17.322650,-20.802478,-24.213572,-27.543945,-30.782233,-33.916857,-36.936749,-39.830945,-42.588664,-45.199498,-47.653188,-49.940183,-52.050827,-53.976280,-55.708033,-57.238191,-58.559193,-59.664356,-60.547618,-61.203574,-61.627613,-61.815983,-61.765818,}, // NOLINT + {61.847728,61.882735,61.679892,61.242158,60.573378,59.678231,58.562155,57.231290,55.692459,53.953079,52.021142,49.905128,47.613998,45.157131,42.544322,39.785581,36.891406,33.872451,30.739624,27.504102,24.177108,20.770198,17.294844,13.762878,10.186047,6.576185,2.945122,-0.695106,-4.332772,-7.955765,-11.552347,-15.110570,-18.618719,-22.065365,-25.438649,-28.727335,-31.920050,-35.005758,-37.973621,-40.812926,-43.513338,-46.064731,-48.457381,-50.681851,-52.729184,-54.590760,-56.258556,-57.725007,-58.983124,-60.026553,-60.849613,-61.447326,-61.815488,-61.950742,-61.850598,}, // NOLINT + {61.871911,61.947767,61.789931,61.400978,60.784373,59.944428,58.886154,57.615189,56.138004,54.461548,52.593397,50.541591,48.314589,45.921402,43.371326,40.674110,37.839667,34.878362,31.800622,28.617276,25.339306,21.977774,18.543964,15.049464,11.505404,7.923449,4.315716,0.693396,-2.931476,-6.547337,-10.142250,-13.704631,-17.222672,-20.685016,-24.079640,-27.395781,-30.621384,-33.745645,-36.757666,-39.646395,-42.401391,-45.012317,-47.469159,-49.762195,-51.882135,-53.820112,-55.567613,-57.116679,-58.459909,-59.590477,-60.502181,-61.189550,-61.647853,-61.873147,-61.862368,}, // NOLINT + {61.941949,61.937878,61.698408,61.226712,60.526804,59.603487,58.462335,57.109496,55.551927,53.797003,51.852750,49.727600,47.430456,44.970622,42.357770,39.601938,36.713141,33.702167,30.579712,27.356534,24.044029,20.653187,17.195449,13.682353,10.125370,6.536100,2.926030,-0.692977,-4.309372,-7.911654,-11.487670,-15.026489,-18.516407,-21.945849,-25.303667,-28.578563,-31.759589,-34.835746,-37.796552,-40.631248,-43.329808,-45.882154,-48.278761,-50.510134,-52.567597,-54.442325,-56.126494,-57.612474,-58.893229,-59.962375,-60.814121,-61.443338,-61.845729,-62.017728,-61.956646,}, // NOLINT + {61.973686,62.011031,61.816989,61.394356,60.746764,59.878570,58.795104,57.501903,56.005592,54.313073,52.432100,50.370407,48.136766,45.739855,43.189000,40.493706,37.663888,34.709733,31.641519,28.469851,25.205519,21.859240,18.442480,14.966078,11.441358,7.879773,4.292606,0.691305,-2.912535,-6.507535,-10.082129,-13.624856,-17.124153,-20.569091,-23.947918,-27.249455,-30.462700,-33.576792,-36.580723,-39.463952,-42.216117,-44.826873,-47.286507,-49.585352,-51.714163,-53.664183,-55.426837,-56.994277,-58.359017,-59.514208,-60.453592,-61.171565,-61.663282,-61.924643,-61.952387,}, // NOLINT + {62.029734,61.987424,61.712182,61.207355,60.477117,59.526409,58.360844,56.986752,55.411027,53.641133,51.685032,49.551157,47.248336,44.785768,42.173132,39.420157,36.536998,33.534038,30.421923,27.211111,23.912795,20.537898,17.097694,13.603005,10.065504,6.496391,2.907177,-0.690913,-4.286468,-7.868000,-11.424219,-14.943806,-18.415496,-21.827967,-25.170581,-28.431950,-31.601251,-34.667845,-37.621574,-40.451604,-43.148102,-45.701208,-48.101383,-50.339402,-52.406411,-54.293916,-55.993887,-57.498786,-58.801526,-59.895660,-60.775302,-61.435271,-61.871075,-62.079000,-62.056159,}, // NOLINT + {62.069080,62.068720,61.839284,61.383747,60.705919,59.810327,58.702233,57.387512,55.872662,54.164741,52.271342,50.200311,47.960263,45.559887,43.008426,40.315332,37.490238,34.543240,31.484531,28.324531,25.073609,21.742715,18.342458,14.884180,11.378523,7.836747,4.269835,0.689372,-2.893774,-6.468261,-10.022863,-13.546180,-17.027324,-20.454754,-23.817733,-27.105169,-30.306317,-33.409926,-36.405876,-39.283495,-42.032507,-44.643092,-47.105245,-49.409546,-51.546872,-53.508325,-55.285721,-56.870919,-58.256536,-59.435667,-60.401976,-61.149785,-61.674105,-61.970695,-62.036121,}, // NOLINT + {62.111320,62.031603,61.721405,61.184249,60.424447,59.447055,58.257800,56.863063,55.269784,53.485421,51.517936,49.375773,47.067572,44.602613,41.990349,39.240401,36.362864,33.367922,30.265889,27.067506,23.783308,20.424135,17.000858,13.524833,10.006492,6.457387,2.888486,-0.688993,-4.263935,-7.825297,-11.361563,-14.862343,-18.315921,-21.712063,-25.039384,-28.287364,-31.445038,-34.502204,-37.448604,-40.273892,-42.968188,-45.521805,-47.925363,-50.169558,-52.245774,-54.145525,-55.860775,-57.383981,-58.708063,-59.826495,-60.733333,-61.423279,-61.891715,-62.134770,-62.149366,}, // NOLINT + {62.158320,62.121044,61.856992,61.369326,60.661998,59.739672,58.607692,57.272037,55.739241,54.016404,52.110973,50.031036,47.784980,45.381445,42.829643,40.138749,37.318536,34.378765,31.329527,28.180969,24.943528,21.627804,18.243896,14.803473,11.316578,7.794331,4.247530,0.687417,-2.875282,-6.429499,-9.964419,-13.468521,-16.931389,-20.341939,-23.689303,-26.962712,-30.151487,-33.245040,-36.232961,-39.104925,-41.850985,-44.460873,-46.925295,-49.234776,-51.380154,-53.352775,-55.144255,-56.746659,-58.152540,-59.354945,-60.347454,-61.124342,-61.680490,-62.011512,-62.113807,}, // NOLINT + {62.186933,62.070607,61.726248,61.157538,60.368901,59.365543,58.153254,56.738467,55.128171,53.329895,51.351421,49.201261,46.888061,44.420927,41.809182,39.062479,36.190714,33.203709,30.111951,26.925682,23.655449,20.311845,16.905608,13.447454,9.948130,6.418800,2.870061,-0.687110,-4.241740,-7.783122,-11.300067,-14.782081,-18.217997,-21.597551,-24.909932,-28.144439,-31.290754,-34.338516,-37.277577,-40.097983,-42.789947,-45.343869,-47.750426,-50.000579,-52.085610,-53.997063,-55.727148,-57.268098,-58.612905,-59.754963,-60.688317,-61.407511,-61.907831,-62.185243,-62.236507,}, // NOLINT + {62.241633,62.168194,61.870276,61.351215,60.615098,59.666719,58.511514,57.155510,55.605317,53.867993,51.951125,49.862585,47.610796,45.204406,42.652319,39.963980,37.148679,34.216181,31.176407,28.039295,24.815146,21.514237,18.146948,14.723917,11.255543,7.752602,4.225701,0.685608,-2.856969,-6.391273,-9.906508,-13.391902,-16.836838,-20.230586,-23.562459,-26.821970,-29.998641,-33.082005,-36.061865,-38.928131,-41.670791,-44.280169,-46.746673,-49.060899,-51.214002,-53.197296,-55.002449,-56.621520,-58.047060,-59.272066,-60.290130,-61.095375,-61.682597,-62.047283,-62.185663,}, // NOLINT + {62.256790,62.104635,61.726868,61.127320,60.310579,59.281842,58.047217,56.612984,54.986205,53.174435,51.185417,49.027648,46.709705,44.240658,41.629666,38.886292,36.020201,33.041301,29.959684,26.785527,23.529148,20.200900,16.811398,13.370941,9.890832,6.380675,2.851785,-0.685346,-4.220089,-7.741566,-11.239427,-14.702909,-18.121475,-21.484840,-24.782237,-28.003394,-31.138466,-34.176564,-37.108370,-39.923826,-42.613460,-45.167295,-47.576648,-49.832383,-51.925850,-53.848760,-55.593006,-57.151173,-58.516111,-59.681192,-60.640367,-61.388111,-61.919568,-62.230601,-62.317783,}, // NOLINT + {62.319217,62.210353,61.879301,61.329548,60.565329,59.591546,58.413726,57.037963,55.470880,53.719583,51.791603,49.694898,47.437709,45.028692,42.476766,39.790875,36.980659,34.055388,31.025094,27.899344,24.688303,21.402238,18.051177,14.645432,11.195390,7.711473,4.204119,0.683859,-2.838839,-6.353411,-9.849593,-13.316208,-16.743437,-20.120596,-23.437121,-26.682859,-29.847227,-32.920715,-35.892542,-38.752920,-41.492265,-44.100743,-46.568993,-48.887852,-51.048345,-53.041943,-54.860265,-56.495493,-57.940136,-59.187161,-60.230099,-61.063009,-61.680586,-62.078189,-62.251897,}, // NOLINT + {62.321092,62.133858,61.723414,61.093750,60.249572,59.196245,57.939750,56.486600,54.843822,53.018912,51.019893,48.854864,46.532515,44.061712,41.451643,38.711683,35.851418,32.880574,29.809146,26.646954,23.404312,20.091433,16.718415,13.295879,9.833614,6.343004,2.833661,-0.683667,-4.198567,-7.700542,-11.179552,-14.624809,-18.026145,-21.373282,-24.655929,-27.864023,-30.987513,-34.016363,-36.940899,-39.751271,-42.438094,-44.992007,-47.403903,-49.664906,-51.766452,-53.700239,-55.458344,-57.033212,-58.417720,-59.605202,-60.589559,-61.365170,-61.927089,-62.271026,-62.393399,}, // NOLINT + {62.391267,62.247689,61.884198,61.304445,60.512786,59.514227,58.314384,56.919401,55.335909,53.571129,51.632474,49.527909,47.265673,44.854269,42.302434,39.619331,36.814225,33.896425,30.875333,27.761002,24.563130,21.291536,17.956479,14.567957,11.136043,7.670927,4.182917,0.682234,-2.820868,-6.315996,-9.792751,-13.241391,-16.651116,-20.011725,-23.313189,-26.545269,-29.697870,-32.761075,-35.724806,-38.579417,-41.315188,-43.922638,-46.392465,-48.715580,-50.883142,-52.886645,-54.717712,-56.368602,-57.831793,-59.100278,-60.167441,-61.027357,-61.674599,-62.104399,-62.312704,}, // NOLINT + {62.380027,62.158438,61.716023,61.056925,60.185964,59.108598,57.830864,56.359351,54.701172,52.863617,50.854780,48.682791,46.356293,43.883959,41.275001,38.538537,35.684195,32.721390,29.660057,26.509859,23.280943,19.983004,16.626426,13.221208,9.777425,6.305706,2.815730,-0.682070,-4.177463,-7.660389,-11.120486,-14.547749,-17.932102,-21.263062,-24.531195,-27.726193,-30.838325,-33.857817,-36.774944,-39.580231,-42.264285,-44.817912,-47.232112,-49.498104,-51.607377,-53.551667,-55.323167,-56.914230,-58.317767,-59.527092,-60.535999,-61.338836,-61.930542,-62.306683,-62.463545,}, // NOLINT + {62.457965,62.280361,61.885109,61.276008,60.457549,59.434810,58.213494,56.799824,55.200504,53.422487,51.473658,49.361431,47.094485,44.680901,42.129521,39.449329,36.649262,33.738759,30.727245,27.624300,24.439315,21.182381,17.863264,14.491535,11.077592,7.630984,4.161999,0.680707,-2.802998,-6.278969,-9.736952,-13.167396,-16.559554,-19.904168,-23.190577,-26.409121,-29.549836,-32.602911,-35.558611,-38.407264,-41.139458,-43.745731,-46.216925,-48.544090,-50.718333,-52.731331,-54.574766,-56.240843,-57.722068,-59.011400,-60.102239,-60.988518,-61.664791,-62.126071,-62.368262,}, // NOLINT + {62.433772,62.178511,61.704823,61.016942,60.119825,59.019083,57.720597,56.231214,54.557947,52.708265,50.690001,48.511456,46.181005,43.707533,41.099679,38.366959,35.518464,32.563778,29.512480,26.374163,23.158724,19.875797,16.535425,13.147498,9.721806,6.268792,2.797958,-0.680542,-4.156689,-7.620514,-11.062149,-14.471533,-17.839046,-21.154268,-24.407852,-27.589976,-30.690742,-33.700794,-36.610540,-39.410590,-42.091756,-44.644932,-47.061205,-49.331847,-51.448572,-53.403067,-55.187438,-56.794238,-58.216286,-59.446884,-60.479765,-61.309197,-61.930044,-62.337724,-62.528393,}, // NOLINT + {62.519481,62.308517,61.882155,61.244341,60.399670,59.353343,58.111113,56.679251,55.064534,53.273901,51.315077,49.195784,46.924186,44.508656,41.957849,39.280588,36.485803,33.582716,30.580588,27.488844,24.316849,21.074416,17.770732,14.415966,11.019622,7.591515,4.141424,0.679173,-2.785326,-6.242314,-9.681709,-13.094172,-16.469380,-19.797658,-23.069217,-26.274298,-29.403177,-32.446198,-35.393665,-38.236540,-40.964958,-43.569922,-46.042275,-48.373157,-50.553869,-52.575975,-54.431442,-56.112213,-57.610982,-58.920647,-60.034568,-60.946597,-61.651191,-62.143346,-62.418746,}, // NOLINT + {62.482491,62.194248,61.689917,60.973891,60.051230,58.927513,57.608957,56.102211,54.414390,52.552865,50.525638,48.340695,46.006576,43.532002,40.925558,38.196561,35.354271,32.407523,29.366223,26.239748,23.037675,19.769653,16.445382,13.074512,9.666730,6.232206,2.780305,-0.679110,-4.136231,-7.581421,-11.004577,-14.396356,-17.746875,-21.046653,-24.285812,-27.454994,-30.544600,-33.545277,-36.447587,-39.242329,-41.920459,-44.473006,-46.891104,-49.166224,-51.289988,-53.254242,-55.051135,-56.673234,-58.113300,-59.364629,-60.420916,-61.276357,-61.925664,-62.364291,-62.588112,}, // NOLINT + {62.575970,62.332285,61.875449,61.209525,60.339247,59.269878,58.007247,56.557671,54.927921,53.125119,51.156692,49.030500,46.754633,44.337398,41.787324,39.113135,36.323717,33.428063,30.435329,27.354808,24.195658,20.967380,17.679532,14.341395,10.962480,7.552663,4.121142,0.677766,-2.767765,-6.205971,-9.626992,-13.021673,-16.379892,-19.692220,-22.949017,-26.140732,-29.257839,-32.290935,-35.230366,-38.067042,-40.791662,-43.395111,-45.868430,-48.202842,-50.389674,-52.420626,-54.287581,-55.982717,-57.498543,-58.828012,-59.964447,-60.901660,-61.633990,-62.156355,-62.464304,}, // NOLINT + {62.526336,62.205754,61.671415,60.927856,59.980195,58.834157,57.495960,55.972296,54.270272,52.397366,50.361392,48.170445,45.832930,43.357401,40.752554,38.027406,35.191074,32.252618,29.221265,26.106554,22.917808,19.664506,16.356121,13.002226,9.612166,6.195979,2.762769,-0.677645,-4.116039,-7.542502,-10.947651,-14.322018,-17.655941,-20.940048,-24.165015,-27.321337,-30.399719,-33.390966,-36.285843,-39.075131,-41.750240,-44.301961,-46.721718,-49.001089,-51.131611,-53.105262,-54.914311,-56.551218,-58.008825,-59.280376,-60.359546,-61.240386,-61.917642,-62.386511,-62.642855,}, // NOLINT + {62.627587,62.351795,61.865083,61.171648,60.276305,59.184436,57.901908,56.435058,54.790776,52.976062,50.998452,48.865660,46.585773,44.167026,41.617859,38.946715,36.162890,33.274712,30.291398,27.221980,24.075647,20.861583,17.589106,14.267367,10.905880,7.514066,4.101114,0.676417,-2.750307,-6.169940,-9.572770,-12.949843,-16.291279,-19.587741,-22.829895,-26.008338,-29.113718,-32.136753,-35.068104,-37.898704,-40.619401,-43.221232,-45.695282,-48.032985,-50.225720,-52.265235,-54.143268,-55.852311,-57.384764,-58.733542,-59.891971,-60.853775,-61.613265,-62.165220,-62.505091,}, // NOLINT + {62.565457,62.213155,61.649414,60.878890,59.906810,58.738951,57.381602,55.841475,54.125704,52.241741,50.197386,48.000694,45.659948,43.183705,40.580557,37.859362,35.029091,32.098782,29.077498,25.974601,22.799002,19.560351,16.267721,12.930588,9.558082,6.160041,2.745383,-0.676437,-4.096101,-7.504171,-10.891278,-14.248343,-17.565857,-20.834579,-24.045366,-27.188945,-30.256194,-33.238004,-36.125196,-38.909329,-41.581043,-44.131809,-46.553013,-48.836244,-50.973324,-52.956038,-54.776856,-56.428182,-57.902879,-59.194158,-60.295624,-61.201380,-61.905959,-62.404511,-62.692766,}, // NOLINT + {62.674464,62.367167,61.851159,61.130781,60.210906,59.097042,57.795110,56.311516,54.653019,52.826807,50.840278,48.701214,46.417557,43.997501,41.449376,38.781742,36.003389,33.122531,30.148651,27.090384,23.956744,20.756777,17.499622,14.194387,10.850011,7.476012,4.081347,0.675315,-2.732997,-6.134224,-9.519011,-12.878642,-16.203377,-19.484166,-22.711787,-25.877020,-28.970750,-31.983741,-34.906996,-37.731438,-40.448135,-43.048158,-45.522867,-47.863587,-50.061875,-52.109511,-53.998488,-55.720994,-57.269625,-58.637254,-59.817161,-60.803046,-61.589109,-62.170066,-62.541237,}, // NOLINT + {62.599985,62.216545,61.623991,60.827080,59.831098,58.641921,57.265887,55.709710,53.980621,52.085919,50.033496,47.831310,45.487607,43.010800,40.409492,37.692420,34.868261,31.946151,28.934801,25.843469,22.681051,19.456978,16.180073,12.859362,9.504445,6.124407,2.728021,-0.675403,-4.076423,-7.466250,-10.835727,-14.175475,-17.476615,-20.730109,-23.926874,-27.057678,-30.113784,-33.086258,-35.966016,-38.744450,-41.412776,-43.962498,-46.384874,-48.671797,-50.815072,-52.806586,-54.638773,-56.304115,-57.795450,-59.105989,-60.229295,-61.159376,-61.890733,-62.418399,-62.737978,}, // NOLINT + {62.716726,62.378495,61.833767,61.086968,60.143114,59.007741,57.686860,56.186857,54.514740,52.677245,50.682171,48.537128,46.249840,43.828697,41.281789,38.617602,35.844705,32.971645,30.007037,26.959872,23.838889,20.652953,17.411014,14.121950,10.794558,7.438288,4.061837,0.674335,-2.715747,-6.098744,-9.465682,-12.808121,-16.116237,-19.381429,-22.594599,-25.746679,-28.828785,-31.831832,-34.746906,-37.565146,-40.277711,-42.875872,-45.350974,-47.694532,-49.898154,-51.953664,-53.853110,-55.588754,-57.153140,-58.539156,-59.740058,-60.749493,-61.561587,-62.170994,-62.572874,}, // NOLINT + {62.630014,62.216056,61.595234,60.772435,59.753090,58.543082,57.148780,55.577036,53.834902,51.929870,49.869656,47.662239,45.315781,42.838628,40.239265,37.526295,34.708420,31.794416,28.793135,25.713479,22.564218,19.354454,16.093107,12.789102,9.451224,6.088965,2.710814,-0.674036,-4.056995,-7.428756,-10.780456,-14.103289,-17.388196,-20.626545,-23.809224,-26.927466,-29.972466,-32.935392,-35.807694,-38.580534,-41.245378,-43.793746,-46.217241,-48.507624,-50.656765,-52.656805,-54.500026,-56.178999,-57.686529,-59.015895,-60.160549,-61.114465,-61.872058,-62.428281,-62.778614,}, // NOLINT + {62.754495,62.385894,61.812972,61.040278,60.072934,58.916530,57.577139,56.061279,54.375622,52.527412,50.524022,48.373153,46.082640,43.660518,41.115069,38.454361,35.687029,32.821585,29.866471,26.830380,23.721996,20.550014,17.323292,14.050241,10.740049,7.401144,4.042558,0.673026,-2.698590,-6.063525,-9.412751,-12.737882,-16.029732,-19.279425,-22.478269,-25.617335,-28.687809,-31.680886,-34.587788,-37.399916,-40.108106,-42.704228,-45.179584,-47.525757,-49.734506,-51.797572,-53.707162,-55.455604,-57.035297,-58.439274,-59.660692,-60.693209,-61.530785,-62.168061,-62.600111,}, // NOLINT + {62.655685,62.211729,61.563228,60.715068,59.672826,58.442444,57.030350,55.443410,53.688530,51.773518,49.705813,47.493405,45.144401,42.667104,40.069769,37.361056,34.549481,31.643688,28.652350,25.584250,22.448125,19.252674,16.006754,12.719125,9.398385,6.053784,2.693670,-0.673197,-4.037795,-7.391744,-10.726033,-14.031941,-17.300676,-20.523848,-23.692583,-26.798234,-29.832155,-32.785701,-35.650334,-38.417492,-41.078734,-43.625659,-46.050012,-48.343603,-50.498459,-52.506614,-54.360581,-56.052815,-57.576194,-58.923897,-60.089417,-61.066682,-61.850007,-62.434242,-62.814785,}, // NOLINT + {62.787878,62.389436,61.788847,60.990782,60.000402,58.823433,57.465895,55.934487,54.235827,52.377137,50.365790,48.209416,45.915817,43.492942,40.948877,38.291960,35.530363,32.672479,29.726843,26.701939,23.606008,20.447873,17.236120,13.979150,10.685430,7.364292,4.023502,0.671885,-2.681488,-6.028528,-9.360184,-12.668301,-15.943895,-19.178209,-22.362800,-25.488801,-28.547715,-31.530821,-34.429456,-37.235163,-39.939201,-42.533161,-45.008615,-47.357166,-49.570852,-51.641135,-53.560598,-55.321380,-56.916097,-58.337596,-59.579087,-60.634138,-61.496750,-62.161384,-62.623054,}, // NOLINT + {62.677088,62.203680,61.527956,60.654974,59.590302,58.340004,56.910513,55.308682,53.541650,51.616703,49.541902,47.324740,44.973388,42.496028,39.901021,37.196591,34.391453,31.493752,28.512440,25.455894,22.332767,19.151539,15.921026,12.649626,9.345895,6.018863,2.676606,-0.672047,-4.018807,-7.354958,-10.671497,-13.960858,-17.213744,-20.421925,-23.576805,-26.669932,-29.692751,-32.636806,-35.493828,-38.255263,-40.912762,-43.458143,-45.883171,-48.179807,-50.340028,-52.356110,-54.220443,-55.925512,-57.464354,-58.829998,-60.015951,-61.016075,-61.824623,-62.436377,-62.846602,}, // NOLINT + {62.816973,62.389204,61.761447,60.938474,59.925553,58.728450,57.353291,55.806645,54.095330,52.226472,50.207415,48.045772,45.749288,43.325853,40.783467,38.130297,35.374377,32.524320,29.588080,26.574110,23.490818,20.346511,17.149700,13.908637,10.631661,7.327722,4.004655,0.671055,-2.664495,-5.993719,-9.307949,-12.599202,-15.858523,-19.077607,-22.247912,-25.361046,-28.408413,-31.381627,-34.271817,-37.071326,-39.770918,-42.362579,-44.837938,-47.188755,-49.406851,-51.484391,-53.413354,-55.186188,-56.795507,-58.234128,-59.495246,-60.572422,-61.459550,-62.151043,-62.641799,}, // NOLINT + {62.694325,62.191979,61.489549,60.592188,59.505561,58.235793,56.789273,55.173017,53.393984,51.459731,49.377900,47.156167,44.802572,42.325446,39.732689,37.032765,34.233960,31.344673,28.373294,25.328287,22.218085,19.051103,15.835791,12.580579,9.293720,5.984076,2.659577,-0.671234,-4.000029,-7.318411,-10.617836,-13.890502,-17.127433,-20.320715,-23.461818,-26.542430,-29.554158,-32.488839,-35.338095,-38.093769,-40.747383,-43.291056,-45.716587,-48.016040,-50.181423,-52.205103,-54.079469,-55.797155,-57.351014,-58.734204,-59.940146,-60.962671,-61.795991,-62.434752,-62.874151,}, // NOLINT + {62.841869,62.385272,61.730832,60.883402,59.848393,58.631564,57.239147,55.677684,53.954010,52.075295,50.048889,47.882171,45.582997,43.159138,40.618598,37.969290,35.219387,32.376913,29.450121,26.446984,23.376403,20.245876,17.063893,13.838671,10.578296,7.291492,3.986011,0.670248,-2.647539,-5.959097,-9.256011,-12.530478,-15.773824,-18.977582,-22.133792,-25.233979,-28.269834,-31.233046,-34.115204,-36.908019,-39.603024,-42.192390,-44.667523,-47.020373,-49.242891,-51.327176,-53.265383,-55.050005,-56.673498,-58.128850,-59.409211,-60.508043,-61.419230,-62.137089,-62.656435,}, // NOLINT + {62.707459,62.176669,61.448025,60.526756,59.418595,58.129660,56.666605,55.036175,53.245563,51.302212,49.213576,46.987616,44.632122,42.155231,39.565023,36.869560,34.077220,31.196235,28.234828,25.201335,22.104055,18.951182,15.751065,12.511914,9.241828,5.949477,2.642632,-0.670422,-3.981435,-7.282237,-10.564571,-13.820662,-17.041879,-20.220249,-23.347557,-26.415661,-29.416375,-32.341568,-35.183077,-37.932726,-40.582512,-43.124332,-45.550205,-47.852223,-50.022571,-52.053575,-53.937711,-55.667612,-57.236177,-58.636502,-59.862028,-60.906525,-61.764133,-62.429435,-62.897526,}, // NOLINT + {62.862655,62.377712,61.697057,60.825622,59.768934,58.532800,57.123490,55.547600,53.811896,51.923596,49.889974,47.718526,45.416893,42.992833,40.454180,37.808871,35.064838,32.230211,29.312928,26.321049,23.262715,20.145868,16.978686,13.769199,10.525317,7.255554,3.967550,0.669457,-2.630623,-5.924639,-9.204337,-12.462098,-15.689352,-18.878119,-22.020016,-25.107547,-28.131907,-31.085162,-33.958959,-36.745225,-39.435933,-42.022575,-44.497294,-46.851986,-49.078693,-51.169486,-53.116638,-54.912627,-56.550067,-58.021789,-59.320966,-60.441040,-61.375824,-62.119591,-62.667041,}, // NOLINT + {62.716584,62.157842,61.403379,60.458682,59.329407,58.021827,56.542473,54.898251,53.096346,51.144101,49.049061,46.819007,44.461762,41.985293,39.397622,36.706716,33.921035,31.048320,28.096967,25.074985,21.990549,18.851801,15.666777,12.443603,9.190180,5.915031,2.625692,-0.669662,-3.963028,-7.246426,-10.511684,-13.751300,-16.956819,-20.120361,-23.233925,-26.289606,-29.279288,-32.194953,-35.028644,-37.772340,-40.418074,-42.957904,-45.383939,-47.688351,-49.863419,-51.901491,-53.795092,-55.536875,-57.119802,-58.536904,-59.781607,-60.847642,-61.729114,-62.420504,-62.916804,}, // NOLINT + {62.879392,62.366553,61.660082,60.765151,59.687185,58.432136,57.006299,55.416262,53.668900,51.771308,49.730760,47.554784,45.250867,42.826735,40.290147,37.648939,34.911009,32.084206,29.176342,26.195517,23.149619,20.046444,16.894013,13.700183,10.472702,7.219925,3.949253,0.668736,-2.613755,-5.890316,-9.152887,-12.394066,-15.605438,-18.779085,-21.907186,-24.981671,-27.994546,-30.937807,-33.803306,-36.582978,-39.268923,-41.852960,-44.327188,-46.683497,-48.914068,-51.011231,-52.967074,-54.774182,-56.425174,-57.912912,-59.230510,-60.371417,-61.329379,-62.098595,-62.673683,}, // NOLINT + {62.721764,62.135505,61.355746,60.387988,59.238009,57.912103,56.416871,54.759207,52.946276,50.985408,48.884181,46.650258,44.291457,41.815557,39.230591,36.544519,33.765310,30.901029,27.959643,24.949154,21.877565,18.752854,15.582866,12.375605,9.138737,5.880718,2.608807,-0.668973,-3.944791,-7.210864,-10.459148,-13.682417,-16.872240,-20.021053,-23.121101,-26.164162,-29.142772,-32.048951,-34.874832,-37.612391,-40.253983,-42.791692,-45.217753,-47.524350,-49.703855,-51.748820,-53.651569,-55.404955,-57.001860,-58.435377,-59.698879,-60.786063,-61.690957,-62.407990,-62.932053,}, // NOLINT + {62.892154,62.351865,61.620133,60.701987,59.603145,58.329556,56.887544,55.283683,53.524967,51.618402,49.571212,47.390842,45.084843,42.660813,40.126441,37.489425,34.757575,31.938628,29.040337,26.070561,23.037043,19.947550,16.809816,13.631644,10.420425,7.184530,3.931125,0.668080,-2.596908,-5.856147,-9.101843,-12.326354,-15.521762,-18.680493,-21.794636,-24.856296,-27.857680,-30.790876,-33.647997,-36.421141,-39.102237,-41.683472,-44.157007,-46.514843,-48.749201,-50.852346,-52.816625,-54.634557,-56.298792,-57.802167,-59.137820,-60.299182,-61.279913,-62.074140,-62.676425,}, // NOLINT +}, // NOLINT +{ + {17.081671,14.738231,12.388497,10.041690,7.707086,5.393961,3.111520,0.868653,-1.325757,-3.463063,-5.534735,-7.532727,-9.449117,-11.276378,-13.007299,-14.635076,-16.153302,-17.555992,-18.837667,-19.993250,-21.018207,-21.908517,-22.660643,-23.271624,-23.739147,-24.061263,-24.236730,-24.264849,-24.145499,-23.879133,-23.466786,-22.910053,-22.211113,-21.372689,-20.398086,-19.291061,-18.055964,-16.697641,-15.221430,-13.633132,-11.938859,-10.145364,-8.259693,-6.289218,-4.241687,-2.125170,0.052014,2.281301,4.553876,6.860805,9.192952,11.541116,13.896013,16.248324,18.588729,}, // NOLINT + {18.415208,16.080185,13.733918,11.385691,9.044740,6.720238,4.421414,2.157205,-0.063467,-2.231902,-4.339602,-6.378306,-8.340059,-10.217130,-12.002268,-13.688494,-15.269018,-16.737904,-18.089395,-19.318160,-20.419435,-21.388922,-22.222868,-22.918008,-23.471671,-23.881641,-24.146432,-24.264951,-24.236768,-24.062006,-23.741361,-23.276083,-22.668021,-21.919552,-21.033585,-20.013622,-18.863689,-17.588127,-16.192123,-14.681051,-13.060828,-11.337810,-9.518755,-7.610733,-5.621304,-3.558213,-1.429563,0.756302,2.990800,5.265202,7.570398,9.897452,12.237379,14.580699,16.918319,}, // NOLINT + {16.792424,14.443881,12.090195,9.740599,7.404298,5.090430,2.808014,0.565998,-1.626849,-3.762010,-5.831128,-7.826142,-9.739298,-11.563097,-13.290480,-14.914608,-16.429297,-17.828543,-19.106991,-20.259507,-21.281763,-22.169729,-22.919905,-23.529424,-23.995858,-24.317413,-24.492818,-24.521381,-24.402985,-24.138080,-23.727665,-23.173333,-22.477239,-21.642022,-20.670971,-19.567817,-18.336867,-16.982809,-15.510978,-13.927057,-12.237198,-10.447959,-8.566298,-6.599540,-4.555336,-2.441607,-0.266634,1.961124,4.233026,6.540062,8.873413,11.223774,13.582064,15.939087,18.285527,}, // NOLINT + {18.119151,15.777926,13.426777,11.074845,8.731458,6.405546,4.106215,1.842393,-0.377108,-2.543669,-4.648921,-6.684630,-8.643076,-10.516480,-12.297754,-13.979883,-15.556358,-17.021281,-18.368755,-19.593696,-20.691348,-21.657527,-22.488468,-23.180919,-23.732303,-24.140480,-24.403870,-24.521476,-24.492852,-24.318123,-23.997975,-23.533655,-22.926976,-22.180304,-21.296489,-20.279006,-19.131789,-17.859277,-16.466355,-14.958581,-13.341652,-11.621835,-9.805895,-7.900772,-5.913960,-3.853088,-1.726183,0.458485,2.692475,4.967039,7.273379,9.602516,11.945389,14.292896,16.635828,}, // NOLINT + {16.514115,14.160115,11.802131,9.449385,7.110918,4.795789,2.512964,0.271224,-1.920630,-4.054264,-6.121412,-8.114081,-10.024524,-11.845439,-13.569793,-15.190871,-16.702480,-18.098774,-19.374382,-20.524337,-21.544242,-22.430148,-23.178667,-23.786873,-24.252416,-24.573508,-24.748899,-24.777900,-24.660391,-24.396809,-23.988160,-23.435991,-22.742434,-21.910091,-20.942281,-19.842533,-18.615233,-17.264933,-15.796983,-14.216928,-12.530860,-10.745270,-8.867032,-6.903398,-4.861865,-2.750380,-0.577038,1.649751,3.921402,6.229140,8.564055,10.917092,13.279236,15.641125,17.993817,}, // NOLINT + {17.834060,15.486361,13.130172,10.774279,8.428000,6.100202,3.799915,1.536014,-0.682843,-2.848119,-4.951493,-6.984855,-8.940524,-10.810886,-12.588798,-14.267463,-15.840445,-17.301730,-18.645733,-19.867262,-20.961734,-21.924909,-22.753132,-23.443233,-23.992587,-24.399102,-24.661232,-24.777989,-24.748940,-24.574199,-24.254455,-23.790937,-23.185447,-22.440296,-21.558374,-20.543017,-19.398165,-18.128232,-16.738049,-15.233004,-13.618836,-11.901730,-10.088328,-8.185565,-6.200770,-4.141567,-2.015841,0.168193,2.402171,4.677480,6.985358,9.316932,11.663222,14.015185,16.363760,}, // NOLINT + {16.245916,13.886108,11.523492,9.167273,6.826180,4.509392,2.225631,-0.016310,-2.207700,-4.340353,-6.406042,-8.396862,-10.305201,-12.123761,-13.845592,-15.464119,-16.973164,-18.366911,-19.640131,-20.787839,-21.805738,-22.689907,-23.436956,-24.044047,-24.508849,-24.829564,-25.004984,-25.034411,-24.917721,-24.655345,-24.248291,-23.698080,-23.006793,-22.177074,-21.212032,-20.115357,-18.891254,-17.544340,-16.079726,-14.503031,-12.820224,-11.037735,-9.162367,-7.201277,-5.161908,-3.052098,-0.879854,1.346499,3.618434,5.927278,8.264249,10.620250,12.986403,15.353590,17.712731,}, // NOLINT + {17.559137,15.204931,12.843234,10.483124,8.133558,5.803510,3.501860,1.237369,-0.981338,-3.145820,-5.247841,-7.279413,-9.232811,-11.100618,-12.875739,-14.551430,-16.121361,-17.579561,-18.920492,-20.139043,-21.230684,-22.191215,-23.017042,-23.705002,-24.252529,-24.657541,-24.918523,-25.034492,-25.005023,-24.830238,-24.510809,-24.047964,-23.443473,-22.699631,-21.819300,-20.805747,-19.662960,-18.395186,-17.007285,-15.504541,-13.892662,-12.177777,-10.366422,-8.465476,-6.482197,-4.424124,-2.299084,-0.115098,2.119286,4.395783,6.705629,9.039942,11.390095,13.746840,16.101303,}, // NOLINT + {15.986909,13.621204,11.253734,8.893678,6.549529,4.230568,1.945526,-0.297064,-2.488573,-4.620741,-6.685482,-8.674982,-10.581687,-12.398385,-14.118194,-15.734596,-17.241497,-18.633142,-19.904286,-21.050123,-22.066313,-22.948979,-23.694825,-24.300975,-24.765157,-25.085591,-25.261071,-25.290909,-25.174983,-24.913723,-24.508097,-23.959639,-23.270391,-22.442968,-21.480440,-20.386468,-19.165181,-17.821168,-16.359475,-14.785652,-13.105656,-11.325789,-9.452727,-7.493637,-5.455954,-3.347196,-1.175653,1.050714,3.323391,5.633793,7.973112,10.332506,12.703044,15.075732,17.441568,}, // NOLINT + {17.293606,14.932640,12.565273,10.200637,7.847464,5.514827,3.211377,0.945848,-1.273133,-3.437314,-5.538437,-7.568670,-9.520339,-11.386078,-13.158898,-14.832098,-16.399409,-17.854924,-19.193196,-20.409197,-21.498317,-22.456534,-23.280217,-23.966267,-24.512152,-24.915815,-25.175747,-25.290986,-25.261111,-25.086244,-24.767053,-24.304751,-23.701088,-22.958348,-22.079333,-21.067358,-19.926246,-18.660310,-17.274288,-15.773437,-14.163402,-12.450290,-10.640511,-8.740924,-6.758673,-4.701242,-2.576399,-0.392161,1.843229,4.121340,6.433609,8.771170,11.125334,13.487153,15.847699,}, // NOLINT + {15.736486,13.364624,10.992025,8.627643,6.280242,3.958779,1.671922,-0.571722,-2.763728,-4.895932,-6.960134,-8.948745,-10.854310,-12.669595,-14.387797,-16.002524,-17.507701,-18.897567,-20.167029,-21.311289,-22.326045,-23.207480,-23.952292,-24.557678,-25.021359,-25.341590,-25.517159,-25.547398,-25.432182,-25.171931,-24.767607,-24.220681,-23.533296,-22.707865,-21.747583,-20.655970,-19.437137,-18.095607,-16.636450,-15.065074,-13.387395,-11.609623,-9.738490,-7.780976,-5.744420,-3.636454,-1.464981,0.761778,3.035695,5.348006,7.690104,10.053186,12.428379,14.806754,17.179354,}, // NOLINT + {17.036800,14.668920,12.295741,9.926213,7.569214,5.233497,2.927920,0.661013,-1.558728,-3.723075,-5.823710,-7.853095,-9.803469,-11.667606,-13.438556,-15.109697,-16.674826,-18.128054,-19.464046,-20.677768,-21.764739,-22.720888,-23.542695,-24.227040,-24.771486,-25.173932,-25.432912,-25.547472,-25.517199,-25.342214,-25.023187,-24.561314,-23.958297,-23.216489,-22.338566,-21.327917,-20.188178,-18.923705,-17.539208,-16.039897,-14.431351,-12.719530,-10.910907,-9.012221,-7.030573,-4.973339,-2.848270,-0.663258,1.573492,3.853606,6.168576,8.509726,10.868303,13.235466,15.602301,}, // NOLINT + {15.494008,13.115803,10.737773,8.368827,6.017815,3.693468,1.404468,-0.840680,-3.033605,-5.166185,-7.230359,-9.218561,-11.123355,-12.937650,-14.654695,-16.268090,-17.771848,-19.160355,-20.428453,-21.571400,-22.584976,-23.465417,-24.209355,-24.814160,-25.277455,-25.597555,-25.773248,-25.803880,-25.689322,-25.429987,-25.026833,-24.481330,-23.795517,-22.971897,-22.013544,-20.923977,-19.707283,-18.367921,-16.910867,-15.341526,-13.665753,-11.889689,-10.020001,-8.063607,-6.027768,-3.920046,-1.748309,0.479405,2.754798,5.069387,7.414597,9.781673,12.161822,14.546104,16.925704,}, // NOLINT + {16.788223,14.413157,12.033866,9.659267,7.298087,4.959093,2.650973,0.382303,-1.838591,-4.003413,-6.104129,-8.133012,-10.082534,-11.945483,-13.714935,-15.384454,-16.947772,-18.399124,-19.733208,-20.944948,-22.030041,-22.984409,-23.804558,-24.487440,-25.030560,-25.431912,-25.690019,-25.803950,-25.773289,-25.598161,-25.279227,-24.817674,-24.215222,-23.474108,-22.597080,-21.587407,-20.448819,-19.185539,-17.802255,-16.304097,-14.696601,-12.985763,-11.177886,-9.279693,-7.298208,-5.240747,-3.115067,-0.928900,1.309583,3.592079,5.910215,8.255160,10.618387,12.991206,15.364664,}, // NOLINT + {15.259094,12.874165,10.490457,8.116706,5.761691,3.434172,1.142657,-1.104361,-3.298536,-5.431915,-7.496487,-9.484662,-11.389101,-13.202791,-14.919031,-16.531479,-18.034193,-19.421623,-20.688647,-21.830589,-22.843236,-23.722843,-24.466168,-25.070450,-25.533463,-25.853489,-26.029339,-26.060354,-25.946406,-25.687910,-25.285801,-24.741545,-24.057144,-23.235095,-22.278425,-21.190646,-19.975689,-18.638198,-17.182940,-15.615249,-13.940929,-12.166225,-10.297569,-8.341881,-6.306347,-4.198500,-2.026081,0.202894,2.480200,4.797445,7.146075,9.517469,11.902707,14.293166,16.679947,}, // NOLINT + {16.547148,14.164791,11.779309,9.399281,7.033684,4.691019,2.380057,0.109231,-2.113115,-4.278838,-6.379958,-8.408768,-10.357861,-12.219975,-13.988408,-15.656581,-17.218416,-18.668228,-20.000648,-21.210819,-22.294353,-23.247130,-24.065882,-24.747403,-25.289378,-25.689748,-25.947077,-26.060420,-26.029380,-25.854080,-25.535169,-25.073846,-24.471791,-23.731237,-22.854904,-21.846020,-20.708297,-19.445921,-18.063531,-16.566219,-14.959478,-13.249200,-11.441688,-9.543626,-7.561967,-5.503937,-3.377176,-1.189486,1.051096,3.336324,5.657796,8.006979,10.375225,12.753853,15.134032,}, // NOLINT + {15.030911,12.639207,10.249582,7.870845,5.511493,3.180452,0.886093,-1.363143,-3.559033,-5.693529,-7.758814,-9.747327,-11.651791,-13.465230,-15.181007,-16.792847,-18.294835,-19.681483,-20.947710,-22.088904,-23.100811,-23.979798,-24.722624,-25.326555,-25.789376,-26.109399,-26.285430,-26.316819,-26.203445,-25.945692,-25.544522,-25.001370,-24.318207,-23.497520,-22.542302,-21.456026,-20.242676,-18.906607,-17.452733,-15.886411,-14.213284,-12.439484,-10.571487,-8.616123,-6.580532,-4.472177,-2.298696,-0.068101,2.211461,4.531664,6.884007,9.259847,11.650604,14.047408,16.441505,}, // NOLINT + {16.313138,13.923306,11.531311,9.145753,6.775408,4.428901,2.114776,-0.158517,-2.382708,-4.549719,-6.651548,-8.680649,-10.629607,-12.491326,-14.259022,-15.926269,-17.487024,-18.935558,-20.266686,-21.475460,-22.557590,-23.509110,-24.326573,-25.007019,-25.547961,-25.947468,-26.204083,-26.316883,-26.285472,-26.109967,-25.791026,-25.329844,-24.728062,-23.987910,-23.112084,-22.103796,-20.966691,-19.704953,-18.323171,-16.826382,-15.220045,-13.510057,-11.702599,-9.804280,-7.822035,-5.763094,-3.634949,-1.445381,0.797616,3.085904,5.411087,7.764716,10.138159,12.522847,14.909999,}, // NOLINT + {14.809159,12.410463,10.014694,7.630568,5.266804,2.931913,0.634403,-1.617390,-3.815269,-5.951267,-8.017620,-10.006815,-11.911585,-13.725161,-15.440808,-17.052330,-18.553927,-19.940037,-21.205719,-22.346346,-23.357768,-24.236315,-24.978794,-25.582491,-26.045217,-26.365286,-26.541523,-26.573280,-26.460431,-26.203384,-25.803028,-25.260837,-24.578750,-23.759227,-22.805247,-21.720228,-20.508106,-19.173279,-17.720567,-16.155222,-14.482920,-12.709700,-10.842013,-8.886620,-6.850608,-4.741310,-2.566508,-0.333968,1.948175,4.271606,6.628034,9.008647,11.404989,13.808316,16.209976,}, // NOLINT + {16.085607,13.688238,11.289564,8.898255,6.522974,4.172266,1.854715,-0.421349,-2.647689,-4.816223,-6.919199,-8.948942,-10.898139,-12.759755,-14.527085,-16.193690,-17.753610,-19.201301,-20.531273,-21.738973,-22.820006,-23.770401,-24.586816,-25.266290,-25.806342,-26.205083,-26.461045,-26.573339,-26.541565,-26.365846,-26.046829,-25.585676,-24.984057,-24.244162,-23.368651,-22.360762,-21.224078,-19.962693,-18.581309,-17.084766,-15.478554,-13.768499,-11.960713,-10.061878,-8.078753,-6.018533,-3.888686,-1.696920,0.548837,2.840456,5.169643,7.527962,9.906898,12.297824,14.692100,}, // NOLINT + {14.593356,12.187373,9.785390,7.395806,5.027125,2.688195,0.387224,-1.867399,-4.067593,-6.205400,-8.273146,-10.263355,-12.168874,-13.982761,-15.698574,-17.310086,-18.811484,-20.197368,-21.462750,-22.603083,-23.614153,-24.492421,-25.234693,-25.838267,-26.300982,-26.621150,-26.797618,-26.829733,-26.717375,-26.460935,-26.061325,-25.519964,-24.838806,-24.020266,-23.067330,-21.983336,-20.772229,-19.438312,-17.986464,-16.421817,-14.750010,-12.977082,-11.109379,-9.153623,-7.116858,-5.006400,-2.829861,-0.595073,1.689951,4.016942,6.377498,8.763225,11.165416,13.575380,15.984697,}, // NOLINT + {15.864244,13.459152,11.053715,8.656340,6.275877,3.920804,1.599532,-0.679578,-2.908362,-5.078812,-7.183192,-9.213885,-11.163663,-13.025465,-14.792698,-16.458998,-18.018407,-19.465331,-20.794587,-22.001451,-23.081535,-24.031052,-24.846597,-25.525231,-26.064517,-26.462572,-26.717964,-26.829793,-26.797659,-26.621697,-26.302554,-25.841355,-25.239796,-24.500025,-23.624730,-22.616989,-21.480525,-20.219350,-18.838034,-17.341481,-15.735122,-14.024717,-12.216392,-10.316660,-8.332325,-6.270526,-4.138664,-1.944428,0.304393,2.599633,4.933088,7.296343,9.680957,12.078395,14.479906,}, // NOLINT + {14.383094,11.969792,9.561279,7.165886,4.792286,2.448958,0.144294,-2.113493,-4.316268,-6.456197,-8.525706,-10.517145,-12.423619,-14.238199,-15.954481,-17.566214,-19.067724,-20.453594,-21.718875,-22.859053,-23.869996,-24.748150,-25.490345,-26.093897,-26.556666,-26.876995,-27.053713,-27.086185,-26.974279,-26.718394,-26.319426,-25.778795,-25.098413,-24.280713,-23.328561,-22.245412,-21.035082,-19.701892,-18.250603,-16.686373,-15.014795,-13.241832,-11.373805,-9.417387,-7.379559,-5.267599,-3.089057,-0.851707,1.436443,3.767240,6.132431,8.523271,10.931502,13.348410,15.765383,}, // NOLINT + {15.648603,13.235675,10.823159,8.419687,6.033881,3.674110,1.348863,-0.933581,-3.165083,-5.337722,-7.443765,-9.475705,-11.426314,-13.288642,-15.056074,-16.722343,-18.281490,-19.727996,-21.056694,-22.262917,-23.342308,-24.291139,-25.105938,-25.783851,-26.322503,-26.719971,-26.974846,-27.086237,-27.053755,-26.877535,-26.558204,-26.096914,-25.495293,-24.755533,-23.880260,-22.872578,-21.736103,-20.474889,-19.093375,-17.596637,-15.989862,-14.278852,-12.469696,-10.568783,-8.582970,-6.519310,-4.385323,-2.188025,0.063955,2.363106,4.701058,7.069559,9.460005,11.864019,14.273044,}, // NOLINT + {14.178018,11.757320,9.342005,6.940683,4.561824,2.213928,-0.094737,-2.355895,-4.561530,-6.703886,-8.775264,-10.768374,-12.676083,-14.491619,-16.208598,-17.820839,-19.322698,-20.708753,-21.974188,-23.114335,-24.125343,-25.003540,-25.745763,-26.349405,-26.812303,-27.132823,-27.309809,-27.342627,-27.231147,-26.975772,-26.577349,-26.037323,-25.357601,-24.540563,-23.589077,-22.506543,-21.296769,-19.964046,-18.513058,-16.949012,-15.277381,-13.504084,-11.635470,-9.678116,-7.638935,-5.525211,-3.344360,-1.104198,1.187370,3.522201,5.892023,8.288409,10.702824,13.126834,15.551665,}, // NOLINT + {15.438301,13.017347,10.597770,8.187895,5.796434,3.431894,1.102455,-1.183554,-3.418053,-5.593151,-7.701156,-9.734616,-11.686351,-13.549467,-15.317410,-16.983856,-18.542999,-19.989319,-21.317729,-22.523454,-23.602392,-24.550622,-25.364866,-26.042227,-26.580328,-26.977280,-27.231696,-27.342677,-27.309852,-27.133346,-26.813788,-26.352317,-25.750577,-25.010703,-24.135320,-23.127511,-21.990853,-20.729416,-19.347612,-17.850346,-16.242932,-14.531045,-12.720751,-10.818475,-8.830853,-6.765088,-4.628377,-2.428299,-0.172654,2.130600,4.473289,6.847153,9.243708,11.654569,14.071161,}, // NOLINT + {13.977778,11.549401,9.127258,6.719775,4.335475,1.982750,-0.330039,-2.594895,-4.803681,-6.948656,-9.022270,-11.017155,-12.926376,-14.743162,-16.461069,-18.074056,-19.576473,-20.962943,-22.228644,-23.369153,-24.380301,-25.258595,-26.000970,-26.604787,-27.067864,-27.388636,-27.565907,-27.599064,-27.487978,-27.233030,-26.835092,-26.295593,-25.616382,-24.799853,-23.848883,-22.766783,-21.557376,-20.224897,-18.774038,-17.209881,-15.537944,-13.764112,-11.894610,-9.935902,-7.895222,-5.779417,-3.596051,-1.352811,0.942405,3.281510,5.656241,8.058333,10.479148,12.910300,15.343159,}, // NOLINT + {15.233016,12.803999,10.377067,7.960752,5.563578,3.193846,0.859982,-1.429803,-3.667538,-5.845331,-7.955565,-9.990807,-11.943898,-13.808077,-15.576718,-17.243638,-18.803034,-20.249386,-21.577657,-22.783193,-23.861792,-24.809627,-25.623420,-26.300323,-26.837982,-27.234512,-27.488502,-27.599112,-27.565950,-27.389142,-27.069319,-26.607607,-26.005647,-25.265556,-24.389893,-23.381877,-22.244883,-20.983008,-19.600663,-18.102711,-16.494418,-14.781440,-12.969794,-11.065832,-9.076274,-7.008089,-4.868564,-2.665201,-0.405779,1.901842,4.249477,6.628900,9.031769,11.449592,13.873915,}, // NOLINT + {13.782056,11.345935,8.916734,6.502927,4.112973,1.755235,-0.562024,-2.830727,-5.042911,-7.190719,-9.266794,-11.263799,-13.174751,-14.992949,-16.712023,-18.325965,-19.829112,-21.216224,-22.482408,-23.623245,-24.634708,-25.513344,-26.255985,-26.860030,-27.323391,-27.644426,-27.822006,-27.855499,-27.744775,-27.490216,-27.092696,-26.553605,-25.874801,-25.058680,-24.107999,-23.026191,-21.816956,-20.484534,-19.033558,-17.469091,-15.796657,-14.021965,-12.151350,-10.191265,-8.148606,-6.030489,-3.844352,-1.597798,0.701293,3.044885,5.424783,7.832640,10.260112,12.698512,15.139505,}, // NOLINT + {15.032427,12.595145,10.160834,7.737849,5.334687,2.959729,0.621280,-1.672558,-3.913773,-6.094502,-8.207233,-10.244400,-12.199201,-14.064622,-15.834227,-17.501842,-19.061666,-20.508275,-21.836625,-23.042103,-24.120507,-25.068101,-25.881622,-26.558188,-27.095487,-27.491657,-27.745279,-27.855542,-27.822049,-27.644925,-27.324799,-26.862800,-26.260530,-25.520116,-24.644104,-23.635654,-22.498195,-21.235723,-19.852657,-18.353819,-16.744445,-15.030151,-13.216965,-11.311077,-9.319288,-7.248507,-5.105910,-2.899025,-0.635575,1.676582,4.029380,6.414576,8.823998,11.248822,13.681024,}, // NOLINT + {13.590566,11.146495,8.710045,6.289925,3.894079,1.531126,-0.790770,-3.063559,-5.279282,-7.430252,-9.509006,-11.508334,-13.421244,-15.241099,-16.961567,-18.576659,-20.080765,-21.468648,-22.735516,-23.876854,-24.888775,-25.767810,-26.510791,-27.115178,-27.578863,-27.900208,-28.078107,-28.111926,-28.001541,-27.747324,-27.350142,-26.811378,-26.132875,-25.316995,-24.366522,-23.284829,-22.075585,-20.743007,-19.291714,-17.726730,-16.053483,-14.277802,-12.405829,-10.444012,-8.399311,-6.278636,-4.089480,-1.839397,0.463773,2.812070,5.197357,7.611215,10.045275,12.491129,14.940416,}, // NOLINT + {14.836205,12.390662,9.948757,7.518946,5.109677,2.729294,0.385978,-1.912100,-4.156966,-6.340851,-8.456191,-10.495723,-12.452320,-14.319247,-16.090024,-17.758535,-19.319038,-20.766061,-22.094676,-23.300253,-24.378697,-25.326200,-26.139491,-26.815824,-27.352841,-27.748697,-28.002029,-28.111971,-28.078150,-27.900695,-27.580238,-27.117884,-26.515231,-25.774404,-24.897995,-23.888936,-22.750801,-21.487618,-20.103663,-18.603754,-16.993097,-15.277285,-13.462256,-11.554290,-9.560117,-7.486436,-5.340588,-3.130015,-0.862326,1.454598,3.812748,6.203894,8.619720,11.051968,13.492204,}, // NOLINT + {13.403019,10.950979,8.507257,6.080337,3.678544,1.310200,-1.016518,-3.293570,-5.513060,-7.667412,-9.749086,-11.750923,-13.666003,-15.487719,-17.209776,-18.826205,-20.331444,-21.720281,-22.987903,-24.129970,-25.142529,-26.022011,-26.765439,-27.370219,-27.834274,-28.155972,-28.334209,-28.368352,-28.258280,-28.004362,-27.607475,-27.068931,-26.390630,-25.574852,-24.624496,-23.542734,-22.333320,-21.000342,-19.548570,-17.982922,-16.308706,-14.531773,-12.658251,-10.694523,-8.647504,-6.524040,-4.331668,-2.077781,0.229683,2.582817,4.973534,7.393560,9.834546,12.288052,14.745615,}, // NOLINT + {14.644119,12.190211,9.740580,7.303826,4.888271,2.502244,0.153952,-2.148562,-4.397267,-6.584520,-8.702806,-10.744792,-12.703440,-14.572060,-16.344268,-18.013829,-19.575153,-21.022812,-22.351871,-23.557732,-24.636276,-25.583783,-26.397049,-27.073256,-27.610070,-28.005684,-28.258748,-28.368394,-28.334253,-28.156457,-27.835618,-27.372858,-26.769767,-26.028438,-25.151417,-24.141739,-23.002875,-21.738757,-20.353734,-18.852582,-17.240514,-15.522953,-13.705938,-11.795687,-9.798794,-7.722112,-5.572860,-3.358307,-1.086309,1.235678,3.599307,5.996580,8.419221,10.858902,13.307183,}, // NOLINT + {13.219187,10.759014,8.307837,5.874122,3.466163,1.092230,-1.239475,-3.521006,-5.744515,-7.902359,-9.987132,-11.991691,-13.909145,-15.732901,-17.456728,-19.074690,-20.581222,-21.971178,-23.239750,-24.382618,-25.395830,-26.275965,-27.019940,-27.625176,-28.089635,-28.411731,-28.590312,-28.624773,-28.514989,-28.261333,-27.864635,-27.326277,-26.648079,-25.832365,-24.881906,-23.799960,-22.590223,-21.256835,-19.804351,-18.237736,-16.562367,-14.783977,-12.908648,-10.942814,-8.893214,-6.766848,-4.571188,-2.313243,-0.001314,2.356900,4.753290,7.179637,9.627613,12.088791,14.554799,}, // NOLINT + {14.455888,11.993421,9.536038,7.092213,4.670195,2.278436,-0.075008,-2.382094,-4.634908,-6.825723,-8.947079,-10.991706,-12.952643,-14.823177,-16.596927,-18.267812,-19.830093,-21.278616,-22.608256,-23.814540,-24.893353,-25.841036,-26.654319,-27.330465,-27.867170,-28.262612,-28.515443,-28.624813,-28.590354,-28.412198,-28.090948,-27.627754,-27.024148,-26.282235,-25.404562,-24.394088,-23.254383,-21.989178,-20.602946,-19.100391,-17.486645,-15.767242,-13.948047,-12.035315,-10.035569,-7.955670,-5.802733,-3.584109,-1.307386,1.019609,3.388932,5.792510,8.221814,10.669210,13.125735,}, // NOLINT + {13.038803,10.570359,8.111666,5.671008,3.256742,0.877084,-1.459819,-3.746007,-5.973679,-8.135233,-10.223301,-12.230761,-14.150766,-15.976749,-17.702527,-19.322166,-20.830140,-22.221375,-23.491056,-24.634839,-25.648880,-26.529689,-27.274253,-27.880042,-28.344978,-28.667473,-28.846415,-28.881192,-28.771675,-28.518223,-28.121689,-27.583428,-26.905248,-26.089471,-25.138808,-24.056540,-22.846339,-21.512300,-20.058993,-18.491276,-16.814565,-15.034529,-13.157246,-11.189111,-9.136771,-7.007238,-4.807800,-2.545899,-0.229295,2.134122,4.536352,6.969141,9.424102,11.893338,14.367790,}, // NOLINT + {14.271290,11.800224,9.334930,6.883878,4.455387,2.057651,-0.301148,-2.612951,-4.870035,-7.064595,-9.189171,-11.236666,-13.200086,-15.072702,-16.848197,-18.520544,-20.084103,-21.533501,-22.863901,-24.070720,-25.149943,-26.097889,-26.911308,-27.587498,-28.124157,-28.519484,-28.772113,-28.881229,-28.846460,-28.667934,-28.346264,-27.882550,-27.278372,-26.535809,-25.657348,-24.646032,-23.505283,-22.238933,-20.851349,-19.347235,-17.731700,-16.010241,-14.188720,-12.273300,-10.270535,-8.187221,-6.030444,-3.807534,-1.526054,0.806237,3.181390,5.591379,8.027871,10.482817,12.947608,}, // NOLINT + {12.861724,10.385008,7.918506,5.470824,3.050059,0.664531,-1.677707,-3.968895,-6.200722,-8.366155,-10.457702,-12.468244,-14.390968,-16.219360,-17.947225,-19.568700,-21.078305,-22.470887,-23.741800,-24.886607,-25.901612,-26.783191,-27.528442,-28.134824,-28.600271,-28.923203,-29.102521,-29.137607,-29.028327,-28.775065,-28.378643,-27.840395,-27.162151,-26.346181,-25.395234,-24.312531,-23.101726,-21.766892,-20.312552,-18.743621,-17.065388,-15.283565,-13.404113,-11.433568,-9.378221,-7.245358,-5.041966,-2.775955,-0.454528,1.914288,4.322480,6.761894,9.224179,11.701157,14.184300,}, // NOLINT + {14.090101,11.610241,9.137095,6.678721,4.243507,1.839695,-0.524589,-2.841365,-5.102796,-7.301269,-9.429345,-11.479864,-13.445885,-15.320738,-17.098156,-18.772143,-20.337042,-21.787551,-23.118809,-24.326299,-25.406074,-26.354369,-27.168047,-27.844352,-28.381034,-28.776271,-29.028758,-29.137642,-29.102566,-28.923659,-28.601532,-28.137280,-27.532465,-26.789177,-25.909867,-24.897583,-23.755695,-22.488063,-21.098980,-19.593195,-17.975707,-16.252040,-14.427986,-12.509764,-10.503805,-8.416911,-6.256136,-4.028777,-1.742361,0.595358,2.976509,5.393024,7.836668,10.299372,12.772622,}, // NOLINT + {12.687651,10.202446,7.728220,5.273310,2.845983,0.454436,-1.893298,-4.189283,-6.425829,-8.595342,-10.690450,-12.704229,-14.629844,-16.460790,-18.190915,-19.814382,-21.325711,-22.719857,-23.992119,-25.138097,-26.154025,-27.036499,-27.782504,-28.389531,-28.855530,-29.178927,-29.358628,-29.394018,-29.284970,-29.031844,-28.635475,-28.097193,-27.418800,-26.602562,-25.651213,-24.567942,-23.356469,-22.020649,-20.565164,-18.994820,-17.314929,-15.531103,-13.649381,-11.676017,-9.617757,-7.481356,-5.274176,-3.003532,-0.677115,1.697217,4.111524,6.557634,9.027306,11.512228,14.004149,}, // NOLINT + {13.912108,11.423585,8.942265,6.476444,4.034429,1.624407,-0.745505,-3.067363,-5.333379,-7.535911,-9.667600,-11.721316,-13.690081,-15.567372,-17.346878,-19.022638,-20.589019,-22.040779,-23.373065,-24.581411,-25.661747,-26.610559,-27.424536,-28.101049,-28.637800,-29.033018,-29.285382,-29.394052,-29.358674,-29.179370,-28.856766,-28.391935,-27.786449,-27.042347,-26.162129,-25.148703,-24.005591,-22.736609,-21.345931,-19.838290,-18.218729,-16.492759,-14.666015,-12.744785,-10.735490,-8.644848,-6.479913,-4.247975,-1.956461,0.386862,2.774126,5.197277,7.648306,10.118798,12.600584,}, // NOLINT + {12.516454,10.022708,7.540608,5.078391,2.644334,0.246619,-2.106734,-4.407867,-6.649044,-8.822692,-10.921643,-12.938814,-14.867463,-16.701120,-18.433644,-20.059238,-21.572466,-22.968219,-24.241833,-25.389112,-26.406185,-27.289618,-28.036439,-28.644167,-29.110756,-29.434636,-29.614736,-29.650427,-29.541585,-29.288567,-28.892210,-28.353829,-27.675203,-26.858607,-25.906752,-24.822838,-23.610451,-22.273638,-20.816853,-19.244978,-17.563253,-15.777293,-13.893084,-11.916899,-9.855352,-7.715305,-5.504039,-3.228798,-0.897276,1.482695,3.903278,6.356302,8.833397,11.326466,13.827083,}, // NOLINT + {13.737138,11.239786,8.750268,6.276930,3.827966,1.411621,-0.964059,-3.291135,-5.561873,-7.768608,-9.904063,-11.961088,-13.932822,-15.812691,-17.594469,-19.272106,-20.840126,-22.293267,-23.626693,-24.835969,-25.917054,-26.866393,-27.680799,-28.357576,-28.894470,-29.289709,-29.541986,-29.650460,-29.614784,-29.435082,-29.111969,-28.646523,-28.040303,-27.295340,-26.414123,-25.399656,-24.255111,-22.984578,-21.592208,-20.082599,-18.460834,-16.732352,-14.902823,-12.978462,-10.965675,-8.871133,-6.701892,-4.465221,-2.168417,0.180550,2.574071,5.004065,7.462358,9.940925,12.431284,}, // NOLINT + {12.347830,9.845590,7.355422,4.885837,2.444961,0.040958,-2.318159,-4.624525,-6.870477,-9.048509,-11.151386,-13.172100,-15.103919,-16.940449,-18.675509,-20.303317,-21.818526,-23.216062,-24.491271,-25.639906,-26.658121,-27.542559,-28.290223,-28.898735,-29.365951,-29.690346,-29.870846,-29.906833,-29.798178,-29.545241,-29.148851,-28.610309,-27.931395,-27.114383,-26.161927,-25.077237,-23.863893,-22.525884,-21.067698,-19.494134,-17.810441,-16.022211,-14.135373,-12.156198,-10.091252,-7.947450,-5.731862,-3.451892,-1.115110,1.270697,3.697603,6.157551,8.642221,11.143505,13.652933,}, // NOLINT + {13.564969,11.058753,8.560948,6.079967,3.623984,1.201173,-1.180379,-3.512797,-5.788366,-7.999496,-10.138858,-12.199374,-14.174194,-16.056773,-17.840895,-19.520622,-21.090415,-22.545020,-23.879731,-25.090048,-26.171976,-27.121960,-27.936855,-28.613963,-29.151054,-29.546353,-29.798567,-29.906864,-29.870893,-29.690781,-29.367142,-28.901050,-28.294055,-27.548161,-26.665876,-25.650116,-24.504273,-23.232092,-21.837869,-20.326178,-18.702096,-16.970935,-15.138496,-13.210883,-11.194441,-9.095903,-6.922209,-4.680630,-2.378541,-0.023666,2.376282,4.813130,7.278944,9.765538,12.264637,}, // NOLINT + {12.181937,9.670903,7.172707,4.695544,2.247724,-0.162678,-2.527676,-4.839437,-7.090301,-9.272830,-11.379795,-13.404150,-15.339267,-17.178720,-18.916471,-20.546688,-22.063983,-23.463402,-24.740249,-25.890340,-26.909808,-27.795338,-28.543973,-29.153244,-29.621118,-29.946046,-30.126958,-30.163233,-30.054756,-29.801866,-29.405395,-28.866642,-28.187385,-27.369852,-26.416724,-25.331159,-24.116669,-22.777438,-21.317714,-19.742356,-18.056563,-16.265917,-14.376323,-12.394017,-10.325554,-8.177792,-5.957812,-3.672945,-1.330774,1.060961,3.494337,5.961298,8.453639,10.963202,13.481630,}, // NOLINT + {13.395500,10.880266,8.374146,5.885386,3.422307,0.992964,-1.394609,-3.732517,-6.013053,-8.228661,-10.372085,-12.436223,-14.414259,-16.299691,-18.086319,-19.768236,-21.339912,-22.796168,-24.132223,-25.343671,-26.426531,-27.377267,-28.192703,-28.870219,-29.407558,-29.802950,-30.055129,-30.163265,-30.127005,-29.946488,-29.622289,-29.155511,-28.547718,-27.800825,-26.917405,-25.900351,-24.752962,-23.479096,-22.082894,-20.569052,-18.942511,-17.208686,-15.373133,-13.442113,-11.421906,-9.319216,-7.140963,-4.894358,-2.586810,-0.225955,2.180420,4.624355,7.097844,9.592494,12.100303,}, // NOLINT + {13.249791,10.171499,7.066721,3.949723,0.834658,-2.264418,-5.333705,-8.359584,-11.328764,-14.228302,-17.045559,-19.768604,-22.385582,-24.885433,-27.257539,-29.491979,-31.579286,-33.510782,-35.278426,-36.875007,-38.293726,-39.528848,-40.575317,-41.428742,-42.085752,-42.543604,-42.800481,-42.855341,-42.707988,-42.359047,-41.809973,-41.063026,-40.121272,-38.988750,-37.669983,-36.170488,-34.496484,-32.654923,-30.653509,-28.500573,-26.205166,-23.776933,-21.226155,-18.563651,-15.800801,-12.949462,-10.021756,-7.030629,-3.989058,-0.910394,2.191858,5.303366,8.410521,11.499154,14.555063,}, // NOLINT + {14.250759,11.203020,8.124039,5.027772,1.928327,-1.160602,-4.225272,-7.252131,-10.227992,-13.140004,-15.975684,-18.722710,-21.369413,-23.904724,-26.317828,-28.598629,-30.737568,-32.725794,-34.554983,-36.217607,-37.706793,-39.016393,-40.140986,-41.076030,-41.817626,-42.362757,-42.709159,-42.855396,-42.800855,-42.545736,-42.091053,-41.438642,-40.591144,-39.551969,-38.325379,-36.916367,-35.330650,-33.574894,-31.656172,-29.582467,-27.362372,-25.005196,-22.520726,-19.919476,-17.212402,-14.411143,-11.527303,-8.573675,-5.562899,-2.508182,0.577181,3.679413,6.784686,9.879011,12.948219,}, // NOLINT + {12.797105,9.720234,6.619432,3.508731,0.402015,-2.686935,-5.744451,-8.757272,-11.712240,-14.596726,-17.398364,-20.105255,-22.705936,-25.189561,-27.545691,-29.764479,-31.836802,-33.754092,-35.508467,-37.092746,-38.500453,-39.725878,-40.764033,-41.610716,-42.262505,-42.716822,-42.971800,-43.026446,-42.880562,-42.534763,-41.990469,-41.249908,-40.316103,-39.192819,-37.884788,-36.397239,-34.736291,-32.908744,-30.922160,-28.784713,-26.505261,-24.093244,-21.558800,-18.912528,-16.165519,-13.329380,-10.416450,-7.438712,-4.409418,-1.341520,1.751529,4.856176,7.958458,11.044759,14.100818,}, // NOLINT + {13.804701,10.756768,7.680147,4.588641,1.495977,-1.584146,-4.638318,-7.653313,-10.616109,-13.514027,-16.334786,-19.066378,-21.697420,-24.216872,-26.614146,-28.879463,-31.003371,-32.977151,-34.792778,-36.442738,-37.920329,-39.219542,-40.335091,-41.262456,-41.997868,-42.538350,-42.881688,-43.026497,-42.972164,-42.718890,-42.267638,-41.620289,-40.779328,-39.748261,-38.531027,-37.132716,-35.558913,-33.816009,-31.911090,-29.851946,-27.646981,-25.305367,-22.836671,-20.251211,-17.559742,-14.773574,-11.904462,-8.964597,-5.966520,-2.923342,0.152363,3.246559,6.345599,9.436083,12.503938,}, // NOLINT + {12.357690,9.282248,6.185260,3.080545,-0.018187,-3.097410,-6.143734,-9.144052,-12.085525,-14.955669,-17.742368,-20.433934,-23.019144,-25.487288,-27.828109,-30.032080,-32.090130,-33.993941,-35.735586,-37.308230,-38.705456,-39.921641,-40.951921,-41.792162,-42.438990,-42.889932,-43.143103,-43.197546,-43.053070,-42.710256,-42.170522,-41.436032,-40.509739,-39.395417,-38.097523,-36.621336,-34.972790,-33.158624,-31.186149,-29.063460,-26.799162,-24.402661,-21.883823,-19.252969,-16.521080,-13.699561,-10.800387,-7.835682,-4.818046,-1.760461,1.323966,4.421717,7.519377,10.603174,13.659446,}, // NOLINT + {13.371238,10.323172,7.248853,4.161897,1.075953,-1.995889,-5.040105,-8.043715,-10.993729,-13.878457,-16.685012,-19.401933,-22.017958,-24.522266,-26.904530,-29.155106,-31.264683,-33.224789,-35.027426,-36.665311,-38.131860,-39.421195,-40.528056,-41.448141,-42.177663,-42.713711,-43.054149,-43.197596,-43.143459,-42.891935,-42.444038,-41.801424,-40.966733,-39.943253,-38.735034,-37.346898,-35.784384,-34.053754,-32.162017,-30.116727,-27.926208,-25.599357,-23.145732,-20.575255,-17.898691,-15.127012,-12.271785,-9.345029,-6.359078,-3.326562,-0.260507,2.825899,5.919260,9.006076,12.072544,}, // NOLINT + {11.930888,8.856814,5.763498,2.664531,-0.426557,-3.496578,-6.532206,-9.520608,-12.449209,-15.305580,-18.078182,-20.755149,-23.325582,-25.778995,-28.105315,-30.295116,-32.339657,-34.230391,-35.960056,-37.521609,-38.908843,-40.116241,-41.139005,-41.973112,-42.615297,-43.062942,-43.314393,-43.368643,-43.225492,-42.885536,-42.350139,-41.621436,-40.702262,-39.596474,-38.308303,-36.842943,-35.206256,-33.404774,-31.445778,-29.337186,-27.087413,-24.705697,-22.201650,-19.585565,-16.868098,-14.060487,-11.174549,-8.222162,-5.215708,-2.167913,0.908062,3.999507,7.092626,10.174132,13.230473,}, // NOLINT + {12.949655,9.901474,6.829575,3.746921,0.667158,-2.396552,-5.431227,-8.423994,-11.362329,-14.233946,-17.026994,-19.729876,-22.331576,-24.821481,-27.189426,-29.425909,-31.521848,-33.468808,-35.259102,-36.885483,-38.341514,-39.621438,-40.720102,-41.633167,-42.357015,-42.888879,-43.226546,-43.368688,-43.314739,-43.064885,-42.620121,-41.982088,-41.153353,-40.137153,-38.937485,-37.559054,-36.007312,-34.288407,-32.409158,-30.377106,-28.200345,-25.887586,-23.448231,-20.892118,-18.229685,-15.471742,-12.629875,-9.715608,-6.741182,-3.719037,-0.661941,2.417105,5.504934,8.588136,11.653334,}, // NOLINT + {11.516044,8.443256,5.353399,2.260026,-0.823930,-3.885084,-6.910543,-9.887628,-12.803973,-15.647416,-18.406325,-21.069387,-23.625763,-26.065098,-28.377637,-30.553876,-32.585404,-34.463889,-36.182040,-37.733025,-39.110705,-40.309748,-41.325350,-42.153601,-42.791290,-43.235859,-43.485668,-43.539734,-43.397865,-43.060631,-42.529374,-41.806186,-40.893924,-39.796188,-38.517254,-37.062230,-35.436845,-33.647531,-31.701402,-29.606187,-27.370269,-25.002618,-22.512753,-19.910667,-17.207010,-14.412763,-11.539363,-8.598713,-5.602963,-2.564586,0.503644,3.588608,6.677533,9.756809,12.813199,}, // NOLINT + {12.539700,9.491386,6.421439,3.343028,0.269275,-2.786785,-5.812331,-8.794741,-11.721656,-14.581038,-17.361147,-20.050709,-22.638676,-25.114873,-27.469151,-29.692169,-31.775062,-33.709566,-35.488036,-37.103432,-38.549418,-39.820260,-40.911092,-41.817516,-42.536048,-43.063860,-43.398870,-43.539778,-43.486006,-43.237746,-42.795971,-42.162308,-41.339259,-40.330029,-39.138493,-37.769317,-36.227850,-34.520110,-32.652773,-30.633357,-28.469685,-26.170404,-23.744684,-21.202249,-18.553304,-15.808614,-12.979263,-10.076949,-7.113500,-4.101228,-1.052667,2.019356,5.101894,8.181734,11.245714,}, // NOLINT + {11.112448,8.040938,4.954455,1.866147,-1.210821,-4.263566,-7.279309,-10.245655,-13.150305,-15.981293,-18.727280,-21.377064,-23.920015,-26.345940,-28.645251,-30.808636,-32.827726,-34.694521,-36.401624,-37.942602,-39.311160,-40.502167,-41.511005,-42.333640,-42.967058,-43.408686,-43.656930,-43.710822,-43.570172,-43.235548,-42.708234,-41.990320,-41.084567,-39.994559,-38.724496,-37.279344,-35.664749,-33.887033,-31.953186,-29.870782,-27.647969,-25.293849,-22.817506,-20.228865,-17.538347,-14.756822,-11.895559,-8.965989,-5.980448,-2.951060,0.109627,3.188812,6.273486,9.350611,12.407078,}, // NOLINT + {12.140371,9.091983,6.024055,2.949620,-0.118388,-3.167141,-6.183997,-9.156528,-12.072559,-14.920128,-17.688004,-20.364765,-22.939705,-25.402785,-27.744004,-29.954166,-32.024585,-33.947130,-35.714366,-37.319274,-38.755647,-40.017937,-41.101219,-42.001291,-42.714696,-43.238659,-43.571147,-43.710863,-43.657260,-43.410522,-42.971604,-42.342103,-41.524495,-40.521883,-39.338145,-37.977812,-36.446147,-34.749082,-32.893305,-30.885773,-28.734565,-26.448155,-24.035449,-21.506047,-18.870012,-16.137853,-13.320589,-10.429565,-7.476611,-4.473713,-1.433308,1.632055,4.709555,7.786190,10.848995,}, // NOLINT + {10.719592,7.649220,4.565864,1.482549,-1.588038,-4.632620,-7.639158,-10.595037,-13.488607,-16.307829,-19.041450,-21.678597,-24.208731,-26.621868,-28.908493,-31.059640,-33.066925,-34.922498,-36.619206,-38.150458,-39.510375,-40.693714,-41.695991,-42.513310,-43.142614,-43.581436,-43.828182,-43.881905,-43.742419,-43.410262,-42.886759,-42.173874,-41.274412,-40.191749,-38.930133,-37.494421,-35.890147,-34.123487,-32.201326,-30.131223,-27.921130,-25.579766,-23.116399,-20.540510,-17.862573,-15.093089,-12.243382,-9.324459,-6.348740,-3.327898,-0.274434,2.799028,5.879834,8.954947,12.011489,}, // NOLINT + {11.751311,8.702794,5.636792,2.566198,-0.496415,-3.538206,-6.546683,-9.510041,-12.415516,-15.252002,-18.007999,-20.672558,-23.235102,-25.685545,-28.014284,-30.212175,-32.270704,-34.181893,-35.938283,-37.533155,-38.960361,-40.214418,-41.290461,-42.184521,-42.892979,-43.413279,-43.743361,-43.881945,-43.828502,-43.583219,-43.147033,-42.521515,-41.709100,-40.712822,-39.536533,-38.184648,-36.662335,-34.975508,-33.130538,-31.134550,-28.995330,-26.721151,-24.320794,-21.803923,-19.180174,-16.459926,-13.654225,-10.773998,-7.831055,-4.837121,-1.804429,1.254578,4.327273,7.400950,10.462676,}, // NOLINT + {10.336874,7.267531,4.187161,1.108517,-1.955640,-4.992803,-7.990513,-10.936726,-13.819571,-16.627349,-19.349309,-21.974348,-24.492227,-26.893167,-29.167739,-31.307120,-33.303056,-35.147962,-36.834652,-38.356702,-39.708315,-40.884354,-41.880390,-42.692585,-43.317972,-43.754106,-43.999420,-44.052986,-43.914614,-43.584843,-43.064923,-42.356875,-41.463368,-40.387801,-39.134279,-37.707586,-36.113152,-34.357123,-32.446218,-30.387776,-28.189768,-25.860680,-23.409585,-20.846045,-18.180094,-15.422263,-12.583406,-9.674923,-6.708358,-3.695677,-0.649063,2.419060,5.496087,8.569326,11.625961,}, // NOLINT + {11.372051,8.323297,5.259082,2.192019,-0.865356,-3.900505,-6.901156,-9.855203,-12.750929,-15.576781,-18.321541,-20.974462,-23.525048,-25.963485,-28.280293,-30.466449,-32.513559,-34.413821,-36.159917,-37.745191,-39.163615,-40.409812,-41.479009,-42.367207,-43.071014,-43.587763,-43.915526,-44.053024,-43.999734,-43.755842,-43.322271,-42.700564,-41.893117,-40.902922,-39.733736,-38.389931,-36.876467,-35.199545,-33.364922,-31.379947,-29.252150,-26.989688,-24.601301,-22.096244,-19.484223,-16.775480,-13.980697,-11.110840,-8.177332,-5.191927,-2.166607,0.886378,3.954574,7.025424,10.086208,}, // NOLINT + {9.963764,6.895418,3.817774,0.743569,-2.314687,-5.344585,-8.333935,-11.270786,-14.143403,-16.940697,-19.651190,-22.264697,-24.770866,-27.160131,-29.423178,-31.551338,-33.536510,-35.371121,-37.048142,-38.561435,-39.905096,-41.074135,-42.064178,-42.871506,-43.493145,-43.926704,-44.170650,-44.224063,-44.086759,-43.759264,-43.242823,-42.539383,-41.651625,-40.582786,-39.337016,-37.918960,-36.333932,-34.588087,-32.687883,-30.640693,-28.454176,-26.136888,-23.697610,-21.145784,-18.491330,-15.744577,-12.916213,-10.017487,-7.059784,-4.054906,-1.014815,2.048217,5.121665,8.193176,11.249916,}, // NOLINT + {11.001868,7.952955,4.890433,1.826735,-1.225690,-4.254513,-7.247629,-10.192990,-13.079373,-15.894986,-18.628978,-21.270703,-23.809935,-26.236905,-28.542252,-30.717163,-32.753394,-34.643198,-36.379430,-37.955505,-39.365515,-40.604157,-41.666789,-42.549404,-43.248715,-43.762104,-44.087641,-44.224099,-44.170957,-43.928398,-43.497330,-42.879271,-42.076571,-41.092205,-39.929823,-38.593756,-37.089007,-35.421206,-33.596632,-31.622170,-29.505294,-27.254046,-24.877011,-22.383306,-19.782525,-17.084721,-14.300404,-11.440369,-8.515929,-5.538641,-2.520315,0.526975,3.590910,6.659120,9.719036,}, // NOLINT + {9.599752,6.532204,3.457189,0.387165,-2.665490,-5.688506,-8.669860,-11.597841,-14.460937,-17.247502,-19.947472,-22.549926,-25.044962,-27.423014,-29.675022,-31.792445,-33.767267,-35.592061,-37.259979,-38.764754,-40.100794,-41.263131,-42.247439,-43.050096,-43.668142,-44.099234,-44.341870,-44.395137,-44.258856,-43.933544,-43.420418,-42.721378,-41.839099,-40.776777,-39.538418,-38.128646,-36.552724,-34.816562,-32.926637,-30.890165,-28.714723,-26.408677,-23.980699,-21.440111,-18.796630,-16.060457,-13.242179,-10.352765,-7.403514,-4.406033,-1.372181,1.685874,4.756128,7.825936,10.882874,}, // NOLINT + {10.640495,7.591392,4.530365,1.469863,-1.577892,-4.600700,-7.586625,-10.523877,-13.401121,-16.207012,-18.930695,-21.561746,-24.090046,-26.506006,-28.800437,-30.964574,-32.990361,-34.870151,-36.596912,-38.164187,-39.566135,-40.797552,-41.853799,-42.731142,-43.426143,-43.936289,-44.259710,-44.395172,-44.342171,-44.100887,-43.672221,-43.057659,-42.259530,-41.280734,-40.124874,-38.796218,-37.299732,-35.640820,-33.825755,-31.861402,-29.754983,-27.514466,-25.148299,-22.665464,-20.075403,-17.388088,-14.613655,-11.763079,-8.847284,-5.877720,-2.866049,0.175795,3.235767,6.301510,9.360669,}, // NOLINT + {9.244336,6.177570,3.104919,0.038840,-3.008481,-6.024940,-8.998724,-11.918148,-14.771995,-17.548897,-20.238484,-22.830348,-25.314651,-27.682034,-29.923509,-32.030636,-33.995557,-35.810940,-37.470049,-38.966736,-40.295485,-41.451387,-42.430208,-43.228375,-43.842976,-44.271705,-44.513081,-44.566208,-44.430908,-44.107689,-43.597761,-42.902968,-42.025916,-40.969834,-39.738583,-38.336748,-36.769501,-35.042652,-33.162591,-31.136418,-28.971611,-26.676300,-24.259159,-21.729301,-19.096342,-16.370242,-13.561656,-10.681068,-7.739947,-4.749542,-1.721626,1.331922,4.398958,7.467240,10.524460,}, // NOLINT + {10.287458,7.237996,4.178361,1.120867,-1.922409,-4.939518,-7.918597,-10.848074,-13.716560,-16.513041,-19.227004,-21.847832,-24.365653,-26.771113,-29.055010,-31.208897,-33.224641,-35.094818,-36.812512,-38.371339,-39.765556,-40.990026,-42.040276,-42.912429,-43.603300,-44.110367,-44.431738,-44.566242,-44.513376,-44.273320,-43.846954,-43.235747,-42.441966,-41.468539,-40.318942,-38.997394,-37.508738,-35.858444,-34.052587,-32.097828,-30.001430,-27.771183,-25.415411,-22.942962,-20.363058,-17.685802,-14.921010,-12.079364,-9.171837,-6.209587,-3.204252,-0.167506,2.888657,5.952131,9.010661,}, // NOLINT + {8.897110,5.830889,2.760620,-0.301849,-3.344126,-6.354357,-9.320929,-12.232250,-15.077149,-17.844758,-20.524525,-23.106308,-25.580400,-27.937506,-30.168818,-32.266105,-34.221516,-36.027881,-37.678547,-39.167474,-40.489222,-41.638967,-42.612512,-43.406374,-44.017630,-44.444110,-44.684283,-44.737277,-44.602920,-44.281695,-43.774821,-43.084120,-42.212107,-41.162020,-39.937612,-38.543358,-36.984436,-35.266509,-33.395953,-31.379613,-29.224966,-26.940003,-24.533232,-22.013683,-19.390790,-16.674388,-13.875086,-11.002969,-8.069512,-5.085862,-2.063548,0.985639,4.049707,7.116609,10.174146,}, // NOLINT + {9.942282,6.892440,3.833894,0.779363,-2.259686,-5.271348,-8.243932,-11.165931,-14.026335,-16.813752,-19.518231,-22.129276,-24.637129,-27.032436,-29.306273,-31.450237,-33.456394,-35.317357,-37.026339,-38.577050,-39.963844,-41.181670,-42.226099,-43.093337,-43.780226,-44.284312,-44.603723,-44.737309,-44.684575,-44.445692,-44.021510,-43.413554,-42.623994,-41.655661,-40.512073,-39.197370,-37.716257,-36.074211,-34.277120,-32.331590,-30.244821,-28.024454,-25.678638,-23.216140,-20.646174,-17.978339,-15.222664,-12.389591,-9.489909,-6.534855,-3.535342,-0.503439,2.549165,5.610533,8.668557,}, // NOLINT + {8.557598,5.491864,2.423535,-0.635337,-3.672851,-6.677178,-9.636860,-12.540439,-15.376906,-18.135518,-20.805880,-23.377987,-25.842317,-28.189566,-30.411189,-32.499032,-34.445287,-36.242978,-37.885563,-39.367037,-40.682064,-41.825851,-42.794364,-43.584077,-44.192169,-44.616484,-44.855477,-44.908343,-44.774888,-44.455615,-43.951676,-43.264869,-42.397704,-41.353325,-40.135471,-38.748567,-37.197638,-35.488460,-33.626759,-31.619954,-29.475082,-27.200022,-24.803216,-22.293512,-19.680272,-16.973266,-14.182500,-11.318673,-8.392588,-5.415323,-2.398391,0.646659,3.708046,6.773618,9.831547,}, // NOLINT + {9.604586,6.554296,3.497132,0.445078,-2.589973,-5.596569,-8.562832,-11.477811,-14.330162,-17.109255,-19.804658,-22.406373,-24.904618,-27.290147,-29.554360,-31.688826,-33.685758,-35.537893,-37.238493,-38.781410,-40.161069,-41.372488,-42.411333,-43.273875,-43.956933,-44.458143,-44.775671,-44.908373,-44.855763,-44.618012,-44.195959,-43.591097,-42.805572,-41.842168,-40.704383,-39.396202,-37.922372,-36.288158,-34.499547,-32.562940,-30.485344,-28.274394,-25.938156,-23.485225,-20.924659,-18.265947,-15.519007,-12.694126,-9.801935,-6.853329,-3.859682,-0.832442,2.216883,5.276303,8.333925,}, // NOLINT + {8.225374,5.160043,2.093613,-0.962005,-3.995020,-6.993783,-9.946867,-12.843069,-15.671479,-18.421482,-21.082842,-23.645699,-26.100566,-28.438430,-30.650748,-32.729453,-34.667008,-36.456423,-38.091180,-39.565452,-40.874041,-42.012141,-42.975801,-43.761530,-44.366571,-44.788775,-45.026666,-45.079406,-44.946822,-44.629391,-44.128288,-43.445257,-42.582747,-41.543858,-40.332325,-38.952455,-37.409215,-35.708141,-33.855375,-31.857601,-29.722075,-27.456550,-25.069292,-22.569081,-19.965081,-17.266925,-14.484611,-11.628588,-8.709504,-5.738373,-2.726535,0.314630,3.373357,6.437870,9.496258,}, // NOLINT + {9.274104,6.223155,3.167029,0.117402,-2.914004,-5.915755,-8.876044,-11.784131,-14.628886,-17.399790,-20.086557,-22.679218,-25.168256,-27.544567,-29.799482,-31.924808,-33.912879,-35.756486,-37.449061,-38.984490,-40.357304,-41.562564,-42.596009,-43.454003,-44.133412,-44.631864,-44.947582,-45.079436,-45.026946,-44.790279,-44.370273,-43.768396,-42.986740,-42.028091,-40.895803,-39.593952,-38.127124,-36.500526,-34.719985,-32.791883,-30.723153,-28.521306,-26.194210,-23.750403,-21.198924,-18.548921,-15.810319,-12.993261,-10.108225,-7.166009,-4.177774,-1.154790,1.891362,4.949037,8.006385,}, // NOLINT + {7.900080,4.835018,1.770311,-1.282237,-4.311010,-7.304516,-10.251276,-13.140434,-15.961129,-18.703012,-21.355660,-23.909607,-26.355463,-28.684288,-30.887663,-32.957646,-34.886783,-36.668183,-38.295494,-39.762907,-41.065245,-42.197882,-43.156851,-43.938740,-44.540843,-44.961034,-45.197850,-45.250467,-45.118720,-44.803070,-44.304693,-43.625254,-42.767252,-41.733677,-40.528201,-39.155115,-37.619247,-35.926093,-34.081732,-32.092777,-29.966184,-27.709740,-25.331729,-22.840589,-20.245459,-17.555827,-14.781578,-11.933003,-9.020640,-6.055334,-3.048321,-0.010865,3.045469,6.108967,9.167912,}, // NOLINT + {8.950128,5.898690,2.843454,-0.203910,-3.231855,-6.228713,-9.183513,-12.085087,-14.922678,-17.685723,-20.364180,-22.948234,-25.428364,-27.795778,-30.041781,-32.158327,-34.137880,-35.973330,-37.658147,-39.186465,-40.552559,-41.751928,-42.780210,-43.633800,-44.309643,-44.805499,-45.119457,-45.250495,-45.198121,-44.962510,-44.544469,-43.945456,-43.167546,-42.213459,-41.086539,-39.790724,-38.330605,-36.711300,-34.938551,-33.018694,-30.958425,-28.765254,-26.446997,-24.011997,-21.469085,-18.827507,-16.096916,-13.287322,-10.409101,-7.473075,-4.489840,-1.470945,1.572333,4.628413,7.685561,}, // NOLINT + {7.581359,4.516437,1.453294,-1.596427,-4.621148,-7.609533,-10.550411,-13.432842,-16.246205,-18.980088,-21.624561,-24.169996,-26.607165,-28.927321,-31.122137,-33.183685,-35.104735,-36.878460,-38.498553,-39.959341,-41.255701,-42.383067,-43.337521,-44.115728,-44.714999,-45.133244,-45.369022,-45.421526,-45.290584,-44.976665,-44.480907,-43.804922,-42.951257,-41.922794,-40.723133,-39.356569,-37.827870,-36.142357,-34.306025,-32.325476,-30.207540,-27.959957,-25.590701,-23.108203,-20.521674,-17.840226,-15.073716,-12.232252,-9.326304,-6.366568,-3.364125,-0.330100,2.723957,5.786638,8.846131,}, // NOLINT + {8.632623,5.580498,2.526035,-0.519015,-3.543756,-6.536297,-9.485693,-12.381036,-15.211687,-17.967202,-20.637773,-23.213516,-25.685206,-28.043997,-30.281433,-32.389577,-34.360888,-36.188474,-37.865835,-39.387098,-40.746944,-41.940610,-42.963903,-43.813260,-44.485749,-44.979008,-45.291305,-45.421554,-45.369293,-45.134690,-44.718538,-44.122294,-43.347992,-42.398299,-41.276521,-39.986561,-38.532899,-36.920616,-35.155365,-33.243342,-31.191294,-29.006517,-26.696691,-24.270150,-21.735518,-19.101988,-16.379033,-13.576634,-10.704889,-7.774508,-4.796257,-1.781209,1.259343,4.314049,7.371093,}, // NOLINT + {7.268837,4.203859,1.142226,-1.904809,-4.925775,-7.909373,-10.844653,-13.720601,-16.526876,-19.253236,-21.889773,-24.427031,-26.855879,-29.167655,-31.354194,-33.407705,-35.320978,-37.087253,-38.700457,-40.154851,-41.445441,-42.567739,-43.517857,-44.292486,-44.889046,-45.305414,-45.540192,-45.592584,-45.462415,-45.150151,-44.656884,-43.984321,-43.134791,-42.111241,-40.917242,-39.556927,-38.035051,-36.356902,-34.528375,-32.555856,-30.446305,-28.207193,-25.846404,-23.372373,-20.793952,-18.120211,-15.361253,-12.526602,-9.626777,-6.672356,-3.674250,-0.643370,2.408492,5.470435,8.530599,}, // NOLINT + {8.321179,5.268340,2.214488,-0.828766,-3.850237,-6.838633,-9.782850,-12.672275,-15.496342,-18.244721,-20.907552,-23.475324,-25.938871,-28.289389,-30.518706,-32.618581,-34.582014,-36.402019,-38.072196,-39.586788,-40.940511,-42.128675,-43.147149,-43.992452,-44.661655,-45.152434,-45.463120,-45.592610,-45.540457,-45.306831,-44.892518,-44.298924,-43.528089,-42.582636,-41.465822,-40.181489,-38.734125,-37.128592,-35.370477,-33.466078,-31.421901,-29.245126,-26.943480,-24.525008,-21.998377,-19.372525,-16.656898,-13.861337,-10.995860,-8.070962,-5.097328,-2.085844,0.952091,4.005439,7.062618,}, // NOLINT + {6.962206,3.897248,0.836770,-2.207802,-5.225185,-8.204235,-11.134029,-14.003931,-16.803455,-19.522663,-22.151466,-24.680969,-27.101747,-29.405513,-31.584086,-33.629825,-35.535598,-37.294772,-38.901265,-40.349514,-41.634539,-42.751923,-43.697848,-44.469075,-45.062981,-45.477542,-45.711356,-45.763636,-45.634220,-45.323558,-44.832705,-44.163392,-43.317882,-42.299113,-41.110504,-39.756211,-38.240974,-36.569920,-34.748876,-32.784163,-30.682664,-28.451664,-26.099054,-23.633105,-21.062495,-18.396440,-15.644431,-12.816338,-9.922346,-6.972932,-3.979018,-0.951595,2.098665,5.159988,8.220970,}, // NOLINT + {8.015443,4.961723,1.908451,-1.133051,-4.151525,-7.135906,-10.075307,-12.959040,-15.776699,-18.518204,-21.173865,-23.733874,-26.189539,-28.532113,-30.753366,-32.845543,-34.801361,-36.614038,-38.277316,-39.785423,-41.133252,-42.316088,-43.329964,-44.171341,-44.837371,-45.325787,-45.634903,-45.763662,-45.711619,-45.478933,-45.066386,-44.475370,-43.707882,-42.766503,-41.654482,-40.375581,-38.934160,-37.335150,-35.584091,-33.687007,-31.650401,-29.481345,-27.187536,-24.776839,-22.257876,-19.639445,-16.930869,-14.141866,-11.282314,-8.362611,-5.393273,-2.385376,0.650325,3.702514,6.759843,}, // NOLINT + {6.661128,3.595992,0.536635,-2.505658,-5.519671,-8.494404,-11.419072,-14.283058,-17.076143,-19.788316,-22.409952,-24.931789,-27.344946,-29.641003,-31.811893,-33.850147,-35.748690,-37.500975,-39.101041,-40.543346,-41.823008,-42.935640,-43.877550,-44.645458,-45.236820,-45.649635,-45.882516,-45.934691,-45.805995,-45.496872,-45.008376,-44.342190,-43.500548,-42.486312,-41.303004,-39.954589,-38.445684,-36.781462,-34.967640,-33.010467,-30.916659,-28.693532,-26.348771,-23.890575,-21.327550,-18.668729,-15.923536,-13.101711,-10.213326,-7.268899,-4.278710,-1.253966,1.794370,4.855127,7.916958,}, // NOLINT + {7.715168,4.660528,1.607674,-1.432174,-4.447896,-7.428514,-10.363255,-13.241569,-16.053123,-18.788045,-21.436526,-23.989202,-26.437413,-28.772327,-30.985917,-33.070552,-35.019020,-36.824660,-38.481248,-39.983140,-41.325250,-42.502984,-43.512365,-44.349958,-45.012927,-45.499051,-45.806660,-45.934715,-45.882773,-45.650992,-45.240162,-44.651629,-43.887372,-42.949965,-41.842561,-40.568871,-39.133266,-37.540564,-35.796208,-33.906140,-31.876850,-29.715399,-27.428999,-25.025842,-22.514204,-19.902876,-17.201064,-14.418261,-11.564392,-8.649709,-5.684620,-2.679773,0.353635,3.404852,6.462462,}, // NOLINT + {6.365297,3.299888,0.241484,-2.798575,-5.809523,-8.780136,-11.699889,-14.558290,-17.345184,-20.050692,-22.665263,-25.179873,-27.585620,-29.874213,-32.037749,-34.068766,-35.960352,-37.706025,-39.299822,-40.736439,-42.010891,-43.118973,-44.056943,-44.821639,-45.410569,-45.821690,-46.053670,-46.105742,-45.977741,-45.670109,-45.183893,-44.520711,-43.682821,-42.673034,-41.494763,-40.151985,-38.649239,-36.991598,-35.184774,-33.234852,-31.148525,-28.932943,-26.595757,-24.145043,-21.589284,-18.937428,-16.198770,-13.382930,-10.499920,-7.559949,-4.573595,-1.551578,1.495153,4.555493,7.618248,}, // NOLINT + {7.420015,4.364404,1.311889,-1.726529,-4.739627,-7.716673,-10.646967,-13.520030,-16.325874,-19.054457,-21.696111,-24.241879,-26.682624,-29.010153,-31.216371,-33.293719,-35.235108,-37.033920,-38.684067,-40.180013,-41.516551,-42.689334,-43.694376,-44.528309,-45.188341,-45.672240,-45.978392,-46.105765,-46.053924,-45.823037,-45.413845,-44.827718,-44.066599,-43.132996,-42.030059,-40.761441,-39.331445,-37.744804,-36.006951,-34.123669,-32.101426,-29.947087,-27.668042,-25.272101,-22.767547,-20.163042,-17.467687,-14.690915,-11.842503,-8.932535,-5.971290,-2.969651,0.061913,3.112202,6.170145,}, // NOLINT + {6.074470,3.008682,-0.048886,-3.087114,-6.094899,-9.061701,-11.976803,-14.829801,-17.610745,-20.309873,-22.917685,-25.425292,-27.823894,-30.105342,-32.261745,-34.285812,-36.170654,-37.909907,-39.497719,-40.928750,-42.198219,-43.301884,-44.236076,-44.997705,-45.584226,-45.993724,-46.224821,-46.276791,-46.149464,-45.843273,-45.359259,-44.698982,-43.864717,-42.859210,-41.685833,-40.348498,-38.851710,-37.200520,-35.400352,-33.457450,-31.378316,-29.170040,-26.840144,-24.396592,-21.847880,-19.202647,-16.470336,-13.660270,-10.782352,-7.846779,-4.863934,-1.844391,1.200780,4.260833,7.324564,}, // NOLINT + {7.129749,4.073044,1.020726,-2.016253,-5.026957,-8.000620,-10.926685,-13.794867,-16.595066,-19.317459,-21.952601,-24.491523,-26.925332,-29.245736,-31.444806,-33.515159,-35.449693,-37.241926,-38.885837,-40.375920,-41.707233,-42.875181,-43.876055,-44.706438,-45.363602,-45.845349,-46.150097,-46.276813,-46.225072,-45.995032,-45.587444,-45.003640,-44.245532,-43.315643,-42.217023,-40.953285,-39.528711,-37.947939,-36.216340,-34.339655,-32.324217,-30.176840,-27.904746,-25.515767,-23.018047,-20.420121,-17.730997,-14.959980,-12.116756,-9.211320,-6.253700,-3.254986,-0.225259,2.824234,5.882686,}, // NOLINT + {5.788334,2.722062,-0.334788,-3.371164,-6.376234,-9.339306,-12.249903,-15.097819,-17.873075,-20.566047,-23.167420,-25.668247,-28.059987,-30.334544,-32.484015,-34.501309,-36.379686,-38.112718,-39.694739,-41.120392,-42.385030,-43.484421,-44.414949,-45.173570,-45.757800,-46.165704,-46.395968,-46.447839,-46.321161,-46.016358,-45.534447,-44.877027,-44.046255,-43.044894,-41.876248,-40.544195,-39.053154,-37.408065,-35.614487,-33.678406,-31.606171,-29.404877,-27.082088,-24.645506,-22.103532,-19.464799,-16.738426,-13.933893,-11.060905,-8.129488,-5.149978,-2.132925,0.910931,3.970857,7.035647,}, // NOLINT + {6.844083,3.786280,0.734038,-2.301723,-5.310185,-8.280581,-11.202645,-14.066056,-16.860871,-19.577401,-22.206302,-24.738627,-27.165659,-29.479172,-31.671412,-33.734939,-35.662859,-37.448732,-39.086618,-40.571059,-41.897170,-43.060536,-44.057386,-44.884323,-45.538725,-46.018405,-46.321781,-46.447860,-46.396215,-46.167004,-45.760969,-45.179411,-44.424221,-43.497930,-42.403490,-41.144530,-39.725149,-38.150078,-36.424502,-34.554186,-32.545328,-30.404648,-28.139348,-25.757075,-23.265894,-20.674292,-17.991132,-15.225648,-12.387404,-9.486266,-6.532403,-3.536152,-0.508403,2.540750,5.599759,}, // NOLINT + {5.506638,2.439783,-0.616412,-3.651174,-6.653487,-9.613184,-12.519531,-15.362515,-18.132394,-20.819394,-23.414469,-25.908837,-28.293914,-30.561738,-32.704634,-34.715461,-36.587495,-38.314603,-39.890927,-41.311406,-42.571355,-43.666579,-44.593565,-45.349311,-45.931303,-46.337661,-46.567113,-46.618885,-46.492836,-46.189384,-45.709528,-45.054846,-44.227457,-43.230146,-42.066038,-40.739104,-39.253609,-37.614534,-35.827230,-33.897642,-31.832202,-29.637762,-27.321714,-24.891842,-22.356390,-19.723839,-17.003304,-14.204055,-11.335760,-8.408333,-5.431971,-2.417241,0.625551,3.685313,6.751256,}, // NOLINT + {6.562760,3.503794,0.451667,-2.583068,-5.589555,-8.556796,-11.475005,-14.333929,-17.123548,-19.834438,-22.457316,-24.983269,-27.403774,-29.710652,-31.896224,-33.953178,-35.874690,-37.654417,-39.286454,-40.765443,-42.086540,-43.245453,-44.238347,-45.062019,-45.713712,-46.191378,-46.493443,-46.618906,-46.567356,-46.338949,-45.934413,-45.355054,-44.602691,-43.679848,-42.589482,-41.335102,-39.920804,-38.351243,-36.631538,-34.767361,-32.764822,-30.630657,-28.371879,-25.996067,-23.511284,-20.925713,-18.248304,-15.488120,-12.654658,-9.757646,-6.807105,-3.813400,-0.786932,2.261470,5.321122,}, // NOLINT + {5.229155,2.161611,-0.894077,-3.927320,-6.927280,-9.883548,-12.785822,-15.624112,-18.388614,-21.070035,-23.659132,-26.147216,-28.525884,-30.787235,-32.923710,-34.928234,-36.794197,-38.515466,-40.086379,-41.501832,-42.757213,-43.848437,-44.771977,-45.524930,-46.104731,-46.509605,-46.738252,-46.789930,-46.664489,-46.362339,-45.884477,-45.232446,-44.408359,-43.414876,-42.255267,-40.933265,-39.453188,-37.819875,-36.038669,-34.115423,-32.056505,-29.868634,-27.559166,-25.135757,-22.606541,-19.980019,-17.265068,-14.470921,-11.607119,-8.683485,-5.710055,-2.697401,0.344203,3.403983,6.471112,}, // NOLINT + {6.285617,3.225358,0.173251,-2.860594,-5.864900,-8.829476,-11.743993,-14.598509,-17.383227,-20.088671,-22.705732,-25.225559,-27.639742,-29.940214,-32.119356,-34.169956,-36.085277,-37.859023,-39.485413,-40.959128,-42.275393,-43.429939,-44.419027,-45.239458,-45.888579,-46.364294,-46.665081,-46.789949,-46.738493,-46.510863,-46.107791,-45.530539,-44.780946,-43.861494,-42.775028,-41.525097,-40.115751,-38.551490,-36.837460,-34.979231,-32.982872,-30.854955,-28.602408,-26.232949,-23.754208,-21.174553,-18.502684,-15.747597,-12.918677,-10.025585,-7.078258,-4.086891,-1.061884,1.986160,5.046392,}, // NOLINT + {11.696477,8.223736,4.722193,1.208741,-2.300049,-5.788188,-9.239545,-12.638758,-15.970861,-19.221396,-22.376440,-25.422664,-28.347335,-31.138394,-33.784431,-36.274723,-38.599413,-40.749154,-42.715518,-44.490853,-46.068181,-47.441650,-48.605721,-49.556254,-50.289452,-50.802627,-51.093922,-51.162250,-51.007428,-50.630117,-50.031807,-49.214827,-48.182438,-46.938596,-45.488195,-43.836886,-41.991093,-39.958144,-37.746073,-35.363679,-32.820453,-30.126736,-27.293466,-24.332287,-21.255465,-18.075944,-14.807181,-11.463207,-8.058563,-4.608308,-1.127840,2.366952,5.860043,9.334849,12.774722,}, // NOLINT + {12.416516,8.984961,5.520719,2.039854,-1.441237,-4.906620,-8.340571,-11.728164,-15.054203,-18.304583,-21.465387,-24.523229,-27.465653,-30.280291,-32.955870,-35.481520,-37.847091,-40.043255,-42.061308,-43.893315,-45.532230,-46.971585,-48.205817,-49.230223,-50.040785,-50.634392,-51.008710,-51.162288,-51.094472,-50.805457,-50.296273,-49.568778,-48.625643,-47.470592,-46.107618,-44.542159,-42.780076,-40.828250,-38.694095,-36.386069,-33.913153,-31.285157,-28.512743,-25.606999,-22.579859,-19.443852,-16.212108,-12.898361,-9.516875,-6.082406,-2.610178,0.884156,4.384585,7.874782,11.338027,}, // NOLINT + {11.202405,7.734534,4.241182,0.738915,-2.756127,-6.227948,-9.661020,-13.040302,-16.351041,-19.579196,-22.711011,-25.733586,-28.634443,-31.401788,-34.024625,-36.492256,-38.795220,-40.924295,-42.871423,-44.629092,-46.190526,-47.549843,-48.701864,-49.642431,-50.367913,-50.875714,-51.163944,-51.231605,-51.078499,-50.705266,-50.113367,-49.305070,-48.283536,-47.052616,-45.617060,-43.982379,-42.154849,-40.141645,-37.950494,-35.590036,-33.069641,-30.399050,-27.589286,-24.651568,-21.597945,-18.440931,-15.193770,-11.870194,-8.484438,-5.051181,-1.585570,1.896884,5.380302,8.848612,12.285330,}, // NOLINT + {11.933378,8.505266,5.047524,1.576279,-1.892415,-5.343115,-8.760349,-12.129064,-15.435073,-18.664123,-21.802728,-24.837876,-27.757186,-30.548793,-33.201541,-35.704871,-38.048905,-40.224500,-42.223223,-44.037225,-45.659907,-47.084677,-48.306295,-49.320042,-50.122096,-50.709421,-51.079745,-51.231641,-51.164481,-50.878454,-50.374545,-49.654627,-48.721222,-47.577927,-46.228838,-44.679025,-42.934323,-41.001353,-38.887413,-36.600687,-34.149984,-31.544844,-28.795742,-25.913352,-22.909380,-19.796262,-16.586596,-13.293914,-9.932060,-6.515663,-3.059527,0.421021,3.910362,7.392171,10.850414,}, // NOLINT + {10.718224,7.255480,3.770589,0.279515,-3.201727,-6.657513,-10.072598,-13.432367,-16.722235,-19.928373,-23.037760,-26.037220,-28.914936,-31.659288,-34.259420,-36.705147,-38.987042,-41.096178,-43.024683,-44.765114,-46.311117,-47.656776,-48.797094,-49.728072,-50.446099,-50.948669,-51.233945,-51.300957,-51.149510,-50.780221,-50.194532,-49.394624,-48.383619,-47.165149,-45.744009,-44.125443,-42.315656,-40.321538,-38.150662,-35.811536,-33.313111,-30.665205,-27.878264,-24.963381,-21.932318,-18.797297,-15.571290,-12.267717,-8.900502,-5.484026,-2.033138,1.436942,4.910688,8.372262,11.805609,}, // NOLINT + {11.459483,8.035105,4.584163,1.122639,-2.333765,-5.769791,-9.170504,-12.520900,-15.807132,-19.015334,-22.132278,-25.145241,-28.042272,-30.811196,-33.441807,-35.923408,-38.246592,-40.402291,-42.382277,-44.179000,-45.785734,-47.196455,-48.405778,-49.409196,-50.203030,-50.784277,-51.150721,-51.300992,-51.234469,-50.951337,-50.452576,-49.739945,-48.816067,-47.684154,-46.348436,-44.813834,-43.085931,-41.171229,-39.076911,-36.810842,-34.381705,-31.798789,-29.072249,-26.212656,-23.231383,-20.140446,-16.952349,-13.680249,-10.337781,-6.939068,-3.498780,-0.031931,3.446137,6.919618,10.372511,}, // NOLINT + {10.243629,6.786486,3.309982,-0.169790,-3.637416,-7.077402,-10.474894,-13.815374,-17.084829,-20.269654,-23.356813,-26.333981,-29.189155,-31.911071,-34.489246,-36.913691,-39.175084,-41.264901,-43.175292,-44.899128,-46.430125,-47.762556,-48.891622,-49.813217,-50.524023,-51.021508,-51.303926,-51.370307,-51.220464,-50.855022,-50.275313,-49.483557,-48.482700,-47.276373,-45.869152,-44.266240,-42.473640,-40.498022,-38.346904,-36.028419,-33.551433,-30.925458,-28.160759,-25.268123,-22.259024,-19.145657,-15.940187,-12.656199,-9.307166,-5.907278,-2.470986,0.986777,4.450719,7.905265,11.334719,}, // NOLINT + {10.994667,7.574143,4.130289,0.678590,-2.765572,-6.187134,-9.571341,-12.903873,-16.170782,-19.358609,-22.454405,-25.445731,-28.320691,-31.068047,-33.676998,-36.137601,-38.440451,-40.576752,-42.538508,-44.318422,-45.909792,-47.306803,-48.504260,-49.497718,-50.283574,-50.858954,-51.221642,-51.370341,-51.304438,-51.024100,-50.530323,-49.824785,-48.910018,-47.789276,-46.466504,-44.946568,-43.235042,-41.338072,-39.262703,-37.016784,-34.608592,-32.047300,-29.342707,-26.505269,-23.546074,-20.476804,-17.309762,-14.057772,-10.734447,-7.352991,-3.928346,-0.475060,2.991805,6.456738,9.903950,}, // NOLINT + {9.778221,6.326849,2.859030,-0.609621,-4.063664,-7.488004,-10.868147,-14.189830,-17.439286,-20.603228,-23.668984,-26.624164,-29.457457,-32.157639,-34.714411,-37.118115,-39.359644,-41.430652,-43.323495,-45.031239,-46.547644,-47.867261,-48.985312,-49.897871,-50.601671,-51.094247,-51.373888,-51.439654,-51.291366,-50.929627,-50.355718,-49.571817,-48.580848,-47.386282,-45.992526,-44.404801,-42.628878,-40.671279,-38.539326,-36.240938,-33.784774,-31.180106,-28.437239,-25.566147,-22.578409,-19.485934,-16.300851,-13.036055,-9.704946,-6.321342,-2.899465,0.545975,4.000103,7.447508,10.872702,}, // NOLINT + {10.538226,7.122162,3.685625,0.243639,-3.188282,-6.595525,-9.963616,-13.278464,-16.526388,-19.694318,-22.769478,-25.739675,-28.593311,-31.319288,-33.907372,-36.347510,-38.630564,-40.748107,-42.692225,-44.455706,-46.032219,-47.415951,-48.601866,-49.585656,-50.363790,-50.933431,-51.292511,-51.439687,-51.374388,-51.096794,-50.607828,-49.909164,-49.003265,-47.893269,-46.583126,-45.077499,-43.381768,-41.502048,-39.445168,-37.218739,-34.830928,-32.290610,-29.607431,-26.791550,-23.853848,-20.805744,-17.659266,-14.426994,-11.122014,-7.757947,-4.348720,-0.908876,2.546820,6.003087,9.444550,}, // NOLINT + {9.321823,5.876324,2.417226,-1.040182,-4.480722,-7.889763,-11.252869,-14.556107,-17.785999,-20.929511,-23.974194,-26.908242,-29.720078,-32.399125,-34.935158,-37.318649,-39.540867,-41.593607,-43.469394,-45.161468,-46.663751,-47.970928,-49.078346,-49.982101,-50.679096,-51.166884,-51.443832,-51.508998,-51.362213,-51.004049,-50.435804,-49.659577,-48.678127,-47.494978,-46.114399,-44.541416,-42.781644,-40.841524,-38.728081,-36.449302,-34.013442,-31.429564,-28.707602,-25.857788,-22.891169,-19.819025,-16.653730,-13.407736,-10.094168,-6.726688,-3.319077,0.114184,3.558375,6.998491,10.419259,}, // NOLINT + {10.090303,6.678796,3.249502,-0.182458,-3.602195,-6.995392,-10.347595,-13.645102,-16.874459,-20.022928,-23.077878,-26.027470,-28.860317,-31.565633,-34.133226,-36.553393,-38.817273,-40.916508,-42.843446,-44.591023,-46.153100,-47.523921,-48.698664,-49.673044,-50.443678,-51.007779,-51.363330,-51.509031,-51.444320,-51.169377,-50.685102,-49.993113,-49.095781,-47.996304,-46.698381,-45.206632,-43.526208,-41.663308,-39.624495,-37.416926,-35.048905,-32.529030,-29.866605,-27.071828,-24.155060,-21.127636,-18.001268,-14.788257,-11.501466,-8.154190,-4.760237,-1.333641,2.110818,5.558383,8.993689,}, // NOLINT + {8.874042,5.434649,1.984231,-1.461934,-4.889231,-8.283103,-11.629447,-14.914640,-18.125355,-21.248984,-24.273219,-27.186414,-29.977425,-32.635822,-35.151591,-37.515506,-39.718940,-41.753907,-43.613122,-45.289914,-46.778524,-48.073574,-49.170598,-50.065901,-50.756289,-51.239440,-51.513762,-51.578343,-51.433020,-51.078326,-50.515577,-49.746749,-48.774657,-47.602521,-46.234716,-44.675993,-42.931988,-41.008873,-38.913603,-36.653769,-34.237655,-31.674065,-28.972659,-26.143387,-23.197060,-20.145100,-16.999137,-13.771594,-10.475305,-7.123581,-3.730075,-0.308989,3.125297,6.557921,9.974048,}, // NOLINT + {9.650426,6.243693,2.821880,-0.600207,-4.007962,-7.387113,-10.723650,-14.004125,-17.215349,-20.344530,-23.379905,-26.309373,-29.121947,-31.807043,-34.354659,-36.755485,-39.000632,-41.082118,-42.992205,-44.724522,-46.272482,-47.630783,-48.794558,-49.759906,-50.523275,-51.081960,-51.434103,-51.578376,-51.514241,-51.241866,-50.762136,-50.076636,-49.187693,-48.098388,-46.812355,-45.334045,-43.668691,-41.822018,-39.800580,-37.611594,-35.262766,-32.762825,-30.120737,-27.346422,-24.450112,-21.442842,-18.336107,-15.141963,-11.873024,-8.542243,-5.163270,-1.749952,1.683478,5.122260,8.551605,}, // NOLINT + {8.434506,5.001368,1.559809,-1.875321,-5.289458,-8.668395,-11.998307,-15.265744,-18.457683,-21.561925,-24.566102,-27.459016,-30.229758,-32.867982,-35.364019,-37.708888,-39.894037,-41.911711,-43.754790,-45.416832,-46.892046,-48.175315,-49.262350,-50.149284,-50.833222,-51.311904,-51.583676,-51.647686,-51.503764,-51.152463,-50.595030,-49.833414,-48.870239,-47.708976,-46.353571,-44.808797,-43.080080,-41.173497,-39.095847,-36.854518,-34.457681,-31.913774,-29.232355,-26.423205,-23.496932,-20.464492,-17.337474,-14.127996,-10.848674,-7.512423,-4.132956,-0.723902,2.700321,6.125636,9.536821,}, // NOLINT + {9.218348,5.816634,2.402337,-1.009882,-4.405686,-7.771003,-11.092193,-14.355935,-17.549328,-20.659872,-23.675904,-26.585705,-29.378494,-32.043855,-34.572102,-36.953982,-39.180949,-41.245090,-43.139072,-44.856185,-46.390477,-47.736586,-48.889799,-49.846255,-50.602522,-51.156023,-51.504834,-51.647715,-51.584143,-51.314276,-50.839004,-50.159809,-49.279008,-48.199589,-46.925111,-45.459951,-43.809119,-41.978276,-39.973863,-37.802798,-35.472821,-32.992236,-30.370011,-27.615603,-24.739273,-21.751723,-18.664242,-15.488525,-12.237025,-8.922550,-5.558329,-2.158005,1.264348,4.694371,8.117293,}, // NOLINT + {8.002923,4.576125,1.143411,-2.280657,-5.681802,-9.046030,-12.359756,-15.609816,-18.783490,-21.868439,-24.853268,-27.726347,-30.477468,-33.095925,-35.572727,-37.898962,-40.066260,-42.067119,-43.894533,-45.542147,-47.004378,-48.276226,-49.353440,-50.232310,-50.910019,-51.384283,-51.653573,-51.717026,-51.574481,-51.226455,-50.674208,-49.919593,-48.965183,-47.814403,-46.471069,-44.939840,-43.226003,-41.335539,-39.275037,-37.051756,-34.673568,-32.148987,-29.487129,-26.697680,-23.790852,-20.777544,-17.669012,-14.477341,-11.214645,-7.893798,-4.528022,-1.130913,2.283562,5.701129,9.107247,}, // NOLINT + {8.793863,5.397182,1.990515,-1.411858,-4.795771,-8.147504,-11.453520,-14.700809,-17.876740,-20.969084,-23.966151,-26.856746,-29.630161,-32.276336,-34.785608,-37.149065,-39.358301,-41.405568,-43.283686,-44.986116,-46.507139,-47.841389,-48.984425,-49.932138,-50.681519,-51.229925,-51.575514,-51.717055,-51.654032,-51.386606,-50.915612,-50.242591,-49.369731,-48.299929,-47.036714,-45.584292,-43.947662,-42.132246,-40.144354,-37.990856,-35.679173,-33.217494,-30.614544,-27.879723,-25.022840,-22.054517,-18.985782,-15.828214,-12.593892,-9.295387,-5.945701,-2.558291,0.853159,4.274367,7.690935,}, // NOLINT + {7.579008,4.158689,0.734813,-2.678328,-6.066623,-9.416395,-12.714210,-15.947216,-19.102929,-22.169321,-25.134905,-27.988675,-30.720241,-33.319713,-35.777660,-38.085859,-40.235871,-42.220321,-44.032430,-45.666081,-47.115595,-48.376294,-49.443916,-50.314957,-50.986569,-51.456592,-51.723459,-51.786364,-51.645154,-51.300331,-50.753112,-50.005310,-49.059534,-47.918911,-46.587277,-45.069207,-43.369915,-41.495145,-39.451356,-37.245662,-34.885756,-32.379952,-29.737155,-26.966868,-24.079146,-21.084572,-17.994286,-14.819928,-11.573581,-8.267823,-4.915623,-1.530364,1.874219,5.284170,8.685085,}, // NOLINT + {8.376480,4.985144,1.586122,-1.806438,-5.178646,-8.516933,-11.808029,-15.039174,-18.197949,-21.272334,-24.250964,-27.122762,-29.877275,-32.504647,-34.995423,-37.340919,-39.532858,-41.563654,-43.426344,-45.114568,-46.622556,-47.945253,-49.078203,-50.017578,-50.760251,-51.303724,-51.646163,-51.786392,-51.723907,-51.458860,-50.992049,-50.325050,-49.459901,-48.399467,-47.147230,-45.707305,-44.084439,-42.284089,-40.312384,-38.175887,-35.882046,-33.438812,-30.854711,-28.138893,-25.301105,-22.351497,-19.301267,-16.161438,-12.943925,-9.661113,-6.325551,-2.951020,0.449500,3.861909,7.272026,}, // NOLINT + {7.162438,3.748687,0.333615,-3.068631,-6.444297,-9.779756,-13.061984,-16.278270,-19.416329,-22.464492,-25.411382,-28.246321,-30.959009,-33.539715,-35.979568,-38.269930,-40.402948,-42.371373,-44.168616,-45.788495,-47.225735,-48.475519,-49.533904,-50.397310,-51.063028,-51.528813,-51.793329,-51.855701,-51.715781,-51.374071,-50.831737,-50.090590,-49.153116,-48.022358,-46.702255,-45.197065,-43.511887,-41.652423,-39.624942,-37.436403,-35.094397,-32.606874,-29.982725,-27.231182,-24.362099,-21.385981,-18.313407,-15.156083,-11.925803,-8.634900,-5.296104,-1.922611,1.472210,4.874447,8.270126,}, // NOLINT + {7.966102,4.580120,1.188774,-2.193979,-5.554574,-8.879559,-12.155993,-15.371276,-18.513205,-21.570066,-24.530591,-27.384013,-30.120041,-32.729117,-35.201867,-37.529712,-39.704755,-41.719490,-43.567135,-45.241434,-46.736770,-48.048239,-49.171376,-50.102588,-50.838735,-51.377388,-51.716769,-51.855728,-51.793770,-51.531050,-51.068400,-50.407184,-49.549566,-48.498303,-47.256717,-45.828903,-44.219516,-42.433915,-40.477823,-38.358130,-36.081642,-33.656416,-31.090667,-28.393518,-25.574341,-22.643266,-19.610932,-16.488454,-13.287468,-10.020076,-6.698636,-3.336661,0.053060,3.456704,6.860203,}, // NOLINT + {6.752873,3.345757,-0.060521,-3.452004,-6.815098,-10.136538,-13.403424,-16.603273,-19.724108,-22.754410,-25.682946,-28.499343,-31.193680,-33.755851,-36.178024,-38.451130,-40.567657,-42.520487,-44.303118,-45.909666,-47.334875,-48.574117,-49.623381,-50.479328,-51.139249,-51.600985,-51.863191,-51.925036,-51.786375,-51.447678,-50.910132,-50.175468,-49.246100,-48.125062,-46.816075,-45.323425,-43.652045,-41.807463,-39.795946,-37.624147,-35.299472,-32.829959,-30.224034,-27.490829,-24.640024,-21.681741,-18.626743,-15.486133,-12.271636,-8.995354,-5.669858,-2.307885,1.077104,4.471597,7.861677,}, // NOLINT + {7.562350,4.181855,0.798242,-2.574836,-5.923845,-9.235753,-12.497750,-15.697416,-18.822865,-21.862541,-24.805311,-27.640728,-30.358714,-32.949756,-35.404855,-37.715603,-39.874145,-41.873183,-43.706178,-45.366882,-46.849899,-48.150340,-49.264029,-50.187204,-50.916991,-51.450946,-51.787342,-51.925063,-51.863622,-51.603170,-51.144514,-50.488992,-49.638731,-48.596354,-47.365232,-45.949256,-44.352931,-42.581664,-40.641022,-38.537504,-36.278112,-33.870469,-31.322766,-28.643755,-25.842803,-22.929732,-19.914995,-16.809613,-13.624825,-10.372617,-7.065238,-3.715457,-0.336446,3.058411,6.455354,}, // NOLINT + {6.350070,2.949617,-0.447879,-3.828686,-7.179406,-10.486994,-13.738790,-16.922532,-20.026489,-23.039211,-25.949852,-28.748158,-31.424283,-33.968874,-36.373466,-38.629688,-40.730069,-42.667659,-44.436077,-46.029600,-47.443070,-48.671947,-49.712380,-50.561013,-51.215311,-51.673088,-51.933039,-51.994370,-51.856934,-51.521205,-50.988331,-50.259937,-49.338438,-48.226903,-46.928803,-45.448387,-43.790478,-41.960488,-39.964494,-37.809003,-35.501450,-33.049406,-30.461312,-27.746054,-24.913099,-21.972428,-18.934526,-15.810358,-12.611370,-9.349497,-6.037198,-2.686588,0.688686,4.075408,7.459974,}, // NOLINT + {7.164987,3.790209,0.414162,-2.949210,-6.286871,-9.585853,-12.833593,-16.017873,-19.127110,-22.149837,-25.075350,-27.893142,-30.593566,-33.166914,-35.604751,-37.898740,-40.041102,-42.024936,-43.843518,-45.490974,-46.961941,-48.251674,-49.356021,-50.271438,-50.995001,-51.524377,-51.857879,-51.994396,-51.933463,-51.675227,-51.220475,-50.570513,-49.727390,-48.693774,-47.472825,-46.068410,-44.484988,-42.727630,-40.801985,-38.714375,-36.471627,-34.081153,-31.551061,-28.889881,-26.106739,-23.211363,-20.214081,-17.125192,-13.956350,-10.719023,-7.425339,-4.087833,-0.719350,2.666740,6.056991,}, // NOLINT + {5.953782,2.560005,-0.828802,-4.199076,-7.537500,-10.831451,-14.068405,-17.236333,-20.323623,-23.319167,-26.212326,-28.992968,-31.651307,-34.178570,-36.566057,-38.805738,-40.890325,-42.813029,-44.567580,-46.148362,-47.550365,-48.769157,-49.800925,-50.642472,-51.291223,-51.745119,-52.002876,-52.063702,-51.927459,-51.594611,-51.066243,-50.344037,-49.430270,-48.327955,-47.040490,-45.572024,-43.927268,-42.111533,-40.130688,-37.991298,-35.700325,-33.265415,-30.694748,-27.997068,-25.181619,-22.258212,-19.237088,-16.129051,-12.945339,-9.697611,-6.398012,-3.058912,0.306593,3.685600,7.064506,}, // NOLINT + {6.773740,3.404332,0.036299,-3.317499,-6.643836,-9.930070,-13.163767,-16.333051,-19.426308,-22.432458,-25.340939,-28.141475,-30.824448,-33.380723,-35.801686,-38.079367,-40.205903,-42.174845,-43.979288,-45.613779,-47.072975,-48.352235,-49.447536,-50.355323,-51.072816,-51.597723,-51.928383,-52.063728,-52.003294,-51.747226,-51.296289,-50.651762,-49.815658,-48.790548,-47.579550,-46.186429,-44.615553,-42.871853,-40.960911,-38.888821,-36.662351,-34.288713,-31.775756,-29.132048,-26.366251,-23.488307,-20.507868,-17.435474,-14.282253,-11.059587,-7.779389,-4.453992,-1.096042,2.281412,5.664984,}, // NOLINT + {5.563607,2.176517,-1.203523,-4.563411,-7.889688,-11.170209,-14.392586,-17.544881,-20.615961,-23.594573,-26.470619,-29.233807,-31.874976,-34.385089,-36.755831,-38.979407,-41.048629,-42.956732,-44.697675,-46.266018,-47.656805,-48.865724,-49.889042,-50.723635,-51.366991,-51.817102,-52.072704,-52.133034,-51.997951,-51.667914,-51.143979,-50.427796,-49.521631,-48.428266,-47.151165,-45.694406,-44.062514,-42.260705,-40.294736,-38.170972,-35.896274,-33.478136,-30.924559,-28.244080,-25.445788,-22.539383,-19.534663,-16.442412,-13.273775,-10.040033,-6.753147,-3.425347,-0.069397,3.301855,6.675057,}, // NOLINT + {6.388368,3.024808,-0.335654,-3.679871,-6.995081,-10.268715,-13.488621,-16.643044,-19.720791,-22.710641,-25.602337,-28.385924,-31.051928,-33.591366,-35.995807,-38.257305,-40.368546,-42.322712,-44.113547,-45.735369,-47.183058,-48.452035,-49.538485,-50.438876,-51.150418,-51.670965,-51.998858,-52.133059,-52.073114,-51.819166,-51.371965,-50.732752,-49.903504,-48.886715,-47.685445,-46.303375,-44.744765,-43.014464,-41.117856,-39.060990,-36.850403,-34.493248,-31.997183,-29.370467,-26.621946,-23.760832,-20.796992,-17.740731,-14.602853,-11.394617,-8.127717,-4.814256,-1.466631,1.902091,5.278990,}, // NOLINT + {5.179344,1.798986,-1.572400,-4.921769,-8.236282,-11.503553,-14.711554,-17.848805,-20.903649,-23.865799,-26.724896,-29.471136,-32.095238,-34.588641,-36.943087,-39.150825,-41.204840,-43.098762,-44.826464,-46.382624,-47.762444,-48.961702,-49.976746,-50.804545,-51.442625,-51.889026,-52.142522,-52.202364,-52.068416,-51.741123,-51.221524,-50.511229,-49.612385,-48.527871,-47.260957,-45.815596,-44.196272,-42.408099,-40.456671,-38.348218,-36.089472,-33.687635,-31.150905,-28.487300,-25.705837,-22.815955,-19.827498,-16.750900,-13.596871,-10.376985,-7.102666,-3.786035,-0.439609,2.923888,6.291384,}, // NOLINT + {6.008600,2.650787,-0.701942,-4.036870,-7.340864,-10.602068,-13.808370,-16.948305,-20.010401,-22.984360,-25.859706,-28.626704,-31.275999,-33.798990,-36.187214,-38.432973,-40.529146,-42.468973,-44.246377,-45.855802,-47.292233,-48.551213,-49.628948,-50.522064,-51.227837,-51.744115,-52.069302,-52.202387,-52.142926,-51.891055,-51.447509,-50.813499,-49.990965,-48.982311,-47.790564,-46.419305,-44.872692,-43.155475,-41.272944,-39.230969,-37.035948,-34.694906,-32.215382,-29.605422,-26.873639,-24.029162,-21.081649,-18.041122,-14.918447,-11.724385,-8.470560,-5.168914,-1.831623,1.528530,4.898708,}, // NOLINT + {4.800738,1.427071,-1.935685,-5.274743,-8.577504,-11.831729,-15.025588,-18.147644,-21.186914,-24.132875,-26.975394,-29.704960,-32.312500,-34.789457,-37.127816,-39.320078,-41.359394,-43.239297,-44.953996,-46.498236,-47.867310,-49.057119,-50.064081,-50.885216,-51.518129,-51.960899,-52.212331,-52.271691,-52.138849,-51.814242,-51.298870,-50.594321,-49.702734,-48.626832,-47.369838,-45.935657,-44.328606,-42.553730,-40.616629,-38.523165,-36.280050,-33.894431,-31.373923,-28.726907,-25.962007,-23.088389,-20.115893,-17.054520,-13.915161,-10.708741,-7.446802,-4.141193,-0.804283,2.551478,5.913141,}, // NOLINT + {5.634174,2.282164,-1.062917,-4.388259,-7.681471,-10.930371,-14.123264,-17.248635,-20.295829,-23.254033,-26.113283,-28.864002,-31.496984,-34.003617,-36.376097,-38.606406,-40.687784,-42.613615,-44.377860,-45.975140,-47.400550,-48.649689,-49.718971,-50.604967,-51.305060,-51.817167,-52.139720,-52.271717,-52.212728,-51.962896,-51.522930,-50.894013,-50.078006,-49.077364,-47.894950,-46.534272,-44.999413,-43.295016,-41.426246,-39.398849,-37.219125,-34.893940,-32.430547,-29.836993,-27.121672,-24.293542,-21.362041,-18.337131,-15.229192,-12.049123,-8.808259,-5.518215,-2.191195,1.160493,4.523803,}, // NOLINT + {4.427428,1.060551,-2.293729,-5.622523,-8.913636,-12.155028,-15.334939,-18.442269,-21.466144,-24.396027,-27.222316,-29.935525,-32.526743,-34.987672,-37.310259,-39.487372,-41.512165,-43.378387,-45.080347,-46.612907,-47.971492,-49.152011,-50.151044,-50.965661,-51.593513,-52.032725,-52.282132,-52.341020,-52.209257,-51.887275,-51.376058,-50.677127,-49.792602,-48.725116,-47.477882,-46.054647,-44.459723,-42.697907,-40.774627,-38.695938,-36.468140,-34.098298,-31.593916,-28.963142,-26.214376,-23.356826,-20.399916,-17.353806,-14.228599,-11.035570,-7.785882,-4.491290,-1.163682,2.184357,5.540193,}, // NOLINT + {5.264716,1.918675,-1.418740,-4.734726,-8.017103,-11.253901,-14.433537,-17.544852,-20.577069,-23.519822,-26.363239,-29.097953,-31.714878,-34.205794,-36.562627,-38.777820,-40.844667,-42.756672,-44.508057,-46.093438,-47.508051,-48.747675,-49.808551,-50.687582,-51.382126,-51.890152,-52.210110,-52.341041,-52.282526,-52.034689,-51.598232,-50.974308,-50.164765,-49.171917,-47.998625,-46.648328,-45.125013,-43.433162,-41.577939,-39.564836,-37.400034,-35.090340,-32.642846,-30.065399,-27.366242,-24.554138,-21.638311,-18.628739,-15.535435,-12.369139,-9.140983,-5.862493,-2.545510,0.797627,4.154344,}, // NOLINT + {4.059290,0.699175,-2.646515,-5.965320,-9.244975,-12.473640,-15.639860,-18.732469,-21.741131,-24.655509,-27.465840,-30.162970,-32.738193,-35.183256,-37.490486,-39.652723,-41.663300,-43.516096,-45.205583,-46.726757,-48.074950,-49.246404,-50.237678,-51.045891,-51.668782,-52.104506,-52.351927,-52.410347,-52.279638,-51.960218,-51.453023,-50.759646,-49.882048,-48.822743,-47.585131,-46.172622,-44.589503,-42.840545,-40.930958,-38.866646,-36.653875,-34.299526,-31.810974,-29.196099,-26.463306,-23.621436,-20.679933,-17.648554,-14.537587,-11.357711,-8.120108,-4.836248,-1.518063,1.822283,5.172282,}, // NOLINT + {4.900416,1.560088,-1.769632,-5.076371,-8.348028,-11.572869,-14.739451,-17.836825,-20.854365,-23.781944,-26.609826,-29.328775,-31.930022,-34.405276,-36.746755,-38.947184,-40.999787,-42.898315,-44.637039,-46.210752,-47.614784,-48.844974,-49.897698,-50.769918,-51.459059,-51.963050,-52.280476,-52.410368,-52.352313,-52.106436,-51.673424,-51.054379,-50.251165,-49.266046,-48.101647,-46.761493,-45.249492,-43.569957,-41.727961,-39.728889,-37.578807,-35.284244,-32.852431,-30.290821,-27.607495,-24.811161,-21.910895,-18.916259,-15.837347,-12.684630,-9.469016,-6.201887,-2.894900,0.439727,3.789739,}, // NOLINT + {3.695995,0.342666,-2.994635,-6.303424,-9.571705,-12.787862,-15.940545,-19.018938,-22.012590,-24.911508,-27.706144,-30.387451,-32.946969,-35.376524,-37.668643,-39.816268,-41.812885,-43.652538,-45.329769,-46.839629,-48.177782,-49.340330,-50.323976,-51.125927,-51.743942,-52.176243,-52.421713,-52.479671,-52.349995,-52.033094,-51.529906,-50.841903,-49.971080,-48.919963,-47.691620,-46.289633,-44.718112,-42.981709,-41.085506,-39.035457,-36.837372,-34.498229,-32.025199,-29.425998,-26.708858,-23.882488,-20.956108,-17.939295,-14.842197,-11.675381,-8.449723,-5.176584,-1.867669,1.464978,4.809035,}, // NOLINT + {4.540620,1.206175,-2.115928,-5.413438,-8.674494,-11.887485,-15.041197,-18.124813,-21.127901,-24.040558,-26.853174,-29.556638,-32.142386,-34.602292,-36.928783,-39.114568,-41.153270,-43.038547,-44.764860,-46.327137,-47.720780,-48.941728,-49.986460,-50.851990,-51.535767,-52.035870,-52.350817,-52.479692,-52.422094,-52.178143,-51.748510,-51.134283,-50.337245,-49.359584,-48.204046,-46.873891,-45.372958,-43.705544,-41.876618,-39.891200,-37.755561,-35.475970,-33.059454,-30.513342,-27.845648,-25.064806,-22.179766,-19.199904,-16.135165,-12.995804,-9.792613,-6.536729,-3.239661,0.086578,3.429887,}, // NOLINT + {3.337317,-0.009311,-3.338158,-6.637043,-9.894101,-13.097879,-16.237247,-19.301528,-22.280445,-25.164193,-27.943282,-30.609203,-33.153246,-35.567648,-37.844818,-39.978098,-41.961010,-43.787735,-45.452943,-46.951784,-48.279996,-49.433806,-50.409967,-51.205750,-51.819000,-52.247942,-52.491492,-52.548995,-52.420328,-52.105882,-51.606573,-50.923905,-50.059721,-49.016561,-47.797397,-46.405737,-44.845596,-43.121531,-41.238556,-39.202249,-37.018767,-34.694562,-32.236770,-29.652978,-26.951231,-24.140090,-21.228461,-18.226184,-15.142808,-11.988823,-8.774969,-5.512440,-2.212717,1.112315,4.450439,}, // NOLINT + {4.185216,0.856752,-2.457737,-5.746182,-8.996712,-12.198025,-15.339013,-18.409011,-21.397947,-24.295832,-27.093372,-29.781656,-32.352183,-34.797059,-37.108741,-39.280296,-41.305214,-43.177477,-44.891606,-46.442638,-47.826086,-49.037988,-50.074881,-50.933765,-51.612343,-52.108620,-52.421136,-52.549016,-52.491868,-52.249811,-51.823498,-51.213978,-50.423036,-49.452759,-48.305850,-46.985529,-45.495435,-43.839915,-42.023634,-40.051849,-37.930404,-35.665518,-33.264013,-30.733188,-28.080832,-25.315252,-22.445192,-19.479922,-16.429123,-13.302947,-10.112004,-6.867246,-3.580014,-0.262113,3.074518,}, // NOLINT + {2.983065,-0.356854,-3.677313,-6.966412,-10.212383,-13.403942,-16.530146,-19.580502,-22.544977,-25.413750,-28.177744,-30.828327,-33.357158,-35.756517,-38.019130,-40.138312,-42.107749,-43.921781,-45.575161,-47.063183,-48.381657,-49.526819,-50.495672,-51.285410,-51.893935,-52.319595,-52.561258,-52.618318,-52.490639,-52.178616,-51.683194,-51.005644,-50.148009,-49.112645,-47.902549,-46.520976,-44.972018,-43.260041,-41.390076,-39.367432,-37.198132,-34.888600,-32.445847,-29.877194,-27.190607,-24.394466,-21.497624,-18.509381,-15.439539,-12.298228,-9.096071,-5.844028,-2.553488,0.763889,4.096097,}, // NOLINT + {3.834011,0.511388,-2.795486,-6.074794,-9.314919,-12.504651,-15.633069,-18.689731,-21.664607,-24.547996,-27.330688,-30.003927,-32.559553,-34.989561,-37.286775,-39.444244,-41.455662,-43.315121,-45.017309,-46.557301,-47.930744,-49.133732,-50.162915,-51.015417,-51.688875,-52.181290,-52.491432,-52.618338,-52.561636,-52.321435,-51.898367,-51.293522,-50.508557,-49.545516,-48.407125,-47.096397,-45.617027,-43.973127,-42.169432,-40.210945,-38.103470,-35.852990,-33.466283,-30.950488,-28.313230,-25.562653,-22.707356,-19.756431,-16.719404,-13.606255,-10.427390,-7.193623,-3.916120,-0.606508,2.723414,}, // NOLINT + {2.632966,-0.700233,-4.012396,-7.291746,-10.526751,-13.706098,-16.819463,-19.856094,-22.806234,-25.660340,-28.409401,-31.044937,-33.558802,-35.943408,-38.191665,-40.296962,-42.253195,-44.054696,-45.696489,-47.173860,-48.482734,-49.619508,-50.581109,-51.364922,-51.968807,-52.391218,-52.631029,-52.687640,-52.560928,-52.251283,-51.759580,-51.087169,-50.235940,-49.208220,-48.006952,-46.635378,-45.097406,-43.397359,-41.540090,-39.530898,-37.375613,-35.080554,-32.652524,-30.098755,-27.427110,-24.645748,-21.763346,-18.789152,-15.732625,-12.603855,-9.413248,-6.171638,-2.890147,0.419634,3.745984,}, // NOLINT + {3.486799,0.170129,-3.129213,-6.399479,-9.629302,-12.807599,-15.923600,-18.967047,-21.928094,-24.797153,-27.565240,-30.223756,-32.764599,-35.180063,-37.462961,-39.606590,-41.604730,-43.451663,-45.142031,-46.671162,-48.034718,-49.229014,-50.250631,-51.096785,-51.765147,-52.253925,-52.561709,-52.687660,-52.631398,-52.393039,-51.973174,-51.372902,-50.593785,-49.637902,-48.507830,-47.206591,-45.737758,-44.105349,-42.313964,-40.368585,-38.274761,-36.038527,-33.666383,-31.165362,-28.542982,-25.807191,-22.966455,-20.029694,-17.006214,-13.905857,-10.738915,-7.516094,-4.248278,-0.946878,2.376342,}, // NOLINT + {2.286763,-1.039640,-4.343618,-7.613300,-10.837314,-14.005010,-17.105408,-20.128489,-23.064514,-25.904128,-28.638493,-31.259213,-33.758334,-36.128409,-38.362532,-40.454185,-42.397398,-44.186642,-45.816990,-47.283858,-48.583323,-49.711795,-50.666275,-51.444227,-52.043593,-52.462808,-52.700794,-52.756962,-52.631196,-52.323877,-51.835854,-51.168473,-50.323548,-49.303400,-48.110819,-46.749031,-45.221877,-43.533537,-41.688775,-39.692793,-37.551312,-35.270459,-32.856961,-30.317883,-27.660970,-24.894142,-22.026051,-19.065590,-16.022255,-12.905870,-9.726696,-6.495386,-3.222935,0.079260,3.399542,}, // NOLINT + {3.143352,-0.167305,-3.459156,-6.720378,-9.940081,-13.107004,-16.210783,-19.241198,-22.188544,-25.043495,-27.797193,-30.441165,-32.967456,-35.368554,-37.637393,-39.767403,-41.752483,-43.587010,-45.265848,-46.784258,-48.138202,-49.323853,-50.338018,-51.177944,-51.841368,-52.326484,-52.631964,-52.756980,-52.701156,-52.464602,-52.047898,-51.452117,-50.678779,-49.729922,-48.608050,-47.316132,-45.857679,-44.236563,-42.457303,-40.524758,-38.444468,-36.222208,-33.864427,-31.377909,-28.770230,-26.049000,-23.222595,-20.299779,-17.289722,-14.202115,-11.047022,-7.834911,-4.576630,-1.283448,2.033090,}, // NOLINT + {8.818064,5.112625,1.397908,-2.309067,-5.992190,-9.635299,-13.223356,-16.741570,-20.175792,-23.512590,-26.739195,-29.843391,-32.813922,-35.639852,-38.311194,-40.818606,-43.153451,-45.307829,-47.274551,-49.047141,-50.619794,-51.987479,-53.145856,-54.091273,-54.820814,-55.332249,-55.624056,-55.695406,-55.546174,-55.176932,-54.588941,-53.784169,-52.765269,-51.535598,-50.099165,-48.460768,-46.625830,-44.600490,-42.391569,-40.006582,-37.453773,-34.742032,-31.880966,-28.880785,-25.752659,-22.507932,-19.158981,-15.718723,-12.200636,-8.618845,-4.988032,-1.323416,2.359256,6.043906,9.713519,}, // NOLINT + {9.321341,5.661139,1.988272,-1.680834,-5.330287,-8.944468,-12.508411,-16.007615,-19.428241,-22.756975,-25.981148,-29.088692,-32.068219,-34.908949,-37.600833,-40.134474,-42.501094,-44.692635,-46.701760,-48.521752,-50.146611,-51.570994,-52.790298,-53.800571,-54.598416,-55.181359,-55.547441,-55.695426,-55.624751,-55.335542,-54.828602,-54.105428,-53.168194,-52.019744,-50.663651,-49.104186,-47.346238,-45.395521,-43.258332,-40.941733,-38.453480,-35.802027,-32.996536,-30.046824,-26.963569,-23.757862,-20.441683,-17.027618,-13.528894,-9.959356,-6.333538,-2.666489,1.026352,4.728593,8.423502,}, // NOLINT + {8.303262,4.608301,0.907579,-2.782294,-6.445275,-10.065899,-13.629202,-17.120876,-20.527154,-23.834987,-27.031835,-30.106063,-33.046403,-35.842520,-38.484738,-40.963892,-43.271673,-45.400490,-47.343345,-49.093885,-50.646847,-51.997112,-53.140519,-54.073572,-54.793508,-55.298155,-55.586046,-55.656392,-55.509069,-55.144639,-54.564292,-53.769905,-52.764151,-51.550155,-50.131812,-48.513713,-46.701187,-44.700096,-42.516898,-40.159101,-37.634447,-34.951783,-32.120211,-29.149748,-26.050998,-22.835303,-19.514535,-16.101204,-12.608513,-9.050369,-5.440647,-1.794725,1.872316,5.544398,9.205301,}, // NOLINT + {8.817539,5.166448,1.506251,-2.147045,-5.777689,-9.370704,-12.911074,-16.385202,-19.779032,-23.079837,-26.275268,-29.353656,-32.303791,-35.115383,-37.778604,-40.284345,-42.624124,-44.790238,-46.775472,-48.573383,-50.178216,-51.584790,-52.788630,-53.785952,-54.573551,-55.148959,-55.510306,-55.656410,-55.586730,-55.301378,-54.801131,-54.087417,-53.162396,-52.028635,-50.689768,-49.149858,-47.413492,-45.486263,-43.374382,-41.084470,-38.624110,-36.001438,-33.225450,-30.305497,-27.251987,-24.075706,-20.788294,-17.401952,-13.929572,-10.384683,-6.781402,-3.134390,0.541023,4.229061,7.913442,}, // NOLINT + {7.795762,4.111574,0.425146,-3.247311,-6.890144,-10.488233,-14.026949,-17.492347,-20.871011,-24.150195,-27.317971,-30.362413,-33.273196,-36.040052,-38.653649,-41.105111,-43.386408,-45.490190,-47.409662,-49.138819,-50.672392,-52.005571,-53.134423,-54.055385,-54.765935,-55.263954,-55.548015,-55.617377,-55.471914,-55.112170,-54.539303,-53.755137,-52.762166,-51.563430,-50.162794,-48.564582,-46.773919,-44.796452,-42.638637,-40.307333,-37.810467,-35.156213,-32.353613,-29.412334,-26.342447,-23.155520,-19.862568,-16.475932,-13.008474,-9.473618,-5.885331,-2.258115,1.392902,5.052187,8.703737,}, // NOLINT + {8.320346,4.678919,1.031702,-2.605532,-6.217416,-9.789094,-13.306303,-16.755121,-20.122472,-23.395692,-26.562797,-29.612356,-32.533683,-35.316619,-37.951701,-40.430101,-42.743637,-44.884757,-46.846617,-48.622956,-50.208191,-51.597309,-52.786094,-53.770780,-54.548356,-55.116382,-55.473123,-55.617395,-55.548685,-55.267108,-54.773385,-54.068937,-53.155799,-52.036473,-50.714405,-49.193490,-47.478355,-45.574214,-43.486992,-41.223262,-38.790231,-36.195910,-33.448755,-30.558130,-27.533871,-24.386593,-21.127546,-17.768627,-14.322370,-10.801956,-7.221158,-3.594359,0.063485,3.737168,7.410361,}, // NOLINT + {7.295035,3.622229,-0.049593,-3.704474,-7.327115,-10.902517,-14.416966,-17.856308,-21.207633,-24.458582,-27.597266,-30.612802,-33.494538,-36.232693,-38.818138,-41.242460,-43.497800,-45.577022,-47.473670,-49.181867,-50.696488,-52.012987,-53.127516,-54.036728,-54.738127,-55.229635,-55.509964,-55.578359,-55.434712,-55.079531,-54.513971,-53.739798,-52.759322,-51.575548,-50.192169,-48.613369,-46.844107,-44.889839,-42.756750,-40.451630,-37.981871,-35.355517,-32.581383,-29.668850,-26.627927,-23.468877,-20.203394,-16.843232,-13.400833,-9.889278,-6.322211,-2.713953,0.920937,4.567121,8.208714,}, // NOLINT + {7.829637,4.198294,0.564350,-3.056430,-6.649524,-10.199964,-13.693821,-17.117787,-20.458904,-23.704845,-26.843976,-29.865222,-32.758220,-35.512858,-38.120359,-40.571931,-42.859743,-44.976403,-46.915393,-48.670628,-50.236619,-51.608721,-52.782757,-53.755065,-54.522825,-55.083670,-55.435893,-55.578378,-55.510620,-55.232735,-54.745394,-54.050000,-53.148433,-52.043287,-50.737640,-49.235399,-47.540916,-45.659361,-43.596374,-41.358287,-38.952130,-36.385511,-33.666865,-30.804874,-27.809472,-24.690781,-21.459754,-18.127798,-14.707499,-11.211523,-7.653160,-4.046509,-0.406241,3.252528,6.914227,}, // NOLINT + {6.801006,3.139991,-0.516886,-4.154039,-7.756429,-11.309555,-14.799512,-18.213022,-21.537339,-24.760391,-27.870710,-30.857513,-33.710633,-36.420570,-38.978441,-41.376132,-43.606010,-45.661201,-47.535448,-49.223103,-50.719220,-52.019392,-53.119919,-54.017632,-54.710033,-55.195219,-55.471892,-55.539342,-55.397465,-55.046763,-54.488318,-53.723844,-52.755633,-51.586500,-50.220036,-48.660274,-46.911976,-44.980446,-42.871596,-40.592036,-38.148916,-35.550083,-32.803940,-29.919599,-26.906701,-23.775667,-20.537356,-17.203344,-13.785820,-10.297529,-6.751763,-3.162431,0.455972,4.088590,7.720051,}, // NOLINT + {7.345203,3.724355,0.104157,-3.500431,-7.074456,-10.603567,-14.074216,-17.473500,-20.788587,-24.007604,-27.119118,-30.112405,-32.977399,-35.704486,-38.284807,-40.710016,-42.972532,-45.065243,-46.981791,-48.716307,-50.263567,-51.618990,-52.778555,-53.738794,-54.496979,-55.050824,-55.398620,-55.539359,-55.472536,-55.198247,-54.717193,-54.030631,-53.140452,-52.049034,-50.759594,-49.275521,-47.601407,-45.741975,-43.702648,-41.489723,-39.109873,-36.570517,-33.879691,-31.046124,-28.079117,-24.988577,-21.785199,-18.480243,-15.085556,-11.613640,-8.077675,-4.491318,-0.868794,2.775009,6.424736,}, // NOLINT + {6.313858,2.664951,-0.976951,-4.596269,-8.178377,-11.709141,-15.174893,-18.562864,-21.860418,-25.055943,-28.138208,-31.096766,-33.921754,-36.603948,-39.134761,-41.506211,-43.711197,-45.742828,-47.595107,-49.262700,-50.740645,-52.024856,-53.111688,-53.998110,-54.681728,-55.160705,-55.433801,-55.500322,-55.360178,-55.013827,-54.462394,-53.707422,-52.751135,-51.596366,-50.246433,-48.705334,-46.977564,-45.068326,-42.983220,-40.728783,-38.311811,-35.739972,-33.021310,-30.164835,-27.179619,-24.076142,-20.864683,-17.556595,-14.163786,-10.698592,-7.174021,-3.603859,-0.001971,3.616825,7.237704,}, // NOLINT + {6.866970,3.256989,-0.349400,-3.937242,-7.492106,-11.000277,-14.447718,-17.822505,-21.111829,-24.304286,-27.388453,-30.354358,-33.191715,-35.891560,-38.445157,-40.844549,-43.082272,-45.151477,-47.046015,-48.760242,-50.289111,-51.628253,-52.773638,-53.722098,-54.470880,-55.017806,-55.361306,-55.500339,-55.434434,-55.163683,-54.688746,-54.010849,-53.131822,-52.053902,-50.780152,-49.314106,-47.659843,-45.822004,-43.806015,-41.617746,-39.263690,-36.751162,-34.087780,-31.282037,-28.342998,-25.280199,-22.104190,-18.825740,-15.456519,-12.008666,-8.494973,-4.928899,-1.324307,2.304291,5.941784,}, // NOLINT + {5.833023,2.196387,-1.430073,-5.031427,-8.593244,-12.101664,-15.543521,-18.906036,-22.177172,-25.345461,-28.400081,-31.330821,-34.128130,-36.783089,-39.287263,-41.633103,-43.813509,-45.822018,-47.652749,-49.300621,-50.760831,-52.029381,-53.102760,-53.978182,-54.653211,-55.126119,-55.395692,-55.461301,-55.322846,-54.980791,-54.436152,-53.690495,-52.745950,-51.605252,-50.271486,-48.748609,-47.041021,-45.153669,-43.091849,-40.862042,-38.470797,-35.925455,-33.233933,-30.404764,-27.447061,-24.370593,-21.185701,-17.903272,-14.534941,-11.092759,-7.589513,-4.038390,-0.453233,3.151616,6.761373,}, // NOLINT + {6.394743,2.795925,-0.796293,-4.367399,-7.903124,-11.389953,-14.814751,-18.165051,-21.428893,-24.594892,-27.652222,-30.590963,-33.401276,-36.074351,-38.601723,-40.975646,-43.189027,-45.235188,-47.108136,-48.802439,-50.313333,-51.636409,-52.768024,-53.704879,-54.444467,-54.984666,-55.323957,-55.461317,-55.396316,-55.129030,-54.660084,-53.990682,-53.122489,-52.057886,-50.799609,-49.351082,-47.716186,-45.899729,-43.906559,-41.742524,-39.413970,-36.927628,-34.291243,-31.512912,-28.601366,-25.566161,-22.416983,-19.164809,-15.820795,-12.396801,-8.905340,-5.359486,-1.772888,1.840242,5.465201,}, // NOLINT + {5.358434,1.734504,-1.876442,-5.459720,-9.001266,-12.487512,-15.905521,-19.242879,-22.487832,-25.629253,-28.656591,-31.559863,-34.329966,-36.958050,-39.436086,-41.756739,-43.913080,-45.898901,-47.708609,-49.337049,-50.779838,-52.033050,-53.093349,-53.957855,-54.624481,-55.091428,-55.357569,-55.422279,-55.285476,-54.947595,-54.409672,-53.673113,-52.740109,-51.613050,-50.295218,-48.790197,-47.102383,-45.236425,-43.197604,-40.991972,-38.625990,-36.106730,-33.441803,-30.639674,-27.708988,-24.659273,-21.500620,-18.243643,-14.899611,-11.480345,-7.998257,-4.466303,-0.897995,2.692623,6.291161,}, // NOLINT + {5.928503,2.341081,-1.236801,-4.790989,-8.307577,-11.773288,-15.175323,-18.501438,-21.740009,-24.879911,-27.910839,-30.822737,-33.606323,-36.253019,-38.754552,-41.103573,-43.292988,-45.316497,-47.168267,-48.843099,-50.336273,-51.643620,-52.761722,-53.687215,-54.417802,-54.951408,-55.286565,-55.422295,-55.358179,-55.094293,-54.631214,-53.970154,-53.112685,-52.061021,-50.817895,-49.386575,-47.770878,-45.975194,-44.004451,-41.864199,-39.560412,-37.100116,-34.490287,-31.738894,-28.854552,-25.846282,-22.723861,-19.497658,-16.178611,-12.778299,-9.309025,-5.783417,-2.214868,1.382676,4.994775,}, // NOLINT + {4.889973,1.278899,-2.316287,-5.881398,-9.402729,-12.866835,-16.261171,-19.573625,-22.792707,-25.907485,-28.907969,-31.784272,-34.527489,-37.129161,-39.581521,-41.877339,-44.009982,-45.973587,-47.762532,-49.372027,-50.797731,-52.035891,-53.083275,-53.937217,-54.595571,-55.056662,-55.319427,-55.383257,-55.248073,-54.914293,-54.382894,-53.655286,-52.733526,-51.619987,-50.317711,-48.830305,-47.161799,-45.316839,-43.300589,-41.118747,-38.777586,-36.283982,-33.645365,-30.869742,-27.965699,-24.942548,-21.809730,-18.577960,-15.258046,-11.861614,-8.400585,-4.887815,-1.336422,2.239726,5.826429,}, // NOLINT + {5.467701,1.892191,-1.671178,-5.208354,-8.705786,-12.150415,-15.529763,-18.831914,-22.045455,-25.159665,-28.164278,-31.049813,-33.807118,-36.427789,-38.904031,-41.228376,-43.394281,-45.395531,-47.226496,-48.882182,-50.358006,-51.649996,-52.754697,-53.669123,-54.390887,-54.918026,-55.249131,-55.383272,-55.320027,-55.059470,-54.602185,-53.949264,-53.102280,-52.063342,-50.835095,-49.420662,-47.823713,-46.048518,-44.099819,-41.982921,-39.703768,-37.268764,-34.685008,-31.960301,-29.102732,-26.121158,-23.025056,-19.824547,-16.530275,-13.153590,-9.706287,-6.200920,-2.650528,0.931302,4.530352,}, // NOLINT + {4.427430,0.829514,-2.749886,-6.296877,-9.797898,-13.240211,-16.610813,-19.898530,-23.092004,-26.180546,-29.154474,-32.004141,-34.720919,-37.296559,-39.723608,-41.995038,-44.104502,-46.046175,-47.814779,-49.405627,-50.814556,-52.037961,-53.072699,-53.916256,-54.566419,-55.021818,-55.281271,-55.344233,-55.210623,-54.880875,-54.355876,-53.637047,-52.726289,-51.625929,-50.338980,-48.868850,-47.219263,-45.395090,-43.400941,-41.242471,-38.925589,-36.457410,-33.844641,-31.095216,-28.217465,-25.220240,-22.113282,-18.906452,-15.610483,-12.236661,-8.796706,-5.303114,-1.768888,1.792647,5.367476,}, // NOLINT + {5.012441,1.449063,-2.099568,-5.619695,-9.097946,-12.521576,-15.878374,-19.156706,-22.345493,-25.434223,-28.412986,-31.272403,-34.003769,-36.598829,-39.049947,-41.350238,-43.492964,-45.472391,-47.282900,-48.919795,-50.378618,-51.655468,-52.747089,-53.650628,-54.363728,-54.884532,-55.211670,-55.344248,-55.281860,-55.024580,-54.572927,-53.928043,-53.091347,-52.064893,-50.851258,-49.453403,-47.875017,-46.119804,-44.192739,-42.098896,-39.843806,-37.433890,-34.875937,-32.177335,-29.346158,-26.390882,-23.320865,-20.145779,-16.876048,-13.522734,-10.097386,-6.612230,-3.080023,0.485917,4.071698,}, // NOLINT + {3.970518,0.386050,-3.177437,-6.706206,-10.187014,-13.607199,-16.954645,-20.217899,-23.386060,-26.448815,-29.396297,-32.219681,-34.910345,-37.460420,-39.862554,-42.110014,-44.196621,-46.116774,-47.865346,-49.437912,-50.830365,-52.039226,-53.061577,-53.894852,-54.537184,-54.986897,-55.243101,-55.305208,-55.173154,-54.847354,-54.328638,-53.618407,-52.718467,-51.631123,-50.359199,-48.905956,-47.275176,-45.471207,-43.498772,-41.363325,-39.070647,-36.627179,-34.039886,-31.316307,-28.464503,-25.493165,-22.411520,-19.229393,-15.957183,-12.605899,-9.186957,-5.712612,-2.195487,1.351259,4.913990,}, // NOLINT + {4.562639,1.011515,-2.522290,-6.025228,-9.484285,-12.886983,-16.221360,-19.476079,-22.640381,-25.703842,-28.657016,-31.490714,-34.196432,-36.766262,-39.192870,-41.469299,-43.589261,-45.547090,-47.337649,-48.956016,-50.398071,-51.660148,-52.738937,-53.631749,-54.336344,-54.850930,-55.174173,-55.305222,-55.243679,-54.989615,-54.543587,-53.906504,-53.079912,-52.065765,-50.866438,-49.484871,-47.924483,-46.189141,-44.283383,-42.212081,-39.980782,-37.595530,-35.062936,-32.390181,-29.585026,-26.655742,-23.611481,-20.461564,-17.216191,-13.886016,-10.482582,-7.017592,-3.503582,0.046350,3.618669,}, // NOLINT + {3.519146,-0.051690,-3.599177,-7.109694,-10.570324,-13.968678,-17.292957,-20.531909,-23.674816,-26.712002,-29.633670,-32.431150,-35.096075,-37.620947,-39.998519,-42.222406,-44.286496,-46.185502,-47.914408,-49.468950,-50.845172,-52.039844,-53.049979,-53.873237,-54.507716,-54.951910,-55.204916,-55.266182,-55.135647,-54.813690,-54.301174,-53.599377,-52.710040,-51.635513,-50.378306,-48.941710,-47.329325,-45.545287,-43.594284,-41.481435,-39.212431,-36.793468,-34.231288,-31.533189,-28.707011,-25.761221,-22.704647,-19.547017,-16.298389,-12.969445,-9.571490,-6.116349,-2.616389,0.915396,4.465732,}, // NOLINT + {4.117941,0.579332,-2.939474,-6.425204,-9.865048,-13.246903,-16.559023,-19.790287,-22.930144,-25.968922,-28.896619,-31.705096,-34.385431,-36.930399,-39.332685,-41.585629,-43.683297,-45.620000,-47.390702,-48.990851,-50.416513,-51.663957,-52.730128,-53.612481,-54.308721,-54.817217,-55.136648,-55.266196,-55.205488,-54.954582,-54.514015,-53.884665,-53.068070,-52.065904,-50.880683,-49.515120,-47.972526,-46.256668,-44.371821,-42.322801,-40.114845,-37.753880,-35.246275,-32.598939,-29.819556,-26.916007,-23.897146,-20.772154,-17.550919,-14.243873,-10.862099,-7.417253,-3.921280,-0.387625,3.170994,}, // NOLINT + {3.073082,-0.484095,-4.015306,-7.507581,-10.948069,-14.324498,-17.625956,-20.840846,-23.959006,-26.970712,-29.866827,-32.638621,-35.278233,-37.778082,-40.131615,-42.332181,-44.374211,-46.252371,-47.961954,-49.498795,-50.859116,-52.039763,-53.037914,-53.851293,-54.478092,-54.916856,-55.166718,-55.227155,-55.098108,-54.779957,-54.273501,-53.580010,-52.701105,-51.639079,-50.396391,-48.976099,-47.381826,-45.617447,-43.687491,-41.596944,-39.351251,-36.956427,-34.419015,-31.746137,-28.945201,-26.024538,-22.992932,-19.859551,-16.634323,-13.327638,-9.950544,-6.514629,-3.031884,0.484801,4.022408,}, // NOLINT + {3.678215,0.152354,-3.351361,-6.819816,-10.240536,-13.601566,-16.891519,-20.099526,-23.215215,-26.229229,-29.132038,-31.915255,-34.570807,-37.091247,-39.469610,-41.699498,-43.775087,-45.690946,-47.442220,-49.024508,-50.433960,-51.667033,-52.720903,-53.592876,-54.280934,-54.783413,-55.099090,-55.227169,-55.167281,-54.919483,-54.484289,-53.862539,-53.055655,-52.065408,-50.894033,-49.544222,-48.019140,-46.322427,-44.458287,-42.431040,-40.246151,-37.909101,-35.426144,-32.803983,-30.049933,-27.171865,-24.178018,-21.077780,-17.880470,-14.596323,-11.236148,-7.811398,-4.333883,-0.816223,2.728619,}, // NOLINT + {2.632114,-0.911054,-4.426120,-7.900085,-11.320447,-14.675529,-17.953889,-21.144878,-24.238378,-27.225072,-30.095777,-32.842387,-35.456979,-37.932308,-40.261996,-42.439681,-44.459772,-46.317539,-48.008108,-49.527519,-50.872200,-52.039043,-53.025395,-53.829073,-54.448317,-54.881740,-55.128509,-55.188128,-55.060539,-54.746094,-54.245616,-53.560264,-52.691697,-51.641919,-50.413507,-49.009323,-47.432794,-45.687727,-43.778503,-41.709915,-39.487210,-37.116189,-34.603242,-31.955143,-29.179268,-26.283582,-23.276599,-20.167222,-16.965220,-13.680685,-10.324382,-6.907627,-3.442508,0.059294,3.584088,}, // NOLINT + {3.243234,-0.269716,-3.758150,-7.209317,-10.610849,-13.951172,-17.219101,-20.404035,-23.495907,-26.485313,-29.363445,-32.121873,-34.752802,-37.249009,-39.603784,-41.810931,-43.864762,-45.760104,-47.492243,-49.056924,-50.450458,-51.669477,-52.711081,-53.572905,-54.252926,-54.749499,-55.061504,-55.188141,-55.129063,-54.884325,-54.454417,-53.840140,-53.042865,-52.064276,-50.906535,-49.572223,-48.064377,-46.386447,-44.542550,-42.536994,-40.374774,-38.061354,-35.602708,-33.005331,-30.276374,-27.423377,-24.454537,-21.378640,-18.205080,-14.943712,-11.605090,-8.200324,-4.741107,-1.239690,2.291128,}, // NOLINT + {2.196042,-1.333004,-4.831795,-8.287422,-11.687823,-15.021335,-18.276971,-21.444301,-24.513492,-27.475292,-30.321030,-33.042617,-35.632470,-38.083649,-40.389785,-42.544897,-44.543577,-46.381036,-48.052902,-49.555164,-50.884433,-52.037715,-53.012474,-53.806586,-54.418397,-54.846561,-55.090288,-55.149100,-55.022944,-54.712175,-54.217543,-53.540191,-52.681722,-51.644102,-50.429690,-49.041355,-47.482349,-45.756343,-43.867528,-41.820640,-39.620497,-37.272991,-34.784146,-32.160485,-29.409345,-26.538380,-23.555727,-20.470245,-17.291301,-14.028786,-10.693114,-7.295628,-3.847617,-0.361364,3.150457,}, // NOLINT + {2.812959,-0.687003,-4.160110,-7.593886,-10.976329,-14.295976,-17.541997,-20.704067,-23.772185,-26.737426,-29.591020,-32.324941,-34.931549,-37.403844,-39.735336,-41.920168,-43.952435,-45.827557,-47.540832,-49.088214,-50.466059,-51.671190,-52.700830,-53.552677,-54.224749,-54.715521,-55.023892,-55.149112,-55.090835,-54.849110,-54.424403,-53.817482,-53.029652,-52.062554,-50.918233,-49.599177,-48.108307,-46.448973,-44.625047,-42.640754,-40.500906,-38.210758,-35.776154,-33.203260,-30.499021,-27.670752,-24.726713,-21.675010,-18.524958,-15.286217,-11.969005,-8.584281,-5.143303,-1.658233,1.858503,}, // NOLINT + {1.764820,-1.750092,-5.232539,-8.669884,-12.050277,-15.362394,-18.595445,-21.739287,-24.784307,-27.721537,-30.542522,-33.239407,-35.804899,-38.232185,-40.515121,-42.647967,-44.625508,-46.443052,-48.096410,-49.581735,-50.895871,-52.035789,-52.999137,-53.783846,-54.388340,-54.811326,-55.052054,-55.110070,-54.985323,-54.678153,-54.189299,-53.519834,-52.671298,-51.645593,-50.444994,-49.072242,-47.530462,-45.823233,-43.954672,-41.928901,-39.751211,-37.426880,-34.961840,-32.362495,-29.635702,-26.789201,-23.830669,-20.768830,-17.612766,-14.372149,-11.057248,-7.678754,-4.248166,-0.777319,2.721343,}, // NOLINT + {2.387065,-1.099676,-4.557396,-7.973734,-11.337136,-14.636207,-17.860402,-20.999601,-24.044342,-26.985575,-29.814976,-32.524606,-35.107171,-37.555851,-39.864382,-42.026928,-44.038093,-45.893410,-47.588085,-49.118385,-50.480802,-51.672266,-52.690106,-53.532080,-54.196373,-54.681446,-54.986255,-55.110081,-55.052594,-54.813836,-54.394256,-53.794578,-53.016065,-52.060267,-50.929161,-49.625142,-48.150985,-46.509972,-44.705732,-42.742421,-40.624624,-38.357489,-35.946510,-33.397849,-30.718144,-27.914533,-24.994715,-21.967069,-18.840369,-15.624074,-12.328192,-8.963336,-5.540659,-2.071958,1.430472,}, // NOLINT + {1.338173,-2.162624,-5.628602,-9.047590,-12.408088,-15.698901,-18.909513,-22.030078,-25.051076,-27.964025,-30.760511,-33.432989,-35.974355,-38.378075,-40.638108,-42.748932,-44.705635,-46.503530,-48.138712,-49.607435,-50.906603,-52.033339,-52.985417,-53.760905,-54.358151,-54.776035,-55.013813,-55.071038,-54.947676,-54.644050,-54.160842,-53.499165,-52.660431,-51.646447,-50.459424,-49.102063,-47.577283,-45.888504,-44.039714,-42.035103,-39.879479,-37.577965,-35.136516,-32.561121,-29.858515,-27.036142,-24.101564,-21.063178,-17.929869,-14.711021,-11.416658,-8.057346,-4.644182,-1.188793,2.296572,}, // NOLINT + {1.965359,-1.508038,-4.950179,-8.349151,-11.693412,-14.972005,-18.174515,-21.291186,-24.312369,-27.230040,-30.035406,-32.720987,-35.279890,-37.705205,-39.991039,-42.131723,-44.122114,-45.957612,-47.634048,-49.147520,-50.494725,-51.672717,-52.678934,-53.511232,-54.167852,-54.647299,-54.948592,-55.071049,-55.014344,-54.778513,-54.363981,-53.771419,-53.002096,-52.057443,-50.939366,-49.650172,-48.192501,-46.569507,-44.784719,-42.842099,-40.746096,-38.501611,-36.114057,-33.589308,-30.933814,-28.154521,-25.258896,-22.255003,-19.151485,-15.957517,-12.682845,-9.337856,-5.933477,-2.481097,1.006906,}, // NOLINT + {0.915593,-2.570560,-6.020148,-9.420929,-12.761473,-16.031067,-19.219441,-22.316768,-25.314122,-28.202904,-30.975170,-33.623495,-36.141026,-38.521424,-40.758866,-42.848035,-44.784093,-46.562670,-48.179845,-49.632132,-50.916539,-52.030350,-52.971337,-53.737652,-54.327837,-54.740699,-54.975560,-55.032010,-54.910005,-54.609864,-54.132264,-53.478214,-52.649134,-51.646705,-50.473121,-49.130867,-47.622842,-45.952382,-44.123100,-42.139251,-40.005395,-37.726568,-35.308301,-32.756590,-30.077992,-27.279470,-24.368611,-21.353490,-18.242833,-15.045594,-11.771721,-8.431483,-5.035787,-1.595957,1.875965,}, // NOLINT + {1.547725,-1.912117,-5.338718,-8.720274,-12.045464,-15.303630,-18.484574,-21.578592,-24.576929,-27.470874,-30.252543,-32.914452,-35.449748,-37.852046,-40.115375,-42.234535,-44.204393,-46.020468,-47.678784,-49.175662,-50.507871,-51.672584,-52.667318,-53.490096,-54.139101,-54.613052,-54.910906,-55.032020,-54.976085,-54.743138,-54.333584,-53.748090,-52.987781,-52.054121,-50.948879,-49.674273,-48.232880,-46.627679,-44.862065,-42.939759,-40.865379,-38.643306,-36.278870,-33.777776,-31.146180,-28.390995,-25.519329,-22.538942,-19.458514,-16.286712,-13.033180,-9.707891,-6.321877,-2.886096,0.587549,}, // NOLINT + {0.497271,-2.974443,-6.407301,-9.789863,-13.110605,-16.359092,-19.525267,-22.599582,-25.573591,-28.438382,-31.186645,-33.811081,-36.305040,-38.662353,-40.877518,-42.945256,-44.860961,-46.620427,-48.219899,-49.656006,-50.925831,-52.026863,-52.956919,-53.714229,-54.297405,-54.705311,-54.937298,-54.992976,-54.872311,-54.575590,-54.103473,-53.456952,-52.637390,-51.646387,-50.486024,-49.158702,-47.667201,-46.014710,-44.204786,-42.241444,-40.129097,-37.872634,-35.477362,-32.949117,-30.294144,-27.519402,-24.631992,-21.639958,-18.551671,-15.376048,-12.122639,-8.801438,-5.423184,-1.999054,1.459288,}, // NOLINT + {1.133973,-2.312246,-5.723183,-9.087225,-12.393462,-15.631245,-18.790871,-21.862531,-24.837868,-27.708431,-30.466521,-33.104919,-35.616948,-37.996442,-40.237714,-42.335439,-44.284957,-46.081922,-47.722367,-49.202811,-50.520273,-51.671902,-52.655356,-53.468699,-54.110299,-54.578740,-54.873197,-54.992989,-54.937818,-54.707716,-54.303073,-53.724516,-52.973117,-52.050290,-50.957708,-49.697538,-48.272190,-46.684554,-44.937912,-43.035852,-40.982606,-38.782674,-36.441085,-33.963425,-31.355421,-28.624189,-25.776204,-22.819319,-19.761631,-16.611902,-13.379399,-10.074004,-6.706154,-3.286915,0.172198,}, // NOLINT + {0.082882,-3.374227,-6.790613,-10.154761,-13.455760,-16.683189,-19.827333,-22.878925,-25.829361,-28.670773,-31.395095,-33.995884,-36.466524,-38.801086,-40.994085,-43.040704,-44.936258,-46.676942,-48.258892,-49.679019,-50.934488,-52.022912,-52.942162,-53.690599,-54.266860,-54.669872,-54.899027,-54.953945,-54.834595,-54.541259,-54.074631,-53.435508,-52.625291,-51.645530,-50.498204,-49.185602,-47.710428,-46.075736,-44.284869,-42.341760,-40.250694,-38.016299,-35.643770,-33.138681,-30.507218,-27.755896,-24.891815,-21.922816,-18.856765,-15.702597,-12.469536,-9.167399,-5.806679,-2.398208,1.046456,}, // NOLINT + {0.723901,-2.708578,-6.103791,-9.450377,-12.737572,-15.955057,-19.093221,-22.142822,-25.095336,-27.942721,-30.677495,-33.292619,-35.781628,-38.138543,-40.357877,-42.434540,-44.364049,-46.141995,-47.764851,-49.229179,-50.531982,-51.670686,-52.642996,-53.447053,-54.081285,-54.544365,-54.835467,-54.953955,-54.899540,-54.672250,-54.272452,-53.700735,-52.958158,-52.046010,-50.965964,-49.719989,-48.310489,-46.740153,-45.012341,-43.130088,-41.097872,-38.919842,-36.600882,-34.146319,-31.562031,-28.854139,-26.029728,-23.096070,-20.061058,-16.933269,-13.721739,-10.436016,-7.086445,-3.683752,-0.239311,}, // NOLINT + {-0.327698,-3.770133,-7.169926,-10.515816,-13.797054,-17.003474,-20.125778,-23.154626,-26.081976,-28.899732,-31.600614,-34.178046,-36.625695,-38.937619,-41.108866,-43.134500,-45.010243,-46.732195,-48.296891,-49.701235,-50.942539,-52.018488,-52.927106,-53.666768,-54.236209,-54.634396,-54.860749,-54.914911,-54.796857,-54.506870,-54.045574,-53.413783,-52.612831,-51.644163,-50.509696,-49.211638,-47.752588,-46.135401,-44.363424,-42.440285,-40.370282,-38.157737,-35.807712,-33.325571,-30.717348,-27.989316,-25.148420,-22.202075,-19.158259,-16.025422,-12.812683,-9.529598,-6.186319,-2.793675,0.637154,}, // NOLINT + {0.317322,-3.101278,-6.480702,-9.809862,-13.078015,-16.275298,-19.392164,-22.419719,-25.349637,-28.174007,-30.885547,-33.477669,-35.943893,-38.278496,-40.476099,-42.531927,-44.441483,-46.200823,-47.806281,-49.254733,-50.543017,-51.668957,-52.630280,-53.425167,-54.052137,-54.509920,-54.797716,-54.914920,-54.861255,-54.636742,-54.241728,-53.676771,-52.942856,-52.041298,-50.973585,-49.741676,-48.347824,-46.794639,-45.085161,-43.222768,-41.211392,-39.054924,-36.758330,-34.326679,-31.765591,-29.081149,-26.280064,-23.369356,-20.356997,-17.251042,-14.060316,-10.794291,-7.462959,-4.076883,-0.647177,}, // NOLINT + {-0.734836,-4.162470,-7.545564,-10.873154,-14.134727,-17.320472,-20.420791,-23.427219,-26.331476,-29.125880,-31.803551,-34.357696,-36.782429,-39.072099,-41.221689,-43.226682,-45.082798,-46.786323,-48.333950,-49.722703,-50.950001,-52.013652,-52.911748,-53.642753,-54.205457,-54.598876,-54.822461,-54.875877,-54.759100,-54.472408,-54.016384,-53.391826,-52.599978,-51.642279,-50.520534,-49.236851,-47.793695,-46.193856,-44.440513,-42.537254,-40.487965,-38.297046,-35.969287,-33.509932,-30.924697,-28.219765,-25.401818,-22.478099,-19.456293,-16.344740,-13.152235,-9.888140,-6.562425,-3.185631,0.231315,}, // NOLINT + {-0.085875,-3.490493,-6.854066,-10.165777,-13.414975,-16.592078,-19.687776,-22.693344,-25.600812,-28.402378,-31.091039,-33.660219,-36.103839,-38.416302,-40.592483,-42.627676,-44.517643,-46.258448,-47.846690,-49.279265,-50.553401,-51.666755,-52.617217,-53.403056,-54.022858,-54.475412,-54.759946,-54.875886,-54.822962,-54.601193,-54.210907,-53.652632,-52.927327,-52.036162,-50.980734,-49.762629,-48.384241,-46.847978,-45.156807,-43.313925,-41.322868,-39.187972,-36.913548,-34.504592,-31.966510,-29.305295,-26.527378,-23.639641,-20.649586,-17.565317,-14.395376,-11.148972,-7.835919,-4.466460,-1.051566,}, // NOLINT + {-1.138542,-4.551237,-7.917885,-11.227029,-14.468975,-17.633824,-20.712572,-23.696637,-26.578008,-29.349343,-32.003803,-34.534968,-36.937038,-39.204641,-41.332899,-43.317455,-45.154065,-46.839404,-48.370118,-49.743454,-50.956925,-52.008401,-52.896110,-53.618562,-54.174611,-54.563317,-54.784167,-54.836842,-54.721323,-54.437874,-53.987066,-53.369647,-52.586807,-51.639940,-50.530763,-49.261260,-47.833821,-46.251142,-44.516239,-42.632539,-40.603833,-38.434322,-36.128630,-33.691819,-31.129390,-28.447368,-25.652225,-22.751006,-19.751086,-16.660687,-13.488371,-10.243287,-6.935090,-3.574160,-0.171277,}, // NOLINT + {-0.485998,-3.876556,-7.224389,-10.518325,-13.748627,-16.905610,-19.980229,-22.964036,-25.849088,-28.628000,-31.293916,-33.840378,-36.261618,-38.552180,-40.707111,-42.721881,-44.592366,-46.314890,-47.886171,-49.303138,-50.563197,-51.664099,-52.603828,-53.380730,-53.993455,-54.440840,-54.722158,-54.836851,-54.784662,-54.565606,-54.179996,-53.628319,-52.911488,-52.030649,-50.987195,-49.782891,-48.419791,-46.900278,-45.227153,-43.403557,-41.432892,-39.319170,-37.066636,-34.680208,-32.165068,-29.526768,-26.771816,-23.906796,-20.939023,-17.876325,-14.727112,-11.500288,-8.205466,-4.852701,-1.452712,}, // NOLINT + {-1.539040,-4.936846,-8.286667,-11.577599,-14.799940,-17.944114,-21.001247,-23.963043,-26.821734,-29.570170,-32.201631,-34.709996,-37.089590,-39.335337,-41.442435,-43.406637,-45.224118,-46.891396,-48.405436,-49.763531,-50.963318,-52.002771,-52.880210,-53.594203,-54.143677,-54.527720,-54.745866,-54.797806,-54.683529,-54.403283,-53.957626,-53.347250,-52.573326,-51.637150,-50.540321,-49.284919,-47.873040,-46.307297,-44.590598,-42.726324,-40.717983,-38.569672,-36.285812,-33.871362,-31.331625,-28.672237,-25.899788,-23.020877,-20.042818,-16.973492,-13.821298,-10.595145,-7.304544,-3.959574,-0.570821,}, // NOLINT + {-0.883144,-4.259524,-7.591061,-10.867746,-14.079154,-17.216072,-20.269699,-23.231859,-26.094630,-28.850976,-31.494277,-34.018305,-36.417342,-38.686187,-40.820056,-42.814615,-44.665880,-46.370318,-47.924748,-49.326284,-50.572435,-51.661011,-52.590132,-53.358187,-53.963932,-54.406212,-54.684351,-54.797815,-54.746355,-54.529981,-54.148968,-53.603839,-52.895424,-52.024757,-50.993218,-49.802492,-48.454520,-46.951607,-45.296370,-43.491779,-41.541296,-39.448607,-37.217815,-34.853634,-32.361090,-29.745712,-27.013548,-24.171105,-21.225469,-18.184310,-15.055753,-11.848430,-8.571824,-5.235811,-1.850780,}, // NOLINT +}}; + +} // namespace innovusion_packet +} // namespace drivers +} // namespace nebula + +#endif // SDK_COMMON_ROBIN_NPS_ADJUSTMENT_H_ diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_innovusion/innovusion_driver.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_innovusion/innovusion_driver.hpp new file mode 100644 index 000000000..3c8b49e41 --- /dev/null +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_innovusion/innovusion_driver.hpp @@ -0,0 +1,62 @@ +#ifndef NEBULA_Innovusion_DRIVER_H +#define NEBULA_Innovusion_DRIVER_H + +#include "nebula_common/innovusion/innovusion_common.hpp" +#include "nebula_common/nebula_common.hpp" +#include "nebula_common/nebula_status.hpp" +#include "nebula_common/point_types.hpp" +#include "nebula_decoders/nebula_decoders_common/nebula_driver_base.hpp" +#include "nebula_decoders/nebula_decoders_innovusion/decoders/innovusion_decoder.hpp" + +#include "innovusion_msgs/msg/innovusion_packet.hpp" +#include "innovusion_msgs/msg/innovusion_scan.hpp" + +#include + +#include +#include +#include + +namespace nebula +{ +namespace drivers +{ +/// @brief Innovusion driver +class InnovusionDriver : NebulaDriverBase +{ +private: + /// @brief Current driver status + Status driver_status_; + /// @brief Decoder according to the model + std::shared_ptr scan_decoder_; + +public: + InnovusionDriver() = delete; + /// @brief Constructor + /// @param sensor_configuration SensorConfiguration for this driver + /// @param calibration_configuration CalibrationConfiguration for this driver + explicit InnovusionDriver( + const std::shared_ptr & sensor_configuration, + const std::shared_ptr & calibration_configuration); + + /// @brief Get current status of this driver + /// @return Current status + Status GetStatus(); + + /// @brief Setting CalibrationConfiguration (not used) + /// @param calibration_configuration + /// @return Resulting status + Status SetCalibrationConfiguration( + const CalibrationConfigurationBase & calibration_configuration) override; + + /// @brief Convert InnovusionScan message to point cloud + /// @param innovusion_scan Message + /// @return tuple of Point cloud and timestamp + std::tuple ConvertScanToPointcloud( + const std::shared_ptr & innovusion_scan); +}; + +} // namespace drivers +} // namespace nebula + +#endif // NEBULA_Innovusion_DRIVER_H diff --git a/nebula_decoders/package.xml b/nebula_decoders/package.xml index f25fc698a..72e02ea92 100644 --- a/nebula_decoders/package.xml +++ b/nebula_decoders/package.xml @@ -20,6 +20,7 @@ sensor_msgs velodyne_msgs yaml-cpp + innovusion_msgs ament_cmake_gtest ament_lint_auto diff --git a/nebula_decoders/src/nebula_decoders_innovusion/decoders/innovusion_decoder.cpp b/nebula_decoders/src/nebula_decoders_innovusion/decoders/innovusion_decoder.cpp new file mode 100644 index 000000000..65f9675b3 --- /dev/null +++ b/nebula_decoders/src/nebula_decoders_innovusion/decoders/innovusion_decoder.cpp @@ -0,0 +1,471 @@ +#include "nebula_decoders/nebula_decoders_innovusion/decoders/innovusion_decoder.hpp" + +namespace nebula +{ +namespace drivers +{ +namespace innovusion_packet +{ + +float InnovusionDecoder::sin_table_[kAngleTableSize + 1]; +float InnovusionDecoder::cos_table_[kAngleTableSize + 1]; +int32_t InnovusionDecoder::asin_table_[2 * kASinTableSize]; +int32_t InnovusionDecoder::atan_table_[2 * kATanTableSize]; + +// for robinW +const uint8_t InnovusionDecoder::robinw_channel_mapping[48] = { + 0, 4, 8, 12, 16, 20, 24, 28, 32, 36, 40, 44, + 1, 5, 9, 13, 17, 21, 25, 29, 33, 37, 41, 45, + 2, 6, 10, 14, 18, 22, 26, 30, 34, 38, 42, 46, + 3, 7, 11, 15, 19, 23, 27, 31, 35, 39, 43, 47, +}; + +const uint8_t InnovusionDecoder::robine_channel_mapping[48] = { + 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, + 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, + 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, + 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47 +}; + +int InnovusionDecoder::v_angle_offset_[INNO_ITEM_TYPE_MAX][kInnoChannelNumber]; +int8_t InnovusionDecoder::nps_adjustment_[kVTableSize_][kHTableSize_][kInnoChannelNumber][kXZSize_]; // NOLINT +const double InnovusionDecoder::kAdjustmentUnitInMeter_ = 0.0025; +const double InnovusionDecoder::kAdjustmentUnitInMeterRobin_ = 0.001; +int8_t InnovusionDecoder::robin_nps_adjustment_[kRobinScanlines_][kHTableSize_][kXYZSize_]; // NOLINT + +InnovusionDecoder::InnovusionDecoder( + const std::shared_ptr & sensor_configuration, + const std::shared_ptr & calibration_configuration) + : sensor_configuration_(sensor_configuration), + calibration_configuration_(calibration_configuration), + logger_(rclcpp::get_logger("InnovusionDecoder")) +{ + logger_.set_level(rclcpp::Logger::Level::Debug); + RCLCPP_INFO_STREAM(logger_, sensor_configuration_); + + decode_pc_.reset(new NebulaPointCloud); + output_pc_.reset(new NebulaPointCloud); + + xyz_from_sphere_.resize(kConvertSize); + setup_table_(kRadPerInnoAngleUnit); + init_f(); +} + +template +void InnovusionDecoder::point_xyz_data_parse_(bool is_en_data, bool is_use_refl, uint32_t point_num, PointType point_ptr) { + for (uint32_t i = 0; i < point_num; ++i, ++point_ptr) { + drivers::NebulaPoint point; + if (point_ptr->channel >= kInnoChannelNumber) { + RCLCPP_ERROR_STREAM(logger_, "bad channel " << point_ptr->channel); + continue; + } + + if ((point_ptr->radius < sensor_configuration_->cloud_min_range) || + (point_ptr->radius > sensor_configuration_->cloud_max_range)) { + continue; + } + + if constexpr (std::is_same::value) { + if (is_use_refl) { + point.intensity = point_ptr->reflectance; + } else { + point.intensity = point_ptr->intensity; + } + } else if constexpr (std::is_same::value) { + point.intensity = point_ptr->refl; + } + + point.time_stamp = point_ptr->ts_10us / ten_us_in_second_c + current_ts_start_; + point.distance = point_ptr->radius; + point.x = point_ptr->x; + point.y = point_ptr->y; + point.z = point_ptr->z; + decode_pc_->points.emplace_back(point); + } +} + +void InnovusionDecoder::data_packet_parse_(const InnoDataPacket *pkt) { + current_ts_start_ = pkt->common.ts_start_us / us_in_second_c; + // adapt different data structures form different lidar + if (is_en_xyz_data(pkt->type)) { + const InnoEnXyzPoint *pt = + reinterpret_cast(reinterpret_cast(pkt) + sizeof(InnoDataPacket)); + point_xyz_data_parse_(true, pkt->use_reflectance, pkt->item_number, pt); + } else { + const InnoXyzPoint *pt = + reinterpret_cast(reinterpret_cast(pkt) + sizeof(InnoDataPacket)); + point_xyz_data_parse_(false, pkt->use_reflectance, pkt->item_number, pt); + } + output_scan_timestamp_ns_ = pkt->common.ts_start_us * 1000; +} + +int InnovusionDecoder::unpack(const innovusion_msgs::msg::InnovusionPacket & packet) +{ + const InnoDataPacket *inno_pkt = + reinterpret_cast(reinterpret_cast(&packet.data[0])); + if (is_sphere_data(inno_pkt->type)) { + // convert sphere to xyz + bool ret_val = + convert_to_xyz_pointcloud(*inno_pkt, reinterpret_cast(&xyz_from_sphere_[0]), kConvertSize, false); + if (!ret_val) { + RCLCPP_ERROR_STREAM(logger_, "convert_to_xyz_pointcloud failed"); + return -1; + } + data_packet_parse_(reinterpret_cast(&xyz_from_sphere_[0])); + } else if (is_xyz_data(inno_pkt->type)) { + data_packet_parse_(inno_pkt); + } else { + RCLCPP_ERROR_STREAM(logger_, "cframe type" << inno_pkt->type << "is not supported"); + } + + return 0; +} + +std::tuple InnovusionDecoder::getPointcloud() { + double scan_timestamp_s = static_cast(output_scan_timestamp_ns_) * 1e-9; + std::swap(decode_pc_, output_pc_); + decode_pc_->clear(); + return std::make_pair(output_pc_, scan_timestamp_s); +} + +double InnovusionDecoder::lookup_cos_table_in_unit(int i) { + return cos_table_[i]; +} + +double InnovusionDecoder::lookup_sin_table_in_unit(int i) { + return sin_table_[i]; +} + +void InnovusionDecoder::setup_table_(double inno_angle_unit) { + for (int32_t i = 0; i <= kAngleTableSize; ++i) { + double angle = i * kRadPerInnoAngleUnit; + cos_table_[i] = cos(angle); + sin_table_[i] = sin(angle); + } + + for (int32_t i = -kASinTableSize; i < kASinTableSize; i++) { + asin_table_[i + kASinTableSize] = + static_cast(asin(i/static_cast(kAsinTableScale)) + / inno_angle_unit); + } + + for (int32_t i = -kATanTableSize; i < kATanTableSize; i++) { + atan_table_[i + kATanTableSize] = + static_cast(atan(i/static_cast(kAtanTableScale)) + / inno_angle_unit); + } +} + +void InnovusionDecoder::init_f(void) { + init_f_falcon(); + init_f_robin(); +} + +int InnovusionDecoder::init_f_falcon(void) { + for (uint32_t ich = 0; ich < kInnoChannelNumber; ich++) { + v_angle_offset_[INNO_ITEM_TYPE_SPHERE_POINTCLOUD][ich] = ich * kInnoFaconVAngleDiffBase; + // falconII NT3 + v_angle_offset_[INNO_FALCONII_DOT_1_ITEM_TYPE_SPHERE_POINTCLOUD][ich] = ich * kInnoFaconVAngleDiffBase; + } + // init the nps_adjustment_ + size_t input_size = (kVTableEffeHalfSize_ * 2 + 1) * (kHTableEffeHalfSize_ * 2 + 1) * 2 * kInnoChannelNumber; + memset(nps_adjustment_, 0, sizeof(nps_adjustment_)); + static double k_max[2] = {-100, -100}; + static double k_min[2] = {100, 100}; + for (uint32_t v = 0; v < kVTableEffeHalfSize_ * 2 + 1; v++) { + for (uint32_t h = 0; h < kHTableEffeHalfSize_ * 2 + 1; h++) { + for (uint32_t ich = 0; ich < kInnoChannelNumber; ich++) { + for (uint32_t xz = 0; xz < kXZSize_; xz++) { + double k = kInnoPs2Nps[xz][ich][v][h]; + double u = k / kAdjustmentUnitInMeter_; + double q = std::floor(u + 0.5); + nps_adjustment_[v][h][ich][xz] = q; + k_max[xz] = std::max(k_max[xz], k); + k_min[xz] = std::min(k_min[xz], k); + } + } + } + } + return 0; +} + +int InnovusionDecoder::init_f_robin(void) { + for (uint32_t ich = 0; ich < kInnoChannelNumber; ich++) { + v_angle_offset_[INNO_ROBINE_ITEM_TYPE_SPHERE_POINTCLOUD][ich] = ich * kInnoRobinEVAngleDiffBase; + v_angle_offset_[INNO_ROBINW_ITEM_TYPE_SPHERE_POINTCLOUD][ich] = ich * kInnoRobinWVAngleDiffBase; + } + + // init the nps_adjustment_ + size_t input_size = kRobinScanlines_ * (kHRobinTableEffeHalfSize_ * 2 + 1) * kXYZSize_; + memset(robin_nps_adjustment_, 0, sizeof(robin_nps_adjustment_)); + static double k_max[3] = {-200, -200, -200}; + static double k_min[3] = {200, 200, 200}; + for (uint32_t scan_id = 0; scan_id < kRobinScanlines_; scan_id++) { + for (uint32_t h = 0; h < kHRobinTableEffeHalfSize_ * 2 + 1; h++) { + for (uint32_t xyz = 0; xyz < kXYZSize_; xyz++) { + double k = robinW_kInnoPs2Nps[xyz][scan_id][h]; + double u = k * 0.001 / kAdjustmentUnitInMeterRobin_; + double q = std::floor(u + 0.5); + robin_nps_adjustment_[scan_id][h][xyz] = q; + k_max[xyz] = std::max(k_max[xyz], k); + k_min[xyz] = std::min(k_min[xyz], k); + } + } + } + return 0; +} + +void InnovusionDecoder::get_xyzr_meter(const InnoBlockAngles angles, const uint32_t radius_unit, + const uint32_t channel, InnoXyzrD *result, InnoItemType type) { + if (type == INNO_ITEM_TYPE_SPHERE_POINTCLOUD) { + result->radius = radius_unit * kMeterPerInnoDistanceUnit200; + } else { + result->radius = radius_unit * kMeterPerInnoDistanceUnit400; + } + double t; + if (angles.v_angle >= 0) { + t = result->radius * lookup_cos_table_in_unit(angles.v_angle); + result->x = result->radius * lookup_sin_table_in_unit(angles.v_angle); + } else { + t = result->radius * lookup_cos_table_in_unit(-angles.v_angle); + result->x = -result->radius * lookup_sin_table_in_unit(-angles.v_angle); + } + if (angles.h_angle >= 0) { + result->y = t * lookup_sin_table_in_unit(angles.h_angle); + result->z = t * lookup_cos_table_in_unit(angles.h_angle); + } else { + result->y = -t * lookup_sin_table_in_unit(-angles.h_angle); + result->z = t * lookup_cos_table_in_unit(-angles.h_angle); + } + + // don't do nps for robinE, no data yet + if (type == INNO_ROBINE_ITEM_TYPE_SPHERE_POINTCLOUD) { + return; + } + + // falconI & falconII + if (type == INNO_ITEM_TYPE_SPHERE_POINTCLOUD || type == INNO_FALCONII_DOT_1_ITEM_TYPE_SPHERE_POINTCLOUD) { + double x_adj, z_adj; + lookup_xz_adjustment_(angles, channel, &x_adj, &z_adj); + result->x += x_adj; + result->z += z_adj; + } else if (type == INNO_ROBINW_ITEM_TYPE_SPHERE_POINTCLOUD) { + double adj[3]; + lookup_xyz_adjustment_(angles, channel, adj); + result->x += adj[0]; + result->y += adj[1]; + result->z += adj[2]; + } + + return; +} + +bool InnovusionDecoder::check_data_packet(const InnoDataPacket &pkt, size_t size) { + if (pkt.common.version.magic_number != kInnoMagicNumberDataPacket) { + std::cout << "bad magic " << pkt.common.version.magic_number << std::endl; + return false; + } + if (size && (pkt.common.size > size)) { + std::cout << "bad size " << size << " " << pkt.common.size << std::endl; + return false; + } + bool is_data = true; + switch (pkt.type) { + case INNO_ITEM_TYPE_SPHERE_POINTCLOUD: + if (pkt.multi_return_mode == INNO_MULTIPLE_RETURN_MODE_SINGLE) { + if (pkt.item_size != sizeof(InnoBlock1)) { + std::cout << "bad block1 item size " << pkt.item_size << " " << sizeof(InnoBlock1) << std::endl; + return false; + } + } else if (pkt.multi_return_mode == INNO_MULTIPLE_RETURN_MODE_2_STRONGEST || + pkt.multi_return_mode == INNO_MULTIPLE_RETURN_MODE_2_STRONGEST_FURTHEST) { + if (pkt.item_size != sizeof(InnoBlock2)) { + std::cout << "bad block2 item size " << pkt.item_size << " " << sizeof(InnoBlock2) << std::endl; + return false; + } + } else { + std::cout << "bad return_mode " << pkt.multi_return_mode << std::endl; + return false; + } + break; + case INNO_ROBINE_ITEM_TYPE_SPHERE_POINTCLOUD: + case INNO_ROBINW_ITEM_TYPE_SPHERE_POINTCLOUD: + case INNO_FALCONII_DOT_1_ITEM_TYPE_SPHERE_POINTCLOUD: + if (pkt.multi_return_mode == INNO_MULTIPLE_RETURN_MODE_SINGLE) { + if (pkt.item_size != sizeof(InnoEnBlock1)) { + std::cout << "bad block1 item size " << pkt.item_size << " " << sizeof(InnoEnBlock1) << std::endl; + return false; + } + } else if (pkt.multi_return_mode == INNO_MULTIPLE_RETURN_MODE_2_STRONGEST || + pkt.multi_return_mode == INNO_MULTIPLE_RETURN_MODE_2_STRONGEST_FURTHEST) { + if (pkt.item_size != sizeof(InnoEnBlock2)) { + std::cout << "bad block2 item size " << pkt.item_size << " " << sizeof(InnoEnBlock2) << std::endl; + return false; + } + } else { + std::cout << "bad return_mode " << pkt.multi_return_mode << std::endl; + return false; + } + break; + case INNO_ITEM_TYPE_XYZ_POINTCLOUD: + if (pkt.item_size != sizeof(InnoXyzPoint)) { + std::cout << "bad InnoXyzPoint item size " << pkt.item_size << std::endl; + return false; + } + break; + case INNO_ROBINE_ITEM_TYPE_XYZ_POINTCLOUD: + case INNO_ROBINW_ITEM_TYPE_XYZ_POINTCLOUD: + case INNO_FALCONII_DOT_1_ITEM_TYPE_XYZ_POINTCLOUD: + if (pkt.item_size != sizeof(InnoEnXyzPoint)) { + std::cout << "bad InnoEnXyzPoint item size " << pkt.item_size << std::endl; + return false; + } + break; + default: + is_data = false; + break; + } + + if (is_data) { + size_t s = + get_data_packet_size(InnoItemType(pkt.type), pkt.item_number, InnoMultipleReturnMode(pkt.multi_return_mode)); + if (pkt.common.size != s) { + std::cout << "bad size " << s << " " << pkt.common.size << std::endl; + return false; + } + if (pkt.common.version.major_version > kInnoMajorVersionDataPacket) { + std::cout << "please upgrade client sdk, lidar protocol major version:" << pkt.common.version.major_version + << " sdk major version:" << kInnoMajorVersionDataPacket << std::endl; + return false; + } + return true; + } else if (pkt.type == INNO_ITEM_TYPE_MESSAGE || pkt.type == INNO_ITEM_TYPE_MESSAGE_LOG) { + if (pkt.item_number != 1) { + std::cout << "bad item_number " << pkt.item_number << std::endl; + return false; + } + const InnoMessage *messages = reinterpret_cast(pkt.payload); + if (static_cast(pkt.item_size) != messages[0].size || pkt.item_size <= sizeof(InnoMessage)) { + std::cout << "bad message size " << pkt.item_size << " " << messages[0].size << std::endl; + return false; + } + if (pkt.common.size != pkt.item_size + sizeof(InnoDataPacket)) { + std::cout << "bad message size " << pkt.common.size << " " << pkt.item_size + sizeof(InnoDataPacket) << std::endl; + return false; + } + return true; + } else { + std::cout << "bad type " << pkt.type << std::endl; + return false; + } +} + +bool InnovusionDecoder::convert_to_xyz_pointcloud(const InnoDataPacket &src, InnoDataPacket *dest, size_t dest_size, + bool append) { + if (!is_sphere_data(src.type)) { + std::cout << "invalid type: " << src.type << std::endl; + return false; + } + if (!check_data_packet(src, 0)) { + std::cout << "invalid src datapacket" << std::endl; + return false; + } + + uint32_t item_count = 0; + uint32_t dummy_count = 0; + item_count = get_points_count(src); + + if (append) { + if (!check_data_packet(*dest, dest_size)) { + std::cout << "invalid dest datapacket" << std::endl; + return false; + } + item_count += dest->item_number; + } + + size_t required_size = 0; + uint16_t time_adjust_10us = 0; + if (!append) { + required_size = sizeof(InnoDataPacket); + if (required_size > dest_size) { + std::cout << "not enough size " << "required_size " <type = INNO_ITEM_TYPE_XYZ_POINTCLOUD; + dest->item_size = sizeof(InnoXyzPoint); + } else { + dest->type += 1; // robin & falconIII InnoItemType xyz = sphere+1 + dest->item_size = sizeof(InnoEnXyzPoint); + } + dest->item_number = 0; + } else { + required_size = dest->common.size; + if (src.common.ts_start_us < dest->common.ts_start_us) { + std::cout << "cannot merge earlier packet " << src.common.ts_start_us << " " << dest->common.ts_start_us << std::endl; + return false; + } + time_adjust_10us = (src.common.ts_start_us - dest->common.ts_start_us) / 10; + } + + { + if (src.type == INNO_ITEM_TYPE_SPHERE_POINTCLOUD) { + (void)iterate_inno_data_packet_cpoints( + src, [&](const InnoDataPacketPointsCallbackParams &in_params) { + if (in_params.pt.radius > 0) { + InnoXyzPoint &ipt = dest->xyz_points[dest->item_number]; + required_size += static_cast(sizeof(InnoXyzPoint)); + if (required_size > dest_size) { + std::cerr << "no enough size required_size:" << required_size << ",dest_size:" << dest_size + << std::endl; + } else { + (void)get_xyz_point(in_params.block.header, in_params.pt, in_params.angle.angles[in_params.channel], + in_params.channel, &ipt); + ipt.multi_return = in_params.multi_return; + ipt.is_2nd_return = in_params.pt.is_2nd_return; + ipt.ts_10us += time_adjust_10us; + dest->item_number++; + } + } + }); + } else { + (void)iterate_inno_data_packet_cpoints( + src, [&](const InnoDataPacketPointsCallbackParams &in_params) { + if (in_params.pt.radius > 0) { + InnoEnXyzPoint &ipt = dest->en_xyz_points[dest->item_number]; + required_size += static_cast(sizeof(InnoEnXyzPoint)); + if (required_size > dest_size) { + std::cerr << "no enough size required_size en:" << required_size << ",dest_size:" << dest_size + << std::endl; + } else { + (void)get_xyz_point(in_params.block.header, in_params.pt, in_params.angle.angles[in_params.channel], + in_params.channel, &ipt, static_cast(in_params.pkt.type)); + ipt.multi_return = in_params.multi_return; + ipt.is_2nd_return = in_params.pt.is_2nd_return; + ipt.ts_10us += time_adjust_10us; + dest->item_number++; + } + } + }); + } + } + + if (item_count != dest->item_number) { + std::cout << "item number: " << dest->item_number << " item count " << item_count << std::endl; + } + + dest->common.size = required_size; + + if (!check_data_packet(*dest, dest_size)) { + std::cout << "invalid dest datapacket" << std::endl; + return false; + } + + return true; +} + +} // namespace innovusion_packet +} // namespace drivers +} // namespace nebula diff --git a/nebula_decoders/src/nebula_decoders_innovusion/innovusion_driver.cpp b/nebula_decoders/src/nebula_decoders_innovusion/innovusion_driver.cpp new file mode 100644 index 000000000..a38b733c5 --- /dev/null +++ b/nebula_decoders/src/nebula_decoders_innovusion/innovusion_driver.cpp @@ -0,0 +1,59 @@ +#include "nebula_decoders/nebula_decoders_innovusion/innovusion_driver.hpp" + +namespace nebula +{ +namespace drivers +{ + +InnovusionDriver::InnovusionDriver( + const std::shared_ptr & sensor_configuration, + const std::shared_ptr & calibration_configuration) +{ + scan_decoder_.reset( + new innovusion_packet::InnovusionDecoder(sensor_configuration, calibration_configuration)); +} + +std::tuple InnovusionDriver::ConvertScanToPointcloud( + const std::shared_ptr & innovusion_scan) +{ + std::tuple pointcloud; + auto logger = rclcpp::get_logger("InnovusionDriver"); + + if (driver_status_ != nebula::Status::OK) { + RCLCPP_ERROR(logger, "Driver not OK."); + return pointcloud; + } + + int cnt = 0; + for (auto & packet : innovusion_scan->packets) { + if (scan_decoder_->unpack(packet) == 0) { + cnt++; + } else { + RCLCPP_ERROR_STREAM( + logger, "Failed to unpack packet with timestamp "); + } + } + + pointcloud = scan_decoder_->getPointcloud(); + + if (cnt == 0) { + RCLCPP_ERROR_STREAM( + logger, "Scanned " << innovusion_scan->packets.size() << " packets, but no " + << "pointclouds were generated."); + } + + return pointcloud; +} + +Status InnovusionDriver::SetCalibrationConfiguration( + const CalibrationConfigurationBase & calibration_configuration) +{ +} + +Status InnovusionDriver::GetStatus() +{ + return driver_status_; +} + +} // namespace drivers +} // namespace nebula diff --git a/nebula_examples/CMakeLists.txt b/nebula_examples/CMakeLists.txt index 5072a5f76..b0b1fa5f6 100644 --- a/nebula_examples/CMakeLists.txt +++ b/nebula_examples/CMakeLists.txt @@ -55,6 +55,16 @@ ament_auto_add_executable(velodyne_ros_offline_extract_bag_pcd_node ${CMAKE_CURRENT_SOURCE_DIR}/src/velodyne/velodyne_ros_offline_extract_bag_pcd_main.cpp ) +## Innovusion +# Extraction for TEST Lib +ament_auto_add_library(innovusion_ros_offline_extract_bag_pcd SHARED + ${CMAKE_CURRENT_SOURCE_DIR}/src/innovusion/innovusion_ros_offline_extract_bag_pcd.cpp +) +target_link_libraries(innovusion_ros_offline_extract_bag_pcd ${PCL_LIBRARIES}) +ament_auto_add_executable(innovusion_ros_offline_extract_bag_pcd_node + ${CMAKE_CURRENT_SOURCE_DIR}/src/innovusion/innovusion_ros_offline_extract_bag_pcd_main.cpp +) + if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) ament_lint_auto_find_test_dependencies() diff --git a/nebula_examples/include/innovusion/innovusion_ros_offline_extract_bag_pcd.hpp b/nebula_examples/include/innovusion/innovusion_ros_offline_extract_bag_pcd.hpp new file mode 100644 index 000000000..faf996d20 --- /dev/null +++ b/nebula_examples/include/innovusion/innovusion_ros_offline_extract_bag_pcd.hpp @@ -0,0 +1,108 @@ +// Copyright 2023 Map IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef NEBULA_InnovusionRosOfflineExtractBag_H +#define NEBULA_InnovusionRosOfflineExtractBag_H + +#include "nebula_common/nebula_common.hpp" +#include "nebula_common/nebula_status.hpp" +#include "nebula_common/innovusion/innovusion_common.hpp" +#include "nebula_decoders/nebula_decoders_innovusion/innovusion_driver.hpp" +#include "nebula_ros/common/nebula_driver_ros_wrapper_base.hpp" +#include "rclcpp/serialization.hpp" +#include "rclcpp/serialized_message.hpp" +#include "rcpputils/filesystem_helper.hpp" +#include "rcutils/time.h" +#include "rosbag2_cpp/reader.hpp" +#include "rosbag2_cpp/readers/sequential_reader.hpp" +#include "rosbag2_cpp/writer.hpp" +#include "rosbag2_cpp/writers/sequential_writer.hpp" +#include "rosbag2_storage/storage_options.hpp" + +#include +#include +#include + +#include "innovusion_msgs/msg/innovusion_packet.hpp" +#include "innovusion_msgs/msg/innovusion_scan.hpp" + +#include + +#include +#include + +namespace nebula +{ +namespace ros +{ +/// @brief Offline innovusion driver usage example (Output PCD data) +class InnovusionRosOfflineExtractBag final : public rclcpp::Node, NebulaDriverRosWrapperBase +{ + std::shared_ptr driver_ptr_; + Status wrapper_status_; + + std::shared_ptr calibration_cfg_ptr_; + std::shared_ptr sensor_cfg_ptr_; + + /// @brief Initializing ros wrapper + /// @param sensor_configuration SensorConfiguration for this driver + /// @param calibration_configuration CalibrationConfiguration for this driver + /// @return Resulting status + Status InitializeDriver( + std::shared_ptr sensor_configuration, + std::shared_ptr calibration_configuration) override; + + /// @brief Get configurations from ros parameters + /// @param sensor_configuration Output of SensorConfiguration + /// @param calibration_configuration Output of CalibrationConfiguration + /// @return Resulting status + Status GetParameters( + drivers::InnovusionSensorConfiguration & sensor_configuration, + drivers::InnovusionCalibrationConfiguration & calibration_configuration); + + /// @brief Convert seconds to chrono::nanoseconds + /// @param seconds + /// @return chrono::nanoseconds + static inline std::chrono::nanoseconds SecondsToChronoNanoSeconds(const double seconds) + { + return std::chrono::duration_cast( + std::chrono::duration(seconds)); + } + +public: + explicit InnovusionRosOfflineExtractBag( + const rclcpp::NodeOptions & options, const std::string & node_name); + + /// @brief Get current status of this driver + /// @return Current status + Status GetStatus(); + + /// @brief Read the specified bag file and output point clouds to PCD files + Status ReadBag(); + +private: + std::string bag_path; + std::string storage_id; + std::string out_path; + std::string format; + std::string target_topic; + int out_num; + int skip_num; + bool only_xyz; +}; + +} // namespace ros +} // namespace nebula + +#endif // NEBULA_InnovusionRosOfflineExtractBag_H diff --git a/nebula_examples/launch/innovusion_offline_bag_pcd.xml b/nebula_examples/launch/innovusion_offline_bag_pcd.xml new file mode 100644 index 000000000..f458742eb --- /dev/null +++ b/nebula_examples/launch/innovusion_offline_bag_pcd.xml @@ -0,0 +1,37 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/nebula_examples/package.xml b/nebula_examples/package.xml index 6f1163279..b229a3f38 100644 --- a/nebula_examples/package.xml +++ b/nebula_examples/package.xml @@ -27,6 +27,7 @@ sensor_msgs velodyne_msgs yaml-cpp + innovusion_msgs ament_lint_auto ament_lint_common diff --git a/nebula_examples/src/innovusion/innovusion_ros_offline_extract_bag_pcd.cpp b/nebula_examples/src/innovusion/innovusion_ros_offline_extract_bag_pcd.cpp new file mode 100644 index 000000000..41e339a36 --- /dev/null +++ b/nebula_examples/src/innovusion/innovusion_ros_offline_extract_bag_pcd.cpp @@ -0,0 +1,327 @@ +// Copyright 2023 Map IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "innovusion/innovusion_ros_offline_extract_bag_pcd.hpp" + +namespace nebula +{ +namespace ros +{ +InnovusionRosOfflineExtractBag::InnovusionRosOfflineExtractBag( + const rclcpp::NodeOptions & options, const std::string & node_name) +: rclcpp::Node(node_name, options) +{ + drivers::InnovusionCalibrationConfiguration calibration_configuration; + drivers::InnovusionSensorConfiguration sensor_configuration; + + wrapper_status_ = GetParameters(sensor_configuration, calibration_configuration); + if (Status::OK != wrapper_status_) { + RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << wrapper_status_); + return; + } + RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Starting..."); + + calibration_cfg_ptr_ = + std::make_shared(calibration_configuration); + + sensor_cfg_ptr_ = std::make_shared(sensor_configuration); + + RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Driver "); + wrapper_status_ = InitializeDriver( + std::const_pointer_cast(sensor_cfg_ptr_), + std::static_pointer_cast(calibration_cfg_ptr_)); + + RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << "Wrapper=" << wrapper_status_); +} + +Status InnovusionRosOfflineExtractBag::InitializeDriver( + std::shared_ptr sensor_configuration, + std::shared_ptr calibration_configuration) +{ + // driver should be initialized here with proper decoder + driver_ptr_ = std::make_shared( + std::static_pointer_cast(sensor_configuration), + std::static_pointer_cast(calibration_configuration)); + return driver_ptr_->GetStatus(); +} + +Status InnovusionRosOfflineExtractBag::GetStatus() {return wrapper_status_;} + +Status InnovusionRosOfflineExtractBag::GetParameters( + drivers::InnovusionSensorConfiguration & sensor_configuration, + drivers::InnovusionCalibrationConfiguration & calibration_configuration) +{ + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = 4; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("sensor_model", "Falcon"); + sensor_configuration.sensor_model = + nebula::drivers::SensorModelFromString(this->get_parameter("sensor_model").as_string()); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = 4; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("return_mode", "Dual", descriptor); + sensor_configuration.return_mode = + nebula::drivers::ReturnModeFromString(this->get_parameter("return_mode").as_string()); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = 4; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("frame_id", "innovusion", descriptor); + sensor_configuration.frame_id = this->get_parameter("frame_id").as_string(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = 4; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("calibration_file", "/home/demo/github2/nebula/src/nebula_decoders/calibration/innovusion/Falcon.yaml", descriptor); + calibration_configuration.calibration_file = + this->get_parameter("calibration_file").as_string(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = 3; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("min_range", 0.3, descriptor); + sensor_configuration.min_range = this->get_parameter("min_range").as_double(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = 3; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("max_range", 500., descriptor); + sensor_configuration.max_range = this->get_parameter("max_range").as_double(); + } + double view_width = 360 * M_PI / 180; + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = 3; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("view_width", 300., descriptor); + view_width = this->get_parameter("view_width").as_double() * M_PI / 180; + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = 4; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("bag_path", "/home/demo/github2/nebula/bag_inno/", descriptor); + bag_path = this->get_parameter("bag_path").as_string(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = 4; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("storage_id", "sqlite3", descriptor); + storage_id = this->get_parameter("storage_id").as_string(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = 4; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("out_path", "/home/demo/github2/nebula/output", descriptor); + out_path = this->get_parameter("out_path").as_string(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = 4; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("format", "cdr", descriptor); + format = this->get_parameter("format").as_string(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = 2; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("out_num", 3, descriptor); + out_num = this->get_parameter("out_num").as_int(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = 2; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("skip_num", 3, descriptor); + skip_num = this->get_parameter("skip_num").as_int(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = 1; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("only_xyz", false, descriptor); + only_xyz = this->get_parameter("only_xyz").as_bool(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = 4; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("target_topic", "/innovusion_packets", descriptor); + target_topic = this->get_parameter("target_topic").as_string(); + } + + if (sensor_configuration.sensor_model == nebula::drivers::SensorModel::UNKNOWN) { + return Status::INVALID_SENSOR_MODEL; + } + if (sensor_configuration.return_mode == nebula::drivers::ReturnMode::UNKNOWN) { + return Status::INVALID_ECHO_MODE; + } + + if (calibration_configuration.calibration_file.empty()) { + return Status::INVALID_CALIBRATION_FILE; + } else { + auto cal_status = + calibration_configuration.LoadFromFile(calibration_configuration.calibration_file); + if (cal_status != Status::OK) { + RCLCPP_ERROR_STREAM( + this->get_logger(), + "Given Calibration File: '" << calibration_configuration.calibration_file << "'"); + return cal_status; + } + } + + RCLCPP_INFO_STREAM( + this->get_logger(), "Sensor model: " << sensor_configuration.sensor_model + << ", Return mode: " << sensor_configuration.return_mode); + return Status::OK; +} + +Status InnovusionRosOfflineExtractBag::ReadBag() +{ + rosbag2_storage::StorageOptions storage_options; + rosbag2_cpp::ConverterOptions converter_options; + + std::cout << bag_path << std::endl; + std::cout << storage_id << std::endl; + std::cout << out_path << std::endl; + std::cout << format << std::endl; + std::cout << target_topic << std::endl; + std::cout << out_num << std::endl; + std::cout << skip_num << std::endl; + std::cout << only_xyz << std::endl; + + rcpputils::fs::path o_dir(out_path); + auto target_topic_name = target_topic; + if (target_topic_name.substr(0, 1) == "/") { + target_topic_name = target_topic_name.substr(1); + } + target_topic_name = std::regex_replace(target_topic_name, std::regex("/"), "_"); + o_dir = o_dir / rcpputils::fs::path(target_topic_name); + if (rcpputils::fs::create_directories(o_dir)) { + std::cout << "created: " << o_dir << std::endl; + } + // return Status::OK; + + pcl::PCDWriter writer; + + std::unique_ptr writer_; + bool needs_open = true; + storage_options.uri = bag_path; + storage_options.storage_id = storage_id; + converter_options.output_serialization_format = format; // "cdr"; + { + rosbag2_cpp::Reader reader(std::make_unique()); + reader.open(storage_options, converter_options); + int cnt = 0; + int out_cnt = 0; + while (reader.has_next()) { + auto bag_message = reader.read_next(); + + std::cout << "Found topic name " << bag_message->topic_name << std::endl; + + if (bag_message->topic_name == target_topic) { + std::cout << (cnt + 1) << ", " << (out_cnt + 1) << "/" << out_num << std::endl; + innovusion_msgs::msg::InnovusionScan extracted_msg; + rclcpp::Serialization serialization; + rclcpp::SerializedMessage extracted_serialized_msg(*bag_message->serialized_data); + serialization.deserialize_message(&extracted_serialized_msg, &extracted_msg); + + std::cout << "Found data in topic " << bag_message->topic_name << ": " + << bag_message->time_stamp << std::endl; + + // nebula::drivers::NebulaPointCloudPtr pointcloud = + // driver_ptr_->ConvertScanToPointcloud( + // std::make_shared(extracted_msg)); + auto pointcloud_ts = driver_ptr_->ConvertScanToPointcloud( + std::make_shared(extracted_msg)); + auto pointcloud = std::get<0>(pointcloud_ts); + auto fn = std::to_string(bag_message->time_stamp) + ".pcd"; + + if (needs_open) { + const rosbag2_storage::StorageOptions storage_options_w( + {(o_dir / std::to_string(bag_message->time_stamp)).string(), "sqlite3"}); + const rosbag2_cpp::ConverterOptions converter_options_w( + {rmw_get_serialization_format(), rmw_get_serialization_format()}); + writer_ = std::make_unique(); + writer_->open(storage_options_w, converter_options_w); + writer_->create_topic( + {bag_message->topic_name, "innovusion_msgs/msg/InnovusionScan", + rmw_get_serialization_format(), ""}); + needs_open = false; + } + writer_->write(bag_message); + cnt++; + if (skip_num < cnt) { + out_cnt++; + if (only_xyz) { + pcl::PointCloud cloud_xyz; + pcl::copyPointCloud(*pointcloud, cloud_xyz); + writer.writeBinary((o_dir / fn).string(), cloud_xyz); + } else { + writer.writeBinary((o_dir / fn).string(), *pointcloud); + } + } + if (out_num <= out_cnt) { + break; + } + } + } + // close on scope exit + } + return Status::OK; +} + +} // namespace ros +} // namespace nebula diff --git a/nebula_examples/src/innovusion/innovusion_ros_offline_extract_bag_pcd_main.cpp b/nebula_examples/src/innovusion/innovusion_ros_offline_extract_bag_pcd_main.cpp new file mode 100644 index 000000000..06177510d --- /dev/null +++ b/nebula_examples/src/innovusion/innovusion_ros_offline_extract_bag_pcd_main.cpp @@ -0,0 +1,48 @@ +// Copyright 2023 Map IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "innovusion/innovusion_ros_offline_extract_bag_pcd.hpp" + +#include + +#include + +int main(int argc, char * argv[]) +{ + setvbuf(stdout, NULL, _IONBF, BUFSIZ); + + std::string node_name = "nebula_innovusion_offline_extraction_with_bag"; + + rclcpp::init(argc, argv); + rclcpp::executors::SingleThreadedExecutor exec; + rclcpp::NodeOptions options; + + auto innovusion_driver = + std::make_shared(options, node_name); + exec.add_node(innovusion_driver->get_node_base_interface()); + + RCLCPP_INFO_STREAM(rclcpp::get_logger(node_name), "Get Status"); + nebula::Status driver_status = innovusion_driver->GetStatus(); + if (driver_status == nebula::Status::OK) { + RCLCPP_INFO_STREAM(rclcpp::get_logger(node_name), "Reading Started"); + driver_status = innovusion_driver->ReadBag(); + // exec.spin(); + } else { + RCLCPP_ERROR_STREAM(rclcpp::get_logger(node_name), driver_status); + } + RCLCPP_INFO_STREAM(rclcpp::get_logger(node_name), "Ending"); + rclcpp::shutdown(); + + return 0; +} diff --git a/nebula_hw_interfaces/CMakeLists.txt b/nebula_hw_interfaces/CMakeLists.txt index c1e34ab62..a3420dde6 100644 --- a/nebula_hw_interfaces/CMakeLists.txt +++ b/nebula_hw_interfaces/CMakeLists.txt @@ -32,6 +32,10 @@ ament_auto_add_library(nebula_hw_interfaces_velodyne SHARED src/nebula_velodyne_hw_interfaces/velodyne_hw_interface.cpp ) +ament_auto_add_library(nebula_hw_interfaces_innovusion SHARED + src/nebula_innovusion_hw_interfaces/innovusion_hw_interface.cpp + ) + if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) ament_lint_auto_find_test_dependencies() diff --git a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_innovusion/innovusion_hw_interface.hpp b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_innovusion/innovusion_hw_interface.hpp new file mode 100644 index 000000000..16a12d2ee --- /dev/null +++ b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_innovusion/innovusion_hw_interface.hpp @@ -0,0 +1,180 @@ +#ifndef NEBULA_Innovusion_HW_INTERFACE_H +#define NEBULA_Innovusion_HW_INTERFACE_H +// Have to define macros to silence warnings about deprecated headers being used by +// boost/property_tree/ in some versions of boost. +// See: https://github.com/boostorg/property_tree/issues/51 +#include +#if (BOOST_VERSION / 100 >= 1073 && BOOST_VERSION / 100 <= 1076) // Boost 1.73 - 1.76 +#define BOOST_BIND_GLOBAL_PLACEHOLDERS +#endif +#if (BOOST_VERSION / 100 == 1074) // Boost 1.74 +#define BOOST_ALLOW_DEPRECATED_HEADERS +#endif +#include "nebula_common/innovusion/innovusion_common.hpp" +#include "nebula_common/innovusion/innovusion_status.hpp" +#include "nebula_hw_interfaces/nebula_hw_interfaces_common/nebula_hw_interface_base.hpp" +#include "boost_tcp_driver/http_client_driver.hpp" +#include "boost_tcp_driver/tcp_driver.hpp" +#include "boost_udp_driver/udp_driver.hpp" + +#include + +#include "innovusion_msgs/msg/innovusion_packet.hpp" +#include "innovusion_msgs/msg/innovusion_scan.hpp" + +#include +#include +#include + +#include +#include + +namespace nebula +{ +namespace drivers +{ + +const uint16_t kInnoMagicNumberDataPacket = 0x176A; +const uint16_t kInnoProtocolOldHeaderLen = 54; +const uint16_t kInnoProtocolNewHeaderLen = 70; +const uint16_t kInnoCommonHeaderLength = 26; +const uint16_t kInnoPktIdSection = 26; +const uint16_t kInnoPktIdLength = 8; +const uint16_t kInnoPktTypeIndex = 38; +const uint16_t kInnoPktSizeSectionIndex = 10; +const uint16_t kInnoPktSizeSectionLength = 4; +const uint16_t kInnoPktMajorVersionSection = 2; +const uint16_t kInnoPktMinorVersionSection = 3; +const uint16_t kInnoPktVersionSectionLen = 1; +const uint32_t kInnoProtocolMajorV1 = 1; +const uint32_t kInnoPktMax = 10000; + +/// @brief Hardware interface of Innovusion driver +class InnovusionHwInterface : NebulaHwInterfaceBase +{ +private: + std::unique_ptr<::drivers::common::IoContext> cloud_io_context_; + std::shared_ptr m_owned_ctx; + std::shared_ptr m_owned_ctx_s; + std::unique_ptr<::drivers::udp_driver::UdpDriver> cloud_udp_driver_; + std::unique_ptr<::drivers::tcp_driver::HttpClientDriver> http_client_driver_; + std::shared_ptr sensor_configuration_; + std::shared_ptr calibration_configuration_; + std::unique_ptr scan_cloud_ptr_; + std::function buffer)> + scan_reception_callback_; /**This function pointer is called when the scan is complete*/ + std::uint64_t current_packet_id = 0; + + std::shared_ptr parent_node_logger; + + /// @brief check packet vaild + /// @param buffer Point Udp Data Buffer + bool IsPacketValid(const std::vector & buffer); + /// @brief Printing the string to RCLCPP_INFO_STREAM + /// @param buffer Point Udp Data Buffer + void ProtocolCompatibility(std::vector & buffer); + /// @brief Printing the string to RCLCPP_INFO_STREAM + /// @param info Target string + void PrintInfo(std::string info); + /// @brief Printing the string to RCLCPP_ERROR_STREAM + /// @param error Target string + void PrintError(std::string error); + /// @brief Printing the string to RCLCPP_DEBUG_STREAM + /// @param debug Target string + void PrintDebug(std::string debug); + + /// @brief Get sensor configuration and status data + /// @param key information key + /// @return value of key + std::string GetSensorParameter(const std::string & key); + + /// @brief Set sensor configuration and status data + /// @param key information key + std::string SetSensorParameter(const std::string & key, const std::string &value); + + /// @brief Init HttpClientDriver + void InitHttpClientDriver(); + + /// @brief Print sensor common information + void DisplayCommonVersion(); + + /// @brief check ip is broadcast + bool IsBroadcast(std::string strIp); + + /// @brief check ip is multicast + bool IsMulticast(std::string strIp); + + /// @brief add to multicast group + /// @param strMuiticastIp remote Lidar send udp data ip + /// @param uMulticastPort remote send udp data port + /// @param strLocalIp local ip + /// @param uLocalPort local port + void AddToMuiticastGroup(const std::string &strMuiticastIp, const uint16_t &uMulticastPort, + const std::string &strLocalIp, const uint16_t &uLocalPort); + + /// @brief update unicast ip port + /// @param strUnicastIp remote Lidar send udp data ip + /// @param uUnicastPort remote send udp data port + /// @param strLocalIp local ip + /// @param uLocalPort local port + void UpdateUnicastIpPort(const std::string &strUnicastIp, const uint16_t &uUnicastPort, + const std::string &strLocalIp, const uint16_t &uLocalPort); + + /// @brief update unicast ip port for robin by restApi + void RobinSetUdpPortIP(std::string strUdpIp, uint16_t uUdpPort); + +public: + /// @brief Constructor + InnovusionHwInterface(); + /// @brief Callback function to receive the Cloud Packet data from the UDP Driver + /// @param buffer Buffer containing the data received from the UDP socket + void ReceiveCloudPacketCallback(const std::vector & buffer) final; + /// @brief Starting the interface that handles UDP streams + /// @return Resulting status + Status CloudInterfaceStart() final; + /// @brief Function for stopping the interface that handles UDP streams + /// @return Resulting status + Status CloudInterfaceStop() final; + /// @brief Setting sensor configuration + /// @param sensor_configuration SensorConfiguration for this interface + /// @return Resulting status + Status SetSensorConfiguration( + std::shared_ptr sensor_configuration) final; + /// @brief Printing sensor configuration + /// @param sensor_configuration SensorConfiguration for this interface + /// @return Resulting status + Status GetSensorConfiguration(SensorConfigurationBase & sensor_configuration) final; + /// @brief Printing calibration configuration + /// @param calibration_configuration CalibrationConfiguration for the checking + /// @return Resulting status + Status GetCalibrationConfiguration(CalibrationConfigurationBase & calibration_configuration) final; + /// @brief Registering callback for InnovusionScan + /// @param scan_callback Callback function + /// @return Resulting status + Status RegisterScanCallback( + std::function)> scan_callback); + /// @brief Setting rclcpp::Logger + /// @param node Logger + void SetLogger(std::shared_ptr node); + /// @brief Get a one-off HTTP client to communicate with the hardware + /// @param ctx IO Context + /// @param hcd Got http client driver + /// @return Resulting status + Status GetHttpClientDriverOnce( + std::shared_ptr ctx, + std::unique_ptr<::drivers::tcp_driver::HttpClientDriver> & hcd); + /// @brief Getting current sensor configuration and status data (async) + /// @param str_callback Callback function for received JSON string + /// @param snapshot snapshot information + /// @return Resulting status + Status GetSnapshotAsync( + std::function str_callback, const std::string & snapshot); + /// @brief Parsing JSON string to property_tree + /// @param str JSON string + /// @return property_tree + boost::property_tree::ptree ParseJson(const std::string & str); +}; +} // namespace drivers +} // namespace nebula + +#endif // NEBULA_Innovusion_HW_INTERFACE_H diff --git a/nebula_hw_interfaces/package.xml b/nebula_hw_interfaces/package.xml index aa169d320..84bbb0a5a 100644 --- a/nebula_hw_interfaces/package.xml +++ b/nebula_hw_interfaces/package.xml @@ -19,6 +19,7 @@ boost_tcp_driver boost_udp_driver velodyne_msgs + innovusion_msgs ament_cmake_gtest ament_lint_auto diff --git a/nebula_hw_interfaces/src/nebula_innovusion_hw_interfaces/innovusion_hw_interface.cpp b/nebula_hw_interfaces/src/nebula_innovusion_hw_interfaces/innovusion_hw_interface.cpp new file mode 100644 index 000000000..4120a1fab --- /dev/null +++ b/nebula_hw_interfaces/src/nebula_innovusion_hw_interfaces/innovusion_hw_interface.cpp @@ -0,0 +1,334 @@ +#include "nebula_hw_interfaces/nebula_hw_interfaces_innovusion/innovusion_hw_interface.hpp" + +namespace nebula +{ +namespace drivers +{ +InnovusionHwInterface::InnovusionHwInterface() +: cloud_io_context_{new ::drivers::common::IoContext(1)}, + m_owned_ctx{new boost::asio::io_context(1)}, + m_owned_ctx_s{new boost::asio::io_context(1)}, + cloud_udp_driver_{new ::drivers::udp_driver::UdpDriver(*cloud_io_context_)}, + http_client_driver_{new ::drivers::tcp_driver::HttpClientDriver(m_owned_ctx)}, + scan_cloud_ptr_{std::make_unique()} +{ +} + +Status InnovusionHwInterface::SetSensorConfiguration( + std::shared_ptr sensor_configuration) +{ + InnovusionStatus status = Status::OK; + try { + sensor_configuration_ = std::static_pointer_cast(sensor_configuration); + } catch (const std::exception & ex) { + status = Status::SENSOR_CONFIG_ERROR; + std::cerr << status << std::endl; + return status; + } + return Status::OK; +} + +Status InnovusionHwInterface::CloudInterfaceStart() +{ + try { + InitHttpClientDriver(); + + std::cout << "Starting UDP server on: " << *sensor_configuration_ << std::endl; + cloud_udp_driver_->init_receiver( + sensor_configuration_->host_ip, sensor_configuration_->data_port, kInnoPktMax); + cloud_udp_driver_->receiver()->open(); + cloud_udp_driver_->receiver()->bind(); + cloud_udp_driver_->receiver()->asyncReceive( + std::bind(&InnovusionHwInterface::ReceiveCloudPacketCallback, this, std::placeholders::_1)); + } catch (const std::exception & ex) { + Status status = Status::UDP_CONNECTION_ERROR; + std::cerr << status << sensor_configuration_->sensor_ip << "," + << sensor_configuration_->data_port << std::endl; + return status; + } + return Status::OK; +} + +Status InnovusionHwInterface::RegisterScanCallback( + std::function)> scan_callback) +{ + scan_reception_callback_ = std::move(scan_callback); + return Status::OK; +} + +bool InnovusionHwInterface::IsPacketValid(const std::vector & buffer) { + uint32_t send_packet_size = 0; + std::memcpy(&send_packet_size, &buffer[kInnoPktSizeSectionIndex], kInnoPktSizeSectionLength); + + if (buffer.size() < send_packet_size) { + std::cout << "receive buffer size " << buffer.size() << " < packet size " << send_packet_size + << std::endl; + return false; + } + + uint16_t magic_number = ((buffer[1] << 8) | buffer[0]); + uint16_t packet_type = buffer[kInnoPktTypeIndex]; + + // check packet is data packet + if ((magic_number != kInnoMagicNumberDataPacket) || + (packet_type == 2) || (packet_type == 3)) { + return false; + } + + return true; +} + +void InnovusionHwInterface::ProtocolCompatibility(std::vector & buffer) { + uint8_t major_version = buffer[kInnoPktMajorVersionSection]; + uint32_t* packet_size = reinterpret_cast(&buffer[kInnoPktSizeSectionIndex]); + + if (major_version == kInnoProtocolMajorV1) { + // add 16 bytes to the headr + *packet_size += 16; + buffer.insert(buffer.begin() + kInnoProtocolOldHeaderLen, 16, 0); + } +} + +void InnovusionHwInterface::ReceiveCloudPacketCallback(const std::vector & buffer) +{ + std::vector buffer_copy = buffer; + if (!IsPacketValid(buffer_copy)) { + return; + } + + ProtocolCompatibility(buffer_copy); + + uint64_t packet_id = 0; + std::memcpy(&packet_id, &buffer_copy[kInnoPktIdSection], kInnoPktIdLength); + if (current_packet_id == 0) { + current_packet_id = packet_id; + std::cout << "First packet received" << std::endl; + } + + // publish the whole frame data + if ((scan_reception_callback_ != nullptr) && (current_packet_id != packet_id) && (scan_cloud_ptr_->size > 0)) { + scan_reception_callback_(std::move(scan_cloud_ptr_)); + scan_cloud_ptr_ = std::make_unique(); + scan_cloud_ptr_->packets.clear(); + scan_cloud_ptr_->size = 0; + current_packet_id = packet_id; + } + + // add the point to the frame + uint32_t buffer_size = buffer_copy.size(); + innovusion_msgs::msg::InnovusionPacket innovusion_packet; + uint8_t *p1 = &innovusion_packet.data[0]; + memcpy(p1, &buffer_copy[0], buffer_size); + auto now = std::chrono::system_clock::now(); + auto now_secs = std::chrono::duration_cast(now.time_since_epoch()).count(); + auto now_nanosecs = + std::chrono::duration_cast(now.time_since_epoch()).count(); + innovusion_packet.stamp.sec = static_cast(now_secs); + innovusion_packet.stamp.nanosec = + static_cast((now_nanosecs / 1000000000. - static_cast(now_secs)) * 1000000000); + scan_cloud_ptr_->packets.emplace_back(innovusion_packet); + ++scan_cloud_ptr_->size; +} + +Status InnovusionHwInterface::CloudInterfaceStop() { return Status::ERROR_1; } + +Status InnovusionHwInterface::GetSensorConfiguration(SensorConfigurationBase & sensor_configuration) +{ + std::stringstream ss; + ss << sensor_configuration; + PrintDebug(ss.str()); + return Status::ERROR_1; +} + +Status InnovusionHwInterface::GetCalibrationConfiguration( + CalibrationConfigurationBase & calibration_configuration) +{ + PrintDebug(calibration_configuration.calibration_file); + return Status::ERROR_1; +} + +void InnovusionHwInterface::SetLogger(std::shared_ptr logger) +{ + parent_node_logger = logger; +} + +void InnovusionHwInterface::PrintInfo(std::string info) +{ + if (parent_node_logger) { + RCLCPP_INFO_STREAM((*parent_node_logger), info); + } else { + std::cout << info << std::endl; + } +} + +void InnovusionHwInterface::PrintError(std::string error) +{ + if (parent_node_logger) { + RCLCPP_ERROR_STREAM((*parent_node_logger), error); + } else { + std::cerr << error << std::endl; + } +} + +void InnovusionHwInterface::PrintDebug(std::string debug) +{ + if (parent_node_logger) { + RCLCPP_DEBUG_STREAM((*parent_node_logger), debug); + } else { + std::cout << debug << std::endl; + } +} + +std::string InnovusionHwInterface::GetSensorParameter(const std::string &key) { + auto rt = http_client_driver_->get("/command/?get_" + key); + http_client_driver_->client()->close(); + return rt; +} + +std::string InnovusionHwInterface::SetSensorParameter(const std::string &key, const std::string &value) { + auto rt = http_client_driver_->get("/command/?set_" + key + "=" + value); + http_client_driver_->client()->close(); + return rt; +} + +void InnovusionHwInterface::InitHttpClientDriver() { + uint16_t data_port; + uint16_t status_port; + uint16_t message_port; + char ip[20]{0}; + + http_client_driver_->init_client(sensor_configuration_->sensor_ip, 8010); + DisplayCommonVersion(); + + std::string strUdpInfo = GetSensorParameter("udp_ports_ip"); + + if (sscanf(strUdpInfo.c_str(), "%hu,%hu,%hu,%*32[^,],%32[^,], %*s", &data_port, &status_port, &message_port, ip) == 4) { + std::cout << "udp_info:" << data_port << "," << status_port << "," << message_port << "," << ip << std::endl; + + if (IsBroadcast(ip)) { + // broadcast ip, do nothing + sensor_configuration_->host_ip = "0.0.0.0"; + std::cout << "broadcast ip" << std::endl; + } else if (IsMulticast(ip)) { + // multicast ip + std::cout << "multicast ip" << std::endl; + AddToMuiticastGroup(ip, data_port, sensor_configuration_->host_ip, sensor_configuration_->data_port); + } else { + // unicast ip + std::cout << "unicast ip" << std::endl; + UpdateUnicastIpPort(ip, data_port, sensor_configuration_->host_ip, sensor_configuration_->data_port); + } + } +} + +void InnovusionHwInterface::DisplayCommonVersion() { + std::cout<<"*************** Innovusion Lidar Version Info ***************"< 4 && strcmp(strIp.c_str() + strIp.size() - 4, ".255") == 0) { + bRet = true; + } + return bRet; +} + +bool InnovusionHwInterface::IsMulticast(std::string strIp) { + bool bRet = false; + uint16_t uHead = 0; + if (sscanf(strIp.c_str(), "%hu", &uHead) == 1) { + if (uHead >= 224 && uHead <= 239) { + bRet = true; + } + } + return bRet; +} + +void InnovusionHwInterface::AddToMuiticastGroup(const std::string &strMuiticastIp, const uint16_t &uMulticastPort, + const std::string &strLocalIp, const uint16_t &uLocalPort) { + //TODO: multicast access to point cloud data is not supported + std::cout<<"Attention!!!!!!!!! Currently, multicast access to point cloud data is not supported! We shall change to unicast!"<sensor_model == nebula::drivers::SensorModel::INNOVUSION_ROBIN){ + RobinSetUdpPortIP(strLocalIp, uLocalPort); + } else if(sensor_configuration_->sensor_model == nebula::drivers::SensorModel::INNOVUSION_FALCON){ + std::string strSendInfo = std::to_string(uLocalPort) + "," + std::to_string(uLocalPort) + + "," + std::to_string(uLocalPort) + "," + strLocalIp; + std::cout << "UpdateFalconUnicastIpPort, strSendInfo:" << strSendInfo << std::endl; + + SetSensorParameter("force_udp_ports_ip", strSendInfo); + } else { + std::cout << "UpdateUnicastIpPort, not support sensor model" << std::endl; + } +} + +void InnovusionHwInterface::RobinSetUdpPortIP(std::string strUdpIp, uint16_t uUdpPort) +{ + std::string strSendInfo = "{\"ip\":\"" + strUdpIp + "\",\"port_data\":" + std::to_string(uUdpPort) + + ",\"port_message\":" + std::to_string(uUdpPort) + ",\"port_status\":" + std::to_string(uUdpPort) + "}"; + std::cout << "UpdateFalconUnicastIpPort, strSendInfo:" << strSendInfo << std::endl; + + auto rt = http_client_driver_->post("/v1/lidar/force_udp_ports_ip", strSendInfo); + http_client_driver_->client()->close(); + std::cout << "UpdateRobinUnicastIpPort, rt:" << rt << std::endl; +} + +boost::property_tree::ptree InnovusionHwInterface::ParseJson(const std::string &str) { + boost::property_tree::ptree tree; + try { + std::stringstream ss; + ss << str; + boost::property_tree::read_json(ss, tree); + } catch (boost::property_tree::json_parser_error & e) { + std::cerr << "Error on ParseJson:" << e.what() << std::endl; + } + return tree; +} + +Status InnovusionHwInterface::GetHttpClientDriverOnce( + std::shared_ptr ctx, + std::unique_ptr<::drivers::tcp_driver::HttpClientDriver> & hcd) +{ + hcd = std::unique_ptr<::drivers::tcp_driver::HttpClientDriver>( + new ::drivers::tcp_driver::HttpClientDriver(ctx)); + try { + hcd->init_client(sensor_configuration_->sensor_ip, 8088); + } catch (const std::exception & ex) { + Status status = Status::HTTP_CONNECTION_ERROR; + std::cerr << status << sensor_configuration_->sensor_ip << "," << 8088 << std::endl; + return Status::HTTP_CONNECTION_ERROR; + } + return Status::OK; +} + +Status InnovusionHwInterface::GetSnapshotAsync( + std::function str_callback, const std::string & snapshot) +{ + auto ctx = std::make_shared(); + std::unique_ptr<::drivers::tcp_driver::HttpClientDriver> hcd; + auto st = GetHttpClientDriverOnce(ctx, hcd); + if (st != Status::OK) { + return st; + } + hcd->asyncGet(str_callback, snapshot); + ctx->run(); + return Status::OK; +} + +} // namespace drivers +} // namespace nebula diff --git a/nebula_messages/innovusion_msgs/CMakeLists.txt b/nebula_messages/innovusion_msgs/CMakeLists.txt new file mode 100644 index 000000000..bda6c05b9 --- /dev/null +++ b/nebula_messages/innovusion_msgs/CMakeLists.txt @@ -0,0 +1,24 @@ +cmake_minimum_required(VERSION 3.5) +project(innovusion_msgs) + +if (NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) + set(CMAKE_CXX_STANDARD_REQUIRED ON) + set(CMAKE_CXX_EXTENSIONS OFF) +endif () + +if (CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif () + +find_package(ament_cmake_auto REQUIRED) +ament_auto_find_build_dependencies() + +rosidl_generate_interfaces(${PROJECT_NAME} + "msg/InnovusionPacket.msg" + "msg/InnovusionScan.msg" + DEPENDENCIES + std_msgs + ) + +ament_package() diff --git a/nebula_messages/innovusion_msgs/msg/InnovusionPacket.msg b/nebula_messages/innovusion_msgs/msg/InnovusionPacket.msg new file mode 100644 index 000000000..2b0be57c6 --- /dev/null +++ b/nebula_messages/innovusion_msgs/msg/InnovusionPacket.msg @@ -0,0 +1,4 @@ +# Raw Innovusion LIDAR packet. + +builtin_interfaces/Time stamp # packet timestamp +uint8[10000] data # packet contents diff --git a/nebula_messages/innovusion_msgs/msg/InnovusionScan.msg b/nebula_messages/innovusion_msgs/msg/InnovusionScan.msg new file mode 100644 index 000000000..b85f4f430 --- /dev/null +++ b/nebula_messages/innovusion_msgs/msg/InnovusionScan.msg @@ -0,0 +1,3 @@ +std_msgs/Header header +uint32 size +InnovusionPacket[] packets # packet contents diff --git a/nebula_messages/innovusion_msgs/package.xml b/nebula_messages/innovusion_msgs/package.xml new file mode 100644 index 000000000..938d2d2c0 --- /dev/null +++ b/nebula_messages/innovusion_msgs/package.xml @@ -0,0 +1,25 @@ + + + innovusion_msgs + 0.0.0 + + ROS message definition for the Innovusion LiDAR + sensor. + + hirakawa + Apache 2 + + ament_cmake_auto + rosidl_default_generators + + builtin_interfaces + std_msgs + + rosidl_default_runtime + + rosidl_interface_packages + + + ament_cmake + + diff --git a/nebula_ros/CMakeLists.txt b/nebula_ros/CMakeLists.txt index 6848b9dec..a83786c32 100644 --- a/nebula_ros/CMakeLists.txt +++ b/nebula_ros/CMakeLists.txt @@ -90,6 +90,38 @@ rclcpp_components_register_node(velodyne_driver_ros_wrapper EXECUTABLE velodyne_driver_ros_wrapper_node ) + +## Innovusion +# Hw Interface +ament_auto_add_library(innovusion_hw_ros_wrapper SHARED + src/innovusion/innovusion_hw_interface_ros_wrapper.cpp + ) + +rclcpp_components_register_node(innovusion_hw_ros_wrapper + PLUGIN "InnovusionHwInterfaceRosWrapper" + EXECUTABLE innovusion_hw_interface_ros_wrapper_node + ) + +# Monitor +ament_auto_add_library(innovusion_hw_monitor_ros_wrapper SHARED + src/innovusion/innovusion_hw_monitor_ros_wrapper.cpp + ) + +rclcpp_components_register_node(innovusion_hw_monitor_ros_wrapper + PLUGIN "InnovusionHwMonitorRosWrapper" + EXECUTABLE innovusion_hw_monitor_ros_wrapper_node + ) + +# DriverDecoder +ament_auto_add_library(innovusion_driver_ros_wrapper SHARED + src/innovusion/innovusion_decoder_ros_wrapper.cpp + ) + +rclcpp_components_register_node(innovusion_driver_ros_wrapper + PLUGIN "InnovusionDriverRosWrapper" + EXECUTABLE innovusion_driver_ros_wrapper_node + ) + if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) ament_lint_auto_find_test_dependencies() diff --git a/nebula_ros/config/innovusion/Falcon.yaml b/nebula_ros/config/innovusion/Falcon.yaml new file mode 100644 index 000000000..70035df32 --- /dev/null +++ b/nebula_ros/config/innovusion/Falcon.yaml @@ -0,0 +1,11 @@ +/**: + ros__parameters: + sensor_model: "Falcon" # See readme for supported models + sensor_ip: "172.168.1.10" # Lidar Sensor IP + host_ip: "172.168.1.101" # Broadcast IP from Sensor + frame_id: "innovusion" + data_port: 8010 # LiDAR Data Port + cloud_min_range: 0.4 + cloud_max_range: 2000.0 + setup_sensor: false + online: True diff --git a/nebula_ros/config/innovusion/Robin.yaml b/nebula_ros/config/innovusion/Robin.yaml new file mode 100644 index 000000000..34f502386 --- /dev/null +++ b/nebula_ros/config/innovusion/Robin.yaml @@ -0,0 +1,11 @@ +/**: + ros__parameters: + sensor_model: "Robin" # See readme for supported models + sensor_ip: "172.168.1.10" # Lidar Sensor IP + host_ip: "172.168.1.101" # Broadcast IP from Sensor + frame_id: "innovusion" + data_port: 8050 # LiDAR Data Port + cloud_min_range: 0.4 + cloud_max_range: 2000.0 + setup_sensor: true + online: True diff --git a/nebula_ros/include/nebula_ros/innovusion/innovusion_decoder_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/innovusion/innovusion_decoder_ros_wrapper.hpp new file mode 100644 index 000000000..e3cbc1fa1 --- /dev/null +++ b/nebula_ros/include/nebula_ros/innovusion/innovusion_decoder_ros_wrapper.hpp @@ -0,0 +1,87 @@ +#ifndef NEBULA_InnovusionDriverRosWrapper_H +#define NEBULA_InnovusionDriverRosWrapper_H + +#include "nebula_common/innovusion/innovusion_common.hpp" +#include "nebula_common/nebula_common.hpp" +#include "nebula_common/nebula_status.hpp" +#include "nebula_decoders/nebula_decoders_innovusion/innovusion_driver.hpp" +#include "nebula_hw_interfaces/nebula_hw_interfaces_innovusion/innovusion_hw_interface.hpp" +#include "nebula_ros/common/nebula_driver_ros_wrapper_base.hpp" + +#include +#include +#include +#include + +#include + +#include "innovusion_msgs/msg/innovusion_packet.hpp" +#include "innovusion_msgs/msg/innovusion_scan.hpp" + +namespace nebula +{ +namespace ros +{ +/// @brief Ros wrapper of Innovusion driver +class InnovusionDriverRosWrapper final : public rclcpp::Node, NebulaDriverRosWrapperBase +{ + std::shared_ptr driver_ptr_; + Status wrapper_status_; + rclcpp::Subscription::SharedPtr innovusion_scan_sub_; + rclcpp::Publisher::SharedPtr nebula_points_pub_; + rclcpp::Publisher::SharedPtr aw_points_ex_pub_; + rclcpp::Publisher::SharedPtr aw_points_base_pub_; + + std::shared_ptr calibration_cfg_ptr_; + std::shared_ptr sensor_cfg_ptr_; + + /// @brief Initializing ros wrapper + /// @param sensor_configuration SensorConfiguration for this driver + /// @param calibration_configuration CalibrationConfiguration for this driver + /// @return Resulting status + Status InitializeDriver( + std::shared_ptr sensor_configuration, + std::shared_ptr calibration_configuration) override; + + /// @brief Get configurations from ros parameters + /// @param sensor_configuration Output of SensorConfiguration + /// @param calibration_configuration Output of CalibrationConfiguration + /// @return Resulting status + Status GetParameters( + drivers::InnovusionSensorConfiguration & sensor_configuration, + drivers::InnovusionCalibrationConfiguration & calibration_configuration); + + /// @brief Convert seconds to chrono::nanoseconds + /// @param seconds + /// @return chrono::nanoseconds + static inline std::chrono::nanoseconds SecondsToChronoNanoSeconds(const double seconds) + { + return std::chrono::duration_cast( + std::chrono::duration(seconds)); + } + + /*** + * Publishes a sensor_msgs::msg::PointCloud2 to the specified publisher + * @param pointcloud unique pointer containing the point cloud to publish + * @param publisher + */ + void PublishCloud( + std::unique_ptr pointcloud, + const rclcpp::Publisher::SharedPtr & publisher); + +public: + explicit InnovusionDriverRosWrapper(const rclcpp::NodeOptions & options); + + /// @brief Callback for InnovusionPacket subscriber + /// @param scan_msg Received InnovusionPacket + void ReceiveScanMsgCallback(const innovusion_msgs::msg::InnovusionScan::SharedPtr scan_msg); + + /// @brief Get current status of this driver + /// @return Current status + Status GetStatus(); +}; + +} // namespace ros +} // namespace nebula + +#endif // NEBULA_InnovusionDriverRosWrapper_H diff --git a/nebula_ros/include/nebula_ros/innovusion/innovusion_hw_interface_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/innovusion/innovusion_hw_interface_ros_wrapper.hpp new file mode 100644 index 000000000..8bd9f7f47 --- /dev/null +++ b/nebula_ros/include/nebula_ros/innovusion/innovusion_hw_interface_ros_wrapper.hpp @@ -0,0 +1,89 @@ +#ifndef NEBULA_InnovusionHwInterfaceRosWrapper_H +#define NEBULA_InnovusionHwInterfaceRosWrapper_H + +#include "nebula_common/innovusion/innovusion_common.hpp" +#include "nebula_common/nebula_common.hpp" +#include "nebula_hw_interfaces/nebula_hw_interfaces_innovusion/innovusion_hw_interface.hpp" +#include "nebula_ros/common/nebula_hw_interface_ros_wrapper_base.hpp" +#include "boost_tcp_driver/tcp_driver.hpp" + +#include +#include +#include + +#include "innovusion_msgs/msg/innovusion_packet.hpp" +#include "innovusion_msgs/msg/innovusion_scan.hpp" + +#include + +#include +#include + +namespace nebula +{ +namespace ros +{ +/// @brief Get parameter from rclcpp::Parameter +/// @tparam T +/// @param p Parameter from rclcpp parameter callback +/// @param name Target parameter name +/// @param value Corresponding value +/// @return Whether the target name existed +template +bool get_param(const std::vector & p, const std::string & name, T & value) +{ + auto it = std::find_if(p.cbegin(), p.cend(), [&name](const rclcpp::Parameter & parameter) { + return parameter.get_name() == name; + }); + if (it != p.cend()) { + value = it->template get_value(); + return true; + } + return false; +} + +/// @brief Hardware interface ros wrapper of Innovusion driver +class InnovusionHwInterfaceRosWrapper final : public rclcpp::Node, NebulaHwInterfaceWrapperBase +{ + drivers::InnovusionHwInterface hw_interface_; + Status interface_status_; + + drivers::InnovusionSensorConfiguration sensor_configuration_; + + /// @brief Received Innovusion message publisher + rclcpp::Publisher::SharedPtr innovusion_scan_pub_; + + /// @brief Initializing hardware interface ros wrapper + /// @param sensor_configuration SensorConfiguration for this driver + /// @return Resulting status + Status InitializeHwInterface( + const drivers::SensorConfigurationBase & sensor_configuration) override; + /// @brief Callback for receiving InnovusionScan + /// @param scan_buffer Received InnovusionScan + void ReceiveScanDataCallback(std::unique_ptr scan_buffer); + +public: + explicit InnovusionHwInterfaceRosWrapper(const rclcpp::NodeOptions & options); + ~InnovusionHwInterfaceRosWrapper() noexcept override; + /// @brief Start point cloud streaming (Call CloudInterfaceStart of HwInterface) + /// @return Resulting status + Status StreamStart() override; + /// @brief Stop point cloud streaming (not used) + /// @return Resulting status + Status StreamStop() override; + /// @brief Shutdown (not used) + /// @return Resulting status + Status Shutdown() override; + /// @brief Get configurations from ros parameters + /// @param sensor_configuration Output of SensorConfiguration + /// @return Resulting status + Status GetParameters(drivers::InnovusionSensorConfiguration & sensor_configuration); + +private: + std::mutex mtx_config_; +}; + +} // namespace ros +} // namespace nebula + +#endif // NEBULA_InnovusionHwInterfaceRosWrapper_H diff --git a/nebula_ros/include/nebula_ros/innovusion/innovusion_hw_monitor_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/innovusion/innovusion_hw_monitor_ros_wrapper.hpp new file mode 100644 index 000000000..24278cfa8 --- /dev/null +++ b/nebula_ros/include/nebula_ros/innovusion/innovusion_hw_monitor_ros_wrapper.hpp @@ -0,0 +1,138 @@ +#ifndef NEBULA_InnovusionHwMonitorRosWrapper_H +#define NEBULA_InnovusionHwMonitorRosWrapper_H + +#include "nebula_common/innovusion/innovusion_common.hpp" +#include "nebula_common/nebula_common.hpp" +#include "nebula_hw_interfaces/nebula_hw_interfaces_innovusion/innovusion_hw_interface.hpp" +#include "nebula_ros/common/nebula_hw_monitor_ros_wrapper_base.hpp" +#include "boost_tcp_driver/tcp_driver.hpp" + +#include +#include +#include +#include + +#include + +#include +#include +#include +#include + +#include + +namespace nebula +{ +namespace ros +{ +/// @brief Get parameter from rclcpp::Parameter +/// @tparam T +/// @param p Parameter from rclcpp parameter callback +/// @param name Target parameter name +/// @param value Corresponding value +/// @return Whether the target name existed +template +bool get_param(const std::vector & p, const std::string & name, T & value) +{ + auto it = std::find_if(p.cbegin(), p.cend(), [&name](const rclcpp::Parameter & parameter) { + return parameter.get_name() == name; + }); + if (it != p.cend()) { + value = it->template get_value(); + return true; + } + return false; +} + +/// @brief Hardware monitor ros wrapper of Innovusion driver +class InnovusionHwMonitorRosWrapper final : public rclcpp::Node, NebulaHwMonitorWrapperBase +{ +private: + drivers::InnovusionHwInterface hw_interface_; + diagnostic_updater::Updater diagnostics_updater_; + Status interface_status_; + drivers::InnovusionSensorConfiguration sensor_configuration_; + std::shared_ptr current_snapshot_; + std::shared_ptr lidar_info_; + std::shared_ptr current_snapshot_time_; + rclcpp::TimerBase::SharedPtr diagnostics_snapshot_timer_; + rclcpp::TimerBase::SharedPtr diagnostics_update_timer_; + uint16_t diag_span_; + rclcpp::CallbackGroup::SharedPtr cbg_r_; + rclcpp::CallbackGroup::SharedPtr cbg_m_; + uint8_t current_diag_status_; + bool setup_sensor_; + + std::string key_lidar_info_; + std::string key_lidar_snapshot_; + std::string key_lidar_rpm_; + std::string key_laser_voltage_; + std::string key_lidar_up_time_; + std::string key_det_temp_; + std::string key_laser_temp_; + std::string key_lidar_sn_; + + /// @brief Initializing hardware monitor ros wrapper + /// @param sensor_configuration SensorConfiguration for this driver + /// @return Resulting status + Status InitializeHwMonitor( + const drivers::SensorConfigurationBase & sensor_configuration) override; + + /// @brief Check the current motor rpm for diagnostic_updater + /// @param diagnostics DiagnosticStatusWrapper + void InnovusionCheckMotorRpm( + diagnostic_updater::DiagnosticStatusWrapper & diagnostics); + /// @brief Check the laser voltage for diagnostic_updater + /// @param diagnostics + void InnovusionCheckLaserVoltage( + diagnostic_updater::DiagnosticStatusWrapper & diagnostics); + /// @brief Check the uptime for diagnostic_updater + void InnovusionCheckUptime( + diagnostic_updater::DiagnosticStatusWrapper & diagnostics); + /// @brief Check the det temperature for diagnostic_updater + void InnovusionCheckDetTemp( + diagnostic_updater::DiagnosticStatusWrapper & diagnostics); + /// @brief Check the laser temperature for diagnostic_updater + void InnovusionCheckLaserTemp( + diagnostic_updater::DiagnosticStatusWrapper & diagnostics); + /// @brief Get value from property_tree + /// @param pt property_tree + /// @param key Pey string + /// @return Value + std::tuple InnovusionCommonGet( + std::shared_ptr pt,std::string key); + /// @brief Get value from property_tree + /// @param pt property_tree + /// @param key Pey string + /// @return Value + std::string GetPtreeValue( + std::shared_ptr pt, const std::string & key); + +public: + explicit InnovusionHwMonitorRosWrapper(const rclcpp::NodeOptions & options); + ~InnovusionHwMonitorRosWrapper() noexcept override; + /// @brief Not used + /// @return Current status + Status MonitorStart() override; + /// @brief Not used + /// @return Status::OK + Status MonitorStop() override; + /// @brief Not used + /// @return Status::OK + Status Shutdown() override; + /// @brief Get configurations from ros parameters + /// @param sensor_configuration Output of SensorConfiguration + /// @return Resulting status + Status GetParameters(drivers::InnovusionSensorConfiguration & sensor_configuration); + /// @brief Initializing diagnostics + void InitializeInnovusionDiagnostics(); + /// @brief Callback of the timer for getting the current lidar snapshot + void OnInnovusionSnapshotTimer(); + /// @brief Get the key of the lidar snapshot + const std::string & GetKeyLidarSnapshot() const { return key_lidar_snapshot_; } +}; + +} // namespace ros +} // namespace nebula + +#endif // NEBULA_InnovusionHwMonitorRosWrapper_H diff --git a/nebula_ros/launch/innovusion_launch_all_hw.xml b/nebula_ros/launch/innovusion_launch_all_hw.xml new file mode 100644 index 000000000..983774d48 --- /dev/null +++ b/nebula_ros/launch/innovusion_launch_all_hw.xml @@ -0,0 +1,47 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/nebula_ros/launch/nebula_launch.py b/nebula_ros/launch/nebula_launch.py index f9c30f47d..a336c33dd 100644 --- a/nebula_ros/launch/nebula_launch.py +++ b/nebula_ros/launch/nebula_launch.py @@ -20,6 +20,8 @@ def get_lidar_make(sensor_name): return "Hesai", ".csv" elif sensor_name[:3].lower() in ["hdl", "vlp", "vls"]: return "Velodyne", ".yaml" + elif sensor_name[:3].lower() in ["fal", "rob"]: + return "Innovusion", ".yaml" return "unrecognized_sensor_model" @@ -105,7 +107,7 @@ def launch_setup(context, *args, **kwargs): container_kwargs = {} if LaunchConfiguration("debug_logging").perform(context) == "true": container_kwargs["ros_arguments"] = ['--log-level', 'debug'] - + container = ComposableNodeContainer( name="nebula_ros_node", namespace="", diff --git a/nebula_ros/src/hesai/hesai_decoder_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_decoder_ros_wrapper.cpp index d8e206995..cdcd6b923 100644 --- a/nebula_ros/src/hesai/hesai_decoder_ros_wrapper.cpp +++ b/nebula_ros/src/hesai/hesai_decoder_ros_wrapper.cpp @@ -65,6 +65,7 @@ void HesaiDriverRosWrapper::ReceiveScanMsgCallback( RCLCPP_WARN_STREAM(get_logger(), "Empty cloud parsed."); return; }; + if ( nebula_points_pub_->get_subscription_count() > 0 || nebula_points_pub_->get_intra_process_subscription_count() > 0) { diff --git a/nebula_ros/src/innovusion/innovusion_decoder_ros_wrapper.cpp b/nebula_ros/src/innovusion/innovusion_decoder_ros_wrapper.cpp new file mode 100644 index 000000000..76b4d1225 --- /dev/null +++ b/nebula_ros/src/innovusion/innovusion_decoder_ros_wrapper.cpp @@ -0,0 +1,220 @@ +#include "nebula_ros/innovusion/innovusion_decoder_ros_wrapper.hpp" + +namespace nebula +{ +namespace ros +{ +InnovusionDriverRosWrapper::InnovusionDriverRosWrapper(const rclcpp::NodeOptions & options) +: rclcpp::Node("Innovusion_driver_ros_wrapper", options) +{ + drivers::InnovusionCalibrationConfiguration calibration_configuration; + drivers::InnovusionSensorConfiguration sensor_configuration; + + setvbuf(stdout, NULL, _IONBF, BUFSIZ); + + wrapper_status_ = + GetParameters(sensor_configuration, calibration_configuration); + if (Status::OK != wrapper_status_) { + RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << wrapper_status_); + return; + } + RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Starting..."); + + calibration_cfg_ptr_ = + std::make_shared(calibration_configuration); + + sensor_cfg_ptr_ = std::make_shared(sensor_configuration); + + RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Driver "); + + wrapper_status_ = InitializeDriver( + std::const_pointer_cast(sensor_cfg_ptr_), + std::static_pointer_cast(calibration_cfg_ptr_)); + + + RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << "Wrapper=" << wrapper_status_); + innovusion_scan_sub_ = create_subscription( + "innovusion_packets", rclcpp::SensorDataQoS(), + std::bind(&InnovusionDriverRosWrapper::ReceiveScanMsgCallback, this, std::placeholders::_1)); + +#if 1 + rclcpp::QoS qos(rclcpp::KeepLast(10)); + nebula_points_pub_ = + this->create_publisher("innovusion_points", qos); +#else + nebula_points_pub_ = + this->create_publisher("innovusion_points", rclcpp::SensorDataQoS()); +#endif + + aw_points_base_pub_ = + this->create_publisher("aw_points", rclcpp::SensorDataQoS()); + aw_points_ex_pub_ = + this->create_publisher("aw_points_ex", rclcpp::SensorDataQoS()); +} + +void InnovusionDriverRosWrapper::ReceiveScanMsgCallback( + const innovusion_msgs::msg::InnovusionScan::SharedPtr scan_msg) +{ + auto t_start = std::chrono::high_resolution_clock::now(); + + std::tuple pointcloud_ts = + driver_ptr_->ConvertScanToPointcloud(scan_msg); + nebula::drivers::NebulaPointCloudPtr pointcloud = std::get<0>(pointcloud_ts); + + if (pointcloud == nullptr) { + RCLCPP_WARN_STREAM(get_logger(), "Empty cloud parsed."); + return; + }; + + if ( + nebula_points_pub_->get_subscription_count() > 0 || + nebula_points_pub_->get_intra_process_subscription_count() > 0) { + auto ros_pc_msg_ptr = std::make_unique(); + pcl::toROSMsg(*pointcloud, *ros_pc_msg_ptr); + ros_pc_msg_ptr->header.stamp = + rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); + PublishCloud(std::move(ros_pc_msg_ptr), nebula_points_pub_); + } + if ( + aw_points_base_pub_->get_subscription_count() > 0 || + aw_points_base_pub_->get_intra_process_subscription_count() > 0) { + const auto autoware_cloud_xyzi = + nebula::drivers::convertPointXYZIRCAEDTToPointXYZIR(pointcloud); + auto ros_pc_msg_ptr = std::make_unique(); + pcl::toROSMsg(*autoware_cloud_xyzi, *ros_pc_msg_ptr); + ros_pc_msg_ptr->header.stamp = + rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); + PublishCloud(std::move(ros_pc_msg_ptr), aw_points_base_pub_); + } + if ( + aw_points_ex_pub_->get_subscription_count() > 0 || + aw_points_ex_pub_->get_intra_process_subscription_count() > 0) { + const auto autoware_ex_cloud = + nebula::drivers::convertPointXYZIRCAEDTToPointXYZIRADT(pointcloud, std::get<1>(pointcloud_ts)); + auto ros_pc_msg_ptr = std::make_unique(); + pcl::toROSMsg(*autoware_ex_cloud, *ros_pc_msg_ptr); + ros_pc_msg_ptr->header.stamp = + rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); + PublishCloud(std::move(ros_pc_msg_ptr), aw_points_ex_pub_); + } + + auto runtime = std::chrono::high_resolution_clock::now() - t_start; + RCLCPP_DEBUG(get_logger(), "PROFILING {'d_total': %lu, 'n_out': %lu}", runtime.count(), pointcloud->size()); +} + +void InnovusionDriverRosWrapper::PublishCloud( + std::unique_ptr pointcloud, + const rclcpp::Publisher::SharedPtr & publisher) +{ + if (pointcloud->header.stamp.sec < 0) { + RCLCPP_WARN_STREAM(this->get_logger(), "Timestamp error, verify clock source."); + } + pointcloud->header.frame_id = sensor_cfg_ptr_->frame_id; + publisher->publish(std::move(pointcloud)); +} + +Status InnovusionDriverRosWrapper::InitializeDriver( + std::shared_ptr sensor_configuration, + std::shared_ptr calibration_configuration) +{ + driver_ptr_ = std::make_shared( + std::static_pointer_cast(sensor_configuration), + std::static_pointer_cast(calibration_configuration)); + return driver_ptr_->GetStatus(); +} + +Status InnovusionDriverRosWrapper::GetStatus() { return wrapper_status_; } + +Status InnovusionDriverRosWrapper::GetParameters( + drivers::InnovusionSensorConfiguration & sensor_configuration, + drivers::InnovusionCalibrationConfiguration &) +{ + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("host_ip", "255.255.255.255", descriptor); + sensor_configuration.host_ip = this->get_parameter("host_ip").as_string(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("sensor_ip", "192.168.1.201", descriptor); + sensor_configuration.sensor_ip = this->get_parameter("sensor_ip").as_string(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("data_port", 2368, descriptor); + sensor_configuration.data_port = this->get_parameter("data_port").as_int(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("sensor_model", ""); + sensor_configuration.sensor_model = + nebula::drivers::SensorModelFromString(this->get_parameter("sensor_model").as_string()); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("return_mode", "", descriptor); + sensor_configuration.return_mode = nebula::drivers::ReturnModeFromStringInnovusion( + this->get_parameter("return_mode").as_string()); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("frame_id", "innovusion", descriptor); + sensor_configuration.frame_id = this->get_parameter("frame_id").as_string(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("cloud_min_range", 0.4, descriptor); + sensor_configuration.cloud_min_range = this->get_parameter("cloud_min_range").as_double(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("cloud_max_range", 2000.0, descriptor); + sensor_configuration.cloud_max_range = this->get_parameter("cloud_max_range").as_double(); + } + + if (sensor_configuration.sensor_model == nebula::drivers::SensorModel::UNKNOWN) { + return Status::INVALID_SENSOR_MODEL; + } + if (sensor_configuration.return_mode == nebula::drivers::ReturnMode::UNKNOWN) { + return Status::INVALID_ECHO_MODE; + } + + RCLCPP_INFO_STREAM(this->get_logger(), "SensorConfig:" << sensor_configuration); + return Status::OK; +} + +RCLCPP_COMPONENTS_REGISTER_NODE(InnovusionDriverRosWrapper) +} // namespace ros +} // namespace nebula diff --git a/nebula_ros/src/innovusion/innovusion_hw_interface_ros_wrapper.cpp b/nebula_ros/src/innovusion/innovusion_hw_interface_ros_wrapper.cpp new file mode 100644 index 000000000..7ec150ebd --- /dev/null +++ b/nebula_ros/src/innovusion/innovusion_hw_interface_ros_wrapper.cpp @@ -0,0 +1,145 @@ +#include "nebula_ros/innovusion/innovusion_hw_interface_ros_wrapper.hpp" + +namespace nebula +{ +namespace ros +{ +InnovusionHwInterfaceRosWrapper::InnovusionHwInterfaceRosWrapper(const rclcpp::NodeOptions & options) +: rclcpp::Node("Innovusion_hw_interface_ros_wrapper", options), hw_interface_() +{ + if (mtx_config_.try_lock()) { + interface_status_ = GetParameters(sensor_configuration_); + mtx_config_.unlock(); + } + if (Status::OK != interface_status_) { + RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << interface_status_); + return; + } + hw_interface_.SetLogger(std::make_shared(this->get_logger())); + std::shared_ptr sensor_cfg_ptr = + std::make_shared(sensor_configuration_); + hw_interface_.SetSensorConfiguration( + std::static_pointer_cast(sensor_cfg_ptr)); + hw_interface_.RegisterScanCallback( + std::bind(&InnovusionHwInterfaceRosWrapper::ReceiveScanDataCallback, this, std::placeholders::_1)); + innovusion_scan_pub_ = + this->create_publisher("innovusion_packets", rclcpp::SensorDataQoS()); + StreamStart(); +} + +InnovusionHwInterfaceRosWrapper::~InnovusionHwInterfaceRosWrapper() { + RCLCPP_INFO_STREAM(get_logger(), "Closing TcpDriver"); +} + +Status InnovusionHwInterfaceRosWrapper::StreamStart() +{ + if (Status::OK == interface_status_) { + interface_status_ = hw_interface_.CloudInterfaceStart(); + } + return interface_status_; +} + +Status InnovusionHwInterfaceRosWrapper::StreamStop() { return Status::OK; } +Status InnovusionHwInterfaceRosWrapper::Shutdown() { return Status::OK; } + +Status InnovusionHwInterfaceRosWrapper::InitializeHwInterface( + const drivers::SensorConfigurationBase & sensor_configuration) +{ + std::stringstream ss; + ss << sensor_configuration; + RCLCPP_DEBUG_STREAM(this->get_logger(), ss.str()); + return Status::OK; +} + +Status InnovusionHwInterfaceRosWrapper::GetParameters( + drivers::InnovusionSensorConfiguration & sensor_configuration) +{ + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("sensor_model", ""); + sensor_configuration.sensor_model = + nebula::drivers::SensorModelFromString(this->get_parameter("sensor_model").as_string()); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("return_mode", "", descriptor); + sensor_configuration.return_mode = nebula::drivers::ReturnModeFromStringInnovusion( + this->get_parameter("return_mode").as_string()); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("host_ip", "255.255.255.255", descriptor); + sensor_configuration.host_ip = this->get_parameter("host_ip").as_string(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("sensor_ip", "192.168.1.201", descriptor); + sensor_configuration.sensor_ip = this->get_parameter("sensor_ip").as_string(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("frame_id", "innovusion", descriptor); + sensor_configuration.frame_id = this->get_parameter("frame_id").as_string(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("data_port", 2368, descriptor); + sensor_configuration.data_port = this->get_parameter("data_port").as_int(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("setup_sensor", true, descriptor); + this->setup_sensor = this->get_parameter("setup_sensor").as_bool(); + } + + if (sensor_configuration.sensor_model == nebula::drivers::SensorModel::UNKNOWN) { + return Status::INVALID_SENSOR_MODEL; + } + if (sensor_configuration.return_mode == nebula::drivers::ReturnMode::UNKNOWN) { + return Status::INVALID_ECHO_MODE; + } + + RCLCPP_INFO_STREAM(this->get_logger(), "SensorConfig:" << sensor_configuration); + return Status::OK; +} + +void InnovusionHwInterfaceRosWrapper::ReceiveScanDataCallback( + std::unique_ptr scan_buffer) +{ + // Publish + scan_buffer->header.frame_id = sensor_configuration_.frame_id; + scan_buffer->header.stamp = scan_buffer->packets.front().stamp; + innovusion_scan_pub_->publish(*scan_buffer); +} + +RCLCPP_COMPONENTS_REGISTER_NODE(InnovusionHwInterfaceRosWrapper) +} // namespace ros +} // namespace nebula diff --git a/nebula_ros/src/innovusion/innovusion_hw_monitor_ros_wrapper.cpp b/nebula_ros/src/innovusion/innovusion_hw_monitor_ros_wrapper.cpp new file mode 100644 index 000000000..cba6e1ea9 --- /dev/null +++ b/nebula_ros/src/innovusion/innovusion_hw_monitor_ros_wrapper.cpp @@ -0,0 +1,321 @@ +#include "nebula_ros/innovusion/innovusion_hw_monitor_ros_wrapper.hpp" + +namespace nebula +{ +namespace ros +{ +InnovusionHwMonitorRosWrapper::InnovusionHwMonitorRosWrapper(const rclcpp::NodeOptions & options) +: rclcpp::Node("Innovusion_hw_monitor_ros_wrapper", options), + hw_interface_(), + diagnostics_updater_(this) +{ + cbg_r_ = create_callback_group(rclcpp::CallbackGroupType::Reentrant); + cbg_m_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + + interface_status_ = GetParameters(sensor_configuration_); + if (Status::OK != interface_status_) { + RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << interface_status_); + return; + } + InitializeHwMonitor(sensor_configuration_); + + // Initialize sensor_configuration + hw_interface_.SetLogger(std::make_shared(this->get_logger())); + RCLCPP_INFO_STREAM(this->get_logger(), "Initialize sensor_configuration"); + std::shared_ptr sensor_cfg_ptr = + std::make_shared(sensor_configuration_); + RCLCPP_INFO_STREAM(this->get_logger(), "hw_interface_.InitializeSensorConfiguration"); + hw_interface_.SetSensorConfiguration( + std::static_pointer_cast(sensor_cfg_ptr)); + + if (setup_sensor_) { + // Initialize diagnostics updater + InitializeInnovusionDiagnostics(); + } +} + +Status InnovusionHwMonitorRosWrapper::MonitorStart() { return interface_status_; } + +Status InnovusionHwMonitorRosWrapper::MonitorStop() { return Status::OK; } +Status InnovusionHwMonitorRosWrapper::Shutdown() { return Status::OK; } + +Status InnovusionHwMonitorRosWrapper::InitializeHwMonitor( + const drivers::SensorConfigurationBase & sensor_configuration) +{ + + switch (sensor_configuration.sensor_model) { + case nebula::drivers::SensorModel::INNOVUSION_ROBIN: + key_lidar_info_ = ":get-lidar-info"; + key_lidar_snapshot_ = ":get-lidar-status"; + key_lidar_rpm_ = "motor.polygon_speed"; + key_laser_voltage_ = "laser_info.laser_5V"; + key_lidar_up_time_ = "uptime"; + key_det_temp_ = "temperature.det"; + key_laser_temp_ = "temperature.laser"; + key_lidar_sn_ = "sn"; + break; + case nebula::drivers::SensorModel::INNOVUSION_FALCON: + key_lidar_info_ = ":get-lidar-info"; + key_lidar_snapshot_ = ":get_lidar_status"; + key_lidar_rpm_ = "motor_status.polygon_speed"; + key_laser_voltage_ = "laser_status.pump_voltage"; + key_lidar_up_time_ = "uptime"; + key_det_temp_ = "temperature.det"; + key_laser_temp_ = "temperature.laser"; + key_lidar_sn_ = "sn"; + break; + default: + return Status::INVALID_SENSOR_MODEL; + break; + } + return Status::OK; +} + +void InnovusionHwMonitorRosWrapper::InitializeInnovusionDiagnostics() +{ + hw_interface_.GetSnapshotAsync([this](const std::string & str) { + lidar_info_ = + std::make_shared(hw_interface_.ParseJson(str)); + try { + std::string info_serial = GetPtreeValue(lidar_info_, key_lidar_sn_); + auto hardware_id = "innovusion:" + info_serial; + diagnostics_updater_.setHardwareID(hardware_id); + } catch (boost::bad_lexical_cast & ex) { + RCLCPP_ERROR_STREAM( + this->get_logger(), this->get_name() << " Error:" + << "Can't get lidar sn"); + return; + } + }, key_lidar_info_); + + // get lidar snapshot + hw_interface_.GetSnapshotAsync([this](const std::string & str) { + current_snapshot_time_.reset(new rclcpp::Time(this->get_clock()->now())); + current_snapshot_ = + std::make_shared(hw_interface_.ParseJson(str)); + }, key_lidar_snapshot_); + + diagnostics_updater_.add( + "innovusion_motor", this, &InnovusionHwMonitorRosWrapper::InnovusionCheckMotorRpm); + diagnostics_updater_.add( + "innovusion_laser_voltage", this, &InnovusionHwMonitorRosWrapper::InnovusionCheckLaserVoltage); + diagnostics_updater_.add( + "innovusion_lidar_uptime", this, &InnovusionHwMonitorRosWrapper::InnovusionCheckUptime); + diagnostics_updater_.add( + "innovusion_det_temp", this, &InnovusionHwMonitorRosWrapper::InnovusionCheckDetTemp); + diagnostics_updater_.add( + "innovusion_laser_temp", this, &InnovusionHwMonitorRosWrapper::InnovusionCheckLaserTemp); + + // get time snapshot cycle + auto on_timer_snapshot = [this] { OnInnovusionSnapshotTimer(); }; + diagnostics_snapshot_timer_ = std::make_shared>( + this->get_clock(), std::chrono::milliseconds(diag_span_), std::move(on_timer_snapshot), + this->get_node_base_interface()->get_context()); + this->get_node_timers_interface()->add_timer(diagnostics_snapshot_timer_, cbg_m_); + + auto on_timer_update = [this] { + auto now = this->get_clock()->now(); + auto dif = (now - *current_snapshot_time_).seconds(); + if (diag_span_ * 2.0 < dif * 1000) { + current_diag_status_ = diagnostic_msgs::msg::DiagnosticStatus::STALE; + RCLCPP_DEBUG_STREAM(get_logger(), "STALE"); + } else { + current_diag_status_ = diagnostic_msgs::msg::DiagnosticStatus::OK; + RCLCPP_DEBUG_STREAM(get_logger(), "OK"); + } + diagnostics_updater_.force_update(); + }; + diagnostics_update_timer_ = std::make_shared>( + this->get_clock(), std::chrono::milliseconds(1000), std::move(on_timer_update), + this->get_node_base_interface()->get_context()); + this->get_node_timers_interface()->add_timer(diagnostics_update_timer_, cbg_r_); +} + +void InnovusionHwMonitorRosWrapper::OnInnovusionSnapshotTimer() +{ + // get lidar snapshot + hw_interface_.GetSnapshotAsync([this](const std::string & str) { + current_snapshot_time_.reset(new rclcpp::Time(this->get_clock()->now())); + current_snapshot_ = + std::make_shared(hw_interface_.ParseJson(str)); + }, key_lidar_snapshot_); +} + +Status InnovusionHwMonitorRosWrapper::GetParameters( + drivers::InnovusionSensorConfiguration & sensor_configuration) +{ + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("sensor_model", ""); + sensor_configuration.sensor_model = + nebula::drivers::SensorModelFromString(this->get_parameter("sensor_model").as_string()); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("return_mode", "", descriptor); + sensor_configuration.return_mode = + nebula::drivers::ReturnModeFromString(this->get_parameter("return_mode").as_string()); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("host_ip", "255.255.255.255", descriptor); + sensor_configuration.host_ip = this->get_parameter("host_ip").as_string(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("sensor_ip", "192.168.1.201", descriptor); + sensor_configuration.sensor_ip = this->get_parameter("sensor_ip").as_string(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("frame_id", "innovusion", descriptor); + sensor_configuration.frame_id = this->get_parameter("frame_id").as_string(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("data_port", 8010, descriptor); + sensor_configuration.data_port = this->get_parameter("data_port").as_int(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = "milliseconds"; + this->declare_parameter("diag_span", 1000, descriptor); + this->diag_span_ = this->get_parameter("diag_span").as_int(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("setup_sensor", true, descriptor); + this->setup_sensor_ = this->get_parameter("setup_sensor").as_bool(); + } + + RCLCPP_INFO_STREAM(this->get_logger(), "SensorConfig:" << sensor_configuration); + return Status::OK; +} + +std::tuple +InnovusionHwMonitorRosWrapper::InnovusionCommonGet( + std::shared_ptr pt,std::string key) +{ + bool not_ex = true; + uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; + std::string mes; + std::string error_mes; + try { + mes = GetPtreeValue(pt, key); + } catch (boost::bad_lexical_cast & ex) { + not_ex = false; + level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; + mes = "Error"; + } + return std::make_tuple(not_ex, level, mes, error_mes); +} + +void InnovusionHwMonitorRosWrapper::InnovusionCheckMotorRpm( + diagnostic_updater::DiagnosticStatusWrapper & diagnostics) +{ + if ( + InnovusionHwMonitorRosWrapper::current_snapshot_ && + !InnovusionHwMonitorRosWrapper::current_snapshot_->empty()) { + auto tpl = InnovusionCommonGet(current_snapshot_, key_lidar_rpm_); + diagnostics.add("sensor", sensor_configuration_.frame_id); + diagnostics.summary(std::get<1>(tpl), std::get<2>(tpl)); + } +} + +void InnovusionHwMonitorRosWrapper::InnovusionCheckLaserVoltage( + diagnostic_updater::DiagnosticStatusWrapper & diagnostics) +{ + if ( + InnovusionHwMonitorRosWrapper::current_snapshot_ && + !InnovusionHwMonitorRosWrapper::current_snapshot_->empty()) { + auto tpl = InnovusionCommonGet(current_snapshot_, key_laser_voltage_); + diagnostics.add("sensor", sensor_configuration_.frame_id); + diagnostics.summary(std::get<1>(tpl), std::get<2>(tpl)); + } +} + +void InnovusionHwMonitorRosWrapper::InnovusionCheckUptime( + diagnostic_updater::DiagnosticStatusWrapper & diagnostics) +{ + if ( + InnovusionHwMonitorRosWrapper::current_snapshot_ && + !InnovusionHwMonitorRosWrapper::current_snapshot_->empty()) { + auto tpl = InnovusionCommonGet(current_snapshot_, key_lidar_up_time_); + diagnostics.add("sensor", sensor_configuration_.frame_id); + diagnostics.summary(std::get<1>(tpl), std::get<2>(tpl)); + } +} + +void InnovusionHwMonitorRosWrapper::InnovusionCheckDetTemp( + diagnostic_updater::DiagnosticStatusWrapper & diagnostics) +{ + if ( + InnovusionHwMonitorRosWrapper::current_snapshot_ && + !InnovusionHwMonitorRosWrapper::current_snapshot_->empty()) { + auto tpl = InnovusionCommonGet(current_snapshot_, key_det_temp_); + diagnostics.add("sensor", sensor_configuration_.frame_id); + diagnostics.summary(std::get<1>(tpl), std::get<2>(tpl)); + } +} + +void InnovusionHwMonitorRosWrapper::InnovusionCheckLaserTemp( + diagnostic_updater::DiagnosticStatusWrapper & diagnostics) +{ + if ( + InnovusionHwMonitorRosWrapper::current_snapshot_ && + !InnovusionHwMonitorRosWrapper::current_snapshot_->empty()) { + auto tpl = InnovusionCommonGet(current_snapshot_, key_laser_temp_); + diagnostics.add("sensor", sensor_configuration_.frame_id); + diagnostics.summary(std::get<1>(tpl), std::get<2>(tpl)); + } +} + +std::string InnovusionHwMonitorRosWrapper::GetPtreeValue( + std::shared_ptr pt, const std::string & key) +{ + boost::optional value = pt->get_optional(key); + if (value) { + return value.get(); + } else { + return "Not support"; + } +} + +InnovusionHwMonitorRosWrapper::~InnovusionHwMonitorRosWrapper() { + RCLCPP_INFO_STREAM(get_logger(), "Closing TcpDriver"); +} + +RCLCPP_COMPONENTS_REGISTER_NODE(InnovusionHwMonitorRosWrapper) +} // namespace ros +} // namespace nebula diff --git a/nebula_sensor_driver/package.xml b/nebula_sensor_driver/package.xml index fa656a543..17a06f618 100644 --- a/nebula_sensor_driver/package.xml +++ b/nebula_sensor_driver/package.xml @@ -18,6 +18,7 @@ nebula_tests pandar_msgs velodyne_msgs + innovusion_msgs ament_cmake diff --git a/nebula_tests/CMakeLists.txt b/nebula_tests/CMakeLists.txt index bd58aa6fc..8074b1e9d 100644 --- a/nebula_tests/CMakeLists.txt +++ b/nebula_tests/CMakeLists.txt @@ -50,11 +50,13 @@ if(BUILD_TESTING) rosbag2_cpp pandar_msgs velodyne_msgs + innovusion_msgs ) add_subdirectory(hesai) add_subdirectory(velodyne) + add_subdirectory(innovusion) endif() diff --git a/nebula_tests/data/innovusion/1699435339354672202/1699435339354672202_0.db3 b/nebula_tests/data/innovusion/1699435339354672202/1699435339354672202_0.db3 new file mode 100644 index 000000000..7b27f7a00 Binary files /dev/null and b/nebula_tests/data/innovusion/1699435339354672202/1699435339354672202_0.db3 differ diff --git a/nebula_tests/data/innovusion/1699435339354672202/metadata.yaml b/nebula_tests/data/innovusion/1699435339354672202/metadata.yaml new file mode 100644 index 000000000..a944a3185 --- /dev/null +++ b/nebula_tests/data/innovusion/1699435339354672202/metadata.yaml @@ -0,0 +1,19 @@ +rosbag2_bagfile_information: + version: 4 + storage_identifier: sqlite3 + relative_file_paths: + - 1699435339354672202_0.db3 + duration: + nanoseconds: 4296672446 + starting_time: + nanoseconds_since_epoch: 1699435339354672202 + message_count: 6 + topics_with_message_count: + - topic_metadata: + name: /innovusion_packets + type: innovusion_msgs/msg/InnovusionScan + serialization_format: cdr + offered_qos_profiles: "" + message_count: 6 + compression_format: "" + compression_mode: "" \ No newline at end of file diff --git a/nebula_tests/data/innovusion/1699435342694585664.pcd b/nebula_tests/data/innovusion/1699435342694585664.pcd new file mode 100644 index 000000000..2bb4c8ce7 Binary files /dev/null and b/nebula_tests/data/innovusion/1699435342694585664.pcd differ diff --git a/nebula_tests/innovusion/CMakeLists.txt b/nebula_tests/innovusion/CMakeLists.txt new file mode 100644 index 000000000..cc79c064f --- /dev/null +++ b/nebula_tests/innovusion/CMakeLists.txt @@ -0,0 +1,20 @@ +# Innovusion +ament_auto_add_library(innovusion_ros_decoder_test SHARED + innovusion_ros_decoder_test.cpp + ) +target_link_libraries(innovusion_ros_decoder_test ${PCL_LIBRARIES} ${NEBULA_TEST_LIBRARIES}) + +ament_add_gtest(innovusion_ros_decoder_test_main + innovusion_ros_decoder_test_main.cpp + ) +ament_target_dependencies(innovusion_ros_decoder_test_main + ${NEBULA_TEST_DEPENDENCIES} + ) +target_include_directories(innovusion_ros_decoder_test_main PUBLIC + ${PROJECT_SOURCE_DIR}/src/innovusion + include + ) +target_link_libraries(innovusion_ros_decoder_test_main + ${PCL_LIBRARIES} + innovusion_ros_decoder_test + ) diff --git a/nebula_tests/innovusion/innovusion_ros_decoder_test.cpp b/nebula_tests/innovusion/innovusion_ros_decoder_test.cpp new file mode 100644 index 000000000..4df1cf0ee --- /dev/null +++ b/nebula_tests/innovusion/innovusion_ros_decoder_test.cpp @@ -0,0 +1,316 @@ +#include "innovusion_ros_decoder_test.hpp" + +#include "rclcpp/serialization.hpp" +#include "rclcpp/serialized_message.hpp" +#include "rcpputils/filesystem_helper.hpp" +#include "rcutils/time.h" +#include "rosbag2_cpp/reader.hpp" +#include "rosbag2_cpp/readers/sequential_reader.hpp" +#include "rosbag2_cpp/writer.hpp" +#include "rosbag2_cpp/writers/sequential_writer.hpp" +#include "rosbag2_storage/storage_options.hpp" + +#include + +#include +#include + +namespace nebula +{ +namespace ros +{ +InnovusionRosDecoderTest::InnovusionRosDecoderTest( + const rclcpp::NodeOptions & options, const std::string & node_name) +: rclcpp::Node(node_name, options) +{ + drivers::InnovusionCalibrationConfiguration calibration_configuration; + drivers::InnovusionSensorConfiguration sensor_configuration; + + wrapper_status_ = GetParameters(sensor_configuration, calibration_configuration); + if (Status::OK != wrapper_status_) { + RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << wrapper_status_); + return; + } + RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Starting..."); + + calibration_cfg_ptr_ = + std::make_shared(calibration_configuration); + + sensor_cfg_ptr_ = std::make_shared(sensor_configuration); + + RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Driver "); + wrapper_status_ = InitializeDriver( + std::const_pointer_cast(sensor_cfg_ptr_), + std::static_pointer_cast(calibration_cfg_ptr_)); + + RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << "Wrapper=" << wrapper_status_); +} + +Status InnovusionRosDecoderTest::InitializeDriver( + std::shared_ptr sensor_configuration, + std::shared_ptr calibration_configuration) +{ + // driver should be initialized here with proper decoder + driver_ptr_ = std::make_shared( + std::static_pointer_cast(sensor_configuration), + std::static_pointer_cast(calibration_configuration)); + return driver_ptr_->GetStatus(); +} + +Status InnovusionRosDecoderTest::GetStatus() { return wrapper_status_; } + +Status InnovusionRosDecoderTest::GetParameters( + drivers::InnovusionSensorConfiguration & sensor_configuration, + drivers::InnovusionCalibrationConfiguration & calibration_configuration) +{ + std::filesystem::path calib_dir = + _SRC_CALIBRATION_DIR_PATH; // variable defined in CMakeLists.txt; + calib_dir /= "innovusion"; + std::filesystem::path bag_root_dir = + _SRC_RESOURCES_DIR_PATH; // variable defined in CMakeLists.txt; + bag_root_dir /= "innovusion"; + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = 4; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("sensor_model", "Falcon"); + sensor_configuration.sensor_model = + nebula::drivers::SensorModelFromString(this->get_parameter("sensor_model").as_string()); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = 4; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("return_mode", "Dual", descriptor); + sensor_configuration.return_mode = + nebula::drivers::ReturnModeFromString(this->get_parameter("return_mode").as_string()); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = 4; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("frame_id", "innovusion", descriptor); + sensor_configuration.frame_id = this->get_parameter("frame_id").as_string(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = 4; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter( + "calibration_file", (calib_dir / "Falcon.yaml").string(), descriptor); + calibration_configuration.calibration_file = + this->get_parameter("calibration_file").as_string(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = 3; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("min_range", 0.3, descriptor); + sensor_configuration.min_range = this->get_parameter("min_range").as_double(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = 3; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("max_range", 300., descriptor); + sensor_configuration.max_range = this->get_parameter("max_range").as_double(); + } + double view_width = 360 * M_PI / 180; + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = 3; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("view_width", 300., descriptor); + view_width = this->get_parameter("view_width").as_double() * M_PI / 180; + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = 4; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter( + "bag_path", (bag_root_dir / "1699435339354672202").string(), descriptor); + bag_path = this->get_parameter("bag_path").as_string(); + std::cout << bag_path << std::endl; + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = 4; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("storage_id", "sqlite3", descriptor); + storage_id = this->get_parameter("storage_id").as_string(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = 4; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("format", "cdr", descriptor); + format = this->get_parameter("format").as_string(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = 4; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("target_topic", "/innovusion_packets", descriptor); + target_topic = this->get_parameter("target_topic").as_string(); + } + + if (sensor_configuration.sensor_model == nebula::drivers::SensorModel::UNKNOWN) { + return Status::INVALID_SENSOR_MODEL; + } + if (sensor_configuration.return_mode == nebula::drivers::ReturnMode::UNKNOWN) { + return Status::INVALID_ECHO_MODE; + } + if (calibration_configuration.calibration_file.empty()) { + return Status::INVALID_CALIBRATION_FILE; + } else { + auto cal_status = + calibration_configuration.LoadFromFile(calibration_configuration.calibration_file); + if (cal_status != Status::OK) { + RCLCPP_ERROR_STREAM( + this->get_logger(), + "Given Calibration File: '" << calibration_configuration.calibration_file << "'"); + return cal_status; + } + } + + RCLCPP_INFO_STREAM(this->get_logger(), "SensorConfig:" << sensor_configuration); + return Status::OK; +} + +void printPCD(nebula::drivers::NebulaPointCloudPtr pp) +{ + for (auto p : pp->points) { + std::cout << "(" << p.x << ", " << p.y << "," << p.z << "): " << p.intensity << ", " + << p.channel << ", " << p.azimuth << ", " << p.return_type << ", " << p.time_stamp + << std::endl; + } +} + +void checkPCDs(nebula::drivers::NebulaPointCloudPtr pp1, nebula::drivers::NebulaPointCloudPtr pp2) +{ + EXPECT_EQ(pp1->points.size(), pp2->points.size()); + for (uint32_t i = 0; i < pp1->points.size(); i++) { + auto p1 = pp1->points[i]; + auto p2 = pp2->points[i]; + EXPECT_FLOAT_EQ(p1.x, p2.x); + EXPECT_FLOAT_EQ(p1.y, p2.y); + EXPECT_FLOAT_EQ(p1.z, p2.z); + EXPECT_FLOAT_EQ(p1.intensity, p2.intensity); + EXPECT_EQ(p1.channel, p2.channel); + EXPECT_FLOAT_EQ(p1.azimuth, p2.azimuth); + EXPECT_EQ(p1.return_type, p2.return_type); + EXPECT_DOUBLE_EQ(p1.time_stamp, p2.time_stamp); + } +} + +void checkPCDs(nebula::drivers::NebulaPointCloudPtr pp1, pcl::PointCloud::Ptr pp2) +{ + std::cout<<"checkPCDs, pp1 size:"<points.size()<<", pp2 size:"<points.size()<points.size(), pp2->points.size()); + for (uint32_t i = 0; i < pp1->points.size(); i++) { + auto p1 = pp1->points[i]; + auto p2 = pp2->points[i]; + EXPECT_FLOAT_EQ(p1.x, p2.x); + EXPECT_FLOAT_EQ(p1.y, p2.y); + EXPECT_FLOAT_EQ(p1.z, p2.z); + } +} + +void InnovusionRosDecoderTest::ReadBag() +{ + rosbag2_storage::StorageOptions storage_options; + rosbag2_cpp::ConverterOptions converter_options; + + std::cout << bag_path << std::endl; + std::cout << storage_id << std::endl; + std::cout << format << std::endl; + std::cout << target_topic << std::endl; + + auto target_topic_name = target_topic; + if (target_topic_name.substr(0, 1) == "/") { + target_topic_name = target_topic_name.substr(1); + } + target_topic_name = std::regex_replace(target_topic_name, std::regex("/"), "_"); + + pcl::PCDReader pcd_reader; + + rcpputils::fs::path bag_dir(bag_path); + rcpputils::fs::path pcd_dir = bag_dir.parent_path(); + int check_cnt = 0; + + storage_options.uri = bag_path; + storage_options.storage_id = storage_id; + converter_options.output_serialization_format = format; //"cdr"; + rclcpp::Serialization serialization; + nebula::drivers::NebulaPointCloudPtr pointcloud(new nebula::drivers::NebulaPointCloud); + // nebula::drivers::NebulaPointCloudPtr ref_pointcloud(new nebula::drivers::NebulaPointCloud); + pcl::PointCloud::Ptr ref_pointcloud(new pcl::PointCloud); + { + rosbag2_cpp::Reader bag_reader(std::make_unique()); + bag_reader.open(storage_options, converter_options); + while (bag_reader.has_next()) { + auto bag_message = bag_reader.read_next(); + + std::cout << "Found topic name " << bag_message->topic_name << std::endl; + + if (bag_message->topic_name == target_topic) { + innovusion_msgs::msg::InnovusionScan extracted_msg; + rclcpp::SerializedMessage extracted_serialized_msg(*bag_message->serialized_data); + serialization.deserialize_message(&extracted_serialized_msg, &extracted_msg); + + std::cout << "Found data in topic " << bag_message->topic_name << ": " + << bag_message->time_stamp << std::endl; + + auto extracted_msg_ptr = std::make_shared(extracted_msg); + auto pointcloud_ts = driver_ptr_->ConvertScanToPointcloud(extracted_msg_ptr); + pointcloud = std::get<0>(pointcloud_ts); + + // There are very rare cases where has_scanned_ does not become true, but it is not known + // whether it is because of decoder or deserialize_message. + if (!pointcloud) continue; + + auto fn = std::to_string(bag_message->time_stamp) + ".pcd"; + + auto target_pcd_path = (pcd_dir / fn); + std::cout << target_pcd_path << std::endl; + if (target_pcd_path.exists()) { + std::cout << "exists: " << target_pcd_path << std::endl; + auto rt = pcd_reader.read(target_pcd_path.string(), *ref_pointcloud); + std::cout << rt << " loaded: " << target_pcd_path << std::endl; + checkPCDs(pointcloud, ref_pointcloud); + check_cnt++; + // ref_pointcloud.reset(new nebula::drivers::NebulaPointCloud); + ref_pointcloud.reset(new pcl::PointCloud); + } + pointcloud.reset(new nebula::drivers::NebulaPointCloud); + } + } + EXPECT_GT(check_cnt, 0); + // close on scope exit + } +} + +} // namespace ros +} // namespace nebula diff --git a/nebula_tests/innovusion/innovusion_ros_decoder_test.hpp b/nebula_tests/innovusion/innovusion_ros_decoder_test.hpp new file mode 100644 index 000000000..1e662943a --- /dev/null +++ b/nebula_tests/innovusion/innovusion_ros_decoder_test.hpp @@ -0,0 +1,91 @@ +#ifndef NEBULA_InnovusionRosDecoderTest_H +#define NEBULA_InnovusionRosDecoderTest_H + +#include "nebula_common/nebula_common.hpp" +#include "nebula_common/nebula_status.hpp" +#include "nebula_common/innovusion/innovusion_common.hpp" +#include "nebula_decoders/nebula_decoders_innovusion/innovusion_driver.hpp" +#include "nebula_ros/common/nebula_driver_ros_wrapper_base.hpp" + +#include +#include +#include + +#include "innovusion_msgs/msg/innovusion_packet.hpp" +#include "innovusion_msgs/msg/innovusion_scan.hpp" + +#include + +namespace nebula +{ +namespace ros +{ +/// @brief Testing decoder (Keeps InnovusionDriverRosWrapper structure as much as possible) +class InnovusionRosDecoderTest final : public rclcpp::Node, + NebulaDriverRosWrapperBase //, testing::Test +{ + std::shared_ptr driver_ptr_; + Status wrapper_status_; + + std::shared_ptr calibration_cfg_ptr_; + std::shared_ptr sensor_cfg_ptr_; + + /// @brief Initializing ros wrapper + /// @param sensor_configuration SensorConfiguration for this driver + /// @param calibration_configuration CalibrationConfiguration for this driver + /// @return Resulting status + Status InitializeDriver( + std::shared_ptr sensor_configuration, + std::shared_ptr calibration_configuration) override; + + /// @brief Get configurations (Magic numbers is described, each function can be + /// integrated if the ros parameter can be passed to Google Test) + /// @param sensor_configuration Output of SensorConfiguration + /// @param calibration_configuration Output of CalibrationConfiguration + /// @return Resulting status + Status GetParameters( + drivers::InnovusionSensorConfiguration & sensor_configuration, + drivers::InnovusionCalibrationConfiguration & calibration_configuration); + + /// @brief Convert seconds to chrono::nanoseconds + /// @param seconds + /// @return chrono::nanoseconds + static inline std::chrono::nanoseconds SecondsToChronoNanoSeconds(const double seconds) + { + return std::chrono::duration_cast( + std::chrono::duration(seconds)); + } + +public: + explicit InnovusionRosDecoderTest( + const rclcpp::NodeOptions & options, const std::string & node_name); + + /// @brief Get current status of this driver + /// @return Current status + Status GetStatus(); + + /// @brief Read the specified bag file and compare the constructed point clouds with the + /// corresponding PCD files + void ReadBag(); + /* + void SetUp() override { + // Setup things that should occur before every test instance should go here + RCLCPP_ERROR_STREAM(this->get_logger(), "DONE WITH SETUP!!"); + } + + void TearDown() override { + std::cout << "DONE WITH TEARDOWN" << std::endl; + } +*/ +private: + std::string bag_path; + std::string storage_id; + std::string format; + std::string target_topic; + std::string correction_file_path; +}; + +} // namespace ros +} // namespace nebula + +#endif // NEBULA_InnovusionRosDecoderTest_H diff --git a/nebula_tests/innovusion/innovusion_ros_decoder_test_main.cpp b/nebula_tests/innovusion/innovusion_ros_decoder_test_main.cpp new file mode 100644 index 000000000..db0cc37b4 --- /dev/null +++ b/nebula_tests/innovusion/innovusion_ros_decoder_test_main.cpp @@ -0,0 +1,46 @@ +#include "innovusion_ros_decoder_test.hpp" + +#include + +#include + +#include + +std::shared_ptr innovusion_driver; + +TEST(TestDecoder, TestPcd) +{ + std::cout << "TEST(TestDecoder, TestPcd)" << std::endl; + innovusion_driver->ReadBag(); +} + +int main(int argc, char * argv[]) +{ + std::cout << "innovusion_ros_decoder_test_main.cpp" << std::endl; + setvbuf(stdout, NULL, _IONBF, BUFSIZ); + + std::string node_name = "nebula_innovusion_decoder_test"; + + rclcpp::init(argc, argv); + ::testing::InitGoogleTest(&argc, argv); + rclcpp::executors::SingleThreadedExecutor exec; + rclcpp::NodeOptions options; + + innovusion_driver = std::make_shared(options, node_name); + exec.add_node(innovusion_driver->get_node_base_interface()); + + RCLCPP_INFO_STREAM(rclcpp::get_logger(node_name), "Get Status"); + nebula::Status driver_status = innovusion_driver->GetStatus(); + int result = 0; + if (driver_status == nebula::Status::OK) { + RCLCPP_INFO_STREAM(rclcpp::get_logger(node_name), "Reading Started"); + result = RUN_ALL_TESTS(); + } else { + RCLCPP_ERROR_STREAM(rclcpp::get_logger(node_name), driver_status); + } + RCLCPP_INFO_STREAM(rclcpp::get_logger(node_name), "Ending"); + innovusion_driver.reset(); + rclcpp::shutdown(); + + return result; +}