From 9de52bb5ec8d286b14c87e22f9647364e47c01ec Mon Sep 17 00:00:00 2001 From: Mohamad Akkawi Date: Thu, 17 Nov 2022 06:37:55 -0500 Subject: [PATCH] [navigator] Tone Down traffic warnings - add unit tests for adsb conflict detection - move adsb conflict detection to lib/adsb and adsb conflict class - use containers/Array.hpp for buffer array - expand fake_traffic --- src/lib/adsb/AdsbConflict.cpp | 501 ++++++ src/lib/adsb/AdsbConflict.h | 158 ++ src/lib/adsb/AdsbConflictTest.cpp | 288 ++++ src/lib/adsb/AdsbConflictTest.h | 1957 ++++++++++++++++++++++ src/lib/adsb/CMakeLists.txt | 6 +- src/lib/adsb/adsb.cpp | 32 - src/lib/adsb/test_adsb_helper.ipynb | 646 +++++++ src/lib/geo/geo.cpp | 21 +- src/lib/geo/geo.h | 2 +- src/modules/navigator/CMakeLists.txt | 1 + src/modules/navigator/navigator.h | 33 +- src/modules/navigator/navigator_main.cpp | 297 +--- src/modules/navigator/navigator_params.c | 26 +- 13 files changed, 3635 insertions(+), 333 deletions(-) create mode 100644 src/lib/adsb/AdsbConflict.cpp create mode 100644 src/lib/adsb/AdsbConflict.h create mode 100644 src/lib/adsb/AdsbConflictTest.cpp create mode 100644 src/lib/adsb/AdsbConflictTest.h delete mode 100644 src/lib/adsb/adsb.cpp create mode 100644 src/lib/adsb/test_adsb_helper.ipynb diff --git a/src/lib/adsb/AdsbConflict.cpp b/src/lib/adsb/AdsbConflict.cpp new file mode 100644 index 0000000000..a7462b8483 --- /dev/null +++ b/src/lib/adsb/AdsbConflict.cpp @@ -0,0 +1,501 @@ +/**************************************************************************** + * + * Copyright (C) 2023 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + + + + +#include "AdsbConflict.h" +#include "geo/geo.h" + +#include + +#include + + +void AdsbConflict::detect_traffic_conflict(double lat_now, double lon_now, float alt_now, float vx_now, float vy_now, + float vz_now) + +{ + + float d_hor, d_vert; + get_distance_to_point_global_wgs84(lat_now, lon_now, alt_now, + _transponder_report.lat, _transponder_report.lon, _transponder_report.altitude, &d_hor, &d_vert); + + const float xyz_traffic_speed = sqrtf(_transponder_report.hor_velocity * _transponder_report.hor_velocity + + _transponder_report.ver_velocity * _transponder_report.ver_velocity); + + const float hor_uav_speed = sqrtf(vx_now * vx_now + vy_now * vy_now); + const float xyz_uav_speed = sqrtf(hor_uav_speed * hor_uav_speed + vz_now * vz_now); + + //assume always pointing at each other + const float relative_uav_traffic_speed = xyz_traffic_speed + xyz_uav_speed; + + + // Predict until the vehicle would have passed this system at its current speed + const float prediction_distance = d_hor + TRAFFIC_TO_UAV_DISTANCE_EXTENSION; + + double end_lat, end_lon; + waypoint_from_heading_and_distance(_transponder_report.lat, _transponder_report.lon, + _transponder_report.heading, prediction_distance, &end_lat, &end_lon); + + + const bool cs_distance_conflict_threshold = (!get_distance_to_line(_crosstrack_error, lat_now, + lon_now, _transponder_report.lat, + _transponder_report.lon, end_lat, + end_lon)) + && (!_crosstrack_error.past_end) + && (fabsf(_crosstrack_error.distance) < _conflict_detection_params.crosstrack_separation); + + const bool _crosstrack_separation_check = (fabsf(alt_now - _transponder_report.altitude) < + _conflict_detection_params.crosstrack_separation); + + bool collision_time_check = false; + + const float d_xyz = sqrtf(d_hor * d_hor + d_vert * d_vert); + + if (relative_uav_traffic_speed > FLT_EPSILON) { + const float time_to_collsion = d_xyz / relative_uav_traffic_speed; + collision_time_check = (time_to_collsion < _conflict_detection_params.collision_time_threshold); + } + + _conflict_detected = (cs_distance_conflict_threshold && _crosstrack_separation_check + && collision_time_check); +} + +int AdsbConflict::find_icao_address_in_conflict_list(uint32_t icao_address) +{ + + for (uint8_t i = 0; i < _traffic_buffer.icao_address.size(); i++) { + if (_traffic_buffer.icao_address[i] == icao_address) { + return i; + } + } + + return -1; +} + +void AdsbConflict::remove_icao_address_from_conflict_list(int traffic_index) +{ + _traffic_buffer.icao_address.remove(traffic_index); + _traffic_buffer.timestamp.remove(traffic_index); +} + +void AdsbConflict::add_icao_address_from_conflict_list(uint32_t icao_address) +{ + _traffic_buffer.timestamp.push_back(hrt_absolute_time()); + _traffic_buffer.icao_address.push_back(icao_address); +} + +void AdsbConflict::get_traffic_state() +{ + + const int traffic_index = find_icao_address_in_conflict_list(_transponder_report.icao_address); + + const bool old_conflict = (traffic_index >= 0); + const bool new_traffic = (traffic_index < 0); + const bool _traffic_buffer_full = (_traffic_buffer.icao_address.size() >= NAVIGATOR_MAX_TRAFFIC); + + bool old_conflict_warning_expired = false; + + if (old_conflict && _conflict_detected) { + old_conflict_warning_expired = (hrt_elapsed_time(&_traffic_buffer.timestamp[traffic_index]) > CONFLICT_WARNING_TIMEOUT); + + } + + if (new_traffic && _conflict_detected && !_traffic_buffer_full) { + add_icao_address_from_conflict_list(_transponder_report.icao_address); + _traffic_state = TRAFFIC_STATE::ADD_CONFLICT; + + } else if (new_traffic && _conflict_detected && _traffic_buffer_full) { + _traffic_state = TRAFFIC_STATE::BUFFER_FULL; + + } else if (old_conflict && _conflict_detected + && old_conflict_warning_expired) { + _traffic_buffer.timestamp[traffic_index] = hrt_absolute_time(); + _traffic_state = TRAFFIC_STATE::REMIND_CONFLICT; + + } else if (old_conflict && !_conflict_detected) { + remove_icao_address_from_conflict_list(traffic_index); + _traffic_state = TRAFFIC_STATE::REMOVE_OLD_CONFLICT; + + } else { + _traffic_state = TRAFFIC_STATE::NO_CONFLICT; + } + +} + + +bool AdsbConflict::handle_traffic_conflict() +{ + + get_traffic_state(); + + char uas_id[UTM_GUID_MSG_LENGTH]; //GUID of incoming UTM messages + + //convert UAS_id byte array to char array for User Warning + for (int i = 0; i < 5; i++) { + snprintf(&uas_id[i * 2], sizeof(uas_id) - i * 2, "%02x", _transponder_report.uas_id[PX4_GUID_BYTE_LENGTH - 5 + i]); + } + + uint64_t uas_id_int = 0; + + for (int i = 0; i < 8; i++) { + uas_id_int |= (uint64_t)(_transponder_report.uas_id[PX4_GUID_BYTE_LENGTH - i - 1]) << (i * 8); + } + + + bool take_action = false; + + switch (_traffic_state) { + + case TRAFFIC_STATE::ADD_CONFLICT: + case TRAFFIC_STATE::REMIND_CONFLICT: { + + take_action = send_traffic_warning(math::degrees(_transponder_report.heading) + 180, + (int)fabsf(_crosstrack_error.distance), _transponder_report.flags, uas_id, + _transponder_report.callsign, + uas_id_int); + + } + break; + + case TRAFFIC_STATE::REMOVE_OLD_CONFLICT: { + + mavlink_log_critical(&_mavlink_log_pub, "TRAFFIC UPDATE: %s is no longer in conflict!", + _transponder_report.flags & transponder_report_s::PX4_ADSB_FLAGS_VALID_CALLSIGN ? + _transponder_report.callsign : uas_id); + + events::send(events::ID("navigator_traffic_resolved"), events::Log::Critical, "Traffic Conflict Resolved", + uas_id_int); + + } + break; + + case TRAFFIC_STATE::BUFFER_FULL: { + + if (_traffic_state_previous != TRAFFIC_STATE::BUFFER_FULL) { + PX4_WARN("Too much traffic! Showing all messages from now on"); + } + + //stop buffering incoming conflicts + take_action = send_traffic_warning(math::degrees(_transponder_report.heading) + 180, + (int)fabsf(_crosstrack_error.distance), _transponder_report.flags, uas_id, + _transponder_report.callsign, + uas_id_int); + + } + break; + + case TRAFFIC_STATE::NO_CONFLICT: { + + } + break; + } + + + _traffic_state_previous = _traffic_state; + + return take_action; + +} + +void AdsbConflict::set_conflict_detection_params(float crosstrack_separation, float vertical_separation, + int collision_time_threshold, uint8_t traffic_avoidance_mode) +{ + + _conflict_detection_params.crosstrack_separation = crosstrack_separation; + _conflict_detection_params.vertical_separation = vertical_separation; + _conflict_detection_params.collision_time_threshold = collision_time_threshold; + _conflict_detection_params.traffic_avoidance_mode = traffic_avoidance_mode; + +} + + +bool AdsbConflict::send_traffic_warning(int traffic_direction, int traffic_seperation, uint16_t tr_flags, + char uas_id[UTM_GUID_MSG_LENGTH], char tr_callsign[UTM_CALLSIGN_LENGTH], uint64_t uas_id_int) +{ + + switch (_conflict_detection_params.traffic_avoidance_mode) { + + case 0: { + PX4_WARN("TRAFFIC %s! dst %d, hdg %d", + tr_flags & transponder_report_s::PX4_ADSB_FLAGS_VALID_CALLSIGN ? tr_callsign : uas_id, + traffic_seperation, + traffic_direction); + break; + } + + case 1: { + mavlink_log_critical(&_mavlink_log_pub, "Warning TRAFFIC %s! dst %d, hdg %d\t", + tr_flags & transponder_report_s::PX4_ADSB_FLAGS_VALID_CALLSIGN ? tr_callsign : uas_id, + traffic_seperation, + traffic_direction); + /* EVENT + * @description + * - ID: {1} + * - Distance: {2m} + * - Direction: {3} degrees + */ + events::send(events::ID("navigator_traffic"), events::Log::Critical, "Traffic alert", + uas_id_int, traffic_seperation, traffic_direction); + break; + } + + case 2: { + mavlink_log_critical(&_mavlink_log_pub, "TRAFFIC: %s Returning home! dst %d, hdg %d\t", + tr_flags & transponder_report_s::PX4_ADSB_FLAGS_VALID_CALLSIGN ? tr_callsign : uas_id, + traffic_seperation, + traffic_direction); + /* EVENT + * @description + * - ID: {1} + * - Distance: {2m} + * - Direction: {3} degrees + */ + events::send(events::ID("navigator_traffic_rtl"), events::Log::Critical, + "Traffic alert, returning home", + uas_id_int, traffic_seperation, traffic_direction); + + return true; + + break; + } + + case 3: { + mavlink_log_critical(&_mavlink_log_pub, "TRAFFIC: %s Landing! dst %d, hdg % d\t", + tr_flags & transponder_report_s::PX4_ADSB_FLAGS_VALID_CALLSIGN ? tr_callsign : uas_id, + traffic_seperation, + traffic_direction); + /* EVENT + * @description + * - ID: {1} + * - Distance: {2m} + * - Direction: {3} degrees + */ + events::send(events::ID("navigator_traffic_land"), events::Log::Critical, + "Traffic alert, landing", + uas_id_int, traffic_seperation, traffic_direction); + + return true; + + break; + + } + + case 4: { + mavlink_log_critical(&_mavlink_log_pub, "TRAFFIC: %s Holding position! dst %d, hdg %d\t", + tr_flags & transponder_report_s::PX4_ADSB_FLAGS_VALID_CALLSIGN ? tr_callsign : uas_id, + traffic_seperation, + traffic_direction); + /* EVENT + * @description + * - ID: {1} + * - Distance: {2m} + * - Direction: {3} degrees + */ + events::send(events::ID("navigator_traffic_hold"), events::Log::Critical, + "Traffic alert, holding position", + uas_id_int, traffic_seperation, traffic_direction); + + return true; + + break; + + } + } + + + return false; + +} + +void AdsbConflict::fake_traffic(const char *callsign, float distance, float direction, float traffic_heading, + float altitude_diff, float hor_velocity, float ver_velocity, int emitter_type, uint32_t icao_address, double lat_uav, + double lon_uav, + float &alt_uav) +{ + double lat{0.0}; + double lon{0.0}; + + waypoint_from_heading_and_distance(lat_uav, lon_uav, direction, distance, &lat, + &lon); + float alt = alt_uav + altitude_diff; + + tr.timestamp = hrt_absolute_time(); + tr.icao_address = icao_address; + tr.lat = lat; // Latitude, expressed as degrees + tr.lon = lon; // Longitude, expressed as degrees + tr.altitude_type = 0; + tr.altitude = alt; + tr.heading = traffic_heading; //-atan2(vel_e, vel_n); // Course over ground in radians + tr.hor_velocity = hor_velocity; //sqrtf(vel_e * vel_e + vel_n * vel_n); // The horizontal velocity in m/s + tr.ver_velocity = ver_velocity; //-vel_d; // The vertical velocity in m/s, positive is up + strncpy(&tr.callsign[0], callsign, sizeof(tr.callsign) - 1); + tr.callsign[sizeof(tr.callsign) - 1] = 0; + tr.emitter_type = emitter_type; // Type from ADSB_EMITTER_TYPE enum + tr.tslc = 2; // Time since last communication in seconds + tr.flags = transponder_report_s::PX4_ADSB_FLAGS_VALID_COORDS | transponder_report_s::PX4_ADSB_FLAGS_VALID_HEADING | + transponder_report_s::PX4_ADSB_FLAGS_VALID_VELOCITY | + transponder_report_s::PX4_ADSB_FLAGS_VALID_ALTITUDE | + (transponder_report_s::ADSB_EMITTER_TYPE_UAV & emitter_type ? 0 : + transponder_report_s::PX4_ADSB_FLAGS_VALID_CALLSIGN); // Flags to indicate various statuses including valid data fields + tr.squawk = 6667; + +#ifndef BOARD_HAS_NO_UUID + px4_guid_t px4_guid; + board_get_px4_guid(px4_guid); + memcpy(tr.uas_id, px4_guid, sizeof(px4_guid_t)); //simulate own GUID +#else + + for (int i = 0; i < PX4_GUID_BYTE_LENGTH ; i++) { + tr.uas_id[i] = 0xe0 + i; //simulate GUID + } + +#endif /* BOARD_HAS_NO_UUID */ + + orb_publish(ORB_ID(transponder_report), fake_traffic_report_publisher, &tr); + +} + + +void AdsbConflict::run_fake_traffic(double &lat_uav, double &lon_uav, + float &alt_uav) +{ + + //first conflict + fake_traffic("LX001", 5, 1.0f, 0.0f, 0.0f, 90000.0f, 90000.0f, + transponder_report_s::ADSB_EMITTER_TYPE_LIGHT, 1, lat_uav, lon_uav, + alt_uav); + + //spam + fake_traffic("LX002", 5, 1.0f, 0.0f, 0.0f, 90000.0f, 90000.0f, + transponder_report_s::ADSB_EMITTER_TYPE_LIGHT, 2, lat_uav, lon_uav, + alt_uav); + fake_traffic("LX0002", 5, 1.0f, 0.0f, 0.0f, 90000.0f, 90000.0f, + transponder_report_s::ADSB_EMITTER_TYPE_LIGHT, 2, lat_uav, lon_uav, + alt_uav); + fake_traffic("LX0002", 5, 1.0f, 0.0f, 0.0f, 90000.0f, 90000.0f, + transponder_report_s::ADSB_EMITTER_TYPE_LIGHT, 2, lat_uav, lon_uav, + alt_uav); + + //stop spamming + + fake_traffic("LX003", 5, 1.0f, 0.0f, 0.0f, 90000.0f, 90000.0f, + transponder_report_s::ADSB_EMITTER_TYPE_LIGHT, 3, lat_uav, lon_uav, + alt_uav); + + fake_traffic("LX004", 5, 1.0f, 0.0f, 0.0f, 90000.0f, 90000.0f, + transponder_report_s::ADSB_EMITTER_TYPE_LIGHT, 4, lat_uav, lon_uav, + alt_uav); + + fake_traffic("LX005", 5, 1.0f, 0.0f, 0.0f, 90000.0f, 90000.0f, + transponder_report_s::ADSB_EMITTER_TYPE_LIGHT, 5, lat_uav, lon_uav, + alt_uav); + + fake_traffic("LX006", 5, 1.0f, 0.0f, 0.0f, 90000.0f, 90000.0f, + transponder_report_s::ADSB_EMITTER_TYPE_LIGHT, 6, lat_uav, lon_uav, + alt_uav); + + fake_traffic("LX007", 5, 1.0f, 0.0f, 0.0f, 90000.0f, 90000.0f, + transponder_report_s::ADSB_EMITTER_TYPE_LIGHT, 7, lat_uav, lon_uav, + alt_uav); + + + fake_traffic("LX008", 5, 1.0f, 0.0f, 0.0f, 90000.0f, 90000.0f, + transponder_report_s::ADSB_EMITTER_TYPE_LIGHT, 8, lat_uav, lon_uav, + alt_uav); + + fake_traffic("LX009", 5, 1.0f, 0.0f, 0.0f, 90000.0f, 90000.0f, + transponder_report_s::ADSB_EMITTER_TYPE_LIGHT, 9, lat_uav, lon_uav, + alt_uav); + + fake_traffic("LX010", 5, 1.0f, 0.0f, 0.0f, 90000.0f, 90000.0f, + transponder_report_s::ADSB_EMITTER_TYPE_LIGHT, 10, lat_uav, lon_uav, + alt_uav); + + //buffer full + fake_traffic("LX011", 5, 1.0f, 0.0f, 0.0f, 90000.0f, 90000.0f, + transponder_report_s::ADSB_EMITTER_TYPE_LIGHT, 11, lat_uav, lon_uav, + alt_uav); + + fake_traffic("LX012", 5, 1.0f, 0.0f, 0.0f, 90000.0f, 90000.0f, + transponder_report_s::ADSB_EMITTER_TYPE_LIGHT, 12, lat_uav, lon_uav, + alt_uav); + + fake_traffic("LX013", 5, 1.0f, 0.0f, 0.0f, 90000.0f, 90000.0f, + transponder_report_s::ADSB_EMITTER_TYPE_LIGHT, 13, lat_uav, lon_uav, + alt_uav); + + + //end conflict + fake_traffic("LX001", 5000, 1.0f, 0.0f, 0.0f, 90000.0f, 90000.0f, + transponder_report_s::ADSB_EMITTER_TYPE_LIGHT, 1, lat_uav, lon_uav, + alt_uav); + fake_traffic("LX002", 5000, 1.0f, 0.0f, 0.0f, 90000.0f, 90000.0f, + transponder_report_s::ADSB_EMITTER_TYPE_LIGHT, 2, lat_uav, lon_uav, + alt_uav); + + fake_traffic("LX003", 5000, 1.0f, 0.0f, 0.0f, 90000.0f, 90000.0f, + transponder_report_s::ADSB_EMITTER_TYPE_LIGHT, 3, lat_uav, lon_uav, + alt_uav); + + fake_traffic("LX004", 5000, 1.0f, 0.0f, 0.0f, 90000.0f, 90000.0f, + transponder_report_s::ADSB_EMITTER_TYPE_LIGHT, 4, lat_uav, lon_uav, + alt_uav); + + + //new conflicts with space in buffer + fake_traffic("LX013", 5, 1.0f, 0.0f, 0.0f, 90000.0f, 90000.0f, + transponder_report_s::ADSB_EMITTER_TYPE_LIGHT, 13, lat_uav, lon_uav, + alt_uav); + + fake_traffic("LX013", 5, 1.0f, 0.0f, 0.0f, 90000.0f, 90000.0f, + transponder_report_s::ADSB_EMITTER_TYPE_LIGHT, 13, lat_uav, lon_uav, + alt_uav); + + fake_traffic("LX014", 5, 1.0f, 0.0f, 0.0f, 90000.0f, 90000.0f, + transponder_report_s::ADSB_EMITTER_TYPE_LIGHT, 14, lat_uav, lon_uav, + alt_uav); + + fake_traffic("LX014", 5, 1.0f, 0.0f, 0.0f, 90000.0f, 90000.0f, + transponder_report_s::ADSB_EMITTER_TYPE_LIGHT, 14, lat_uav, lon_uav, + alt_uav); + + fake_traffic("LX015", 5, 1.0f, 0.0f, 0.0f, 90000.0f, 90000.0f, + transponder_report_s::ADSB_EMITTER_TYPE_LIGHT, 15, lat_uav, lon_uav, + alt_uav); + + for (size_t i = 0; i < _traffic_buffer.icao_address.size(); i++) { + PX4_INFO("%u ", static_cast(_traffic_buffer.icao_address[i])); + } +} diff --git a/src/lib/adsb/AdsbConflict.h b/src/lib/adsb/AdsbConflict.h new file mode 100644 index 0000000000..84ed38287d --- /dev/null +++ b/src/lib/adsb/AdsbConflict.h @@ -0,0 +1,158 @@ +/**************************************************************************** + * + * Copyright (C) 2012-2023 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + + + +#pragma once + +#include +#include + +#include + +#include +#include +#include +#include +#include + +#include +#include + +#include + +#include + +using namespace time_literals; + +static constexpr uint8_t NAVIGATOR_MAX_TRAFFIC{10}; + +static constexpr uint8_t UTM_GUID_MSG_LENGTH{11}; + +static constexpr uint8_t UTM_CALLSIGN_LENGTH{9}; + +static constexpr uint64_t CONFLICT_WARNING_TIMEOUT{60_s}; + +static constexpr float TRAFFIC_TO_UAV_DISTANCE_EXTENSION{1000.0f}; + + +struct traffic_data_s { + double lat_traffic; + double lon_traffic; + float alt_traffic; + float heading_traffic; + float vxy_traffic; + float vz_traffic; + bool in_conflict; +}; + +struct traffic_buffer_s { + px4::Array icao_address {}; + px4::Array timestamp {}; +}; + +struct conflict_detection_params_s { + float crosstrack_separation; + float vertical_separation; + int collision_time_threshold; + uint8_t traffic_avoidance_mode; +}; + +enum class TRAFFIC_STATE { + NO_CONFLICT = 0, + ADD_CONFLICT = 1, + REMIND_CONFLICT = 2, + REMOVE_OLD_CONFLICT = 3, + BUFFER_FULL = 4 +}; + + +class AdsbConflict +{ +public: + AdsbConflict() = default; + ~AdsbConflict() = default; + + void detect_traffic_conflict(double lat_now, double lon_now, float alt_now, float vx_now, float vy_now, float vz_now); + + int find_icao_address_in_conflict_list(uint32_t icao_address); + + void remove_icao_address_from_conflict_list(int traffic_index); + + void add_icao_address_from_conflict_list(uint32_t icao_address); + + void get_traffic_state(); + + void set_conflict_detection_params(float crosstrack_separation, float vertical_separation, + int collision_time_threshold, uint8_t traffic_avoidance_mode); + + + bool send_traffic_warning(int traffic_direction, int traffic_seperation, uint16_t tr_flags, + char uas_id[UTM_GUID_MSG_LENGTH], char tr_callsign[UTM_CALLSIGN_LENGTH], uint64_t uas_id_int); + + transponder_report_s _transponder_report{}; + + bool handle_traffic_conflict(); + + void fake_traffic(const char *const callsign, float distance, float direction, float traffic_heading, + float altitude_diff, + float hor_velocity, float ver_velocity, int emitter_type, uint32_t icao_address, double lat_uav, double lon_uav, + float &alt_uav); + + void run_fake_traffic(double &lat_uav, double &lon_uav, + float &alt_uav); + + bool _conflict_detected{false}; + + TRAFFIC_STATE _traffic_state{TRAFFIC_STATE::NO_CONFLICT}; + + conflict_detection_params_s _conflict_detection_params{}; + + +protected: + traffic_buffer_s _traffic_buffer; + +private: + + orb_advert_t _mavlink_log_pub{nullptr}; + + crosstrack_error_s _crosstrack_error{}; + + + transponder_report_s tr{}; + + orb_advert_t fake_traffic_report_publisher = orb_advertise_queue(ORB_ID(transponder_report), &tr, (unsigned int)20); + + TRAFFIC_STATE _traffic_state_previous{TRAFFIC_STATE::NO_CONFLICT}; + +}; diff --git a/src/lib/adsb/AdsbConflictTest.cpp b/src/lib/adsb/AdsbConflictTest.cpp new file mode 100644 index 0000000000..d83ad82414 --- /dev/null +++ b/src/lib/adsb/AdsbConflictTest.cpp @@ -0,0 +1,288 @@ +#include + +#include "AdsbConflict.h" + +#include "AdsbConflictTest.h" + + +class TestAdsbConflict : public AdsbConflict +{ +public: + TestAdsbConflict() : AdsbConflict() {} + ~TestAdsbConflict() = default; + + void set_traffic_buffer(const traffic_buffer_s &traffic_buffer) + { + _traffic_buffer = traffic_buffer; + } + + void set_conflict(bool &conflict_detected) + { + _conflict_detected = conflict_detected; + } +}; + + +TEST_F(AdsbConflictTest, detectTrafficConflict) +{ + + + int collision_time_threshold = 60; + + float crosstrack_separation = 500.0f; + float vertical_separation = 500.0f; + + double lat_now = 32.617013; + double lon_now = -96.490564; + float alt_now = 1000.0f; + + float vx_now = 0.0f; + float vy_now = 0.0f; + float vz_now = 0.0f; + + uint32_t traffic_dataset_size = sizeof(traffic_dataset) / sizeof(traffic_dataset[0]); + + + TestAdsbConflict adsb_conflict; + + adsb_conflict.set_conflict_detection_params(crosstrack_separation, vertical_separation, collision_time_threshold, 1); + + for (uint32_t i = 0; i < traffic_dataset_size; i++) { + + + printf("---------------%d--------------\n", i); + + struct traffic_data_s traffic = traffic_dataset[i]; + + + adsb_conflict._transponder_report.lat = traffic.lat_traffic; + adsb_conflict._transponder_report.lon = traffic.lon_traffic; + adsb_conflict._transponder_report.altitude = traffic.alt_traffic; + adsb_conflict._transponder_report.heading = traffic.heading_traffic; + adsb_conflict._transponder_report.hor_velocity = traffic.vxy_traffic; + adsb_conflict._transponder_report.ver_velocity = traffic.vz_traffic; + + adsb_conflict.detect_traffic_conflict(lat_now, lon_now, alt_now, vx_now, vy_now, vz_now); + + printf("conflict_detected %d \n", adsb_conflict._conflict_detected); + + printf("------------------------------\n"); + printf("------------------------------\n \n"); + + EXPECT_TRUE(adsb_conflict._conflict_detected == traffic.in_conflict); + } + +} + + +TEST_F(AdsbConflictTest, trafficAlerts) +{ + + struct traffic_buffer_s used_buffer; + used_buffer.icao_address.push_back(2345); + used_buffer.icao_address.push_back(1234); + used_buffer.icao_address.push_back(1897); + used_buffer.icao_address.push_back(0567); + used_buffer.icao_address.push_back(8685); + used_buffer.icao_address.push_back(5000); + + used_buffer.timestamp.push_back(3_s); + used_buffer.timestamp.push_back(800_s); + used_buffer.timestamp.push_back(100_s); + used_buffer.timestamp.push_back(20000_s); + used_buffer.timestamp.push_back(6000_s); + used_buffer.timestamp.push_back(6587_s); + + struct traffic_buffer_s full_buffer; + full_buffer.icao_address.push_back(2345); + full_buffer.icao_address.push_back(1234); + full_buffer.icao_address.push_back(1897); + full_buffer.icao_address.push_back(0567); + full_buffer.icao_address.push_back(8685); + full_buffer.icao_address.push_back(5000); + full_buffer.icao_address.push_back(0000); + full_buffer.icao_address.push_back(2); + full_buffer.icao_address.push_back(589742397); + full_buffer.icao_address.push_back(99999); + + full_buffer.timestamp.push_back(1_s); + full_buffer.timestamp.push_back(800_s); + full_buffer.timestamp.push_back(100_s); + full_buffer.timestamp.push_back(20000_s); + full_buffer.timestamp.push_back(6000_s); + full_buffer.timestamp.push_back(19000_s); + full_buffer.timestamp.push_back(5000_s); + full_buffer.timestamp.push_back(2_s); + full_buffer.timestamp.push_back(1000_s); + full_buffer.timestamp.push_back(58943_s); + + + + struct traffic_buffer_s empty_buffer = {}; + + + TestAdsbConflict adsb_conflict; + + adsb_conflict.set_traffic_buffer(used_buffer); + + bool conflict_detected = false; + adsb_conflict.set_conflict(conflict_detected); + adsb_conflict._transponder_report.icao_address = 00001; + adsb_conflict.get_traffic_state(); + + printf("adsb_conflict._traffic_state %d \n", adsb_conflict._traffic_state); + EXPECT_TRUE(adsb_conflict._traffic_state == TRAFFIC_STATE::NO_CONFLICT); + + conflict_detected = true; + adsb_conflict.set_conflict(conflict_detected); + adsb_conflict._transponder_report.icao_address = 9876; + adsb_conflict.get_traffic_state(); + + printf("adsb_conflict._traffic_state %d \n", adsb_conflict._traffic_state); + EXPECT_TRUE(adsb_conflict._traffic_state == TRAFFIC_STATE::ADD_CONFLICT); + + adsb_conflict.set_traffic_buffer(empty_buffer); + + conflict_detected = true; + adsb_conflict.set_conflict(conflict_detected); + adsb_conflict._transponder_report.icao_address = 9876; + adsb_conflict.get_traffic_state(); + + printf("adsb_conflict._traffic_state %d \n", adsb_conflict._traffic_state); + EXPECT_TRUE(adsb_conflict._traffic_state == TRAFFIC_STATE::ADD_CONFLICT); + + adsb_conflict.set_traffic_buffer(full_buffer); + + conflict_detected = true; + adsb_conflict.set_conflict(conflict_detected); + adsb_conflict._transponder_report.icao_address = 7777; + adsb_conflict.get_traffic_state(); + + printf("adsb_conflict._traffic_state %d \n", adsb_conflict._traffic_state); + EXPECT_TRUE(adsb_conflict._traffic_state == TRAFFIC_STATE::BUFFER_FULL); + + conflict_detected = false; + adsb_conflict.set_conflict(conflict_detected); + adsb_conflict._transponder_report.icao_address = 7777; + adsb_conflict.get_traffic_state(); + + printf("adsb_conflict._traffic_state %d \n", adsb_conflict._traffic_state); + EXPECT_TRUE(adsb_conflict._traffic_state == TRAFFIC_STATE::NO_CONFLICT); + + conflict_detected = false; + adsb_conflict.set_conflict(conflict_detected); + adsb_conflict._transponder_report.icao_address = 8685; + adsb_conflict.get_traffic_state(); + + printf("adsb_conflict._traffic_state %d \n", adsb_conflict._traffic_state); + EXPECT_TRUE(adsb_conflict._traffic_state == TRAFFIC_STATE::REMOVE_OLD_CONFLICT); + + adsb_conflict.set_traffic_buffer(used_buffer); + + conflict_detected = false; + adsb_conflict.set_conflict(conflict_detected); + adsb_conflict._transponder_report.icao_address = 8685; + adsb_conflict.get_traffic_state(); + + printf("adsb_conflict._traffic_state %d \n", adsb_conflict._traffic_state); + EXPECT_TRUE(adsb_conflict._traffic_state == TRAFFIC_STATE::REMOVE_OLD_CONFLICT); + +} + +TEST_F(AdsbConflictTest, trafficReminder) +{ + + struct traffic_buffer_s used_buffer; + used_buffer.icao_address.push_back(2345); + used_buffer.icao_address.push_back(1234); + used_buffer.icao_address.push_back(1897); + used_buffer.icao_address.push_back(0567); + used_buffer.icao_address.push_back(8685); + used_buffer.icao_address.push_back(5000); + + used_buffer.timestamp.push_back(3_s); + used_buffer.timestamp.push_back(800_s); + used_buffer.timestamp.push_back(100_s); + used_buffer.timestamp.push_back(20000_s); + used_buffer.timestamp.push_back(6000_s); + used_buffer.timestamp.push_back(6587_s); + + struct traffic_buffer_s full_buffer; + full_buffer.icao_address.push_back(2345); + full_buffer.icao_address.push_back(1234); + full_buffer.icao_address.push_back(1897); + full_buffer.icao_address.push_back(0567); + full_buffer.icao_address.push_back(8685); + full_buffer.icao_address.push_back(5000); + full_buffer.icao_address.push_back(0000); + full_buffer.icao_address.push_back(2); + full_buffer.icao_address.push_back(589742397); + full_buffer.icao_address.push_back(99999); + + full_buffer.timestamp.push_back(1_s); + full_buffer.timestamp.push_back(800_s); + full_buffer.timestamp.push_back(100_s); + full_buffer.timestamp.push_back(20000_s); + full_buffer.timestamp.push_back(6000_s); + full_buffer.timestamp.push_back(19000_s); + full_buffer.timestamp.push_back(5000_s); + full_buffer.timestamp.push_back(2_s); + full_buffer.timestamp.push_back(1000_s); + full_buffer.timestamp.push_back(58943_s); + + + TestAdsbConflict adsb_conflict; + + adsb_conflict.set_traffic_buffer(used_buffer); + + bool conflict_detected = true; + adsb_conflict.set_conflict(conflict_detected); + adsb_conflict._transponder_report.icao_address = 8685; + adsb_conflict.get_traffic_state(); + + printf("adsb_conflict._traffic_state %d \n", adsb_conflict._traffic_state); + EXPECT_TRUE(adsb_conflict._traffic_state == TRAFFIC_STATE::REMIND_CONFLICT); + + conflict_detected = true; + adsb_conflict.set_conflict(conflict_detected); + adsb_conflict._transponder_report.icao_address = 8685; + adsb_conflict.get_traffic_state(); + + printf("adsb_conflict._traffic_state %d \n", adsb_conflict._traffic_state); + EXPECT_TRUE(adsb_conflict._traffic_state == TRAFFIC_STATE::NO_CONFLICT); + + adsb_conflict.set_traffic_buffer(full_buffer); + + conflict_detected = true; + adsb_conflict.set_conflict(conflict_detected); + adsb_conflict._transponder_report.icao_address = 8685; + adsb_conflict.get_traffic_state(); + + printf("adsb_conflict._traffic_state %d \n", adsb_conflict._traffic_state); + EXPECT_TRUE(adsb_conflict._traffic_state == TRAFFIC_STATE::REMIND_CONFLICT); + + conflict_detected = true; + adsb_conflict.set_conflict(conflict_detected); + adsb_conflict._transponder_report.icao_address = 8685; + adsb_conflict.get_traffic_state(); + + printf("adsb_conflict._traffic_state %d \n", adsb_conflict._traffic_state); + EXPECT_TRUE(adsb_conflict._traffic_state == TRAFFIC_STATE::NO_CONFLICT); + + conflict_detected = false; + adsb_conflict.set_conflict(conflict_detected); + adsb_conflict._transponder_report.icao_address = 8685; + adsb_conflict.get_traffic_state(); + + printf("adsb_conflict._traffic_state %d \n", adsb_conflict._traffic_state); + EXPECT_TRUE(adsb_conflict._traffic_state == TRAFFIC_STATE::REMOVE_OLD_CONFLICT); + + conflict_detected = true; + adsb_conflict.set_conflict(conflict_detected); + adsb_conflict._transponder_report.icao_address = 7777; + adsb_conflict.get_traffic_state(); + + printf("adsb_conflict._traffic_state %d \n", adsb_conflict._traffic_state); + EXPECT_TRUE(adsb_conflict._traffic_state == TRAFFIC_STATE::ADD_CONFLICT); + +} diff --git a/src/lib/adsb/AdsbConflictTest.h b/src/lib/adsb/AdsbConflictTest.h new file mode 100644 index 0000000000..b5ac95fafa --- /dev/null +++ b/src/lib/adsb/AdsbConflictTest.h @@ -0,0 +1,1957 @@ + + +class AdsbConflictTest : public ::testing::Test +{ +public: + + AdsbConflictTest() = default; + virtual ~AdsbConflictTest() = default; + +}; + + +// traffic dataset generated using notebook in adsb/test_adsb_helper.ipynb +traffic_data_s traffic_dataset[1940] = { + + {3.270694516059187151e+01, -9.638379328402535862e+01, 4.470000000000000000e+02, -3.141592653589793116e+00, 2.042375980563040798e+02, 2.042375980563040798e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 7.900000000000000000e+02, -3.109129529502698386e+00, 2.500275609807847104e+03, 2.500275609807847104e+03, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.791000000000000000e+03, -3.076666405415603656e+00, 2.442836539134454554e+01, 2.442836539134454554e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.477000000000000000e+03, -3.044203281328508925e+00, 2.470539903240593205e+01, 2.470539903240593205e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.099000000000000000e+03, -3.011740157241414195e+00, 3.333415007332736877e+03, 3.333415007332736877e+03, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.526000000000000000e+03, -2.979277033154319465e+00, 1.924406636438064311e+02, 1.924406636438064311e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 8.570000000000000000e+02, -2.946813909067224735e+00, 2.272843457257526723e+02, 2.272843457257526723e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.782000000000000000e+03, -2.914350784980130005e+00, 2.003055286306396511e+03, 2.003055286306396511e+03, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.155000000000000000e+03, -2.881887660893035275e+00, 3.401564832300531549e+01, 3.401564832300531549e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 6.900000000000000000e+02, -2.849424536805940544e+00, 2.703351949045676861e+02, 2.703351949045676861e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.160000000000000000e+02, -2.816961412718845814e+00, 1.786010223466191249e+01, 1.786010223466191249e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.960000000000000000e+02, -2.784498288631751084e+00, 2.390488630819377391e+01, 2.390488630819377391e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.840000000000000000e+02, -2.752035164544656354e+00, 1.430947509697754185e+03, 1.430947509697754185e+03, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 2.190000000000000000e+02, -2.719572040457561624e+00, 3.709347191132442276e+02, 3.709347191132442276e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 4.890000000000000000e+02, -2.687108916370466893e+00, 2.243615671666885447e+01, 2.243615671666885447e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 3.180000000000000000e+02, -2.654645792283372163e+00, 2.190726771819353402e+01, 2.190726771819353402e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 7.770000000000000000e+02, -2.622182668196277433e+00, 1.805278546521513761e+01, 1.805278546521513761e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.984000000000000000e+03, -2.589719544109182703e+00, 1.965524935924464103e+02, 1.965524935924464103e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.911000000000000000e+03, -2.557256420022087973e+00, 2.397303001319509264e+01, 2.397303001319509264e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 4.170000000000000000e+02, -2.524793295934993242e+00, 2.042549717943414009e+02, 2.042549717943414009e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 9.630000000000000000e+02, -2.492330171847898512e+00, 1.785720397310970142e+01, 1.785720397310970142e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.137000000000000000e+03, -2.459867047760803782e+00, 2.096534426413398577e+01, 2.096534426413398577e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.478000000000000000e+03, -2.427403923673709052e+00, 6.806605761582918035e+01, 6.806605761582918035e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 5.670000000000000000e+02, -2.394940799586614322e+00, 2.968749592584772401e+01, 2.968749592584772401e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.016000000000000000e+03, -2.362477675499519592e+00, 1.204820048192524382e+02, 1.204820048192524382e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.354000000000000000e+03, -2.330014551412424861e+00, 6.025983379156967601e+01, 6.025983379156967601e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.728000000000000000e+03, -2.297551427325330131e+00, 1.857744125049299910e+01, 1.857744125049299910e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.370000000000000000e+03, -2.265088303238235401e+00, 2.689091912506733806e+01, 2.689091912506733806e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.859000000000000000e+03, -2.232625179151140671e+00, 2.087172925349622332e+01, 2.087172925349622332e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 2.660000000000000000e+02, -2.200162055064045941e+00, 3.090574025195419594e+01, 3.090574025195419594e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.846000000000000000e+03, -2.167698930976951210e+00, 2.588598687541385601e+01, 2.588598687541385601e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 7.260000000000000000e+02, -2.135235806889856480e+00, 3.226411846417861398e+02, 3.226411846417861398e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.002000000000000000e+03, -2.102772682802761750e+00, 1.805054169675090137e+01, 1.805054169675090137e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.362000000000000000e+03, -2.070309558715667020e+00, 2.000655112706835439e+02, 2.000655112706835439e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 7.550000000000000000e+02, -2.037846434628572290e+00, 5.000750256211561464e+03, 5.000750256211561464e+03, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.520000000000000000e+02, -2.005383310541477559e+00, 1.252245183660132852e+03, 1.252245183660132852e+03, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 2.510000000000000000e+02, -1.972920186454382829e+00, 3.283283673345330556e+01, 3.283283673345330556e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 6.610000000000000000e+02, -1.940457062367288099e+00, 1.862732330056778096e+01, 1.862732330056778096e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 7.510000000000000000e+02, -1.907993938280193369e+00, 2.381321405926128989e+02, 2.381321405926128989e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.005000000000000000e+03, -1.875530814193098639e+00, 1.788908877459746094e+01, 1.788908877459746094e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.637000000000000000e+03, -1.843067690106003909e+00, 1.820025288172330704e+02, 1.820025288172330704e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 3.310000000000000000e+02, -1.810604566018909178e+00, 5.005591386140103168e+03, 5.005591386140103168e+03, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.760000000000000000e+03, -1.778141441931814448e+00, 1.885956608163382953e+01, 1.885956608163382953e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.424000000000000000e+03, -1.745678317844719718e+00, 1.755174279030193532e+02, 1.755174279030193532e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.116000000000000000e+03, -1.713215193757624988e+00, 1.751372398308571476e+01, 1.751372398308571476e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.370000000000000000e+02, -1.680752069670530258e+00, 2.782944978728402816e+02, 2.782944978728402816e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 8.060000000000000000e+02, -1.648288945583435527e+00, 3.226109953464362547e+02, 3.226109953464362547e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.180000000000000000e+03, -1.615825821496340797e+00, 1.718352228040834717e+01, 1.718352228040834717e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.671000000000000000e+03, -1.583362697409246067e+00, 3.128515530379883671e+02, 3.128515530379883671e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 8.810000000000000000e+02, -1.550899573322151337e+00, 1.250044252341692072e+03, 1.250044252341692072e+03, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.135000000000000000e+03, -1.518436449235056607e+00, 1.000045561462076535e+03, 1.000045561462076535e+03, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.550000000000000000e+03, -1.485973325147961877e+00, 2.779877678497276747e+02, 2.779877678497276747e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.127000000000000000e+03, -1.453510201060867146e+00, 3.846308929565695394e+02, 3.846308929565695394e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.488000000000000000e+03, -1.421047076973772416e+00, 2.128925921018447980e+02, 2.128925921018447980e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.890000000000000000e+03, -1.388583952886677686e+00, 2.003956586356102036e+02, 2.003956586356102036e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 8.840000000000000000e+02, -1.356120828799582956e+00, 2.500084098585485606e+02, 2.500084098585485606e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 8.410000000000000000e+02, -1.323657704712488226e+00, 6.250395003142801897e+02, 6.250395003142801897e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.209000000000000000e+03, -1.291194580625393495e+00, 1.724326200927686443e+02, 1.724326200927686443e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 8.960000000000000000e+02, -1.258731456538298765e+00, 6.451787352480188531e+01, 6.451787352480188531e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.593000000000000000e+03, -1.226268332451204035e+00, 4.766089221005523768e+02, 4.766089221005523768e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 7.560000000000000000e+02, -1.193805208364109305e+00, 1.818452416227227957e+02, 1.818452416227227957e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.028000000000000000e+03, -1.161342084277014575e+00, 1.798564676255537975e+01, 1.798564676255537975e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 2.550000000000000000e+02, -1.128878960189919844e+00, 7.702973855143075070e+02, 7.702973855143075070e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 8.400000000000000000e+02, -1.096415836102825114e+00, 6.060993926982612834e+01, 6.060993926982612834e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.707000000000000000e+03, -1.063952712015730384e+00, 2.224997428213245030e+02, 2.224997428213245030e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.006000000000000000e+03, -1.031489587928635654e+00, 1.111111211111106513e+03, 1.111111211111106513e+03, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.960000000000000000e+02, -9.990264638415409237e-01, 1.854842104283924584e+02, 1.854842104283924584e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.684000000000000000e+03, -9.665633397544461936e-01, 1.951596406959132324e+01, 1.951596406959132324e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.558000000000000000e+03, -9.341002156673514634e-01, 2.084954390155280635e+01, 2.084954390155280635e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 3.400000000000000000e+02, -9.016370915802567332e-01, 3.336961358947854478e+03, 3.336961358947854478e+03, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 9.150000000000000000e+02, -8.691739674931620030e-01, 1.818214658794319973e+02, 1.818214658794319973e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.954000000000000000e+03, -8.367108434060672728e-01, 1.856060569260251611e+02, 1.856060569260251611e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 6.900000000000000000e+01, -8.042477193189725426e-01, 9.110586907639534502e+02, 9.110586907639534502e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.928000000000000000e+03, -7.717845952318778124e-01, 1.965001269329354727e+02, 1.965001269329354727e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.596000000000000000e+03, -7.393214711447830823e-01, 1.853495640818985066e+02, 1.853495640818985066e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 9.770000000000000000e+02, -7.068583470576883521e-01, 1.736113407116537388e+01, 1.736113407116537388e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.054000000000000000e+03, -6.743952229705936219e-01, 3.571454607047957666e+02, 3.571454607047957666e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.674000000000000000e+03, -6.419320988834988917e-01, 6.674233638903170913e+02, 6.674233638903170913e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 9.460000000000000000e+02, -6.094689747964041615e-01, 2.192998442924184488e+01, 2.192998442924184488e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 5.760000000000000000e+02, -5.770058507093094313e-01, 1.887640262353227172e+01, 1.887640262353227172e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.518000000000000000e+03, -5.445427266222147011e-01, 2.084730385745360479e+02, 2.084730385745360479e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.500000000000000000e+02, -5.120796025351199710e-01, 2.615677863368964395e+01, 2.615677863368964395e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 7.720000000000000000e+02, -4.796164784480252408e-01, 4.000519806225186699e+02, 4.000519806225186699e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 9.230000000000000000e+02, -4.471533543609305106e-01, 9.091043839910439601e+02, 9.091043839910439601e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.378000000000000000e+03, -4.146902302738357804e-01, 4.168154775930365190e+02, 4.168154775930365190e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.882000000000000000e+03, -3.822271061867410502e-01, 3.991804472215255117e+01, 3.991804472215255117e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 2.540000000000000000e+02, -3.497639820996463200e-01, 4.723539261793784760e+01, 4.723539261793784760e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.275000000000000000e+03, -3.173008580125515898e-01, 6.098713686774779319e+01, 6.098713686774779319e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 8.000000000000000000e+01, -2.848377339254568597e-01, 2.385985157134894337e+02, 2.385985157134894337e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.621000000000000000e+03, -2.523746098383621295e-01, 2.001927276401418339e+03, 2.001927276401418339e+03, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 2.230000000000000000e+02, -2.199114857512673993e-01, 3.129713078714744370e+02, 3.129713078714744370e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.469000000000000000e+03, -1.874483616641726691e-01, 2.041938268136135548e+01, 2.041938268136135548e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 3.630000000000000000e+02, -1.549852375770779389e-01, 6.856259647224534604e+01, 6.856259647224534604e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.366000000000000000e+03, -1.225221134899832087e-01, 6.713656603645068799e+01, 6.713656603645068799e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.398000000000000000e+03, -9.005898940288847854e-02, 2.128501982168247935e+02, 2.128501982168247935e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.821000000000000000e+03, -5.759586531579374835e-02, 4.355146456966252799e+02, 4.355146456966252799e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 7.400000000000000000e+01, -2.513274122869901817e-02, 2.226980882686659413e+02, 2.226980882686659413e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 6.110000000000000000e+02, 7.330382858395712020e-03, 1.887506096171068748e+02, 1.887506096171068748e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.762000000000000000e+03, 3.979350694549044221e-02, 4.768812180670619796e+02, 4.768812180670619796e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 2.780000000000000000e+02, 7.225663103258517239e-02, 3.654388182214255210e+01, 3.654388182214255210e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.323000000000000000e+03, 1.047197551196799026e-01, 5.883886991145179763e+02, 5.883886991145179763e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 3.810000000000000000e+02, 1.371828792067746328e-01, 3.574848014822676419e+02, 3.574848014822676419e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.101000000000000000e+03, 1.696460032938693629e-01, 1.683544616455925080e+01, 1.683544616455925080e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.642000000000000000e+03, 2.021091273809640931e-01, 2.459532873891716420e+01, 2.459532873891716420e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.987000000000000000e+03, 2.345722514680588233e-01, 1.961707366065166624e+01, 1.961707366065166624e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.961000000000000000e+03, 2.670353755551535535e-01, 4.247059929455175364e+01, 4.247059929455175364e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 5.260000000000000000e+02, 2.994984996422482837e-01, 1.873710734720440385e+01, 1.873710734720440385e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 5.890000000000000000e+02, 3.319616237293430139e-01, 4.547373697126981256e+02, 4.547373697126981256e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.126000000000000000e+03, 3.644247478164377441e-01, 5.618200501193163632e+01, 5.618200501193163632e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 8.910000000000000000e+02, 3.968878719035324742e-01, 5.263314221362599028e+02, 5.263314221362599028e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 6.630000000000000000e+02, 4.293509959906272044e-01, 1.064131789580262506e+02, 1.064131789580262506e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.423000000000000000e+03, 4.618141200777219346e-01, 3.426189118137053669e+01, 3.426189118137053669e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 7.720000000000000000e+02, 4.942772441648166648e-01, 4.202226687211329903e+01, 4.202226687211329903e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.086000000000000000e+03, 5.267403682519113950e-01, 2.375340830947893522e+01, 2.375340830947893522e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.716000000000000000e+03, 5.592034923390061252e-01, 1.951814463451040282e+01, 1.951814463451040282e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.770000000000000000e+03, 5.916666164261008554e-01, 9.104374119025071650e+02, 9.104374119025071650e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.400000000000000000e+01, 6.241297405131955855e-01, 1.044195357829415087e+02, 1.044195357829415087e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 6.340000000000000000e+02, 6.565928646002903157e-01, 5.001674169715576681e+03, 5.001674169715576681e+03, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 4.880000000000000000e+02, 6.890559886873850459e-01, 2.337979311664152959e+01, 2.337979311664152959e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.089000000000000000e+03, 7.215191127744797761e-01, 7.353086781646577208e+01, 7.353086781646577208e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.057000000000000000e+03, 7.539822368615745063e-01, 2.762453376980698394e+01, 2.762453376980698394e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.209000000000000000e+03, 7.864453609486692365e-01, 1.976500388415134424e+01, 1.976500388415134424e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 8.100000000000000000e+02, 8.189084850357639667e-01, 3.125282018524488308e+02, 3.125282018524488308e+02, 1}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.305000000000000000e+03, 8.513716091228586968e-01, 6.668216903090860797e+02, 6.668216903090860797e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.261000000000000000e+03, 8.838347332099534270e-01, 2.309862096999995984e+01, 2.309862096999995984e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.414000000000000000e+03, 9.162978572970477131e-01, 2.858366852107071736e+02, 2.858366852107071736e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.623000000000000000e+03, 9.487609813841428874e-01, 1.756087459988353601e+02, 1.756087459988353601e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.544000000000000000e+03, 9.812241054712380617e-01, 5.886703332474592116e+02, 5.886703332474592116e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.126000000000000000e+03, 1.013687229558332348e+00, 2.222310420471962686e+02, 2.222310420471962686e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 6.120000000000000000e+02, 1.046150353645426634e+00, 2.908070608148889136e+01, 2.908070608148889136e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.848000000000000000e+03, 1.078613477732521808e+00, 2.467478194404202441e+01, 2.467478194404202441e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.222000000000000000e+03, 1.111076601819616982e+00, 2.941538830619361988e+02, 2.941538830619361988e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.131000000000000000e+03, 1.143539725906711269e+00, 1.865751682051729787e+01, 1.865751682051729787e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 6.850000000000000000e+02, 1.176002849993805555e+00, 2.874275953276229600e+01, 2.874275953276229600e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.816000000000000000e+03, 1.208465974080900729e+00, 5.564795871046821958e+02, 5.564795871046821958e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 5.170000000000000000e+02, 1.240929098167995903e+00, 1.786755450937279477e+02, 1.786755450937279477e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.342000000000000000e+03, 1.273392222255090189e+00, 1.818713395019440782e+02, 1.818713395019440782e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 4.560000000000000000e+02, 1.305855346342184475e+00, 4.507835885228291772e+01, 4.507835885228291772e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.376000000000000000e+03, 1.338318470429279650e+00, 5.001766887810746084e+03, 5.001766887810746084e+03, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 2.160000000000000000e+02, 1.370781594516374824e+00, 2.568039644049956678e+02, 2.568039644049956678e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.193000000000000000e+03, 1.403244718603469110e+00, 2.000186236329007556e+02, 2.000186236329007556e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.608000000000000000e+03, 1.435707842690563396e+00, 3.127886666744816466e+02, 3.127886666744816466e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 4.040000000000000000e+02, 1.468170966777658570e+00, 1.725668355245261694e+02, 1.725668355245261694e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 2.140000000000000000e+02, 1.500634090864753745e+00, 2.191560829570946467e+01, 2.191560829570946467e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.669000000000000000e+03, 1.533097214951848031e+00, 2.727842717242563353e+01, 2.727842717242563353e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 9.100000000000000000e+01, 1.565560339038942317e+00, 2.277417212119433145e+02, 2.277417212119433145e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 9.200000000000000000e+01, 1.598023463126037491e+00, 2.277406909492670550e+01, 2.277406909492670550e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 5.900000000000000000e+01, 1.630486587213132665e+00, 4.597299347108986467e+01, 4.597299347108986467e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 8.000000000000000000e+01, 1.662949711300226951e+00, 5.274282978929767296e+02, 5.274282978929767296e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 8.410000000000000000e+02, 1.695412835387321238e+00, 4.545741820467492289e+02, 4.545741820467492289e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 4.530000000000000000e+02, 1.727875959474416412e+00, 1.713609148870287058e+01, 1.713609148870287058e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.952000000000000000e+03, 1.760339083561511586e+00, 3.712085922093414752e+02, 3.712085922093414752e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.790000000000000000e+03, 1.792802207648605872e+00, 4.769328736692350503e+02, 4.769328736692350503e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.504000000000000000e+03, 1.825265331735700158e+00, 2.771841657867162567e+01, 2.771841657867162567e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 8.600000000000000000e+01, 1.857728455822795333e+00, 3.945221707274337319e+01, 3.945221707274337319e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 8.060000000000000000e+02, 1.890191579909890507e+00, 3.846515713745970402e+02, 3.846515713745970402e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 3.220000000000000000e+02, 1.922654703996984793e+00, 2.860424429759917189e+02, 2.860424429759917189e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 2.800000000000000000e+02, 1.955117828084079079e+00, 3.764267523603876242e+01, 3.764267523603876242e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 7.600000000000000000e+02, 1.987580952171174253e+00, 2.564471768291006981e+01, 2.564471768291006981e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 9.220000000000000000e+02, 2.020044076258269428e+00, 2.564141563805973760e+02, 2.564141563805973760e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 5.740000000000000000e+02, 2.052507200345363714e+00, 2.067052865969747799e+01, 2.067052865969747799e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.478000000000000000e+03, 2.084970324432458000e+00, 3.474205024141280518e+01, 3.474205024141280518e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.709000000000000000e+03, 2.117433448519553174e+00, 3.850984284000819002e+02, 3.850984284000819002e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 9.850000000000000000e+02, 2.149896572606648348e+00, 1.745201679755395929e+01, 1.745201679755395929e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 6.770000000000000000e+02, 2.182359696693742634e+00, 7.248266583294785903e+01, 7.248266583294785903e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 9.700000000000000000e+02, 2.214822820780836921e+00, 2.100845063019892223e+01, 2.100845063019892223e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 6.970000000000000000e+02, 2.247285944867932095e+00, 6.212605566246924838e+01, 6.212605566246924838e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 4.140000000000000000e+02, 2.279749068955027269e+00, 5.887400716549861954e+02, 5.887400716549861954e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.595000000000000000e+03, 2.312212193042121555e+00, 4.351672483384577959e+02, 4.351672483384577959e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 6.090000000000000000e+02, 2.344675317129215841e+00, 2.565082383303915208e+02, 2.565082383303915208e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 8.410000000000000000e+02, 2.377138441216311016e+00, 1.686447218385916003e+01, 1.686447218385916003e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 8.970000000000000000e+02, 2.409601565303406190e+00, 2.386698143551999607e+01, 2.386698143551999607e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 5.730000000000000000e+02, 2.442064689390500476e+00, 2.000911437320502728e+03, 2.000911437320502728e+03, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.411000000000000000e+03, 2.474527813477594762e+00, 1.389475296344355684e+02, 1.389475296344355684e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.284000000000000000e+03, 2.506990937564689936e+00, 2.222670265943896482e+02, 2.222670265943896482e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.005000000000000000e+03, 2.539454061651785111e+00, 3.448276077586199904e+02, 3.448276077586199904e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 7.400000000000000000e+02, 2.571917185738879397e+00, 2.703159420870034637e+02, 2.703159420870034637e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 9.250000000000000000e+02, 2.604380309825973683e+00, 5.882435661183085358e+02, 5.882435661183085358e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.803000000000000000e+03, 2.636843433913068857e+00, 2.131086649536240429e+02, 2.131086649536240429e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 3.760000000000000000e+02, 2.669306558000164031e+00, 7.583128535363117351e+01, 7.583128535363117351e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 5.500000000000000000e+01, 2.701769682087258317e+00, 2.456446264413684233e+01, 2.456446264413684233e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 5.480000000000000000e+02, 2.734232806174352604e+00, 2.585298784570261432e+01, 2.585298784570261432e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 6.330000000000000000e+02, 2.766695930261447778e+00, 1.695485874284847796e+02, 1.695485874284847796e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.685000000000000000e+03, 2.799159054348542952e+00, 3.575615625957554471e+02, 3.575615625957554471e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.172000000000000000e+03, 2.831622178435637238e+00, 4.000295829060646042e+02, 4.000295829060646042e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 2.460000000000000000e+02, 2.864085302522731524e+00, 2.945353768824623444e+02, 2.945353768824623444e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.405000000000000000e+03, 2.896548426609826699e+00, 5.782716638490356331e+01, 5.782716638490356331e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 5.470000000000000000e+02, 2.929011550696921873e+00, 2.501282227428564227e+02, 2.501282227428564227e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.347000000000000000e+03, 2.961474674784016159e+00, 1.754913995098878559e+02, 1.754913995098878559e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 3.070000000000000000e+02, 2.993937798871110445e+00, 2.002399805233710310e+02, 2.002399805233710310e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 3.600000000000000000e+02, 3.026400922958205619e+00, 2.148119047742885712e+01, 2.148119047742885712e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.314000000000000000e+03, 3.058864047045300794e+00, 1.754818350226009898e+02, 1.754818350226009898e+02, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 8.610000000000000000e+02, 3.091327171132395080e+00, 4.854603404531508204e+01, 4.854603404531508204e+01, 0}, + {3.270694516059187151e+01, -9.638379328402535862e+01, 1.777000000000000000e+03, 3.123790295219489366e+00, 4.552309932675992172e+02, 4.552309932675992172e+02, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 6.920000000000000000e+02, -3.141592653589793116e+00, 4.093765015239638672e+01, 4.093765015239638672e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 7.060000000000000000e+02, -3.109129529502698386e+00, 2.279867050058813849e+00, 2.279867050058813849e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 8.100000000000000000e+02, -3.076666405415603656e+00, 1.990107767532066640e+00, 1.990107767532066640e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.541000000000000000e+03, -3.044203281328508925e+00, 1.811629304979436528e+00, 1.811629304979436528e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.237000000000000000e+03, -3.011740157241414195e+00, 4.023591342195386389e+00, 4.023591342195386389e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 3.210000000000000000e+02, -2.979277033154319465e+00, 2.919179698271986112e+01, 2.919179698271986112e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.666000000000000000e+03, -2.946813909067224735e+00, 3.251001974904114178e+01, 3.251001974904114178e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.961000000000000000e+03, -2.914350784980130005e+00, 5.812658067138765539e+00, 5.812658067138765539e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 2.800000000000000000e+02, -2.881887660893035275e+00, 2.550320025291915815e+00, 2.550320025291915815e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 2.120000000000000000e+02, -2.849424536805940544e+00, 1.257976362432376582e+01, 1.257976362432376582e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.072000000000000000e+03, -2.816961412718845814e+00, 4.353457222950570582e+01, 4.353457222950570582e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 8.540000000000000000e+02, -2.784498288631751084e+00, 1.971205639306483093e+01, 1.971205639306483093e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 6.600000000000000000e+01, -2.752035164544656354e+00, 2.996016104763123522e+01, 2.996016104763123522e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 8.100000000000000000e+02, -2.719572040457561624e+00, 7.761420293375060453e+01, 7.761420293375060453e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 6.730000000000000000e+02, -2.687108916370466893e+00, 1.710640312215802226e+02, 1.710640312215802226e+02, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 9.490000000000000000e+02, -2.654645792283372163e+00, 8.338750322706900420e+01, 8.338750322706900420e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.670000000000000000e+03, -2.622182668196277433e+00, 9.298728474709909264e+00, 9.298728474709909264e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.405000000000000000e+03, -2.589719544109182703e+00, 1.763047963394510731e+01, 1.763047963394510731e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 9.590000000000000000e+02, -2.557256420022087973e+00, 7.695539705631226468e+01, 7.695539705631226468e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 8.320000000000000000e+02, -2.524793295934993242e+00, 1.007031280546935221e+02, 1.007031280546935221e+02, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.116000000000000000e+03, -2.492330171847898512e+00, 1.045164959069460409e+01, 1.045164959069460409e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.958000000000000000e+03, -2.459867047760803782e+00, 2.057652260763802143e+00, 2.057652260763802143e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.010000000000000000e+02, -2.427403923673709052e+00, 2.418260137122452491e+01, 2.418260137122452491e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 6.760000000000000000e+02, -2.394940799586614322e+00, 3.419694593251144283e+02, 3.419694593251144283e+02, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.621000000000000000e+03, -2.362477675499519592e+00, 3.017025470725188896e+00, 3.017025470725188896e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 5.270000000000000000e+02, -2.330014551412424861e+00, 3.234508762454854303e+00, 3.234508762454854303e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 4.990000000000000000e+02, -2.297551427325330131e+00, 5.226089081314129636e+00, 5.226089081314129636e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.820000000000000000e+02, -2.265088303238235401e+00, 3.969870942071258124e+00, 3.969870942071258124e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.369000000000000000e+03, -2.232625179151140671e+00, 4.697635461125079459e+00, 4.697635461125079459e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.474000000000000000e+03, -2.200162055064045941e+00, 4.837955767548259622e+00, 4.837955767548259622e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.478000000000000000e+03, -2.167698930976951210e+00, 3.198717029311723437e+01, 3.198717029311723437e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.443000000000000000e+03, -2.135235806889856480e+00, 2.095828714375294410e+01, 2.095828714375294410e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.628000000000000000e+03, -2.102772682802761750e+00, 4.376650774279346123e+00, 4.376650774279346123e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.601000000000000000e+03, -2.070309558715667020e+00, 6.003063074545832656e+00, 6.003063074545832656e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.777000000000000000e+03, -2.037846434628572290e+00, 2.710196602084390172e+00, 2.710196602084390172e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.968000000000000000e+03, -2.005383310541477559e+00, 2.053935201819193068e+01, 2.053935201819193068e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 8.700000000000000000e+01, -1.972920186454382829e+00, 3.889828661096453644e+00, 3.889828661096453644e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.418000000000000000e+03, -1.940457062367288099e+00, 1.042766512695915026e+03, 1.042766512695915026e+03, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 7.610000000000000000e+02, -1.907993938280193369e+00, 2.535449294503836271e+01, 2.535449294503836271e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.532000000000000000e+03, -1.875530814193098639e+00, 2.395550783531023686e+00, 2.395550783531023686e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.970000000000000000e+03, -1.843067690106003909e+00, 2.755957109023444040e+00, 2.755957109023444040e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 2.690000000000000000e+02, -1.810604566018909178e+00, 2.251382242090400894e+02, 2.251382242090400894e+02, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 4.580000000000000000e+02, -1.778141441931814448e+00, 2.020614656104831042e+00, 2.020614656104831042e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 7.360000000000000000e+02, -1.745678317844719718e+00, 1.048736897733385831e+01, 1.048736897733385831e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 7.510000000000000000e+02, -1.713215193757624988e+00, 1.819680910108098404e+00, 1.819680910108098404e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.675000000000000000e+03, -1.680752069670530258e+00, 2.185536510076953487e+00, 2.185536510076953487e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.520000000000000000e+03, -1.648288945583435527e+00, 2.048957015671877357e+01, 2.048957015671877357e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.070000000000000000e+03, -1.615825821496340797e+00, 4.353148915674903918e+01, 4.353148915674903918e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.374000000000000000e+03, -1.583362697409246067e+00, 2.110975661252161473e+01, 2.110975661252161473e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.581000000000000000e+03, -1.550899573322151337e+00, 2.219920988906162851e+00, 2.219920988906162851e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 8.030000000000000000e+02, -1.518436449235056607e+00, 2.969575395183907673e+01, 2.969575395183907673e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 4.500000000000000000e+02, -1.485973325147961877e+00, 1.490226648185759117e+01, 1.490226648185759117e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 8.170000000000000000e+02, -1.453510201060867146e+00, 1.709046598481978663e+01, 1.709046598481978663e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.692000000000000000e+03, -1.421047076973772416e+00, 3.373629708558471663e+01, 3.373629708558471663e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.481000000000000000e+03, -1.388583952886677686e+00, 7.544698435974490280e+01, 7.544698435974490280e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 8.800000000000000000e+02, -1.356120828799582956e+00, 1.433705061747929221e+02, 1.433705061747929221e+02, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.557000000000000000e+03, -1.323657704712488226e+00, 2.234443210169465566e+00, 2.234443210169465566e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 9.000000000000000000e+02, -1.291194580625393495e+00, 2.680472948631473784e+00, 2.680472948631473784e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.748000000000000000e+03, -1.258731456538298765e+00, 2.630840100088494182e+01, 2.630840100088494182e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.161000000000000000e+03, -1.226268332451204035e+00, 6.290371175952179073e+01, 6.290371175952179073e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.354000000000000000e+03, -1.193805208364109305e+00, 4.123412179251547371e+01, 4.123412179251547371e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.301000000000000000e+03, -1.161342084277014575e+00, 2.588352870386408267e+00, 2.588352870386408267e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 8.730000000000000000e+02, -1.128878960189919844e+00, 5.577911961644056760e+01, 5.577911961644056760e+01, 1}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 9.280000000000000000e+02, -1.096415836102825114e+00, 2.860843317938946129e+01, 2.860843317938946129e+01, 1}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.034000000000000000e+03, -1.063952712015730384e+00, 5.001444791257822544e+02, 5.001444791257822544e+02, 1}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.606000000000000000e+03, -1.031489587928635654e+00, 4.945191336578585606e+01, 4.945191336578585606e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.343000000000000000e+03, -9.990264638415409237e-01, 5.119363096895791720e+00, 5.119363096895791720e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.359000000000000000e+03, -9.665633397544461936e-01, 1.813211349348813783e+00, 1.813211349348813783e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 7.440000000000000000e+02, -9.341002156673514634e-01, 1.801865136999160066e+00, 1.801865136999160066e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 2.660000000000000000e+02, -9.016370915802567332e-01, 2.728006695607728460e+00, 2.728006695607728460e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.829000000000000000e+03, -8.691739674931620030e-01, 3.311847009184587876e+01, 3.311847009184587876e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.430000000000000000e+02, -8.367108434060672728e-01, 5.846418775626666502e+02, 5.846418775626666502e+02, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 9.930000000000000000e+02, -8.042477193189725426e-01, 6.250076562031060945e+01, 6.250076562031060945e+01, 1}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.011000000000000000e+03, -7.717845952318778124e-01, 3.496609264134554529e+00, 3.496609264134554529e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.290000000000000000e+03, -7.393214711447830823e-01, 3.357922707563754994e+00, 3.357922707563754994e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 9.390000000000000000e+02, -7.068583470576883521e-01, 2.327743762138382166e+01, 2.327743762138382166e+01, 1}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.845000000000000000e+03, -6.743952229705936219e-01, 1.213446661159511564e+01, 1.213446661159511564e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.241000000000000000e+03, -6.419320988834988917e-01, 3.497987360854011740e+00, 3.497987360854011740e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.860000000000000000e+02, -6.094689747964041615e-01, 3.884912042426451606e+00, 3.884912042426451606e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.817000000000000000e+03, -5.770058507093094313e-01, 2.309757130089655277e+02, 2.309757130089655277e+02, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 5.370000000000000000e+02, -5.445427266222147011e-01, 3.897142036080121130e+01, 3.897142036080121130e+01, 1}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.429000000000000000e+03, -5.120796025351199710e-01, 3.870362395880496820e+01, 3.870362395880496820e+01, 1}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 6.820000000000000000e+02, -4.796164784480252408e-01, 1.863580486967213901e+01, 1.863580486967213901e+01, 1}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.327000000000000000e+03, -4.471533543609305106e-01, 2.125019021386089779e+00, 2.125019021386089779e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.810000000000000000e+03, -4.146902302738357804e-01, 2.237690324531151465e+00, 2.237690324531151465e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 6.930000000000000000e+02, -3.822271061867410502e-01, 1.824048153878497169e+00, 1.824048153878497169e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.035000000000000000e+03, -3.497639820996463200e-01, 1.389314170999756470e+01, 1.389314170999756470e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.400000000000000000e+02, -3.173008580125515898e-01, 6.649912228340166820e+00, 6.649912228340166820e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.819000000000000000e+03, -2.848377339254568597e-01, 5.450880412980172451e+00, 5.450880412980172451e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 9.020000000000000000e+02, -2.523746098383621295e-01, 5.275779602628645648e+00, 5.275779602628645648e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.052000000000000000e+03, -2.199114857512673993e-01, 7.096991288413670773e+00, 7.096991288413670773e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.589000000000000000e+03, -1.874483616641726691e-01, 2.256799621421892965e+01, 2.256799621421892965e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 4.230000000000000000e+02, -1.549852375770779389e-01, 6.171599203990313143e+00, 6.171599203990313143e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 5.350000000000000000e+02, -1.225221134899832087e-01, 3.629893883794674991e+01, 3.629893883794674991e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 9.110000000000000000e+02, -9.005898940288847854e-02, 2.830447155870200238e+00, 2.830447155870200238e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.560000000000000000e+02, -5.759586531579374835e-02, 2.068465832277463612e+00, 2.068465832277463612e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 5.150000000000000000e+02, -2.513274122869901817e-02, 1.874418324340918929e+00, 1.874418324340918929e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.191000000000000000e+03, 7.330382858395712020e-03, 2.419853802294197553e+00, 2.419853802294197553e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.165000000000000000e+03, 3.979350694549044221e-02, 1.753977776658123489e+00, 1.753977776658123489e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 7.810000000000000000e+02, 7.225663103258517239e-02, 2.462090550226922137e+00, 2.462090550226922137e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.700000000000000000e+03, 1.047197551196799026e-01, 1.865879063914832825e+00, 1.865879063914832825e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.867000000000000000e+03, 1.371828792067746328e-01, 7.331024879322808374e+01, 7.331024879322808374e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.180000000000000000e+02, 1.696460032938693629e-01, 3.801749419312437794e+01, 3.801749419312437794e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 2.220000000000000000e+02, 2.021091273809640931e-01, 8.779487928348876835e+01, 8.779487928348876835e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 6.600000000000000000e+02, 2.345722514680588233e-01, 3.174364335518786273e+00, 3.174364335518786273e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.657000000000000000e+03, 2.670353755551535535e-01, 2.494670410904126001e+00, 2.494670410904126001e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.026000000000000000e+03, 2.994984996422482837e-01, 1.786016045931987506e+01, 1.786016045931987506e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.535000000000000000e+03, 3.319616237293430139e-01, 3.686773770160361607e+01, 3.686773770160361607e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 6.000000000000000000e+02, 3.644247478164377441e-01, 4.723774929733301065e+01, 4.723774929733301065e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.279000000000000000e+03, 3.968878719035324742e-01, 2.682301307591886186e+01, 2.682301307591886186e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 4.990000000000000000e+02, 4.293509959906272044e-01, 3.929244753728772110e+01, 3.929244753728772110e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.399000000000000000e+03, 4.618141200777219346e-01, 2.808211506043211614e+01, 2.808211506043211614e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.693000000000000000e+03, 4.942772441648166648e-01, 2.320018277735712076e+01, 2.320018277735712076e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.040000000000000000e+03, 5.267403682519113950e-01, 6.669332800213227586e+01, 6.669332800213227586e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 4.340000000000000000e+02, 5.592034923390061252e-01, 9.617103506094689891e+00, 9.617103506094689891e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 3.600000000000000000e+02, 5.916666164261008554e-01, 3.658779395736598303e+02, 3.658779395736598303e+02, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.489000000000000000e+03, 6.241297405131955855e-01, 2.791801740947291499e+00, 2.791801740947291499e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 6.990000000000000000e+02, 6.565928646002903157e-01, 2.004704674122806285e+00, 2.004704674122806285e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 5.730000000000000000e+02, 6.890559886873850459e-01, 2.611470490930349087e+01, 2.611470490930349087e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.027000000000000000e+03, 7.215191127744797761e-01, 8.404892717609200758e+00, 8.404892717609200758e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 3.280000000000000000e+02, 7.539822368615745063e-01, 1.876533749791125416e+01, 1.876533749791125416e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.935000000000000000e+03, 7.864453609486692365e-01, 3.163050847666153853e+00, 3.163050847666153853e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.682000000000000000e+03, 8.189084850357639667e-01, 3.066873172937052860e+00, 3.066873172937052860e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 2.020000000000000000e+02, 8.513716091228586968e-01, 2.609583814701189297e+01, 2.609583814701189297e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 8.410000000000000000e+02, 8.838347332099534270e-01, 2.053674290743660080e+01, 2.053674290743660080e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.164000000000000000e+03, 9.162978572970477131e-01, 5.687579348303133386e+00, 5.687579348303133386e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.163000000000000000e+03, 9.487609813841428874e-01, 2.013240671156829364e+00, 2.013240671156829364e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.197000000000000000e+03, 9.812241054712380617e-01, 6.350035436242318809e+00, 6.350035436242318809e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 3.410000000000000000e+02, 1.013687229558332348e+00, 1.576058439297741529e+02, 1.576058439297741529e+02, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.550000000000000000e+03, 1.046150353645426634e+00, 6.311548157022039618e+01, 6.311548157022039618e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.405000000000000000e+03, 1.078613477732521808e+00, 3.586890684147453268e+00, 3.586890684147453268e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 3.860000000000000000e+02, 1.111076601819616982e+00, 8.386019642463698176e+01, 8.386019642463698176e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 2.140000000000000000e+02, 1.143539725906711269e+00, 5.526912086979907990e+00, 5.526912086979907990e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 9.990000000000000000e+02, 1.176002849993805555e+00, 4.081633673469260870e+00, 4.081633673469260870e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 5.250000000000000000e+02, 1.208465974080900729e+00, 1.990376008098315097e+01, 1.990376008098315097e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.715000000000000000e+03, 1.240929098167995903e+00, 2.118225262575640144e+00, 2.118225262575640144e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 6.000000000000000000e+01, 1.273392222255090189e+00, 1.500937207214212492e+02, 1.500937207214212492e+02, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.656000000000000000e+03, 1.305855346342184475e+00, 1.030230456042870912e+01, 1.030230456042870912e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 6.500000000000000000e+02, 1.338318470429279650e+00, 2.128450183681457997e+00, 2.128450183681457997e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 4.200000000000000000e+01, 1.370781594516374824e+00, 4.473488433586488355e+01, 4.473488433586488355e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 9.660000000000000000e+02, 1.403244718603469110e+00, 1.852386959725119553e+01, 1.852386959725119553e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 5.580000000000000000e+02, 1.435707842690563396e+00, 4.635854877202032931e+00, 4.635854877202032931e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.010000000000000000e+02, 1.468170966777658570e+00, 2.060778203808698361e+00, 2.060778203808698361e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 9.120000000000000000e+02, 1.500634090864753745e+00, 3.036164029004244469e+01, 3.036164029004244469e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 4.800000000000000000e+01, 1.533097214951848031e+00, 3.013668860376003522e+01, 3.013668860376003522e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 3.560000000000000000e+02, 1.565560339038942317e+00, 2.719809368986564557e+00, 2.719809368986564557e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.400000000000000000e+03, 1.598023463126037491e+00, 1.039230484541326263e+02, 1.039230484541326263e+02, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 4.680000000000000000e+02, 1.630486587213132665e+00, 4.625175971665958841e+00, 4.625175971665958841e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.889000000000000000e+03, 1.662949711300226951e+00, 3.937230414051651337e+02, 3.937230414051651337e+02, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 8.130000000000000000e+02, 1.695412835387321238e+00, 3.722156335784448711e+00, 3.722156335784448711e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 4.220000000000000000e+02, 1.727875959474416412e+00, 8.309978317960306526e+01, 8.309978317960306526e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 3.450000000000000000e+02, 1.760339083561511586e+00, 3.813319126559205685e+00, 3.813319126559205685e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 2.670000000000000000e+02, 1.792802207648605872e+00, 5.119732729658892367e+00, 5.119732729658892367e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 6.100000000000000000e+01, 1.825265331735700158e+00, 7.060932283054579273e+01, 7.060932283054579273e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 3.940000000000000000e+02, 1.857728455822795333e+00, 5.726011021301520998e+01, 5.726011021301520998e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.228000000000000000e+03, 1.890191579909890507e+00, 1.761587186031011720e+00, 1.761587186031011720e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 2.010000000000000000e+02, 1.922654703996984793e+00, 5.860023157611817801e+00, 5.860023157611817801e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.018000000000000000e+03, 1.955117828084079079e+00, 4.762290460570312689e+01, 4.762290460570312689e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.052000000000000000e+03, 1.987580952171174253e+00, 2.042195452380260434e+01, 2.042195452380260434e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.988000000000000000e+03, 2.020044076258269428e+00, 5.303763332016389143e+01, 5.303763332016389143e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.652000000000000000e+03, 2.052507200345363714e+00, 7.197120189593371187e+00, 7.197120189593371187e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 7.240000000000000000e+02, 2.084970324432458000e+00, 5.993329625508680181e+01, 5.993329625508680181e+01, 1}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 3.730000000000000000e+02, 2.117433448519553174e+00, 3.125359734396627331e+01, 3.125359734396627331e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.524000000000000000e+03, 2.149896572606648348e+00, 2.734453996463849990e+01, 2.734453996463849990e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 2.600000000000000000e+01, 2.182359696693742634e+00, 2.321650494216593863e+00, 2.321650494216593863e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 2.330000000000000000e+02, 2.214822820780836921e+00, 6.391037755361468342e+00, 6.391037755361468342e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 2.530000000000000000e+02, 2.247285944867932095e+00, 5.140594596923332205e+01, 5.140594596923332205e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 7.200000000000000000e+02, 2.279749068955027269e+00, 2.080431826510148241e+01, 2.080431826510148241e+01, 1}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 4.100000000000000000e+01, 2.312212193042121555e+00, 1.108475774300120520e+01, 1.108475774300120520e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.855000000000000000e+03, 2.344675317129215841e+00, 2.148072525227568530e+00, 2.148072525227568530e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 7.640000000000000000e+02, 2.377138441216311016e+00, 8.310068752826285987e+00, 8.310068752826285987e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.100000000000000000e+02, 2.409601565303406190e+00, 4.544406145904535066e+01, 4.544406145904535066e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.625000000000000000e+03, 2.442064689390500476e+00, 1.853056746243209929e+01, 1.853056746243209929e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.575000000000000000e+03, 2.474527813477594762e+00, 2.840780027287382836e+01, 2.840780027287382836e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 3.620000000000000000e+02, 2.506990937564689936e+00, 4.388206011572383147e+01, 4.388206011572383147e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 9.760000000000000000e+02, 2.539454061651785111e+00, 2.415806738245151575e+00, 2.415806738245151575e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.473000000000000000e+03, 2.571917185738879397e+00, 4.009315043955446356e+00, 4.009315043955446356e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.547000000000000000e+03, 2.604380309825973683e+00, 5.360980553965850959e+02, 5.360980553965850959e+02, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.144000000000000000e+03, 2.636843433913068857e+00, 3.709116724283793243e+00, 3.709116724283793243e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.629000000000000000e+03, 2.669306558000164031e+00, 4.541285733621258203e+00, 4.541285733621258203e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 7.700000000000000000e+01, 2.701769682087258317e+00, 2.388275109781115475e+02, 2.388275109781115475e+02, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.108000000000000000e+03, 2.734232806174352604e+00, 1.790913858615090248e+01, 1.790913858615090248e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 7.270000000000000000e+02, 2.766695930261447778e+00, 2.860847838227458695e+00, 2.860847838227458695e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.300000000000000000e+02, 2.799159054348542952e+00, 6.786555510306898853e+00, 6.786555510306898853e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.509000000000000000e+03, 2.831622178435637238e+00, 5.313992143388997391e+00, 5.313992143388997391e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.761000000000000000e+03, 2.864085302522731524e+00, 6.105312761242544184e+00, 6.105312761242544184e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.406000000000000000e+03, 2.896548426609826699e+00, 3.096408318163015760e+00, 3.096408318163015760e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 3.560000000000000000e+02, 2.929011550696921873e+00, 1.098802985070572049e+03, 1.098802985070572049e+03, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 7.160000000000000000e+02, 2.961474674784016159e+00, 7.444997848698590381e+00, 7.444997848698590381e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.904000000000000000e+03, 2.993937798871110445e+00, 4.945199692631229027e+01, 4.945199692631229027e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 2.830000000000000000e+02, 3.026400922958205619e+00, 1.933068894471402288e+01, 1.933068894471402288e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.284000000000000000e+03, 3.058864047045300794e+00, 1.821365545128048069e+01, 1.821365545128048069e+01, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.517000000000000000e+03, 3.091327171132395080e+00, 2.177356707379768164e+00, 2.177356707379768164e+00, 0}, + {3.260801978394081146e+01, -9.647988692840254998e+01, 1.977000000000000000e+03, 3.123790295219489366e+00, 1.279397581577029719e+01, 1.279397581577029719e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.379000000000000000e+03, -3.141592653589793116e+00, 1.284877303673869164e+01, 1.284877303673869164e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 9.000000000000000000e+01, -3.109129529502698386e+00, 4.397296313288872227e+01, 4.397296313288872227e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 5.980000000000000000e+02, -3.076666405415603656e+00, 1.564347200620875071e+02, 1.564347200620875071e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 3.750000000000000000e+02, -3.044203281328508925e+00, 1.624717891524807669e+02, 1.624717891524807669e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 5.200000000000000000e+01, -3.011740157241414195e+00, 1.040237774789578253e+02, 1.040237774789578253e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.197000000000000000e+03, -2.979277033154319465e+00, 2.157064252746354782e+02, 2.157064252746354782e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.723000000000000000e+03, -2.946813909067224735e+00, 1.195922318832877806e+01, 1.195922318832877806e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 9.120000000000000000e+02, -2.914350784980130005e+00, 8.511504022084482202e+00, 8.511504022084482202e+00, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 8.910000000000000000e+02, -2.881887660893035275e+00, 1.465484964411295010e+01, 1.465484964411295010e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.387000000000000000e+03, -2.849424536805940544e+00, 2.492282769464704373e+01, 2.492282769464704373e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.531000000000000000e+03, -2.816961412718845814e+00, 8.186008262383587919e+00, 8.186008262383587919e+00, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 3.000000000000000000e+01, -2.784498288631751084e+00, 3.577617492665771692e+01, 3.577617492665771692e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 6.800000000000000000e+01, -2.752035164544656354e+00, 1.200893158287650841e+01, 1.200893158287650841e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 4.540000000000000000e+02, -2.719572040457561624e+00, 1.340449397589941860e+01, 1.340449397589941860e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 8.900000000000000000e+01, -2.687108916370466893e+00, 1.018549601861356280e+01, 1.018549601861356280e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.152000000000000000e+03, -2.654645792283372163e+00, 1.006437354308825434e+02, 1.006437354308825434e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 4.480000000000000000e+02, -2.622182668196277433e+00, 7.574143149191494331e+02, 7.574143149191494331e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.813000000000000000e+03, -2.589719544109182703e+00, 1.901684400479684882e+02, 1.901684400479684882e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.113000000000000000e+03, -2.557256420022087973e+00, 2.998938784278445269e+01, 2.998938784278445269e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 3.640000000000000000e+02, -2.524793295934993242e+00, 5.290665473962832976e+01, 5.290665473962832976e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.683000000000000000e+03, -2.492330171847898512e+00, 1.731322153265116626e+01, 1.731322153265116626e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.405000000000000000e+03, -2.459867047760803782e+00, 5.214644016699610063e+01, 5.214644016699610063e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 5.730000000000000000e+02, -2.427403923673709052e+00, 9.223066740146604658e+00, 9.223066740146604658e+00, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.876000000000000000e+03, -2.394940799586614322e+00, 8.017311217784883581e+01, 8.017311217784883581e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 9.900000000000000000e+02, -2.362477675499519592e+00, 1.104316607473571992e+02, 1.104316607473571992e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.496000000000000000e+03, -2.330014551412424861e+00, 1.138159452097388780e+01, 1.138159452097388780e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 8.740000000000000000e+02, -2.297551427325330131e+00, 1.600201091759516814e+01, 1.600201091759516814e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.884000000000000000e+03, -2.265088303238235401e+00, 4.570637592284034412e+01, 4.570637592284034412e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.385000000000000000e+03, -2.232625179151140671e+00, 8.217154966983267528e+00, 8.217154966983267528e+00, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 2.030000000000000000e+02, -2.200162055064045941e+00, 2.668205446303411321e+01, 2.668205446303411321e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 4.300000000000000000e+01, -2.167698930976951210e+00, 1.907492741539998065e+02, 1.907492741539998065e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.873000000000000000e+03, -2.135235806889856480e+00, 8.995236893271545853e+00, 8.995236893271545853e+00, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 9.240000000000000000e+02, -2.102772682802761750e+00, 1.115273764552802227e+01, 1.115273764552802227e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.513000000000000000e+03, -2.070309558715667020e+00, 1.582648224002944559e+01, 1.582648224002944559e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 9.820000000000000000e+02, -2.037846434628572290e+00, 1.561279468600203124e+01, 1.561279468600203124e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 4.500000000000000000e+01, -2.005383310541477559e+00, 1.237236148465948418e+02, 1.237236148465948418e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.612000000000000000e+03, -1.972920186454382829e+00, 1.082934829897436089e+02, 1.082934829897436089e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.600000000000000000e+02, -1.940457062367288099e+00, 1.630888076591201070e+02, 1.630888076591201070e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.491000000000000000e+03, -1.907993938280193369e+00, 6.487120756875557390e+02, 6.487120756875557390e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 7.500000000000000000e+01, -1.875530814193098639e+00, 7.624487687707285204e+02, 7.624487687707285204e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 4.870000000000000000e+02, -1.843067690106003909e+00, 8.906275299781276544e+01, 8.906275299781276544e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.610000000000000000e+02, -1.810604566018909178e+00, 1.522131564615884372e+03, 1.522131564615884372e+03, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 7.000000000000000000e+01, -1.778141441931814448e+00, 9.571546964862704954e+00, 9.571546964862704954e+00, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 8.620000000000000000e+02, -1.745678317844719718e+00, 2.830464984989215793e+01, 2.830464984989215793e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 5.490000000000000000e+02, -1.713215193757624988e+00, 4.538909615755748632e+02, 4.538909615755748632e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 5.510000000000000000e+02, -1.680752069670530258e+00, 4.126191338108024524e+02, 4.126191338108024524e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.415000000000000000e+03, -1.648288945583435527e+00, 1.512397379438794587e+03, 1.512397379438794587e+03, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.553000000000000000e+03, -1.615825821496340797e+00, 1.076906795512445747e+01, 1.076906795512445747e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 4.460000000000000000e+02, -1.583362697409246067e+00, 8.043553227995696275e+00, 8.043553227995696275e+00, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.289000000000000000e+03, -1.550899573322151337e+00, 2.060137226633697480e+02, 2.060137226633697480e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.415000000000000000e+03, -1.518436449235056607e+00, 9.863461170253009413e+01, 9.863461170253009413e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.242000000000000000e+03, -1.485973325147961877e+00, 1.018185409237875838e+01, 1.018185409237875838e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.347000000000000000e+03, -1.453510201060867146e+00, 8.304644999480910172e+00, 8.304644999480910172e+00, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 8.470000000000000000e+02, -1.421047076973772416e+00, 1.176359722187831558e+01, 1.176359722187831558e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 5.820000000000000000e+02, -1.388583952886677686e+00, 1.334508773976428131e+02, 1.334508773976428131e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 8.500000000000000000e+01, -1.356120828799582956e+00, 2.407203668447072289e+02, 2.407203668447072289e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.665000000000000000e+03, -1.323657704712488226e+00, 2.167640414364521746e+02, 2.167640414364521746e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 4.270000000000000000e+02, -1.291194580625393495e+00, 8.265064283071595241e+01, 8.265064283071595241e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.473000000000000000e+03, -1.258731456538298765e+00, 1.405581773951236890e+01, 1.405581773951236890e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.521000000000000000e+03, -1.226268332451204035e+00, 8.475103854510077639e+00, 8.475103854510077639e+00, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.822000000000000000e+03, -1.193805208364109305e+00, 1.472531780272531421e+02, 1.472531780272531421e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.000000000000000000e+01, -1.161342084277014575e+00, 1.174741008288592070e+02, 1.174741008288592070e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.881000000000000000e+03, -1.128878960189919844e+00, 1.384953928085735981e+02, 1.384953928085735981e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.600000000000000000e+03, -1.096415836102825114e+00, 2.262451144458124119e+01, 2.262451144458124119e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 3.640000000000000000e+02, -1.063952712015730384e+00, 1.338227149296481286e+02, 1.338227149296481286e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 5.980000000000000000e+02, -1.031489587928635654e+00, 2.716531066946430073e+01, 2.716531066946430073e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 4.500000000000000000e+01, -9.990264638415409237e-01, 8.477358795044462170e+01, 8.477358795044462170e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.958000000000000000e+03, -9.665633397544461936e-01, 6.540124507333830479e+02, 6.540124507333830479e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 9.700000000000000000e+01, -9.341002156673514634e-01, 4.618681152693471859e+01, 4.618681152693471859e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 7.170000000000000000e+02, -9.016370915802567332e-01, 7.868251018858986257e+00, 7.868251018858986257e+00, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 7.720000000000000000e+02, -8.691739674931620030e-01, 1.006791554676488687e+02, 1.006791554676488687e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.130000000000000000e+03, -8.367108434060672728e-01, 3.019083746216170425e+02, 3.019083746216170425e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 7.300000000000000000e+02, -8.042477193189725426e-01, 1.016079822986465331e+01, 1.016079822986465331e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.918000000000000000e+03, -7.717845952318778124e-01, 4.235173646521067781e+01, 4.235173646521067781e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.235000000000000000e+03, -7.393214711447830823e-01, 1.742592628254618035e+02, 1.742592628254618035e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.926000000000000000e+03, -7.068583470576883521e-01, 7.624656276405733024e+02, 7.624656276405733024e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 7.200000000000000000e+02, -6.743952229705936219e-01, 4.443156291602089425e+01, 4.443156291602089425e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.602000000000000000e+03, -6.419320988834988917e-01, 9.095317916378733969e+01, 9.095317916378733969e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 6.040000000000000000e+02, -6.094689747964041615e-01, 2.268171510269891314e+03, 2.268171510269891314e+03, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.753000000000000000e+03, -5.770058507093094313e-01, 9.247247267520725345e+00, 9.247247267520725345e+00, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.947000000000000000e+03, -5.445427266222147011e-01, 1.695163963809262668e+02, 1.695163963809262668e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.492000000000000000e+03, -5.120796025351199710e-01, 1.034405158931766522e+01, 1.034405158931766522e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 3.910000000000000000e+02, -4.796164784480252408e-01, 1.511004964556329710e+01, 1.511004964556329710e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.773000000000000000e+03, -4.471533543609305106e-01, 1.088440631918192203e+01, 1.088440631918192203e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 7.100000000000000000e+01, -4.146902302738357804e-01, 4.867125391282629465e+01, 4.867125391282629465e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 5.240000000000000000e+02, -3.822271061867410502e-01, 4.127441726616085589e+02, 4.127441726616085589e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.308000000000000000e+03, -3.497639820996463200e-01, 2.385751332029922196e+02, 2.385751332029922196e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.724000000000000000e+03, -3.173008580125515898e-01, 9.113086853531025326e+02, 9.113086853531025326e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.574000000000000000e+03, -2.848377339254568597e-01, 3.010495652755515295e+01, 3.010495652755515295e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 4.590000000000000000e+02, -2.523746098383621295e-01, 1.406756791154432307e+01, 1.406756791154432307e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 3.890000000000000000e+02, -2.199114857512673993e-01, 1.374096393517372228e+01, 1.374096393517372228e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.844000000000000000e+03, -1.874483616641726691e-01, 2.836556132441012679e+01, 2.836556132441012679e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 9.290000000000000000e+02, -1.549852375770779389e-01, 1.796813850466294937e+01, 1.796813850466294937e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 2.000000000000000000e+01, -1.225221134899832087e-01, 8.642292129009932466e+01, 8.642292129009932466e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.155000000000000000e+03, -9.005898940288847854e-02, 9.224071147657507908e+00, 9.224071147657507908e+00, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.455000000000000000e+03, -5.759586531579374835e-02, 1.088515400186691551e+01, 1.088515400186691551e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 3.520000000000000000e+02, -2.513274122869901817e-02, 1.422130883568738113e+02, 1.422130883568738113e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.606000000000000000e+03, 7.330382858395712020e-03, 1.151373311799652477e+01, 1.151373311799652477e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 2.500000000000000000e+01, 3.979350694549044221e-02, 3.053254183835848039e+02, 3.053254183835848039e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 5.910000000000000000e+02, 7.225663103258517239e-02, 2.234935820177734556e+01, 2.234935820177734556e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.560000000000000000e+03, 1.047197551196799026e-01, 2.238904062786872018e+01, 2.238904062786872018e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 7.300000000000000000e+02, 1.371828792067746328e-01, 1.666072062691042532e+01, 1.666072062691042532e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 6.860000000000000000e+02, 1.696460032938693629e-01, 7.657319853770708562e+00, 7.657319853770708562e+00, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 2.220000000000000000e+02, 2.021091273809640931e-01, 3.145511268696746754e+01, 3.145511268696746754e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.215000000000000000e+03, 2.345722514680588233e-01, 1.562153171971035448e+01, 1.562153171971035448e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.358000000000000000e+03, 2.670353755551535535e-01, 5.668454650519839788e+02, 5.668454650519839788e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.994000000000000000e+03, 2.994984996422482837e-01, 3.272802113399065433e+02, 3.272802113399065433e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.126000000000000000e+03, 3.319616237293430139e-01, 2.156461471275920019e+02, 2.156461471275920019e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 4.830000000000000000e+02, 3.644247478164377441e-01, 1.138452922198017525e+01, 1.138452922198017525e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.058000000000000000e+03, 3.968878719035324742e-01, 4.116253010077879821e+02, 4.116253010077879821e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.185000000000000000e+03, 4.293509959906272044e-01, 1.294166266957461744e+02, 1.294166266957461744e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.705000000000000000e+03, 4.618141200777219346e-01, 1.938320643535812238e+01, 1.938320643535812238e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 2.990000000000000000e+02, 4.942772441648166648e-01, 1.138686208421793253e+02, 1.138686208421793253e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.986000000000000000e+03, 5.267403682519113950e-01, 2.411083479622049595e+02, 2.411083479622049595e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.827000000000000000e+03, 5.592034923390061252e-01, 8.864660281366893102e+00, 8.864660281366893102e+00, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 8.070000000000000000e+02, 5.916666164261008554e-01, 1.709339182677982905e+01, 1.709339182677982905e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.796000000000000000e+03, 6.241297405131955855e-01, 7.866455219284195266e+01, 7.866455219284195266e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 3.660000000000000000e+02, 6.565928646002903157e-01, 2.879640977328243778e+01, 2.879640977328243778e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.536000000000000000e+03, 6.890559886873850459e-01, 9.465683634406269675e+01, 9.465683634406269675e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.590000000000000000e+03, 7.215191127744797761e-01, 1.026382065811677613e+01, 1.026382065811677613e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 9.300000000000000000e+02, 7.539822368615745063e-01, 2.663507716602559867e+02, 2.663507716602559867e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 6.860000000000000000e+02, 7.864453609486692365e-01, 1.009606537512752666e+01, 1.009606537512752666e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.791000000000000000e+03, 8.189084850357639667e-01, 2.131826736514554810e+01, 2.131826736514554810e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 6.400000000000000000e+01, 8.513716091228586968e-01, 2.473411451305806352e+01, 2.473411451305806352e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.540000000000000000e+03, 8.838347332099534270e-01, 8.909343056293927532e+01, 8.909343056293927532e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.893000000000000000e+03, 9.162978572970477131e-01, 1.276958736630009561e+01, 1.276958736630009561e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 5.310000000000000000e+02, 9.487609813841428874e-01, 1.469197940927348611e+01, 1.469197940927348611e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.780000000000000000e+03, 9.812241054712380617e-01, 1.137446915864062191e+01, 1.137446915864062191e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 5.690000000000000000e+02, 1.013687229558332348e+00, 2.268968956376441838e+03, 2.268968956376441838e+03, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.770000000000000000e+03, 1.046150353645426634e+00, 1.291873226428558574e+01, 1.291873226428558574e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 9.360000000000000000e+02, 1.078613477732521808e+00, 1.509306242395271340e+02, 1.509306242395271340e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.385000000000000000e+03, 1.111076601819616982e+00, 9.882068718463537849e+00, 9.882068718463537849e+00, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.914000000000000000e+03, 1.143539725906711269e+00, 8.795359605594076413e+01, 8.795359605594076413e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 2.010000000000000000e+02, 1.176002849993805555e+00, 1.702539630187532538e+01, 1.702539630187532538e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.682000000000000000e+03, 1.208465974080900729e+00, 2.937614398773142455e+01, 2.937614398773142455e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 7.290000000000000000e+02, 1.240929098167995903e+00, 1.118949593982179991e+01, 1.118949593982179991e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.416000000000000000e+03, 1.273392222255090189e+00, 1.626250152801420867e+01, 1.626250152801420867e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 4.790000000000000000e+02, 1.305855346342184475e+00, 8.259373938213457222e+01, 8.259373938213457222e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 2.970000000000000000e+02, 1.338318470429279650e+00, 1.786234884733007178e+01, 1.786234884733007178e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.920000000000000000e+03, 1.370781594516374824e+00, 1.063764756421167448e+02, 1.063764756421167448e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 9.590000000000000000e+02, 1.403244718603469110e+00, 3.482911835242317125e+02, 3.482911835242317125e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.451000000000000000e+03, 1.435707842690563396e+00, 1.172844861952389905e+01, 1.172844861952389905e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 3.150000000000000000e+02, 1.468170966777658570e+00, 4.743257790395313123e+01, 4.743257790395313123e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 8.440000000000000000e+02, 1.500634090864753745e+00, 1.258065583483499807e+02, 1.258065583483499807e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.051000000000000000e+03, 1.533097214951848031e+00, 8.757903642148400891e+00, 8.757903642148400891e+00, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.074000000000000000e+03, 1.565560339038942317e+00, 9.240805960187449841e+01, 9.240805960187449841e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.301000000000000000e+03, 1.598023463126037491e+00, 8.552249833587131889e+01, 8.552249833587131889e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.087000000000000000e+03, 1.630486587213132665e+00, 8.354447376185456520e+00, 8.354447376185456520e+00, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 6.490000000000000000e+02, 1.662949711300226951e+00, 1.280929407807625964e+01, 1.280929407807625964e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 9.730000000000000000e+02, 1.695412835387321238e+00, 1.977175904445867971e+01, 1.977175904445867971e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 2.010000000000000000e+02, 1.727875959474416412e+00, 1.941619663362802939e+01, 1.941619663362802939e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.600000000000000000e+03, 1.760339083561511586e+00, 3.248233428829163927e+02, 3.248233428829163927e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.498000000000000000e+03, 1.792802207648605872e+00, 5.676707067041596702e+02, 5.676707067041596702e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.870000000000000000e+03, 1.825265331735700158e+00, 7.252848025759043082e+01, 7.252848025759043082e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.343000000000000000e+03, 1.857728455822795333e+00, 4.772825257835054913e+01, 4.772825257835054913e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.543000000000000000e+03, 1.890191579909890507e+00, 4.057092604143630155e+01, 4.057092604143630155e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 6.400000000000000000e+01, 1.922654703996984793e+00, 1.143952796228935398e+02, 1.143952796228935398e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.442000000000000000e+03, 1.955117828084079079e+00, 9.887727498409475402e+00, 9.887727498409475402e+00, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 4.750000000000000000e+02, 1.987580952171174253e+00, 1.016305575383969639e+01, 1.016305575383969639e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 8.480000000000000000e+02, 2.020044076258269428e+00, 5.032186771544126600e+02, 5.032186771544126600e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 6.000000000000000000e+02, 2.052507200345363714e+00, 4.124107717168638487e+01, 4.124107717168638487e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.687000000000000000e+03, 2.084970324432458000e+00, 1.751414664893030704e+02, 1.751414664893030704e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 9.410000000000000000e+02, 2.117433448519553174e+00, 7.957618226819549001e+00, 7.957618226819549001e+00, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 9.560000000000000000e+02, 2.149896572606648348e+00, 1.085803229142461390e+01, 1.085803229142461390e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.609000000000000000e+03, 2.182359696693742634e+00, 8.422453598730652402e+01, 8.422453598730652402e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 5.480000000000000000e+02, 2.214822820780836921e+00, 3.242113822927308888e+02, 3.242113822927308888e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 9.820000000000000000e+02, 2.247285944867932095e+00, 2.263855229470294717e+02, 2.263855229470294717e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.558000000000000000e+03, 2.279749068955027269e+00, 1.817940901129627207e+02, 1.817940901129627207e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.609000000000000000e+03, 2.312212193042121555e+00, 3.032083295543034751e+02, 3.032083295543034751e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.987000000000000000e+03, 2.344675317129215841e+00, 3.272261629740108333e+02, 3.272261629740108333e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.388000000000000000e+03, 2.377138441216311016e+00, 1.225945230945022644e+02, 1.225945230945022644e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.693000000000000000e+03, 2.409601565303406190e+00, 7.590221139363756038e+02, 7.590221139363756038e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.440000000000000000e+03, 2.442064689390500476e+00, 1.752266313263881514e+01, 1.752266313263881514e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.994000000000000000e+03, 2.474527813477594762e+00, 1.142624179241568783e+01, 1.142624179241568783e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 8.220000000000000000e+02, 2.506990937564689936e+00, 8.643972685971196057e+00, 8.643972685971196057e+00, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.770000000000000000e+02, 2.539454061651785111e+00, 9.316201241976685310e+01, 9.316201241976685310e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 3.840000000000000000e+02, 2.571917185738879397e+00, 9.888252754308076931e+01, 9.888252754308076931e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.540000000000000000e+03, 2.604380309825973683e+00, 7.807156286443132309e+00, 7.807156286443132309e+00, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 8.940000000000000000e+02, 2.636843433913068857e+00, 2.156339490896551467e+02, 2.156339490896551467e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 9.730000000000000000e+02, 2.669306558000164031e+00, 3.018488547454025479e+02, 3.018488547454025479e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.480000000000000000e+03, 2.701769682087258317e+00, 1.126649245275540423e+01, 1.126649245275540423e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 8.050000000000000000e+02, 2.734232806174352604e+00, 1.155559097417309289e+01, 1.155559097417309289e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 5.210000000000000000e+02, 2.766695930261447778e+00, 5.044826282660506536e+02, 5.044826282660506536e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.240000000000000000e+02, 2.799159054348542952e+00, 1.912078407588863271e+01, 1.912078407588863271e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.808000000000000000e+03, 2.831622178435637238e+00, 2.401893989509551020e+01, 2.401893989509551020e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 6.650000000000000000e+02, 2.864085302522731524e+00, 9.252826374593190906e+01, 9.252826374593190906e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 7.360000000000000000e+02, 2.896548426609826699e+00, 2.729842923395615628e+01, 2.729842923395615628e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 8.360000000000000000e+02, 2.929011550696921873e+00, 9.846037845125167109e+00, 9.846037845125167109e+00, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.105000000000000000e+03, 2.961474674784016159e+00, 1.053093321380896015e+02, 1.053093321380896015e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.772000000000000000e+03, 2.993937798871110445e+00, 8.604682176453617615e+01, 8.604682176453617615e+01, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 8.530000000000000000e+02, 3.026400922958205619e+00, 2.156612175866932546e+02, 2.156612175866932546e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.718000000000000000e+03, 3.058864047045300794e+00, 2.070940318225731005e+02, 2.070940318225731005e+02, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 1.756000000000000000e+03, 3.091327171132395080e+00, 7.623981851488119688e+00, 7.623981851488119688e+00, 0}, + {3.258104013576325286e+01, -9.654394935798733002e+01, 9.190000000000000000e+02, 3.123790295219489366e+00, 1.968719489216574914e+02, 1.968719489216574914e+02, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 3.690000000000000000e+02, -3.141592653589793116e+00, 8.920584113961149342e+01, 8.920584113961149342e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 8.120000000000000000e+02, -3.109129529502698386e+00, 2.754994393504285810e+01, 2.754994393504285810e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 9.440000000000000000e+02, -3.076666405415603656e+00, 7.500653304879514849e+01, 7.500653304879514849e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 8.070000000000000000e+02, -3.044203281328508925e+00, 5.709320302478900544e+00, 5.709320302478900544e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.525000000000000000e+03, -3.011740157241414195e+00, 7.146291937523618465e+00, 7.146291937523618465e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.910000000000000000e+03, -2.979277033154319465e+00, 5.122257746503519726e+00, 5.122257746503519726e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.651000000000000000e+03, -2.946813909067224735e+00, 7.226455435638229119e+01, 7.226455435638229119e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 4.770000000000000000e+02, -2.914350784980130005e+00, 8.236261962023116112e+00, 8.236261962023116112e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 9.800000000000000000e+02, -2.881887660893035275e+00, 2.083356481352881673e+01, 2.083356481352881673e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.312000000000000000e+03, -2.849424536805940544e+00, 8.264013906956195754e+00, 8.264013906956195754e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 2.990000000000000000e+02, -2.816961412718845814e+00, 7.659129343949971691e+00, 7.659129343949971691e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.346000000000000000e+03, -2.784498288631751084e+00, 3.762449750495014769e+02, 3.762449750495014769e+02, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.233000000000000000e+03, -2.752035164544656354e+00, 7.153620660110013318e+01, 7.153620660110013318e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.858000000000000000e+03, -2.719572040457561624e+00, 4.372474664749647673e+02, 4.372474664749647673e+02, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 2.570000000000000000e+02, -2.687108916370466893e+00, 9.517677067321230311e+01, 9.517677067321230311e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.371000000000000000e+03, -2.654645792283372163e+00, 6.273850499239325984e+01, 6.273850499239325984e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.576000000000000000e+03, -2.622182668196277433e+00, 5.148846528569337444e+00, 5.148846528569337444e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.820000000000000000e+03, -2.589719544109182703e+00, 8.986822340435281831e+01, 8.986822340435281831e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 2.830000000000000000e+02, -2.557256420022087973e+00, 1.226830303792178611e+01, 1.226830303792178611e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.168000000000000000e+03, -2.524793295934993242e+00, 8.804548618000374915e+00, 8.804548618000374915e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.063000000000000000e+03, -2.492330171847898512e+00, 9.869508986083603830e+00, 9.869508986083603830e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.121000000000000000e+03, -2.459867047760803782e+00, 5.557814509877085385e+01, 5.557814509877085385e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.163000000000000000e+03, -2.427403923673709052e+00, 7.543249414342374948e+00, 7.543249414342374948e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.611000000000000000e+03, -2.394940799586614322e+00, 8.213957800802129228e+00, 8.213957800802129228e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.140000000000000000e+03, -2.362477675499519592e+00, 5.750254576524165273e+00, 5.750254576524165273e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.643000000000000000e+03, -2.330014551412424861e+00, 7.056415060780182102e+01, 7.056415060780182102e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.500000000000000000e+01, -2.297551427325330131e+00, 1.023186373145357564e+01, 1.023186373145357564e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 5.450000000000000000e+02, -2.265088303238235401e+00, 1.040414745116068644e+02, 1.040414745116068644e+02, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.918000000000000000e+03, -2.232625179151140671e+00, 2.740556896798866759e+01, 2.740556896798866759e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.485000000000000000e+03, -2.200162055064045941e+00, 6.162323383896162454e+01, 6.162323383896162454e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 3.320000000000000000e+02, -2.167698930976951210e+00, 2.318288311613473596e+01, 2.318288311613473596e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.910000000000000000e+02, -2.135235806889856480e+00, 1.090733259494431451e+02, 1.090733259494431451e+02, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.084000000000000000e+03, -2.102772682802761750e+00, 1.282302539481748482e+01, 1.282302539481748482e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.457000000000000000e+03, -2.070309558715667020e+00, 5.916380177283487996e+01, 5.916380177283487996e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 9.630000000000000000e+02, -2.037846434628572290e+00, 9.646669071267677253e+00, 9.646669071267677253e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.290000000000000000e+02, -2.005383310541477559e+00, 8.059388505016508475e+01, 8.059388505016508475e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 8.290000000000000000e+02, -1.972920186454382829e+00, 9.592446521335187271e+00, 9.592446521335187271e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 6.370000000000000000e+02, -1.940457062367288099e+00, 5.627963975844841649e+00, 5.627963975844841649e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 7.270000000000000000e+02, -1.907993938280193369e+00, 7.767969856259687056e+00, 7.767969856259687056e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 6.800000000000000000e+02, -1.875530814193098639e+00, 7.337856662038544187e+01, 7.337856662038544187e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.129000000000000000e+03, -1.843067690106003909e+00, 5.174804189026685464e+01, 5.174804189026685464e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.805000000000000000e+03, -1.810604566018909178e+00, 5.462476928113724206e+00, 5.462476928113724206e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 2.000000000000000000e+01, -1.778141441931814448e+00, 6.283659881606030950e+01, 6.283659881606030950e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.069000000000000000e+03, -1.745678317844719718e+00, 1.031064166243427849e+01, 1.031064166243427849e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.704000000000000000e+03, -1.713215193757624988e+00, 6.082041762434716503e+00, 6.082041762434716503e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 3.450000000000000000e+02, -1.680752069670530258e+00, 6.458599041930635565e+01, 6.458599041930635565e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.767000000000000000e+03, -1.648288945583435527e+00, 6.351312371219475494e+01, 6.351312371219475494e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.831000000000000000e+03, -1.615825821496340797e+00, 1.132224130409470177e+02, 1.132224130409470177e+02, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.100000000000000000e+02, -1.583362697409246067e+00, 2.554414751410236875e+02, 2.554414751410236875e+02, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 5.860000000000000000e+02, -1.550899573322151337e+00, 2.318653200183652814e+02, 2.318653200183652814e+02, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.812000000000000000e+03, -1.518436449235056607e+00, 1.527225589099396927e+02, 1.527225589099396927e+02, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.432000000000000000e+03, -1.485973325147961877e+00, 1.005170632280907768e+02, 1.005170632280907768e+02, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.294000000000000000e+03, -1.453510201060867146e+00, 1.029861086814495685e+01, 1.029861086814495685e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.098000000000000000e+03, -1.421047076973772416e+00, 5.567347359195229828e+00, 5.567347359195229828e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.740000000000000000e+02, -1.388583952886677686e+00, 1.278798131717079656e+01, 1.278798131717079656e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 2.900000000000000000e+02, -1.356120828799582956e+00, 2.027812176268359678e+02, 2.027812176268359678e+02, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 3.750000000000000000e+02, -1.323657704712488226e+00, 7.580943419192626607e+02, 7.580943419192626607e+02, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 6.600000000000000000e+01, -1.291194580625393495e+00, 5.370343109540256066e+00, 5.370343109540256066e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 8.260000000000000000e+02, -1.258731456538298765e+00, 8.830946882264110798e+01, 8.830946882264110798e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.454000000000000000e+03, -1.226268332451204035e+00, 5.915936160371811070e+01, 5.915936160371811070e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.476000000000000000e+03, -1.193805208364109305e+00, 1.295631882797934686e+01, 1.295631882797934686e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.672000000000000000e+03, -1.161342084277014575e+00, 7.444605115700881015e+00, 7.444605115700881015e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.014000000000000000e+03, -1.128878960189919844e+00, 2.912637216785311622e+01, 2.912637216785311622e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 3.380000000000000000e+02, -1.096415836102825114e+00, 1.518150354872665275e+02, 1.518150354872665275e+02, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.209000000000000000e+03, -1.063952712015730384e+00, 5.363639067216151091e+01, 5.363639067216151091e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 5.900000000000000000e+02, -1.031489587928635654e+00, 5.287676806311299060e+01, 5.287676806311299060e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 5.350000000000000000e+02, -9.990264638415409237e-01, 9.062957837943409700e+00, 9.062957837943409700e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.118000000000000000e+03, -9.665633397544461936e-01, 1.667311171680282484e+02, 1.667311171680282484e+02, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 2.380000000000000000e+02, -9.341002156673514634e-01, 1.825151468715254666e+01, 1.825151468715254666e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.189000000000000000e+03, -9.016370915802567332e-01, 1.011102786068513559e+01, 1.011102786068513559e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.293000000000000000e+03, -8.691739674931620030e-01, 1.207688985326631581e+01, 1.207688985326631581e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.085000000000000000e+03, -8.367108434060672728e-01, 7.674173971683030615e+00, 7.674173971683030615e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 6.440000000000000000e+02, -8.042477193189725426e-01, 6.952754753346910732e+00, 6.952754753346910732e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 6.510000000000000000e+02, -7.717845952318778124e-01, 1.157743450186483898e+02, 1.157743450186483898e+02, 1}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.648000000000000000e+03, -7.393214711447830823e-01, 1.004897441330968100e+01, 1.004897441330968100e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.440000000000000000e+02, -7.068583470576883521e-01, 3.687291872483300637e+01, 3.687291872483300637e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.748000000000000000e+03, -6.743952229705936219e-01, 7.084345435068421182e+01, 7.084345435068421182e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.124000000000000000e+03, -6.419320988834988917e-01, 1.523492923763599727e+01, 1.523492923763599727e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.293000000000000000e+03, -6.094689747964041615e-01, 2.485244275589514729e+01, 2.485244275589514729e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.740000000000000000e+03, -5.770058507093094313e-01, 9.399047677359348540e+00, 9.399047677359348540e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 8.900000000000000000e+02, -5.445427266222147011e-01, 5.771169546027397246e+01, 5.771169546027397246e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.952000000000000000e+03, -5.120796025351199710e-01, 8.133856772178486239e+00, 8.133856772178486239e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 8.890000000000000000e+02, -4.796164784480252408e-01, 2.858120547007156631e+01, 2.858120547007156631e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 6.690000000000000000e+02, -4.471533543609305106e-01, 7.637350843615528184e+00, 7.637350843615528184e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.564000000000000000e+03, -4.146902302738357804e-01, 9.170884579305430861e+01, 9.170884579305430861e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 9.500000000000000000e+01, -3.822271061867410502e-01, 5.448477564435820319e+00, 5.448477564435820319e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.155000000000000000e+03, -3.497639820996463200e-01, 4.288573451032167441e+02, 4.288573451032167441e+02, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 4.910000000000000000e+02, -3.173008580125515898e-01, 4.953299916129032709e+01, 4.953299916129032709e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.482000000000000000e+03, -2.848377339254568597e-01, 7.223201585746125808e+00, 7.223201585746125808e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.511000000000000000e+03, -2.523746098383621295e-01, 5.648003240629955179e+00, 5.648003240629955179e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 9.500000000000000000e+02, -2.199114857512673993e-01, 5.199667809532130036e+00, 5.199667809532130036e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.039000000000000000e+03, -1.874483616641726691e-01, 1.071473838329470993e+02, 1.071473838329470993e+02, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.180000000000000000e+02, -1.549852375770779389e-01, 6.128282630558089750e+01, 6.128282630558089750e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 6.140000000000000000e+02, -1.225221134899832087e-01, 8.782480305850656421e+00, 8.782480305850656421e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.273000000000000000e+03, -9.005898940288847854e-02, 5.536287908604970553e+00, 5.536287908604970553e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 9.320000000000000000e+02, -5.759586531579374835e-02, 1.083171591548573254e+01, 1.083171591548573254e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 4.950000000000000000e+02, -2.513274122869901817e-02, 1.208470934693921350e+02, 1.208470934693921350e+02, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.257000000000000000e+03, 7.330382858395712020e-03, 2.504582536183536376e+02, 2.504582536183536376e+02, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.285000000000000000e+03, 3.979350694549044221e-02, 1.312996127154665871e+01, 1.312996127154665871e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.728000000000000000e+03, 7.225663103258517239e-02, 1.184375461835711718e+01, 1.184375461835711718e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.359000000000000000e+03, 1.047197551196799026e-01, 1.244099556592647282e+01, 1.244099556592647282e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 5.800000000000000000e+01, 1.371828792067746328e-01, 6.146114870387633999e+01, 6.146114870387633999e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 6.390000000000000000e+02, 1.696460032938693629e-01, 2.737127724790748857e+02, 2.737127724790748857e+02, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 5.500000000000000000e+02, 2.021091273809640931e-01, 5.801591931091951260e+00, 5.801591931091951260e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 2.210000000000000000e+02, 2.345722514680588233e-01, 6.778113106458950199e+01, 6.778113106458950199e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.400000000000000000e+02, 2.670353755551535535e-01, 8.055297116453806439e+01, 8.055297116453806439e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 6.430000000000000000e+02, 2.994984996422482837e-01, 9.408131300652243567e+01, 9.408131300652243567e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.172000000000000000e+03, 3.319616237293430139e-01, 1.288611296646715765e+01, 1.288611296646715765e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.551000000000000000e+03, 3.644247478164377441e-01, 2.327072531754723457e+02, 2.327072531754723457e+02, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.564000000000000000e+03, 3.968878719035324742e-01, 1.513195955585395893e+02, 1.513195955585395893e+02, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.072000000000000000e+03, 4.293509959906272044e-01, 7.693415304873020943e+00, 7.693415304873020943e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.627000000000000000e+03, 4.618141200777219346e-01, 1.516291899668398173e+03, 1.516291899668398173e+03, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 3.020000000000000000e+02, 4.942772441648166648e-01, 1.089723748560934702e+01, 1.089723748560934702e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 8.670000000000000000e+02, 5.267403682519113950e-01, 6.760075949003512719e+00, 6.760075949003512719e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.464000000000000000e+03, 5.592034923390061252e-01, 2.718818020922023493e+01, 2.718818020922023493e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.335000000000000000e+03, 5.916666164261008554e-01, 7.776066025033793849e+00, 7.776066025033793849e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 5.780000000000000000e+02, 6.241297405131955855e-01, 9.725173573802304361e+01, 9.725173573802304361e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 6.580000000000000000e+02, 6.565928646002903157e-01, 3.009731217235187160e+03, 3.009731217235187160e+03, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.366000000000000000e+03, 6.890559886873850459e-01, 7.944966512299399319e+00, 7.944966512299399319e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 8.100000000000000000e+01, 7.215191127744797761e-01, 7.155182614656720119e+00, 7.155182614656720119e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.661000000000000000e+03, 7.539822368615745063e-01, 5.805338003619411325e+00, 5.805338003619411325e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.350000000000000000e+02, 7.864453609486692365e-01, 8.057150649751918081e+01, 8.057150649751918081e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.853000000000000000e+03, 8.189084850357639667e-01, 3.777819030679303580e+01, 3.777819030679303580e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.420000000000000000e+03, 8.513716091228586968e-01, 7.060103420140422692e+00, 7.060103420140422692e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 9.710000000000000000e+02, 8.838347332099534270e-01, 7.143024005987474823e+01, 7.143024005987474823e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 3.690000000000000000e+02, 9.162978572970477131e-01, 1.849389389479750534e+01, 1.849389389479750534e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 8.470000000000000000e+02, 9.487609813841428874e-01, 1.000650038724827937e+03, 1.000650038724827937e+03, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 9.010000000000000000e+02, 9.812241054712380617e-01, 7.714181590874458649e+00, 7.714181590874458649e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 3.370000000000000000e+02, 1.013687229558332348e+00, 5.235189317858226943e+00, 5.235189317858226943e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.062000000000000000e+03, 1.046150353645426634e+00, 6.818909809620268447e+01, 6.818909809620268447e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.312000000000000000e+03, 1.078613477732521808e+00, 1.285513274415408169e+01, 1.285513274415408169e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.802000000000000000e+03, 1.111076601819616982e+00, 3.053129869494580930e+02, 3.053129869494580930e+02, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.006000000000000000e+03, 1.143539725906711269e+00, 6.172845679009257402e+00, 6.172845679009257402e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.523000000000000000e+03, 1.176002849993805555e+00, 5.302996736951725154e+01, 5.302996736951725154e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.742000000000000000e+03, 1.208465974080900729e+00, 5.517273123565372472e+00, 5.517273123565372472e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 6.300000000000000000e+01, 1.240929098167995903e+00, 1.428973505187879312e+01, 1.428973505187879312e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 4.520000000000000000e+02, 1.273392222255090189e+00, 5.126986130799115671e+01, 5.126986130799115671e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 4.380000000000000000e+02, 1.305855346342184475e+00, 6.304595573644847661e+01, 6.304595573644847661e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 9.290000000000000000e+02, 1.338318470429279650e+00, 5.085457718518276771e+00, 5.085457718518276771e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 2.700000000000000000e+01, 1.370781594516374824e+00, 5.261338666560884114e+00, 5.261338666560884114e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 5.390000000000000000e+02, 1.403244718603469110e+00, 6.339617888994727224e+00, 6.339617888994727224e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 7.150000000000000000e+02, 1.435707842690563396e+00, 7.125026377213708351e+00, 7.125026377213708351e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 3.230000000000000000e+02, 1.468170966777658570e+00, 5.956772547045885347e+01, 5.956772547045885347e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 4.500000000000000000e+01, 1.500634090864753745e+00, 2.365433082680432051e+02, 2.365433082680432051e+02, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 8.640000000000000000e+02, 1.533097214951848031e+00, 6.003081875170452442e+00, 6.003081875170452442e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 5.270000000000000000e+02, 1.565560339038942317e+00, 1.023249663376216390e+01, 1.023249663376216390e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 7.660000000000000000e+02, 1.598023463126037491e+00, 2.567999602655214986e+01, 2.567999602655214986e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.350000000000000000e+02, 1.630486587213132665e+00, 1.331181411698143222e+02, 1.331181411698143222e+02, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 8.190000000000000000e+02, 1.662949711300226951e+00, 6.983090330782964372e+01, 6.983090330782964372e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 6.800000000000000000e+02, 1.695412835387321238e+00, 2.164403763622879850e+01, 2.164403763622879850e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.054000000000000000e+03, 1.727875959474416412e+00, 1.067702131729286918e+01, 1.067702131729286918e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.101000000000000000e+03, 1.760339083561511586e+00, 7.319146251041878770e+01, 7.319146251041878770e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.240000000000000000e+03, 1.792802207648605872e+00, 5.669426728550450889e+01, 5.669426728550450889e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.390000000000000000e+02, 1.825265331735700158e+00, 1.330936286553862260e+02, 1.330936286553862260e+02, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.520000000000000000e+02, 1.857728455822795333e+00, 9.270722698754850910e+01, 9.270722698754850910e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.854000000000000000e+03, 1.890191579909890507e+00, 2.448138296747142206e+01, 2.448138296747142206e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.773000000000000000e+03, 1.922654703996984793e+00, 6.098775122924274683e+02, 6.098775122924274683e+02, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 7.050000000000000000e+02, 1.955117828084079079e+00, 1.113793829261730366e+02, 1.113793829261730366e+02, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 5.740000000000000000e+02, 1.987580952171174253e+00, 2.108451100298334424e+01, 2.108451100298334424e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.300000000000000000e+01, 2.020044076258269428e+00, 5.220527318856692034e+01, 5.220527318856692034e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.476000000000000000e+03, 2.052507200345363714e+00, 8.625206534054822782e+01, 8.625206534054822782e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.235000000000000000e+03, 2.084970324432458000e+00, 2.483139304856234730e+01, 2.483139304856234730e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 9.450000000000000000e+02, 2.117433448519553174e+00, 1.363750942156009955e+02, 1.363750942156009955e+02, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 7.300000000000000000e+02, 2.149896572606648348e+00, 9.000206172115895242e+00, 9.000206172115895242e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.000000000000000000e+03, 2.182359696693742634e+00, 5.084745762711864359e+01, 5.084745762711864359e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 5.610000000000000000e+02, 2.214822820780836921e+00, 1.117043453415111571e+02, 1.117043453415111571e+02, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.892000000000000000e+03, 2.247285944867932095e+00, 6.737556837685731992e+00, 6.737556837685731992e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 7.380000000000000000e+02, 2.279749068955027269e+00, 5.173347487100466324e+00, 5.173347487100466324e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.780000000000000000e+02, 2.312212193042121555e+00, 7.275686376205200645e+01, 7.275686376205200645e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.260000000000000000e+02, 2.344675317129215841e+00, 6.961352135448902345e+01, 6.961352135448902345e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.090000000000000000e+02, 2.377138441216311016e+00, 6.256006027163952155e+01, 6.256006027163952155e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.220000000000000000e+02, 2.409601565303406190e+00, 6.252177296718664934e+01, 6.252177296718664934e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.716000000000000000e+03, 2.442064689390500476e+00, 3.497036096642899849e+01, 3.497036096642899849e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 8.140000000000000000e+02, 2.474527813477594762e+00, 1.364946189112799289e+02, 1.364946189112799289e+02, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.489000000000000000e+03, 2.506990937564689936e+00, 8.183905167304182271e+00, 8.183905167304182271e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 6.010000000000000000e+02, 2.539454061651785111e+00, 8.121934082396128574e+00, 8.121934082396128574e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.150000000000000000e+02, 2.571917185738879397e+00, 1.683831751460394699e+01, 1.683831751460394699e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.505000000000000000e+03, 2.604380309825973683e+00, 9.873128551420926158e+00, 9.873128551420926158e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 4.640000000000000000e+02, 2.636843433913068857e+00, 7.375235504764820149e+00, 7.375235504764820149e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.285000000000000000e+03, 2.669306558000164031e+00, 1.698735102363946226e+01, 1.698735102363946226e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.344000000000000000e+03, 2.701769682087258317e+00, 3.715858245361219048e+01, 3.715858245361219048e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.931000000000000000e+03, 2.734232806174352604e+00, 5.295484273046988477e+01, 5.295484273046988477e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 2.380000000000000000e+02, 2.766695930261447778e+00, 2.540002460628729182e+02, 2.540002460628729182e+02, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 7.850000000000000000e+02, 2.799159054348542952e+00, 7.585478821749399359e+00, 7.585478821749399359e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.279000000000000000e+03, 2.831622178435637238e+00, 3.378067137230760864e+01, 3.378067137230760864e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.476000000000000000e+03, 2.864085302522731524e+00, 5.410075783009298256e+00, 5.410075783009298256e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.888000000000000000e+03, 2.896548426609826699e+00, 8.283804505948243957e+01, 8.283804505948243957e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.965000000000000000e+03, 2.929011550696921873e+00, 1.654098685555444348e+01, 1.654098685555444348e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 6.620000000000000000e+02, 2.961474674784016159e+00, 5.924222982200778809e+00, 5.924222982200778809e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 6.890000000000000000e+02, 2.993937798871110445e+00, 8.129862931988122909e+01, 8.129862931988122909e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.229000000000000000e+03, 3.026400922958205619e+00, 7.906228697430050545e+01, 7.906228697430050545e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 1.795000000000000000e+03, 3.058864047045300794e+00, 5.383094109523620219e+00, 5.383094109523620219e+00, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 7.330000000000000000e+02, 3.091327171132395080e+00, 5.367740856310985009e+01, 5.367740856310985009e+01, 0}, + {3.264399264817755864e+01, -9.652259521479238913e+01, 7.960000000000000000e+02, 3.123790295219489366e+00, 1.001155332603287604e+02, 1.001155332603287604e+02, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.055000000000000000e+03, -3.141592653589793116e+00, 6.174126230548238503e+00, 6.174126230548238503e+00, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 3.340000000000000000e+02, -3.109129529502698386e+00, 9.474860245955298410e+00, 9.474860245955298410e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 8.100000000000000000e+02, -3.076666405415603656e+00, 2.677063067368168348e+01, 2.677063067368168348e+01, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.105000000000000000e+03, -3.044203281328508925e+00, 8.499465677961424159e-01, 8.499465677961424159e-01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.048000000000000000e+03, -3.011740157241414195e+00, 4.139990965912152099e+00, 4.139990965912152099e+00, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 8.870000000000000000e+02, -2.979277033154319465e+00, 2.393006786760430415e+01, 2.393006786760430415e+01, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.232000000000000000e+03, -2.946813909067224735e+00, 5.389032071408247582e+00, 5.389032071408247582e+00, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.238000000000000000e+03, -2.914350784980130005e+00, 4.506634031876247448e+00, 4.506634031876247448e+00, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 7.160000000000000000e+02, -2.881887660893035275e+00, 6.201793149391507942e-01, 6.201793149391507942e-01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.869000000000000000e+03, -2.849424536805940544e+00, 2.692519537224072668e+00, 2.692519537224072668e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.532000000000000000e+03, -2.816961412718845814e+00, 1.434485695036503472e+00, 1.434485695036503472e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 8.310000000000000000e+02, -2.784498288631751084e+00, 8.960836882408703019e+00, 8.960836882408703019e+00, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 7.180000000000000000e+02, -2.752035164544656354e+00, 5.359044982099320231e-01, 5.359044982099320231e-01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 6.610000000000000000e+02, -2.719572040457561624e+00, 6.999700513267181901e-01, 6.999700513267181901e-01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.254000000000000000e+03, -2.687108916370466893e+00, 6.400201952595996779e+00, 6.400201952595996779e+00, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.737000000000000000e+03, -2.654645792283372163e+00, 1.116395091354310836e+02, 1.116395091354310836e+02, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.032000000000000000e+03, -2.622182668196277433e+00, 8.386497083606082370e+00, 8.386497083606082370e+00, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 6.860000000000000000e+02, -2.589719544109182703e+00, 1.789387482386435524e+00, 1.789387482386435524e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.304000000000000000e+03, -2.557256420022087973e+00, 8.388913967315460241e+00, 8.388913967315460241e+00, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.457000000000000000e+03, -2.524793295934993242e+00, 9.744416294226523334e+00, 9.744416294226523334e+00, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.566000000000000000e+03, -2.492330171847898512e+00, 1.315919297911508323e+01, 1.315919297911508323e+01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.764000000000000000e+03, -2.459867047760803782e+00, 4.500488254761920714e+00, 4.500488254761920714e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 7.610000000000000000e+02, -2.427403923673709052e+00, 5.950922735589723622e+00, 5.950922735589723622e+00, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.250000000000000000e+03, -2.394940799586614322e+00, 3.813242232868325488e+01, 3.813242232868325488e+01, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 6.840000000000000000e+02, -2.362477675499519592e+00, 2.478346909011530652e+00, 2.478346909011530652e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.534000000000000000e+03, -2.330014551412424861e+00, 1.857788998296851091e+01, 1.857788998296851091e+01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 2.890000000000000000e+02, -2.297551427325330131e+00, 1.352683675143601327e+00, 1.352683675143601327e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.737000000000000000e+03, -2.265088303238235401e+00, 9.318823800954180170e-01, 9.318823800954180170e-01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.194000000000000000e+03, -2.232625179151140671e+00, 1.165981853817610991e+00, 1.165981853817610991e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.529000000000000000e+03, -2.200162055064045941e+00, 9.024901419489713916e+00, 9.024901419489713916e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.308000000000000000e+03, -2.167698930976951210e+00, 7.448086293104938527e-01, 7.448086293104938527e-01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.992000000000000000e+03, -2.135235806889856480e+00, 1.548631076778011151e+00, 1.548631076778011151e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.598000000000000000e+03, -2.102772682802761750e+00, 8.825712460033937390e+00, 8.825712460033937390e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.492000000000000000e+03, -2.070309558715667020e+00, 1.003219816391203523e+01, 1.003219816391203523e+01, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.434000000000000000e+03, -2.037846434628572290e+00, 6.426371107711963404e+00, 6.426371107711963404e+00, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.050000000000000000e+02, -2.005383310541477559e+00, 6.033737791413974350e+01, 6.033737791413974350e+01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.932000000000000000e+03, -1.972920186454382829e+00, 1.434798185576401153e+01, 1.434798185576401153e+01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.831000000000000000e+03, -1.940457062367288099e+00, 1.376296395755175928e+00, 1.376296395755175928e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 9.960000000000000000e+02, -1.907993938280193369e+00, 3.390169474577965580e+00, 3.390169474577965580e+00, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 3.230000000000000000e+02, -1.875530814193098639e+00, 1.306827856685315981e+00, 1.306827856685315981e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.800000000000000000e+03, -1.843067690106003909e+00, 1.304347826086956630e+01, 1.304347826086956630e+01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.534000000000000000e+03, -1.810604566018909178e+00, 8.201371777510090277e-01, 8.201371777510090277e-01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.351000000000000000e+03, -1.778141441931814448e+00, 1.874990196052799973e+01, 1.874990196052799973e+01, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 4.420000000000000000e+02, -1.745678317844719718e+00, 1.459932614655153893e+00, 1.459932614655153893e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.090000000000000000e+02, -1.713215193757624988e+00, 1.872563031766683705e+00, 1.872563031766683705e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.359000000000000000e+03, -1.680752069670530258e+00, 8.079313863194076362e+01, 8.079313863194076362e+01, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.291000000000000000e+03, -1.648288945583435527e+00, 7.102731290505018835e-01, 7.102731290505018835e-01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.719000000000000000e+03, -1.615825821496340797e+00, 3.213727583772302410e+01, 3.213727583772302410e+01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 5.290000000000000000e+02, -1.583362697409246067e+00, 6.640767135735916593e-01, 6.640767135735916593e-01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 9.830000000000000000e+02, -1.550899573322151337e+00, 3.478488269688588819e-01, 3.478488269688588819e-01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.757000000000000000e+03, -1.518436449235056607e+00, 9.603751650239621407e-01, 9.603751650239621407e-01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 2.850000000000000000e+02, -1.485973325147961877e+00, 2.099237776600492378e+00, 2.099237776600492378e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.714000000000000000e+03, -1.453510201060867146e+00, 4.451189490417393202e+00, 4.451189490417393202e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.197000000000000000e+03, -1.421047076973772416e+00, 1.860537281114984953e+00, 1.860537281114984953e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 2.550000000000000000e+02, -1.388583952886677686e+00, 9.550550429261512875e+00, 9.550550429261512875e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 3.940000000000000000e+02, -1.356120828799582956e+00, 1.264392110402400515e+00, 1.264392110402400515e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 4.120000000000000000e+02, -1.323657704712488226e+00, 2.342033183167951282e+00, 2.342033183167951282e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.905000000000000000e+03, -1.291194580625393495e+00, 3.943864316117459357e+00, 3.943864316117459357e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.064000000000000000e+03, -1.258731456538298765e+00, 1.206212293456592555e+01, 1.206212293456592555e+01, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 4.200000000000000000e+02, -1.226268332451204035e+00, 8.465480182968336820e-01, 8.465480182968336820e-01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.962000000000000000e+03, -1.193805208364109305e+00, 1.489556540701213905e+00, 1.489556540701213905e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.329000000000000000e+03, -1.161342084277014575e+00, 5.478404379088524401e+00, 5.478404379088524401e+00, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.080000000000000000e+03, -1.128878960189919844e+00, 4.330127018922193649e+00, 4.330127018922193649e+00, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 8.450000000000000000e+02, -1.096415836102825114e+00, 5.469124494868339292e-01, 5.469124494868339292e-01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.524000000000000000e+03, -1.063952712015730384e+00, 1.830677459901884774e+01, 1.830677459901884774e+01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.619000000000000000e+03, -1.031489587928635654e+00, 8.442598533080108991e-01, 8.442598533080108991e-01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.960000000000000000e+02, -9.990264638415409237e-01, 2.869844781568296810e+01, 2.869844781568296810e+01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 8.540000000000000000e+02, -9.665633397544461936e-01, 1.056682260031030385e+00, 1.056682260031030385e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 3.570000000000000000e+02, -9.341002156673514634e-01, 2.871177457999115834e+00, 2.871177457999115834e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.645000000000000000e+03, -9.016370915802567332e-01, 9.764873216929871091e+00, 9.764873216929871091e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.478000000000000000e+03, -8.691739674931620030e-01, 1.785166149639349698e+01, 1.785166149639349698e+01, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.327000000000000000e+03, -8.367108434060672728e-01, 5.469045488554670209e-01, 5.469045488554670209e-01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.648000000000000000e+03, -8.042477193189725426e-01, 1.190361899275663582e+01, 1.190361899275663582e+01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 4.520000000000000000e+02, -7.717845952318778124e-01, 1.639339155844206530e+00, 1.639339155844206530e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.737000000000000000e+03, -7.393214711447830823e-01, 2.937881819353449586e+01, 2.937881819353449586e+01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 4.040000000000000000e+02, -7.068583470576883521e-01, 2.120385120173040505e+01, 2.120385120173040505e+01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 2.870000000000000000e+02, -6.743952229705936219e-01, 6.779847205136705668e+01, 6.779847205136705668e+01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.940000000000000000e+03, -6.419320988834988917e-01, 7.230397349615948599e+00, 7.230397349615948599e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 6.580000000000000000e+02, -6.094689747964041615e-01, 6.837002588994367525e-01, 6.837002588994367525e-01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.189000000000000000e+03, -5.770058507093094313e-01, 1.202710480539685101e+01, 1.202710480539685101e+01, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 2.200000000000000000e+02, -5.445427266222147011e-01, 4.512966198114654937e+00, 4.512966198114654937e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.985000000000000000e+03, -5.120796025351199710e-01, 2.012906848684628613e+01, 2.012906848684628613e+01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 3.790000000000000000e+02, -4.796164784480252408e-01, 1.608382555378055656e+02, 1.608382555378055656e+02, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 4.460000000000000000e+02, -4.471533543609305106e-01, 9.182434379204387209e-01, 9.182434379204387209e-01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 4.260000000000000000e+02, -4.146902302738357804e-01, 3.231998812891275463e+01, 3.231998812891275463e+01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.218000000000000000e+03, -3.822271061867410502e-01, 1.014101951332949225e+00, 1.014101951332949225e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 6.130000000000000000e+02, -3.497639820996463200e-01, 1.412275670485208146e+01, 1.412275670485208146e+01, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.798000000000000000e+03, -3.173008580125515898e-01, 6.651853914047357819e+01, 6.651853914047357819e+01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 3.800000000000000000e+01, -2.848377339254568597e-01, 7.090289133737778116e+01, 7.090289133737778116e+01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 2.490000000000000000e+02, -2.523746098383621295e-01, 9.851577759225412789e-01, 9.851577759225412789e-01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 5.760000000000000000e+02, -2.199114857512673993e-01, 4.004441978048321715e+01, 4.004441978048321715e+01, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 3.220000000000000000e+02, -1.874483616641726691e-01, 7.420902635014647331e+01, 7.420902635014647331e+01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 7.850000000000000000e+02, -1.549852375770779389e-01, 1.141918242575742681e+01, 1.141918242575742681e+01, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.104000000000000000e+03, -1.225221134899832087e-01, 7.347983780340524795e+00, 7.347983780340524795e+00, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.032000000000000000e+03, -9.005898940288847854e-02, 4.193248541803041185e+00, 4.193248541803041185e+00, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 9.250000000000000000e+02, -5.759586531579374835e-02, 5.172795424139640375e+01, 5.172795424139640375e+01, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 9.510000000000000000e+02, -2.513274122869901817e-02, 1.014895314798526549e+01, 1.014895314798526549e+01, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.300000000000000000e+01, 7.330382858395712020e-03, 1.578273595588889577e+01, 1.578273595588889577e+01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.965000000000000000e+03, 3.979350694549044221e-02, 9.608977609191166280e+00, 9.608977609191166280e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 7.760000000000000000e+02, 7.225663103258517239e-02, 2.551234995056315569e+01, 2.551234995056315569e+01, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.814000000000000000e+03, 1.047197551196799026e-01, 1.638016850407806313e+00, 1.638016850407806313e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 3.830000000000000000e+02, 1.371828792067746328e-01, 5.852953463634555931e+00, 5.852953463634555931e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 2.100000000000000000e+01, 1.696460032938693629e-01, 2.510695353257194284e+00, 2.510695353257194284e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.671000000000000000e+03, 2.021091273809640931e-01, 1.410680914229521798e+00, 1.410680914229521798e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.437000000000000000e+03, 2.345722514680588233e-01, 7.967147011001617374e-01, 7.967147011001617374e-01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.855000000000000000e+03, 2.670353755551535535e-01, 1.996233961731988416e+00, 1.996233961731988416e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 8.390000000000000000e+02, 2.994984996422482837e-01, 1.643796315402432384e+01, 1.643796315402432384e+01, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.465000000000000000e+03, 3.319616237293430139e-01, 7.401035930208465174e+00, 7.401035930208465174e+00, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.085000000000000000e+03, 3.644247478164377441e-01, 1.491686143604078829e+01, 1.491686143604078829e+01, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 9.330000000000000000e+02, 3.968878719035324742e-01, 3.710012068745227043e-01, 3.710012068745227043e-01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 7.110000000000000000e+02, 4.293509959906272044e-01, 6.558209411182225335e-01, 6.558209411182225335e-01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 6.600000000000000000e+01, 4.618141200777219346e-01, 2.816557222140060990e+00, 2.816557222140060990e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.890000000000000000e+03, 4.942772441648166648e-01, 1.435523524112291582e+01, 1.435523524112291582e+01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 4.620000000000000000e+02, 5.267403682519113950e-01, 5.306086091587634890e+00, 5.306086091587634890e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 8.730000000000000000e+02, 5.592034923390061252e-01, 3.779934034869750104e+00, 3.779934034869750104e+00, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 5.500000000000000000e+01, 5.916666164261008554e-01, 5.166699853869253012e+00, 5.166699853869253012e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 8.860000000000000000e+02, 6.241297405131955855e-01, 4.146806713262599864e+00, 4.146806713262599864e+00, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.488000000000000000e+03, 6.565928646002903157e-01, 2.144292005937881385e+00, 2.144292005937881385e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 5.670000000000000000e+02, 6.890559886873850459e-01, 9.282003843545514332e-01, 9.282003843545514332e-01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.800000000000000000e+01, 7.215191127744797761e-01, 1.505432869642482530e+01, 1.505432869642482530e+01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 2.100000000000000000e+01, 7.539822368615745063e-01, 7.665633684944838322e+00, 7.665633684944838322e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.294000000000000000e+03, 7.864453609486692365e-01, 5.746519964855324458e-01, 5.746519964855324458e-01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 3.620000000000000000e+02, 8.189084850357639667e-01, 4.699804598630258567e+00, 4.699804598630258567e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 5.190000000000000000e+02, 8.513716091228586968e-01, 1.066388332629281877e+01, 1.066388332629281877e+01, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 4.200000000000000000e+01, 8.838347332099534270e-01, 1.701965767218217795e+00, 1.701965767218217795e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 4.800000000000000000e+01, 9.162978572970477131e-01, 1.553645618374638993e+00, 1.553645618374638993e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 8.560000000000000000e+02, 9.487609813841428874e-01, 4.179295385953233355e-01, 4.179295385953233355e-01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 5.470000000000000000e+02, 9.812241054712380617e-01, 6.522108981490821744e-01, 6.522108981490821744e-01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 5.680000000000000000e+02, 1.013687229558332348e+00, 4.102462456537178781e+00, 4.102462456537178781e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 4.400000000000000000e+01, 1.046150353645426634e+00, 2.357724325448142810e+00, 2.357724325448142810e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.001000000000000000e+03, 1.078613477732521808e+00, 1.117325418972590967e+00, 1.117325418972590967e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.400000000000000000e+01, 1.111076601819616982e+00, 1.576795942484126201e+01, 1.576795942484126201e+01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.093000000000000000e+03, 1.143539725906711269e+00, 5.263346131502278702e+00, 5.263346131502278702e+00, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.900000000000000000e+03, 1.176002849993805555e+00, 3.924018842390098172e+01, 3.924018842390098172e+01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.806000000000000000e+03, 1.208465974080900729e+00, 3.178956082246683934e+01, 3.178956082246683934e+01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.088000000000000000e+03, 1.240929098167995903e+00, 6.036208627820655037e-01, 6.036208627820655037e-01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.681000000000000000e+03, 1.273392222255090189e+00, 1.489776041242852145e+01, 1.489776041242852145e+01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 2.910000000000000000e+02, 1.305855346342184475e+00, 1.026159066048595525e+00, 1.026159066048595525e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 8.850000000000000000e+02, 1.338318470429279650e+00, 1.079496410369205392e+02, 1.079496410369205392e+02, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.917000000000000000e+03, 1.370781594516374824e+00, 2.609848495908839894e+01, 2.609848495908839894e+01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 9.070000000000000000e+02, 1.403244718603469110e+00, 1.275962698546006857e+00, 1.275962698546006857e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 9.240000000000000000e+02, 1.435707842690563396e+00, 4.217804103321139420e-01, 4.217804103321139420e-01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.538000000000000000e+03, 1.468170966777658570e+00, 9.466805581907453693e-01, 9.466805581907453693e-01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 6.610000000000000000e+02, 1.500634090864753745e+00, 2.601555357430969195e+01, 2.601555357430969195e+01, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 8.680000000000000000e+02, 1.533097214951848031e+00, 4.414159036554981697e+01, 4.414159036554981697e+01, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.884000000000000000e+03, 1.565560339038942317e+00, 2.769192879653106676e+00, 2.769192879653106676e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.435000000000000000e+03, 1.598023463126037491e+00, 9.655151625354582379e+00, 9.655151625354582379e+00, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.682000000000000000e+03, 1.630486587213132665e+00, 1.898453481082618133e+00, 1.898453481082618133e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 8.710000000000000000e+02, 1.662949711300226951e+00, 5.784716945409184241e+00, 5.784716945409184241e+00, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 5.500000000000000000e+01, 1.695412835387321238e+00, 2.120074408122641696e+00, 2.120074408122641696e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.724000000000000000e+03, 1.727875959474416412e+00, 1.616545079198098023e+01, 1.616545079198098023e+01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.981000000000000000e+03, 1.760339083561511586e+00, 7.762670113350425005e+00, 7.762670113350425005e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.453000000000000000e+03, 1.792802207648605872e+00, 1.547664385361961381e+00, 1.547664385361961381e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.265000000000000000e+03, 1.825265331735700158e+00, 4.955996342601742821e-01, 4.955996342601742821e-01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 2.940000000000000000e+02, 1.857728455822795333e+00, 1.222249822294596733e+01, 1.222249822294596733e+01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.098000000000000000e+03, 1.890191579909890507e+00, 5.027668156492912654e-01, 5.027668156492912654e-01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.338000000000000000e+03, 1.922654703996984793e+00, 1.045785327846543211e+00, 1.045785327846543211e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.134000000000000000e+03, 1.955117828084079079e+00, 1.702382597677660669e+01, 1.702382597677660669e+01, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 9.180000000000000000e+02, 1.987580952171174253e+00, 6.941181455631311170e-01, 6.941181455631311170e-01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.481000000000000000e+03, 2.020044076258269428e+00, 1.793471286694701305e+01, 1.793471286694701305e+01, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.023000000000000000e+03, 2.052507200345363714e+00, 7.431857795199382499e-01, 7.431857795199382499e-01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 6.700000000000000000e+01, 2.084970324432458000e+00, 2.572312663162934498e+00, 2.572312663162934498e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.910000000000000000e+02, 2.117433448519553174e+00, 1.082149487249844810e+01, 1.082149487249844810e+01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 3.900000000000000000e+01, 2.149896572606648348e+00, 6.268588927525695631e+00, 6.268588927525695631e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 3.140000000000000000e+02, 2.182359696693742634e+00, 2.098753916017788157e+01, 2.098753916017788157e+01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 8.030000000000000000e+02, 2.214822820780836921e+00, 9.197372974568416293e-01, 9.197372974568416293e-01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.665000000000000000e+03, 2.247285944867932095e+00, 1.110851484580162385e+01, 1.110851484580162385e+01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.758000000000000000e+03, 2.279749068955027269e+00, 1.079406901739544011e+01, 1.079406901739544011e+01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.818000000000000000e+03, 2.312212193042121555e+00, 1.200028834717003612e+00, 1.200028834717003612e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.050000000000000000e+02, 2.344675317129215841e+00, 2.885700682850161769e+01, 2.885700682850161769e+01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 3.630000000000000000e+02, 2.377138441216311016e+00, 7.582048247096675908e+00, 7.582048247096675908e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.588000000000000000e+03, 2.409601565303406190e+00, 9.227610741681727902e+00, 9.227610741681727902e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.516000000000000000e+03, 2.442064689390500476e+00, 7.850689235138156086e+00, 7.850689235138156086e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.487000000000000000e+03, 2.474527813477594762e+00, 1.971419278382783968e+00, 1.971419278382783968e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.374000000000000000e+03, 2.506990937564689936e+00, 4.736699962063487135e+01, 4.736699962063487135e+01, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.659000000000000000e+03, 2.539454061651785111e+00, 1.152477792403598222e+01, 1.152477792403598222e+01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 8.350000000000000000e+02, 2.571917185738879397e+00, 1.929531103086389088e+00, 1.929531103086389088e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.710000000000000000e+03, 2.604380309825973683e+00, 1.217154292881879707e+00, 1.217154292881879707e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 5.580000000000000000e+02, 2.636843433913068857e+00, 7.421105039008678261e+01, 7.421105039008678261e+01, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.260000000000000000e+03, 2.669306558000164031e+00, 7.943320296611768860e-01, 7.943320296611768860e-01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 5.580000000000000000e+02, 2.701769682087258317e+00, 6.871393554637665879e+00, 6.871393554637665879e+00, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 9.170000000000000000e+02, 2.734232806174352604e+00, 6.513545081693225214e+00, 6.513545081693225214e+00, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.640000000000000000e+03, 2.766695930261447778e+00, 9.162456945817023524e+00, 9.162456945817023524e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 6.680000000000000000e+02, 2.799159054348542952e+00, 5.818911973990820385e+00, 5.818911973990820385e+00, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 3.730000000000000000e+02, 2.831622178435637238e+00, 1.568964411202888876e+01, 1.568964411202888876e+01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 8.550000000000000000e+02, 2.864085302522731524e+00, 8.026780748449123593e+00, 8.026780748449123593e+00, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.081000000000000000e+03, 2.896548426609826699e+00, 4.316175512044652662e-01, 4.316175512044652662e-01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.204000000000000000e+03, 2.929011550696921873e+00, 4.566532994949706215e+00, 4.566532994949706215e+00, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.664000000000000000e+03, 2.961474674784016159e+00, 3.925700480214331378e+01, 3.925700480214331378e+01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 9.620000000000000000e+02, 2.993937798871110445e+00, 3.104568117350024359e+00, 3.104568117350024359e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 5.400000000000000000e+02, 3.026400922958205619e+00, 1.358852889112938334e+00, 1.358852889112938334e+00, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.400000000000000000e+03, 3.058864047045300794e+00, 1.154700538379251640e+02, 1.154700538379251640e+02, 1}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 5.990000000000000000e+02, 3.091327171132395080e+00, 5.982547447331441060e-01, 5.982547447331441060e-01, 0}, + {3.261881164321184201e+01, -9.649269941431950315e+01, 1.876000000000000000e+03, 3.123790295219489366e+00, 1.141952990630566767e+01, 1.141952990630566767e+01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 8.050000000000000000e+02, -3.141592653589793116e+00, 4.995863127948433902e-01, 4.995863127948433902e-01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.407000000000000000e+03, -3.109129529502698386e+00, 3.197693999365831541e+00, 3.197693999365831541e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 4.390000000000000000e+02, -3.076666405415603656e+00, 8.815264538792293436e+00, 8.815264538792293436e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 4.870000000000000000e+02, -3.044203281328508925e+00, 1.242280064207872847e+00, 1.242280064207872847e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.900000000000000000e+02, -3.011740157241414195e+00, 4.091117805436453381e+01, 4.091117805436453381e+01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.952000000000000000e+03, -2.979277033154319465e+00, 1.121942759482655418e+02, 1.121942759482655418e+02, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 5.140000000000000000e+02, -2.946813909067224735e+00, 1.077284939362577187e+00, 1.077284939362577187e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 9.260000000000000000e+02, -2.914350784980130005e+00, 5.232590180780452016e+01, 5.232590180780452016e+01, 1}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.820000000000000000e+02, -2.881887660893035275e+00, 9.803616051027049139e+00, 9.803616051027049139e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 4.680000000000000000e+02, -2.849424536805940544e+00, 1.522999221017179217e+00, 1.522999221017179217e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 3.600000000000000000e+01, -2.816961412718845814e+00, 1.600119570572374972e+00, 1.600119570572374972e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.328000000000000000e+03, -2.784498288631751084e+00, 9.954121211553115245e-01, 9.954121211553115245e-01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.742000000000000000e+03, -2.752035164544656354e+00, 9.369164850721753979e+00, 9.369164850721753979e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 8.780000000000000000e+02, -2.719572040457561624e+00, 4.846462208132516492e-01, 4.846462208132516492e-01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 7.880000000000000000e+02, -2.687108916370466893e+00, 1.972455758046685048e+00, 1.972455758046685048e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 2.070000000000000000e+02, -2.654645792283372163e+00, 2.670169892766343533e+00, 2.670169892766343533e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 3.560000000000000000e+02, -2.622182668196277433e+00, 9.293403409880338639e-01, 9.293403409880338639e-01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.998000000000000000e+03, -2.589719544109182703e+00, 2.822770270496697975e+01, 2.822770270496697975e+01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.100000000000000000e+02, -2.557256420022087973e+00, 1.165416731955606089e+01, 1.165416731955606089e+01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.083000000000000000e+03, -2.524793295934993242e+00, 2.729761062255043891e-01, 2.729761062255043891e-01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.170000000000000000e+02, -2.492330171847898512e+00, 1.214737913983893858e+00, 1.214737913983893858e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 3.470000000000000000e+02, -2.459867047760803782e+00, 4.617407281148155107e+02, 4.617407281148155107e+02, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 5.510000000000000000e+02, -2.427403923673709052e+00, 6.684019889531785941e-01, 6.684019889531785941e-01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 4.830000000000000000e+02, -2.394940799586614322e+00, 6.196172980905848560e-01, 6.196172980905848560e-01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 2.580000000000000000e+02, -2.362477675499519592e+00, 1.206145360092915508e+00, 1.206145360092915508e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 2.620000000000000000e+02, -2.330014551412424861e+00, 9.318657223494144048e+00, 9.318657223494144048e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 2.630000000000000000e+02, -2.297551427325330131e+00, 8.985132719560095182e+00, 8.985132719560095182e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 3.060000000000000000e+02, -2.265088303238235401e+00, 1.024492914704517643e+00, 1.024492914704517643e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 6.320000000000000000e+02, -2.232625179151140671e+00, 5.142594772265800529e-01, 5.142594772265800529e-01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 6.190000000000000000e+02, -2.200162055064045941e+00, 6.652041571162335964e-01, 6.652041571162335964e-01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 2.520000000000000000e+02, -2.167698930976951210e+00, 4.407632269396146540e+01, 4.407632269396146540e+01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.218000000000000000e+03, -2.135235806889856480e+00, 3.402853825577645819e-01, 3.402853825577645819e-01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 8.690000000000000000e+02, -2.102772682802761750e+00, 7.530974661417699778e-01, 7.530974661417699778e-01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 6.240000000000000000e+02, -2.070309558715667020e+00, 7.684166177056123148e-01, 7.684166177056123148e-01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 4.780000000000000000e+02, -2.037846434628572290e+00, 1.128775962628066676e+00, 1.128775962628066676e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.054000000000000000e+03, -2.005383310541477559e+00, 1.631784879661263565e-01, 1.631784879661263565e-01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.034000000000000000e+03, -1.972920186454382829e+00, 5.565192259338568731e-02, 5.565192259338568731e-02, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.670000000000000000e+02, -1.940457062367288099e+00, 1.369813834252079410e+01, 1.369813834252079410e+01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 8.960000000000000000e+02, -1.907993938280193369e+00, 2.535831215289687246e-01, 2.535831215289687246e-01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.947000000000000000e+03, -1.875530814193098639e+00, 1.800080972536721946e+00, 1.800080972536721946e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 5.050000000000000000e+02, -1.843067690106003909e+00, 8.046387510053817360e-01, 8.046387510053817360e-01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.034000000000000000e+03, -1.810604566018909178e+00, 5.501517290696250617e-02, 5.501517290696250617e-02, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.243000000000000000e+03, -1.778141441931814448e+00, 4.211444799713995879e-01, 4.211444799713995879e-01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.042000000000000000e+03, -1.745678317844719718e+00, 8.048369867163955582e-02, 8.048369867163955582e-02, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 2.490000000000000000e+02, -1.713215193757624988e+00, 3.069579148387845180e+00, 3.069579148387845180e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.320000000000000000e+03, -1.680752069670530258e+00, 1.528879526889832530e+00, 1.528879526889832530e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.971000000000000000e+03, -1.648288945583435527e+00, 5.492805476257101027e+00, 5.492805476257101027e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.180000000000000000e+02, -1.615825821496340797e+00, 1.417427684105760921e+00, 1.417427684105760921e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 4.090000000000000000e+02, -1.583362697409246067e+00, 1.816956989918476495e+01, 1.816956989918476495e+01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.843000000000000000e+03, -1.550899573322151337e+00, 1.862784426688311257e+01, 1.862784426688311257e+01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.821000000000000000e+03, -1.518436449235056607e+00, 1.612596298205987821e+01, 1.612596298205987821e+01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 3.620000000000000000e+02, -1.485973325147961877e+00, 2.255670631985086629e+02, 2.255670631985086629e+02, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 2.830000000000000000e+02, -1.453510201060867146e+00, 1.891774485487890178e+00, 1.891774485487890178e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.850000000000000000e+02, -1.421047076973772416e+00, 1.297955015015847424e+00, 1.297955015015847424e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.633000000000000000e+03, -1.388583952886677686e+00, 4.069078113555314502e+01, 4.069078113555314502e+01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.856000000000000000e+03, -1.356120828799582956e+00, 1.592851064988643905e+01, 1.592851064988643905e+01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 7.000000000000000000e+02, -1.323657704712488226e+00, 1.607060866333062776e+00, 1.607060866333062776e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.959000000000000000e+03, -1.291194580625393495e+00, 3.390577015789495476e+02, 3.390577015789495476e+02, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.995000000000000000e+03, -1.258731456538298765e+00, 7.035712472806147844e+02, 7.035712472806147844e+02, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 5.100000000000000000e+02, -1.226268332451204035e+00, 2.406127241537557637e+00, 2.406127241537557637e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.632000000000000000e+03, -1.193805208364109305e+00, 2.692117383794566443e+00, 2.692117383794566443e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 9.940000000000000000e+02, -1.161342084277014575e+00, 1.178511301977579195e-01, 1.178511301977579195e-01, 1}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 9.640000000000000000e+02, -1.128878960189919844e+00, 6.089914861893711007e-02, 6.089914861893711007e-02, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 8.210000000000000000e+02, -1.096415836102825114e+00, 2.531442276647840051e-01, 2.531442276647840051e-01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 2.040000000000000000e+02, -1.063952712015730384e+00, 1.025240433195795609e+00, 1.025240433195795609e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.777000000000000000e+03, -1.031489587928635654e+00, 2.747109844909737220e+01, 2.747109844909737220e+01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.372000000000000000e+03, -9.990264638415409237e-01, 8.768124086713189058e+01, 8.768124086713189058e+01, 1}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.823000000000000000e+03, -9.665633397544461936e-01, 3.062888846929098108e+01, 3.062888846929098108e+01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.066000000000000000e+03, -9.341002156673514634e-01, 2.456265660963796726e+00, 2.456265660963796726e+00, 1}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.177000000000000000e+03, -9.016370915802567332e-01, 2.503158005400377917e+01, 2.503158005400377917e+01, 1}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 8.700000000000000000e+01, -8.691739674931620030e-01, 1.803319807886362813e+00, 1.803319807886362813e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.660000000000000000e+02, -8.367108434060672728e-01, 1.054967898943793614e+00, 1.054967898943793614e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.367000000000000000e+03, -8.042477193189725426e-01, 5.884539426200973145e-01, 5.884539426200973145e-01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.162000000000000000e+03, -7.717845952318778124e-01, 5.727564927611035195e+00, 5.727564927611035195e+00, 1}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 2.110000000000000000e+02, -7.393214711447830823e-01, 1.621823402198214970e+00, 1.621823402198214970e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 3.730000000000000000e+02, -7.068583470576883521e-01, 2.383634149483684350e+00, 2.383634149483684350e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 5.360000000000000000e+02, -6.743952229705936219e-01, 7.101678495033724170e-01, 7.101678495033724170e-01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 5.660000000000000000e+02, -6.419320988834988917e-01, 7.672108575874040604e+00, 7.672108575874040604e+00, 1}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 2.190000000000000000e+02, -6.094689747964041615e-01, 1.200544339362377499e+01, 1.200544339362377499e+01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.295000000000000000e+03, -5.770058507093094313e-01, 1.227038237941361665e+01, 1.227038237941361665e+01, 1}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 5.660000000000000000e+02, -5.445427266222147011e-01, 1.394928831977098227e+01, 1.394928831977098227e+01, 1}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 2.200000000000000000e+01, -5.120796025351199710e-01, 4.067943717649667335e+00, 4.067943717649667335e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.250000000000000000e+02, -4.796164784480252408e-01, 2.690080145818387081e+01, 2.690080145818387081e+01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 8.400000000000000000e+01, -4.471533543609305106e-01, 4.318065410445850461e+01, 4.318065410445850461e+01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.374000000000000000e+03, -4.146902302738357804e-01, 1.005543483512428837e+00, 1.005543483512428837e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.176000000000000000e+03, -3.822271061867410502e-01, 2.348128179034572938e+00, 2.348128179034572938e+00, 1}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 6.760000000000000000e+02, -3.497639820996463200e-01, 5.091168824543141902e+00, 5.091168824543141902e+00, 1}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.209000000000000000e+03, -3.173008580125515898e-01, 3.284118161510853895e-01, 3.284118161510853895e-01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 8.260000000000000000e+02, -2.848377339254568597e-01, 2.861315812243238721e+00, 2.861315812243238721e+00, 1}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 9.970000000000000000e+02, -2.523746098383621295e-01, 3.595458209423123275e-02, 3.595458209423123275e-02, 1}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.242000000000000000e+03, -2.199114857512673993e-01, 2.900336288934652451e+00, 2.900336288934652451e+00, 1}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.759000000000000000e+03, -1.874483616641726691e-01, 1.219759197546794560e+01, 1.219759197546794560e+01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.933000000000000000e+03, -1.549852375770779389e-01, 1.385988711863547884e+00, 1.385988711863547884e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.060000000000000000e+02, -1.225221134899832087e-01, 2.202625304462625611e+00, 2.202625304462625611e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.479000000000000000e+03, -9.005898940288847854e-02, 7.283960176093683403e-01, 7.283960176093683403e-01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.120000000000000000e+02, -5.759586531579374835e-02, 2.195492383544245474e+00, 2.195492383544245474e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.190000000000000000e+02, -2.513274122869901817e-02, 1.132656498591542515e+01, 1.132656498591542515e+01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 8.390000000000000000e+02, 7.330382858395712020e-03, 2.641396560812857564e-01, 2.641396560812857564e-01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.732000000000000000e+03, 3.979350694549044221e-02, 3.697158313061091661e+01, 3.697158313061091661e+01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.284000000000000000e+03, 7.225663103258517239e-02, 4.140584038288236957e-01, 4.140584038288236957e-01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.797000000000000000e+03, 1.047197551196799026e-01, 2.561655020934901827e+01, 2.561655020934901827e+01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.901000000000000000e+03, 1.371828792067746328e-01, 1.557709559533201338e+00, 1.557709559533201338e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.708000000000000000e+03, 1.696460032938693629e-01, 9.816305903530894383e+00, 9.816305903530894383e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 8.000000000000000000e+02, 2.021091273809640931e-01, 3.616914481772621759e-01, 3.616914481772621759e-01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.020000000000000000e+02, 2.345722514680588233e-01, 1.763838581959776519e+01, 1.763838581959776519e+01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.649000000000000000e+03, 2.670353755551535535e-01, 5.883491038334223155e+00, 5.883491038334223155e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.910000000000000000e+03, 2.994984996422482837e-01, 2.726555808812535009e+00, 2.726555808812535009e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.545000000000000000e+03, 3.319616237293430139e-01, 1.376332841952387298e+01, 1.376332841952387298e+01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.724000000000000000e+03, 3.644247478164377441e-01, 1.248647096534293688e+01, 1.248647096534293688e+01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.313000000000000000e+03, 3.968878719035324742e-01, 8.227673699308155619e-01, 8.227673699308155619e-01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 3.000000000000000000e+02, 4.293509959906272044e-01, 1.596692731711559077e+01, 1.596692731711559077e+01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.328000000000000000e+03, 4.618141200777219346e-01, 4.503515033576457882e-01, 4.503515033576457882e-01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.327000000000000000e+03, 4.942772441648166648e-01, 7.973238532689691738e+00, 7.973238532689691738e+00, 1}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.105000000000000000e+03, 5.267403682519113950e-01, 1.258410373298092910e+00, 1.258410373298092910e+00, 1}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.964000000000000000e+03, 5.592034923390061252e-01, 2.487777142568729172e+00, 2.487777142568729172e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.044000000000000000e+03, 5.916666164261008554e-01, 1.296362432175337087e+00, 1.296362432175337087e+00, 1}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.581000000000000000e+03, 6.241297405131955855e-01, 7.538147520539157931e-01, 7.538147520539157931e-01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 9.250000000000000000e+02, 6.565928646002903157e-01, 3.535533905932737753e+00, 3.535533905932737753e+00, 1}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 3.860000000000000000e+02, 6.890559886873850459e-01, 7.511480339940141970e-01, 7.511480339940141970e-01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.386000000000000000e+03, 7.215191127744797761e-01, 4.873986027464416892e+00, 4.873986027464416892e+00, 1}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 7.810000000000000000e+02, 7.539822368615745063e-01, 4.885059466241448156e-01, 4.885059466241448156e-01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.320000000000000000e+02, 7.864453609486692365e-01, 1.493354467323414259e+00, 1.493354467323414259e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.458000000000000000e+03, 8.189084850357639667e-01, 5.997313070063680307e+00, 5.997313070063680307e+00, 1}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 6.370000000000000000e+02, 8.513716091228586968e-01, 4.666904755831213336e+00, 4.666904755831213336e+00, 1}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 4.860000000000000000e+02, 8.838347332099534270e-01, 2.795791427152964914e+01, 2.795791427152964914e+01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.621000000000000000e+03, 9.162978572970477131e-01, 1.016465997955662059e+00, 1.016465997955662059e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 7.710000000000000000e+02, 9.487609813841428874e-01, 2.739889219826047162e-01, 2.739889219826047162e-01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 5.090000000000000000e+02, 9.812241054712380617e-01, 6.847917742851968859e-01, 6.847917742851968859e-01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.083000000000000000e+03, 1.013687229558332348e+00, 8.384266119783349680e+00, 8.384266119783349680e+00, 1}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 6.880000000000000000e+02, 1.046150353645426634e+00, 1.461041826027833279e+00, 1.461041826027833279e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 3.320000000000000000e+02, 1.078613477732521808e+00, 1.749434554935606556e+01, 1.749434554935606556e+01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 5.140000000000000000e+02, 1.111076601819616982e+00, 9.043523569912160553e+00, 9.043523569912160553e+00, 1}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 2.360000000000000000e+02, 1.143539725906711269e+00, 2.873561600141075978e+00, 2.873561600141075978e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.750000000000000000e+02, 1.176002849993805555e+00, 1.535166038102372710e+01, 1.535166038102372710e+01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.013000000000000000e+03, 1.208465974080900729e+00, 6.087674275115972228e-02, 6.087674275115972228e-02, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.996000000000000000e+03, 1.240929098167995903e+00, 1.547864514421541493e+00, 1.547864514421541493e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.093000000000000000e+03, 1.273392222255090189e+00, 1.596139093455070934e-01, 1.596139093455070934e-01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.812000000000000000e+03, 1.305855346342184475e+00, 1.125824914359758111e+01, 1.125824914359758111e+01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.750000000000000000e+02, 1.338318470429279650e+00, 1.066477320802379669e+00, 1.066477320802379669e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 3.200000000000000000e+01, 1.370781594516374824e+00, 2.207997948995413040e+01, 2.207997948995413040e+01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 8.400000000000000000e+01, 1.403244718603469110e+00, 2.500810083269797257e+00, 2.500810083269797257e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 7.170000000000000000e+02, 1.435707842690563396e+00, 8.004448763031717817e+00, 8.004448763031717817e+00, 1}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 3.190000000000000000e+02, 1.468170966777658570e+00, 1.605132393293462911e+01, 1.605132393293462911e+01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.009000000000000000e+03, 1.500634090864753745e+00, 1.060660171779821193e+00, 1.060660171779821193e+00, 1}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 8.560000000000000000e+02, 1.533097214951848031e+00, 3.394112549695427816e+01, 3.394112549695427816e+01, 1}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.664000000000000000e+03, 1.565560339038942317e+00, 2.041386533512467594e+01, 2.041386533512467594e+01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 3.630000000000000000e+02, 1.598023463126037491e+00, 2.502372331199059730e+01, 2.502372331199059730e+01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 7.440000000000000000e+02, 1.630486587213132665e+00, 1.630804828682487884e+00, 1.630804828682487884e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.836000000000000000e+03, 1.662949711300226951e+00, 1.316572982342881337e+00, 1.316572982342881337e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 6.720000000000000000e+02, 1.695412835387321238e+00, 1.159655121145937962e+01, 1.159655121145937962e+01, 1}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.799000000000000000e+03, 1.727875959474416412e+00, 2.344308374141292450e+00, 2.344308374141292450e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 3.900000000000000000e+02, 1.760339083561511586e+00, 1.188251064803840240e+00, 1.188251064803840240e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.600000000000000000e+02, 1.792802207648605872e+00, 2.048171366195516985e+00, 2.048171366195516985e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.040000000000000000e+02, 1.825265331735700158e+00, 2.111892253143822131e+02, 2.111892253143822131e+02, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 6.110000000000000000e+02, 1.857728455822795333e+00, 1.687512502340901888e+00, 1.687512502340901888e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 5.150000000000000000e+02, 1.890191579909890507e+00, 6.858935777509510778e+00, 6.858935777509510778e+00, 1}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.053000000000000000e+03, 1.922654703996984793e+00, 1.367761292076168644e-01, 1.367761292076168644e-01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 2.630000000000000000e+02, 1.955117828084079079e+00, 1.261834619211829267e+00, 1.261834619211829267e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 5.090000000000000000e+02, 1.987580952171174253e+00, 3.471894295625948530e+02, 3.471894295625948530e+02, 1}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 6.090000000000000000e+02, 2.020044076258269428e+00, 9.215958381464670168e+00, 9.215958381464670168e+00, 1}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.894000000000000000e+03, 2.052507200345363714e+00, 1.149369931601406236e+01, 1.149369931601406236e+01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.915000000000000000e+03, 2.084970324432458000e+00, 1.617506761964227380e+01, 1.617506761964227380e+01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 6.190000000000000000e+02, 2.117433448519553174e+00, 5.882263834761454202e-01, 5.882263834761454202e-01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.775000000000000000e+03, 2.149896572606648348e+00, 2.740038777097871616e+02, 2.740038777097871616e+02, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.607000000000000000e+03, 2.182359696693742634e+00, 1.089375167970137781e+00, 1.089375167970137781e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.860000000000000000e+03, 2.214822820780836921e+00, 1.372712938646570846e+00, 1.372712938646570846e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.580000000000000000e+02, 2.247285944867932095e+00, 1.215069203589944991e+01, 1.215069203589944991e+01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.682000000000000000e+03, 2.279749068955027269e+00, 9.801764731081817894e-01, 9.801764731081817894e-01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 2.290000000000000000e+02, 2.312212193042121555e+00, 7.269057710597707889e+00, 7.269057710597707889e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 5.540000000000000000e+02, 2.344675317129215841e+00, 5.818627756627309244e-01, 5.818627756627309244e-01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.660000000000000000e+02, 2.377138441216311016e+00, 2.680577525043548093e+01, 2.680577525043548093e+01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.918000000000000000e+03, 2.409601565303406190e+00, 1.838878258156517287e+00, 1.838878258156517287e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 2.440000000000000000e+02, 2.442064689390500476e+00, 1.060660171779821193e+00, 1.060660171779821193e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 4.380000000000000000e+02, 2.474527813477594762e+00, 1.602395205753385898e+00, 1.602395205753385898e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 4.310000000000000000e+02, 2.506990937564689936e+00, 8.560505499896713388e+00, 8.560505499896713388e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 6.700000000000000000e+01, 2.539454061651785111e+00, 1.462817354428046279e+00, 1.462817354428046279e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 3.250000000000000000e+02, 2.571917185738879397e+00, 1.289992100813296183e+01, 1.289992100813296183e+01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 5.460000000000000000e+02, 2.604380309825973683e+00, 1.009517228486454643e+00, 1.009517228486454643e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.073000000000000000e+03, 2.636843433913068857e+00, 1.192119977520045560e-01, 1.192119977520045560e-01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.662000000000000000e+03, 2.669306558000164031e+00, 8.700830653261979464e-01, 8.700830653261979464e-01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.380000000000000000e+03, 2.701769682087258317e+00, 6.011198587268189453e-01, 6.011198587268189453e-01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.232000000000000000e+03, 2.734232806174352604e+00, 6.509871953780913545e-01, 6.509871953780913545e-01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.259000000000000000e+03, 2.766695930261447778e+00, 2.474873734152916338e+00, 2.474873734152916338e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.810000000000000000e+03, 2.799159054348542952e+00, 1.789864039878448443e+00, 1.789864039878448443e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 4.330000000000000000e+02, 2.831622178435637238e+00, 8.018590898655448385e+00, 8.018590898655448385e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 6.460000000000000000e+02, 2.864085302522731524e+00, 5.441647837826909750e+00, 5.441647837826909750e+00, 1}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1, 2.896548426609826699e+00, 2.147111472356720174e+00, 2.147111472356720174e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 3.900000000000000000e+01, 2.929011550696921873e+00, 8.711918163080412114e+00, 8.711918163080412114e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.463000000000000000e+03, 2.961474674784016159e+00, 7.613731155566779485e+00, 7.613731155566779485e+00, 1}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.367000000000000000e+03, 2.993937798871110445e+00, 9.042097167089301335e-01, 9.042097167089301335e-01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 6.840000000000000000e+02, 3.026400922958205619e+00, 4.084931313618812010e-01, 4.084931313618812010e-01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 4.810000000000000000e+02, 3.058864047045300794e+00, 6.327386541996865787e+00, 6.327386541996865787e+00, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.618000000000000000e+03, 3.091327171132395080e+00, 1.213866641036906557e+01, 1.213866641036906557e+01, 0}, + {3.261701300000000003e+01, -9.649056400000000622e+01, 1.979000000000000000e+03, 3.123790295219489366e+00, 9.889393411166143721e+01, 9.889393411166143721e+01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 8.300000000000000000e+02, -3.141592653589793116e+00, 4.496092053105674502e+00, 4.496092053105674502e+00, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 4.210000000000000000e+02, -3.109129529502698386e+00, 3.563912967143428201e+00, 3.563912967143428201e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.020000000000000000e+03, -3.076666405415603656e+00, 1.606237840420901009e+00, 1.606237840420901009e+00, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.218000000000000000e+03, -3.044203281328508925e+00, 4.374740361354296225e-01, 4.374740361354296225e-01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 5.520000000000000000e+02, -3.011740157241414195e+00, 4.240254768199785751e+00, 4.240254768199785751e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 7.760000000000000000e+02, -2.979277033154319465e+00, 4.646336532891946480e-01, 4.646336532891946480e-01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 9.190000000000000000e+02, -2.946813909067224735e+00, 3.754779991033441622e+00, 3.754779991033441622e+00, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 5.060000000000000000e+02, -2.914350784980130005e+00, 6.174917619692436688e+00, 6.174917619692436688e+00, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 4.100000000000000000e+02, -2.881887660893035275e+00, 1.144521495717635950e+00, 1.144521495717635950e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.175000000000000000e+03, -2.849424536805940544e+00, 6.893978946285640452e-01, 6.893978946285640452e-01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 6.680000000000000000e+02, -2.816961412718845814e+00, 1.598151898323330045e+00, 1.598151898323330045e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.352000000000000000e+03, -2.784498288631751084e+00, 6.696285290098574094e+00, 6.696285290098574094e+00, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.724000000000000000e+03, -2.752035164544656354e+00, 5.180135133372486962e+02, 5.180135133372486962e+02, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.616000000000000000e+03, -2.719572040457561624e+00, 1.924756631560790510e+01, 1.924756631560790510e+01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.827000000000000000e+03, -2.687108916370466893e+00, 1.053744689143418345e+00, 1.053744689143418345e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.821000000000000000e+03, -2.654645792283372163e+00, 3.067502137713169930e+00, 3.067502137713169930e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.320000000000000000e+03, -2.622182668196277433e+00, 6.443206889358540357e-01, 6.443206889358540357e-01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.580000000000000000e+03, -2.589719544109182703e+00, 9.492548186571411861e+00, 9.492548186571411861e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.906000000000000000e+03, -2.557256420022087973e+00, 1.290996514325271072e+01, 1.290996514325271072e+01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.766000000000000000e+03, -2.524793295934993242e+00, 1.563951040519765634e+01, 1.563951040519765634e+01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.689000000000000000e+03, -2.492330171847898512e+00, 9.089671161920707121e-01, 9.089671161920707121e-01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 5.400000000000000000e+01, -2.459867047760803782e+00, 6.123440938362990948e+01, 6.123440938362990948e+01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 3.200000000000000000e+01, -2.427403923673709052e+00, 1.544909759244862402e+00, 1.544909759244862402e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.287000000000000000e+03, -2.394940799586614322e+00, 1.432859394953451382e+00, 1.432859394953451382e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 6.400000000000000000e+01, -2.362477675499519592e+00, 4.443712161895477664e+01, 4.443712161895477664e+01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 8.550000000000000000e+02, -2.330014551412424861e+00, 3.774637719015758730e-01, 3.774637719015758730e-01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.309000000000000000e+03, -2.297551427325330131e+00, 1.144623443979868815e+00, 1.144623443979868815e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 7.160000000000000000e+02, -2.265088303238235401e+00, 1.660148991674003938e+01, 1.660148991674003938e+01, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 9.550000000000000000e+02, -2.232625179151140671e+00, 2.663134460790517632e+00, 2.663134460790517632e+00, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.960000000000000000e+03, -2.200162055064045941e+00, 2.255480411687404096e+00, 2.255480411687404096e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.101000000000000000e+03, -2.167698930976951210e+00, 1.283599100647490054e+00, 1.283599100647490054e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 5.650000000000000000e+02, -2.135235806889856480e+00, 9.924642822603239267e+00, 9.924642822603239267e+00, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.744000000000000000e+03, -2.102772682802761750e+00, 2.799970320380887756e+01, 2.799970320380887756e+01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.001000000000000000e+03, -2.070309558715667020e+00, 1.581202074372532529e+01, 1.581202074372532529e+01, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.931000000000000000e+03, -2.037846434628572290e+00, 1.782382737818156260e+00, 1.782382737818156260e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.501000000000000000e+03, -2.005383310541477559e+00, 1.544572412816466178e+00, 1.544572412816466178e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.516000000000000000e+03, -1.972920186454382829e+00, 1.060606906114381687e+00, 1.060606906114381687e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.291000000000000000e+03, -1.940457062367288099e+00, 6.407922365113163377e-01, 6.407922365113163377e-01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.257000000000000000e+03, -1.907993938280193369e+00, 6.193060948049033065e+00, 6.193060948049033065e+00, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 8.740000000000000000e+02, -1.875530814193098639e+00, 3.970446378487492378e+00, 3.970446378487492378e+00, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.550000000000000000e+03, -1.843067690106003909e+00, 1.009828744681141366e+00, 1.009828744681141366e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 8.950000000000000000e+02, -1.810604566018909178e+00, 3.901261144511485868e-01, 3.901261144511485868e-01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 4.150000000000000000e+02, -1.778141441931814448e+00, 1.684577098265318185e+01, 1.684577098265318185e+01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.207000000000000000e+03, -1.745678317844719718e+00, 1.663565448066291097e+01, 1.663565448066291097e+01, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.100000000000000000e+01, -1.713215193757624988e+00, 1.497410621535875386e+01, 1.497410621535875386e+01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1, -1.680752069670530258e+00, 3.384808331005128679e+00, 3.384808331005128679e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.710000000000000000e+02, -1.648288945583435527e+00, 1.848432877213154413e+01, 1.848432877213154413e+01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.801000000000000000e+03, -1.615825821496340797e+00, 5.106100824014347062e+00, 5.106100824014347062e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.136000000000000000e+03, -1.583362697409246067e+00, 1.064025329294688627e+00, 1.064025329294688627e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 5.160000000000000000e+02, -1.550899573322151337e+00, 1.756260231286923812e+01, 1.756260231286923812e+01, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.936000000000000000e+03, -1.518436449235056607e+00, 1.380034832886794183e+00, 1.380034832886794183e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.400000000000000000e+03, -1.485973325147961877e+00, 2.744705636558582018e+00, 2.744705636558582018e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.817000000000000000e+03, -1.453510201060867146e+00, 1.098098819688070549e+00, 1.098098819688070549e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.664000000000000000e+03, -1.421047076973772416e+00, 5.951601675179548323e+01, 5.951601675179548323e+01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 4.070000000000000000e+02, -1.388583952886677686e+00, 8.534037731343822486e+00, 8.534037731343822486e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.697000000000000000e+03, -1.356120828799582956e+00, 1.349064280860386988e+00, 1.349064280860386988e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 4.160000000000000000e+02, -1.323657704712488226e+00, 1.274090179353081176e+01, 1.274090179353081176e+01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 3.390000000000000000e+02, -1.291194580625393495e+00, 8.301863240072093753e-01, 8.301863240072093753e-01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 5.400000000000000000e+02, -1.258731456538298765e+00, 5.625860572543209814e-01, 5.625860572543209814e-01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 4.620000000000000000e+02, -1.226268332451204035e+00, 1.229592262447146478e+00, 1.229592262447146478e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 8.580000000000000000e+02, -1.193805208364109305e+00, 1.277967135727675796e+01, 1.277967135727675796e+01, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.036000000000000000e+03, -1.161342084277014575e+00, 1.694983656558866625e-01, 1.694983656558866625e-01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.962000000000000000e+03, -1.128878960189919844e+00, 4.201320880781101330e+00, 4.201320880781101330e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 7.660000000000000000e+02, -1.096415836102825114e+00, 7.335175526188858264e+00, 7.335175526188858264e+00, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 7.650000000000000000e+02, -1.063952712015730384e+00, 2.044640691064215865e+00, 2.044640691064215865e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 7.870000000000000000e+02, -1.031489587928635654e+00, 3.037525720055716860e+00, 3.037525720055716860e+00, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 8.050000000000000000e+02, -9.990264638415409237e-01, 7.715622002549675784e-01, 7.715622002549675784e-01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 3.450000000000000000e+02, -9.665633397544461936e-01, 1.021421088336021477e+01, 1.021421088336021477e+01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.322000000000000000e+03, -9.341002156673514634e-01, 9.640912819852692550e+00, 9.640912819852692550e+00, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.982000000000000000e+03, -9.016370915802567332e-01, 4.159909486848904159e+00, 4.159909486848904159e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 6.470000000000000000e+02, -8.691739674931620030e-01, 2.181909523024881992e+01, 2.181909523024881992e+01, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.260000000000000000e+03, -8.367108434060672728e-01, 5.266446341102500206e+00, 5.266446341102500206e+00, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.689000000000000000e+03, -8.042477193189725426e-01, 8.674325906718705070e-01, 8.674325906718705070e-01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 2.270000000000000000e+02, -7.717845952318778124e-01, 3.307072924470162878e+00, 3.307072924470162878e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 5.780000000000000000e+02, -7.393214711447830823e-01, 6.274268765564174899e-01, 6.274268765564174899e-01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.755000000000000000e+03, -7.068583470576883521e-01, 1.948329998285850406e+00, 1.948329998285850406e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.739000000000000000e+03, -6.743952229705936219e-01, 9.034159732790900676e-01, 9.034159732790900676e-01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 8.040000000000000000e+02, -6.419320988834988917e-01, 1.139683092364016836e+01, 1.139683092364016836e+01, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 2.360000000000000000e+02, -6.094689747964041615e-01, 3.211667742557020944e+01, 3.211667742557020944e+01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.102000000000000000e+03, -5.770058507093094313e-01, 4.458917407223915497e+00, 4.458917407223915497e+00, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.661000000000000000e+03, -5.445427266222147011e-01, 9.855226424285168374e-01, 9.855226424285168374e-01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 3.300000000000000000e+02, -5.120796025351199710e-01, 1.132812260238002633e+00, 1.132812260238002633e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 3.800000000000000000e+01, -4.796164784480252408e-01, 1.556398417198453465e+01, 1.556398417198453465e+01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 8.110000000000000000e+02, -4.471533543609305106e-01, 7.057980068307653454e+00, 7.057980068307653454e+00, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.420000000000000000e+03, -4.146902302738357804e-01, 4.878209320834701046e+00, 4.878209320834701046e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 5.580000000000000000e+02, -3.822271061867410502e-01, 2.852963390869314608e+00, 2.852963390869314608e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 5.770000000000000000e+02, -3.497639820996463200e-01, 1.546888004995836923e+02, 1.546888004995836923e+02, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 9.500000000000000000e+02, -3.173008580125515898e-01, 1.571733945162320512e-01, 1.571733945162320512e-01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 9.080000000000000000e+02, -2.848377339254568597e-01, 1.709209331867639348e-01, 1.709209331867639348e-01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 2.620000000000000000e+02, -2.523746098383621295e-01, 4.798174584031198719e+01, 4.798174584031198719e+01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 2.850000000000000000e+02, -2.199114857512673993e-01, 1.487572743652623597e+00, 1.487572743652623597e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 9.750000000000000000e+02, -1.874483616641726691e-01, 2.025231468252456146e+00, 2.025231468252456146e+00, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.170000000000000000e+03, -1.549852375770779389e-01, 2.997394702070449668e+00, 2.997394702070449668e+00, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 8.170000000000000000e+02, -1.225221134899832087e-01, 3.075849388110490357e-01, 3.075849388110490357e-01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 2.400000000000000000e+02, -9.005898940288847854e-02, 5.431850513407009373e+01, 5.431850513407009373e+01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.007000000000000000e+03, -5.759586531579374835e-02, 4.400652308549352298e+00, 4.400652308549352298e+00, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 9.480000000000000000e+02, -2.513274122869901817e-02, 6.555597661875883775e-01, 6.555597661875883775e-01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.655000000000000000e+03, 7.330382858395712020e-03, 1.957723752644040971e+01, 1.957723752644040971e+01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 3.670000000000000000e+02, 3.979350694549044221e-02, 2.771504127346748003e+00, 2.771504127346748003e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 4.000000000000000000e+01, 7.225663103258517239e-02, 2.971350281483841016e+01, 2.971350281483841016e+01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.224000000000000000e+03, 1.047197551196799026e-01, 4.784470862248194067e-01, 4.784470862248194067e-01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.300000000000000000e+02, 1.371828792067746328e-01, 1.554490948116361348e+00, 1.554490948116361348e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.059000000000000000e+03, 1.696460032938693629e-01, 7.575389551706083191e-01, 7.575389551706083191e-01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.915000000000000000e+03, 2.021091273809640931e-01, 2.450431482343054856e+00, 2.450431482343054856e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.884000000000000000e+03, 2.345722514680588233e-01, 7.326301182799713985e+00, 7.326301182799713985e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.281000000000000000e+03, 2.670353755551535535e-01, 3.687015652706886026e+00, 3.687015652706886026e+00, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.695000000000000000e+03, 2.994984996422482837e-01, 9.955149421279421063e+01, 9.955149421279421063e+01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.157000000000000000e+03, 3.319616237293430139e-01, 2.523857358702783049e+00, 2.523857358702783049e+00, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.629000000000000000e+03, 3.644247478164377441e-01, 9.611524036075733690e+00, 9.611524036075733690e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.920000000000000000e+03, 3.968878719035324742e-01, 4.680888194105290268e+01, 4.680888194105290268e+01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.586000000000000000e+03, 4.293509959906272044e-01, 2.197077248869506505e+00, 2.197077248869506505e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 6.350000000000000000e+02, 4.618141200777219346e-01, 8.821259693550493886e-01, 8.821259693550493886e-01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 2.860000000000000000e+02, 4.942772441648166648e-01, 9.642007888750946387e-01, 9.642007888750946387e-01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.654000000000000000e+03, 5.267403682519113950e-01, 7.951808309207613057e+00, 7.951808309207613057e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.972000000000000000e+03, 5.592034923390061252e-01, 1.773947632770843885e+00, 1.773947632770843885e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 7.270000000000000000e+02, 5.916666164261008554e-01, 5.489507745769079960e+00, 5.489507745769079960e+00, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 2.900000000000000000e+01, 6.241297405131955855e-01, 4.607580710090708465e+00, 4.607580710090708465e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 8.000000000000000000e+02, 6.565928646002903157e-01, 6.000685831859129404e-01, 6.000685831859129404e-01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.166000000000000000e+03, 6.890559886873850459e-01, 2.358671942711265146e+01, 2.358671942711265146e+01, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.968000000000000000e+03, 7.215191127744797761e-01, 1.565976710507292147e+01, 1.565976710507292147e+01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 5.890000000000000000e+02, 7.539822368615745063e-01, 1.673232437566118946e+00, 1.673232437566118946e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.217000000000000000e+03, 7.864453609486692365e-01, 3.319439114594957996e+00, 3.319439114594957996e+00, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 5.700000000000000000e+01, 8.189084850357639667e-01, 2.238239635666088745e+01, 2.238239635666088745e+01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.049000000000000000e+03, 8.513716091228586968e-01, 1.233089698311373050e+00, 1.233089698311373050e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 6.920000000000000000e+02, 8.838347332099534270e-01, 3.994720058678168151e+00, 3.994720058678168151e+00, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.700000000000000000e+03, 9.162978572970477131e-01, 1.601432720108899588e+00, 1.601432720108899588e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.995000000000000000e+03, 9.487609813841428874e-01, 2.219432415915904677e+00, 2.219432415915904677e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 2.620000000000000000e+02, 9.812241054712380617e-01, 2.399087292015599360e+01, 2.399087292015599360e+01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 2.000000000000000000e+00, 1.013687229558332348e+00, 1.365590450357100494e+01, 1.365590450357100494e+01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.969000000000000000e+03, 1.046150353645426634e+00, 1.815084722120831051e+00, 1.815084722120831051e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.459000000000000000e+03, 1.078613477732521808e+00, 1.265347131492867039e+00, 1.265347131492867039e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 8.500000000000000000e+01, 1.111076601819616982e+00, 4.345431828688349896e+01, 4.345431828688349896e+01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.494000000000000000e+03, 1.143539725906711269e+00, 9.183210819029778094e+00, 9.183210819029778094e+00, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 5.260000000000000000e+02, 1.176002849993805555e+00, 6.942864602350854453e-01, 6.942864602350854453e-01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.521000000000000000e+03, 1.208465974080900729e+00, 1.752510368183169298e+00, 1.752510368183169298e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 6.420000000000000000e+02, 1.240929098167995903e+00, 4.866088255937152107e-01, 4.866088255937152107e-01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.180000000000000000e+02, 1.273392222255090189e+00, 1.259837454948021573e+00, 1.259837454948021573e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 6.850000000000000000e+02, 1.305855346342184475e+00, 6.269296843394426277e-01, 6.269296843394426277e-01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 8.920000000000000000e+02, 1.338318470429279650e+00, 1.373976892090984236e+01, 1.373976892090984236e+01, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.787000000000000000e+03, 1.370781594516374824e+00, 2.443828305423565084e+01, 2.443828305423565084e+01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 2.850000000000000000e+02, 1.403244718603469110e+00, 1.218392913848815340e+01, 1.218392913848815340e+01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.910000000000000000e+03, 1.435707842690563396e+00, 1.473421553520975458e+01, 1.473421553520975458e+01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.053000000000000000e+03, 1.468170966777658570e+00, 1.939911295532286417e-01, 1.939911295532286417e-01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.154000000000000000e+03, 1.500634090864753745e+00, 5.902016182106789577e-01, 5.902016182106789577e-01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.643000000000000000e+03, 1.533097214951848031e+00, 9.634480237798974667e-01, 9.634480237798974667e-01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.390000000000000000e+02, 1.565560339038942317e+00, 4.722541312651922851e+01, 4.722541312651922851e+01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 4.170000000000000000e+02, 1.598023463126037491e+00, 1.362841837179133320e+00, 1.362841837179133320e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 5.970000000000000000e+02, 1.630486587213132665e+00, 3.285856334633614040e+01, 3.285856334633614040e+01, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.018000000000000000e+03, 1.662949711300226951e+00, 3.481520212029148631e+00, 3.481520212029148631e+00, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 3.890000000000000000e+02, 1.695412835387321238e+00, 8.612074086374557069e+00, 8.612074086374557069e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.211000000000000000e+03, 1.727875959474416412e+00, 8.886869769138558084e+00, 8.886869769138558084e+00, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.550000000000000000e+02, 1.760339083561511586e+00, 1.072442380935824113e+00, 1.072442380935824113e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 7.910000000000000000e+02, 1.792802207648605872e+00, 1.289247750943785498e+01, 1.289247750943785498e+01, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.894000000000000000e+03, 1.825265331735700158e+00, 9.954339113547419515e+00, 9.954339113547419515e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 8.500000000000000000e+01, 1.857728455822795333e+00, 2.536244257989309414e+00, 2.536244257989309414e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.486000000000000000e+03, 1.890191579909890507e+00, 1.533174425342896274e+00, 1.533174425342896274e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.684000000000000000e+03, 1.922654703996984793e+00, 2.450397926868205616e+02, 2.450397926868205616e+02, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.751000000000000000e+03, 1.955117828084079079e+00, 1.089025666261823178e+00, 1.089025666261823178e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.831000000000000000e+03, 1.987580952171174253e+00, 1.076043694914923687e+00, 1.076043694914923687e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.146000000000000000e+03, 2.020044076258269428e+00, 2.174427518232470435e-01, 2.174427518232470435e-01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.605000000000000000e+03, 2.052507200345363714e+00, 7.250718355216031341e+01, 7.250718355216031341e+01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 6.390000000000000000e+02, 2.084970324432458000e+00, 7.548797492278568333e-01, 7.548797492278568333e-01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.978000000000000000e+03, 2.117433448519553174e+00, 1.179753551796372513e+01, 1.179753551796372513e+01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.512000000000000000e+03, 2.149896572606648348e+00, 7.562649621955023882e+00, 7.562649621955023882e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.510000000000000000e+02, 2.182359696693742634e+00, 2.522986339527910182e+00, 2.522986339527910182e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.565000000000000000e+03, 2.214822820780836921e+00, 7.377938415831409857e-01, 7.377938415831409857e-01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.583000000000000000e+03, 2.247285944867932095e+00, 2.098776429255865423e+02, 2.098776429255865423e+02, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.012000000000000000e+03, 2.279749068955027269e+00, 2.252436417210676445e-01, 2.252436417210676445e-01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.663000000000000000e+03, 2.312212193042121555e+00, 2.916753725295790911e+00, 2.916753725295790911e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.154000000000000000e+03, 2.344675317129215841e+00, 2.803457686500725465e+00, 2.803457686500725465e+00, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.502000000000000000e+03, 2.377138441216311016e+00, 2.424431204770856496e+01, 2.424431204770856496e+01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 6.930000000000000000e+02, 2.409601565303406190e+00, 7.452555449396317755e+00, 7.452555449396317755e+00, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 6.770000000000000000e+02, 2.442064689390500476e+00, 4.739037614183972735e+00, 4.739037614183972735e+00, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.710000000000000000e+02, 2.474527813477594762e+00, 3.017849595450048383e+00, 3.017849595450048383e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 7.610000000000000000e+02, 2.506990937564689936e+00, 3.398464879659086613e-01, 3.398464879659086613e-01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 4.450000000000000000e+02, 2.539454061651785111e+00, 4.448088783641857447e+01, 4.448088783641857447e+01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.648000000000000000e+03, 2.571917185738879397e+00, 4.894476506942117666e+00, 4.894476506942117666e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.700000000000000000e+01, 2.604380309825973683e+00, 1.706261869038478451e+01, 1.706261869038478451e+01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.796000000000000000e+03, 2.636843433913068857e+00, 1.765161223159078530e+00, 1.765161223159078530e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 9.670000000000000000e+02, 2.669306558000164031e+00, 1.948670381037573840e-01, 1.948670381037573840e-01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 2.100000000000000000e+01, 2.701769682087258317e+00, 1.620365421598859612e+01, 1.620365421598859612e+01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 6.810000000000000000e+02, 2.734232806174352604e+00, 4.051184299164527047e+00, 4.051184299164527047e+00, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 6.350000000000000000e+02, 2.766695930261447778e+00, 6.457668579489117544e-01, 6.457668579489117544e-01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 4.160000000000000000e+02, 2.799159054348542952e+00, 5.065659749235142506e+00, 5.065659749235142506e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.341000000000000000e+03, 2.831622178435637238e+00, 1.103273184767418869e+01, 1.103273184767418869e+01, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.855000000000000000e+03, 2.864085302522731524e+00, 2.154499285859778013e+00, 2.154499285859778013e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.600000000000000000e+02, 2.896548426609826699e+00, 2.171042791170226138e+00, 2.171042791170226138e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.531000000000000000e+03, 2.929011550696921873e+00, 9.135863520629767365e+00, 9.135863520629767365e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 9.020000000000000000e+02, 2.961474674784016159e+00, 4.273515967789081049e-01, 4.273515967789081049e-01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.310000000000000000e+02, 2.993937798871110445e+00, 2.592219897795987382e+00, 2.592219897795987382e+00, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.296000000000000000e+03, 3.026400922958205619e+00, 2.796705651297611794e+01, 2.796705651297611794e+01, 1}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.782000000000000000e+03, 3.058864047045300794e+00, 9.451444050263695384e-01, 9.451444050263695384e-01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.720000000000000000e+03, 3.091327171132395080e+00, 1.472052572264389170e+01, 1.472052572264389170e+01, 0}, + {3.261791232160592102e+01, -9.649003014642013909e+01, 1.263000000000000000e+03, 3.123790295219489366e+00, 5.001868340274644442e-01, 5.001868340274644442e-01, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 2.790000000000000000e+02, -3.141592653589793116e+00, 2.462740099126627028e+05, 2.462740099126627028e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 9.240000000000000000e+02, -3.109129529502698386e+00, 3.701227883039516746e+04, 3.701227883039516746e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.132000000000000000e+03, -3.076666405415603656e+00, 4.001952648820712930e+05, 4.001952648820712930e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.750000000000000000e+02, -3.044203281328508925e+00, 4.573660188576278742e+05, 4.573660188576278742e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.409000000000000000e+03, -3.011740157241414195e+00, 1.359474361775812031e+04, 1.359474361775812031e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.698000000000000000e+03, -2.979277033154319465e+00, 1.940340683774233330e+05, 1.940340683774233330e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.242000000000000000e+03, -2.946813909067224735e+00, 4.001952649824618129e+05, 4.001952649824618129e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 3.460000000000000000e+02, -2.914350784980130005e+00, 1.280624850826470501e+05, 1.280624850826470501e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.396000000000000000e+03, -2.881887660893035275e+00, 1.185763748806571239e+05, 1.185763748806571239e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 5.900000000000000000e+02, -2.849424536805940544e+00, 9.018484850698664377e+04, 9.018484850698664377e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.079000000000000000e+03, -2.816961412718845814e+00, 5.335936864730431698e+05, 5.335936864730431698e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.533000000000000000e+03, -2.784498288631751084e+00, 2.748121995074961524e+04, 2.748121995074961524e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 9.880000000000000000e+02, -2.752035164544656354e+00, 1.103986937489391712e+05, 1.103986937489391712e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.329000000000000000e+03, -2.719572040457561624e+00, 1.265439573450385251e+04, 1.265439573450385251e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 3.220000000000000000e+02, -2.687108916370466893e+00, 1.730574123075809039e+05, 1.730574123075809039e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.732000000000000000e+03, -2.654645792283372163e+00, 1.489098664733316691e+05, 1.489098664733316691e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 3.970000000000000000e+02, -2.622182668196277433e+00, 6.339726981811282167e+04, 6.339726981811282167e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 3.710000000000000000e+02, -2.589719544109182703e+00, 1.103986940151730232e+05, 1.103986940151730232e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.982000000000000000e+03, -2.557256420022087973e+00, 2.065523959704314766e+05, 2.065523959704314766e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.241000000000000000e+03, -2.524793295934993242e+00, 1.883271835206038377e+05, 1.883271835206038377e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 7.990000000000000000e+02, -2.492330171847898512e+00, 2.520915054728441828e+04, 2.520915054728441828e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.556000000000000000e+03, -2.459867047760803782e+00, 3.093296738890135748e+04, 3.093296738890135748e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 8.650000000000000000e+02, -2.427403923673709052e+00, 4.268749492096277536e+05, 4.268749492096277536e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.410000000000000000e+03, -2.394940799586614322e+00, 1.435678081613464383e+04, 1.435678081613464383e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.990000000000000000e+03, -2.362477675499519592e+00, 1.333984224104025925e+05, 1.333984224104025925e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.749000000000000000e+03, -2.330014551412424861e+00, 1.829464074096073746e+05, 1.829464074096073746e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.745000000000000000e+03, -2.297551427325330131e+00, 6.403124259102934040e+06, 6.403124259102934040e+06, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.404000000000000000e+03, -2.265088303238235401e+00, 1.676210535027582227e+04, 1.676210535027582227e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 8.900000000000000000e+02, -2.232625179151140671e+00, 1.730574118352776859e+05, 1.730574118352776859e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 7.310000000000000000e+02, -2.200162055064045941e+00, 1.119427314730431863e+04, 1.119427314730431863e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 8.760000000000000000e+02, -2.167698930976951210e+00, 1.561737619032483199e+05, 1.561737619032483199e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.560000000000000000e+02, -2.135235806889856480e+00, 2.520915065057046013e+04, 2.520915065057046013e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.367000000000000000e+03, -2.102772682802761750e+00, 1.240915550909219019e+04, 1.240915550909219019e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.859000000000000000e+03, -2.070309558715667020e+00, 1.109726909227428405e+04, 1.109726909227428405e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.545000000000000000e+03, -2.037846434628572290e+00, 2.072208494831626740e+04, 2.072208494831626740e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 9.110000000000000000e+02, -2.005383310541477559e+00, 2.462740091439273965e+05, 2.462740091439273965e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.188000000000000000e+03, -1.972920186454382829e+00, 2.207973875452689826e+05, 2.207973875452689826e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.289000000000000000e+03, -1.940457062367288099e+00, 1.092683317524538506e+04, 1.092683317524538506e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 4.250000000000000000e+02, -1.907993938280193369e+00, 1.391983532682953519e+05, 1.391983532682953519e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 5.910000000000000000e+02, -1.875530814193098639e+00, 1.100193169065992151e+04, 1.100193169065992151e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 9.420000000000000000e+02, -1.843067690106003909e+00, 2.910511017074631673e+04, 2.910511017074631673e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 7.000000000000000000e+01, -1.810604566018909178e+00, 2.635030564280461113e+04, 2.635030564280461113e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.024000000000000000e+03, -1.778141441931814448e+00, 4.477709256961775100e+04, 4.477709256961775100e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.306000000000000000e+03, -1.745678317844719718e+00, 2.561249696435488295e+05, 2.561249696435488295e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.880000000000000000e+02, -1.713215193757624988e+00, 1.248172370989455703e+04, 1.248172370989455703e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 8.970000000000000000e+02, -1.680752069670530258e+00, 1.561737618987087917e+05, 1.561737618987087917e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.918000000000000000e+03, -1.648288945583435527e+00, 1.306760055170549458e+05, 1.306760055170549458e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 6.560000000000000000e+02, -1.615825821496340797e+00, 1.185763748528350552e+05, 1.185763748528350552e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 2.980000000000000000e+02, -1.583362697409246067e+00, 1.730574123425300641e+05, 1.730574123425300641e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.214000000000000000e+03, -1.550899573322151337e+00, 1.940340678551782039e+05, 1.940340678551782039e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.889000000000000000e+03, -1.518436449235056607e+00, 1.115526876008658655e+04, 1.115526876008658655e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.538000000000000000e+03, -1.485973325147961877e+00, 1.600781062183434842e+05, 1.600781062183434842e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 7.160000000000000000e+02, -1.453510201060867146e+00, 3.201562120290968101e+06, 3.201562120290968101e+06, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 8.800000000000000000e+01, -1.421047076973772416e+00, 3.123475253613168388e+04, 3.123475253613168388e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.219000000000000000e+03, -1.388583952886677686e+00, 2.207973875622555497e+05, 2.207973875622555497e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.982000000000000000e+03, -1.356120828799582956e+00, 6.669921119878516765e+04, 6.669921119878516765e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 5.600000000000000000e+01, -1.323657704712488226e+00, 1.633450069445373447e+04, 1.633450069445373447e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 6.300000000000000000e+01, -1.291194580625393495e+00, 1.829464077631936816e+05, 1.829464077631936816e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 8.040000000000000000e+02, -1.258731456538298765e+00, 2.884290197717451156e+04, 2.884290197717451156e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.388000000000000000e+03, -1.226268332451204035e+00, 2.561249697324241861e+05, 2.561249697324241861e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.684000000000000000e+03, -1.193805208364109305e+00, 8.003905319624445401e+05, 8.003905319624445401e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.768000000000000000e+03, -1.161342084277014575e+00, 1.280624852092321264e+06, 1.280624852092321264e+06, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 7.880000000000000000e+02, -1.128878960189919844e+00, 2.120239814300535727e+04, 2.120239814300535727e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.348000000000000000e+03, -1.096415836102825114e+00, 2.134374747387055249e+05, 2.134374747387055249e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.418000000000000000e+03, -1.063952712015730384e+00, 1.257981187476360356e+04, 1.257981187476360356e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.634000000000000000e+03, -1.031489587928635654e+00, 1.561737622713803430e+05, 1.561737622713803430e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 6.180000000000000000e+02, -9.990264638415409237e-01, 4.743054994911277754e+04, 4.743054994911277754e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 2.660000000000000000e+02, -9.665633397544461936e-01, 2.561249703387094487e+05, 2.561249703387094487e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.638000000000000000e+03, -9.341002156673514634e-01, 1.164204409695499489e+05, 1.164204409695499489e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 2.380000000000000000e+02, -9.016370915802567332e-01, 1.119427318199858200e+04, 1.119427318199858200e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.110000000000000000e+02, -8.691739674931620030e-01, 1.238515332357775515e+04, 1.238515332357775515e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.475000000000000000e+03, -8.367108434060672728e-01, 5.041830115151200152e+04, 5.041830115151200152e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.828000000000000000e+03, -8.042477193189725426e-01, 1.208136653622718295e+05, 1.208136653622718295e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.932000000000000000e+03, -7.717845952318778124e-01, 1.170589446315707210e+04, 1.170589446315707210e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 3.600000000000000000e+01, -7.393214711447830823e-01, 3.617584335432633816e+04, 3.617584335432633816e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 7.420000000000000000e+02, -7.068583470576883521e-01, 1.422916497784830281e+05, 1.422916497784830281e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 5.710000000000000000e+02, -6.743952229705936219e-01, 3.701227887062684022e+04, 3.701227887062684022e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.710000000000000000e+02, -6.419320988834988917e-01, 4.326435313692635827e+04, 4.326435313692635827e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 8.320000000000000000e+02, -6.094689747964041615e-01, 1.356594118333646293e+04, 1.356594118333646293e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 9.260000000000000000e+02, -5.770058507093094313e-01, 1.958141968699281279e+04, 1.958141968699281279e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.607000000000000000e+03, -5.445427266222147011e-01, 1.143415044967565191e+05, 1.143415044967565191e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.404000000000000000e+03, -5.120796025351199710e-01, 1.365271693775130734e+04, 1.365271693775130734e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.779000000000000000e+03, -4.796164784480252408e-01, 3.049106791012385511e+05, 3.049106791012385511e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.796000000000000000e+03, -4.471533543609305106e-01, 1.137322249053534142e+04, 1.137322249053534142e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.652000000000000000e+03, -4.146902302738357804e-01, 1.730574122710911033e+05, 1.730574122710911033e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.931000000000000000e+03, -3.822271061867410502e-01, 1.085275300215962670e+04, 1.085275300215962670e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 6.800000000000000000e+01, -3.497639820996463200e-01, 5.122499417077533872e+04, 5.122499417077533872e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.171000000000000000e+03, -3.173008580125515898e-01, 1.255514556583238736e+05, 1.255514556583238736e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.113000000000000000e+03, -2.848377339254568597e-01, 2.656898024037923096e+04, 2.656898024037923096e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 9.100000000000000000e+01, -2.523746098383621295e-01, 2.078936451199253497e+04, 2.078936451199253497e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 8.300000000000000000e+01, -2.199114857512673993e-01, 1.778645630628902290e+05, 1.778645630628902290e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.073000000000000000e+03, -1.874483616641726691e-01, 5.335936864700758597e+05, 5.335936864700758597e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.432000000000000000e+03, -1.549852375770779389e-01, 1.231370047061402292e+05, 1.231370047061402292e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.466000000000000000e+03, -1.225221134899832087e-01, 1.455255510434401185e+04, 1.455255510434401185e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 7.900000000000000000e+01, -9.005898940288847854e-02, 2.783967074152650312e+05, 2.783967074152650312e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.644000000000000000e+03, -5.759586531579374835e-02, 1.872258553691687121e+04, 1.872258553691687121e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.557000000000000000e+03, -2.513274122869901817e-02, 4.963662208950416243e+04, 4.963662208950416243e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.181000000000000000e+03, 7.330382858395712020e-03, 1.489098660165569745e+05, 1.489098660165569745e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.253000000000000000e+03, 3.979350694549044221e-02, 2.964409370338879671e+04, 2.964409370338879671e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.339000000000000000e+03, 7.225663103258517239e-02, 2.667968434133233386e+05, 2.667968434133233386e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.189000000000000000e+03, 1.047197551196799026e-01, 1.735264021362471613e+04, 1.735264021362471613e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 2.130000000000000000e+02, 1.371828792067746328e-01, 1.778645628226429471e+04, 1.778645628226429471e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.570000000000000000e+02, 1.696460032938693629e-01, 5.666481650600911962e+04, 5.666481650600911962e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.105000000000000000e+03, 2.021091273809640931e-01, 1.535521399967218713e+04, 1.535521399967218713e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 5.190000000000000000e+02, 2.345722514680588233e-01, 3.370065392876830301e+05, 3.370065392876830301e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 9.330000000000000000e+02, 2.670353755551535535e-01, 3.577164378552019480e+04, 3.577164378552019480e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.073000000000000000e+03, 2.994984996422482837e-01, 1.199086935887810978e+04, 1.199086935887810978e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.741000000000000000e+03, 3.319616237293430139e-01, 2.561249703548343969e+05, 2.561249703548343969e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 5.330000000000000000e+02, 3.644247478164377441e-01, 4.573660175676995423e+05, 4.573660175676995423e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 8.390000000000000000e+02, 3.968878719035324742e-01, 1.085275294651676959e+05, 1.085275294651676959e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.218000000000000000e+03, 4.293509959906272044e-01, 4.268749492858899757e+05, 4.268749492858899757e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.270000000000000000e+03, 4.618141200777219346e-01, 3.300579505298512959e+04, 3.300579505298512959e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.151000000000000000e+03, 4.942772441648166648e-01, 1.829464068092308298e+04, 1.829464068092308298e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.021000000000000000e+03, 5.267403682519113950e-01, 1.280624847490013417e+04, 1.280624847490013417e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.104000000000000000e+03, 5.592034923390061252e-01, 5.821022034413766814e+05, 5.821022034413766814e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.306000000000000000e+03, 5.916666164261008554e-01, 1.143415043051557150e+05, 1.143415043051557150e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 9.970000000000000000e+02, 6.241297405131955855e-01, 1.448670641953212726e+04, 1.448670641953212726e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 3.110000000000000000e+02, 6.565928646002903157e-01, 1.255514559993645089e+05, 1.255514559993645089e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 2.860000000000000000e+02, 6.890559886873850459e-01, 1.123355132866146887e+05, 1.123355132866146887e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.906000000000000000e+03, 7.215191127744797761e-01, 1.255514562643354875e+05, 1.255514562643354875e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.784000000000000000e+03, 7.539822368615745063e-01, 1.296179000289703254e+04, 1.296179000289703254e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 7.180000000000000000e+02, 7.864453609486692365e-01, 1.255514556968184188e+05, 1.255514556968184188e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.670000000000000000e+02, 8.189084850357639667e-01, 9.147320377892374527e+05, 9.147320377892374527e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 9.400000000000000000e+01, 8.513716091228586968e-01, 1.455255515791161160e+05, 1.455255515791161160e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 2.740000000000000000e+02, 8.838347332099534270e-01, 2.039211547137486923e+04, 2.039211547137486923e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.341000000000000000e+03, 9.162978572970477131e-01, 2.561249696789143782e+05, 2.561249696789143782e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.350000000000000000e+02, 9.487609813841428874e-01, 1.231370051278101309e+05, 1.231370051278101309e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.635000000000000000e+03, 9.812241054712380617e-01, 3.201562126588069950e+05, 3.201562126588069950e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.843000000000000000e+03, 1.013687229558332348e+00, 1.883271842699714762e+05, 1.883271842699714762e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 3.000000000000000000e+00, 1.046150353645426634e+00, 1.240915557411313966e+04, 1.240915557411313966e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 8.100000000000000000e+01, 1.078613477732521808e+00, 2.246710270318391485e+04, 2.246710270318391485e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 5.020000000000000000e+02, 1.111076601819616982e+00, 4.573660176511270110e+05, 4.573660176511270110e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.771000000000000000e+03, 1.143539725906711269e+00, 2.407189571669876386e+04, 2.407189571669876386e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.906000000000000000e+03, 1.176002849993805555e+00, 4.268749512987406924e+05, 4.268749512987406924e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.158000000000000000e+03, 1.208465974080900729e+00, 3.201562119203764480e+06, 3.201562119203764480e+06, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.635000000000000000e+03, 1.240929098167995903e+00, 1.641826731583625660e+05, 1.641826731583625660e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.042000000000000000e+03, 1.273392222255090189e+00, 1.600781059375430050e+05, 1.600781059375430050e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.784000000000000000e+03, 1.305855346342184475e+00, 1.535521405618976860e+04, 1.535521405618976860e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 8.580000000000000000e+02, 1.338318470429279650e+00, 1.561737619078078133e+05, 1.561737619078078133e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 7.350000000000000000e+02, 1.370781594516374824e+00, 1.208136649089561106e+05, 1.208136649089561106e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.781000000000000000e+03, 1.403244718603469110e+00, 2.667968442186593311e+05, 2.667968442186593311e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 7.260000000000000000e+02, 1.435707842690563396e+00, 1.778645622323353891e+05, 1.778645622323353891e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.550000000000000000e+03, 1.468170966777658570e+00, 3.049106785354042222e+04, 3.049106785354042222e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.813000000000000000e+03, 1.500634090864753745e+00, 5.081844653364565602e+04, 5.081844653364565602e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.387000000000000000e+03, 1.533097214951848031e+00, 1.883271836258925614e+05, 1.883271836258925614e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.955000000000000000e+03, 1.565560339038942317e+00, 2.262588082346799274e+04, 2.262588082346799274e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.557000000000000000e+03, 1.598023463126037491e+00, 3.049106785498113022e+05, 3.049106785498113022e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 4.590000000000000000e+02, 1.630486587213132665e+00, 1.641826730476954253e+05, 1.641826730476954253e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 9.370000000000000000e+02, 1.662949711300226951e+00, 1.208136648601474008e+05, 1.208136648601474008e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.777000000000000000e+03, 1.695412835387321238e+00, 1.382964203240714232e+04, 1.382964203240714232e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.380000000000000000e+02, 1.727875959474416412e+00, 2.453304316645150539e+04, 2.453304316645150539e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.425000000000000000e+03, 1.760339083561511586e+00, 1.253057582091011682e+04, 1.253057582091011682e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 7.800000000000000000e+02, 1.792802207648605872e+00, 3.811383475787233328e+04, 3.811383475787233328e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.885000000000000000e+03, 1.825265331735700158e+00, 3.518200147259695950e+04, 3.518200147259695950e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.030000000000000000e+02, 1.857728455822795333e+00, 1.016368931563103542e+05, 1.016368931563103542e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 8.790000000000000000e+02, 1.890191579909890507e+00, 3.370065388423412223e+05, 3.370065388423412223e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.590000000000000000e+03, 1.922654703996984793e+00, 9.147320358605529182e+05, 9.147320358605529182e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.895000000000000000e+03, 1.955117828084079079e+00, 1.032761978823809623e+05, 1.032761978823809623e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.649000000000000000e+03, 1.987580952171174253e+00, 4.268749502585324226e+05, 4.268749502585324226e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 6.170000000000000000e+02, 2.020044076258269428e+00, 1.489098661200021452e+05, 1.489098661200021452e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.102000000000000000e+03, 2.052507200345363714e+00, 1.391983529965012276e+05, 1.391983529965012276e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.250000000000000000e+02, 2.084970324432458000e+00, 1.698441450218960745e+04, 1.698441450218960745e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.987000000000000000e+03, 2.117433448519553174e+00, 2.416273311497266695e+04, 2.416273311497266695e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.548000000000000000e+03, 2.149896572606648348e+00, 1.081608825871241606e+04, 1.081608825871241606e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.125000000000000000e+03, 2.182359696693742634e+00, 3.766543669437001226e+05, 3.766543669437001226e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 8.160000000000000000e+02, 2.214822820780836921e+00, 1.600781059688675741e+05, 1.600781059688675741e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.362000000000000000e+03, 2.247285944867932095e+00, 6.403124242549258284e+06, 6.403124242549258284e+06, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.883000000000000000e+03, 2.279749068955027269e+00, 1.730574126452591736e+05, 1.730574126452591736e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 8.560000000000000000e+02, 2.312212193042121555e+00, 7.359912917520060728e+04, 7.359912917520060728e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.967000000000000000e+03, 2.344675317129215841e+00, 1.900036876540635058e+04, 1.900036876540635058e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.283000000000000000e+03, 2.377138441216311016e+00, 1.229006572084414438e+04, 1.229006572084414438e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.651000000000000000e+03, 2.409601565303406190e+00, 1.565556052317725516e+04, 1.565556052317725516e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 9.830000000000000000e+02, 2.442064689390500476e+00, 1.471982583320490085e+04, 1.471982583320490085e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.098000000000000000e+03, 2.474527813477594762e+00, 1.362366859108047211e+05, 1.362366859108047211e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.101000000000000000e+03, 2.506990937564689936e+00, 1.127310605251959714e+04, 1.127310605251959714e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.450000000000000000e+03, 2.539454061651785111e+00, 2.286830087621123821e+05, 2.286830087621123821e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 2.230000000000000000e+02, 2.571917185738879397e+00, 8.003905326255633263e+05, 8.003905326255633263e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 6.500000000000000000e+02, 2.604380309825973683e+00, 2.561249696886268212e+05, 2.561249696886268212e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.913000000000000000e+03, 2.636843433913068857e+00, 5.616775675419517938e+04, 5.616775675419517938e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.381000000000000000e+03, 2.669306558000164031e+00, 3.283653458000221872e+04, 3.283653458000221872e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.859000000000000000e+03, 2.701769682087258317e+00, 5.335936888535217149e+05, 5.335936888535217149e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 4.690000000000000000e+02, 2.734232806174352604e+00, 1.085275296346030082e+05, 1.085275296346030082e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 7.370000000000000000e+02, 2.766695930261447778e+00, 2.845832995614864194e+04, 2.845832995614864194e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 6.880000000000000000e+02, 2.799159054348542952e+00, 1.187963681119386638e+04, 1.187963681119386638e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.151000000000000000e+03, 2.831622178435637238e+00, 6.403124238323079189e+05, 6.403124238323079189e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 3.150000000000000000e+02, 2.864085302522731524e+00, 1.883271839927354595e+05, 1.883271839927354595e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 9.510000000000000000e+02, 2.896548426609826699e+00, 1.455255508528770879e+05, 1.455255508528770879e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.331000000000000000e+03, 2.929011550696921873e+00, 1.524553390883449174e+05, 1.524553390883449174e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 8.780000000000000000e+02, 2.961474674784016159e+00, 3.442539912910736894e+04, 3.442539912910736894e+04, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 6.210000000000000000e+02, 2.993937798871110445e+00, 2.000976325950339960e+05, 2.000976325950339960e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.000000000000000000e+01, 3.026400922958205619e+00, 2.910511034408783307e+05, 2.910511034408783307e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.006000000000000000e+03, 3.058864047045300794e+00, 1.333984216132136353e+05, 1.333984216132136353e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.380000000000000000e+02, 3.091327171132395080e+00, 1.883271843071718758e+05, 1.883271843071718758e+05, 0}, + {1.135559575326857527e+02, -8.581349240253584298e+01, 1.140000000000000000e+02, 3.123790295219489366e+00, 6.040683271775276808e+04, 6.040683271775276808e+04, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 5.020000000000000000e+02, -3.141592653589793116e+00, 3.333361666546250746e+01, 3.333361666546250746e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.236000000000000000e+03, -3.109129529502698386e+00, 1.180335545512376711e+02, 1.180335545512376711e+02, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.193000000000000000e+03, -3.076666405415603656e+00, 2.897020094439875404e+00, 2.897020094439875404e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.434000000000000000e+03, -3.044203281328508925e+00, 1.694516167391520156e+01, 1.694516167391520156e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 4.970000000000000000e+02, -3.011740157241414195e+00, 1.453362082261336852e+01, 1.453362082261336852e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.584000000000000000e+03, -2.979277033154319465e+00, 1.629530751635147379e+00, 1.629530751635147379e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 3.330000000000000000e+02, -2.946813909067224735e+00, 1.473627497029015032e+01, 1.473627497029015032e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 7.840000000000000000e+02, -2.914350784980130005e+00, 1.684844390723929886e+00, 1.684844390723929886e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.394000000000000000e+03, -2.881887660893035275e+00, 1.261852606289656720e+01, 1.261852606289656720e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 4.330000000000000000e+02, -2.849424536805940544e+00, 1.954033361968666505e+00, 1.954033361968666505e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.170000000000000000e+02, -2.816961412718845814e+00, 2.809299042663687729e+01, 2.809299042663687729e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.600000000000000000e+01, -2.784498288631751084e+00, 1.661079111133203057e+01, 1.661079111133203057e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.500000000000000000e+02, -2.752035164544656354e+00, 5.034458890845856516e+00, 5.034458890845856516e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 2.000000000000000000e+01, -2.719572040457561624e+00, 9.320734148630377192e+00, 9.320734148630377192e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 3.440000000000000000e+02, -2.687108916370466893e+00, 5.950075415371525622e+00, 5.950075415371525622e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 6.770000000000000000e+02, -2.654645792283372163e+00, 2.532869608441549847e+00, 2.532869608441549847e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 7.760000000000000000e+02, -2.622182668196277433e+00, 4.702598430655120509e+00, 4.702598430655120509e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 7.070000000000000000e+02, -2.589719544109182703e+00, 5.852480817427114346e+00, 5.852480817427114346e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.262000000000000000e+03, -2.557256420022087973e+00, 3.503690590058581478e+01, 3.503690590058581478e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 3.500000000000000000e+01, -2.524793295934993242e+00, 8.866016580178497009e+01, 8.866016580178497009e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.560000000000000000e+02, -2.492330171847898512e+00, 2.653444936533916376e+01, 2.653444936533916376e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 2.000000000000000000e+01, -2.459867047760803782e+00, 2.485529106301433799e+01, 2.485529106301433799e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 7.810000000000000000e+02, -2.427403923673709052e+00, 2.347528061600116089e+01, 2.347528061600116089e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.283000000000000000e+03, -2.394940799586614322e+00, 1.250858212333080921e+01, 1.250858212333080921e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.282000000000000000e+03, -2.362477675499519592e+00, 2.256303160394973251e+00, 2.256303160394973251e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.375000000000000000e+03, -2.330014551412424861e+00, 2.029577890654881145e+00, 2.029577890654881145e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 8.690000000000000000e+02, -2.297551427325330131e+00, 9.624359102827255708e-01, 9.624359102827255708e-01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.541000000000000000e+03, -2.265088303238235401e+00, 1.414535573025405002e+00, 1.414535573025405002e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 9.310000000000000000e+02, -2.232625179151140671e+00, 1.014610266233758651e+01, 1.014610266233758651e+01, 1}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.450000000000000000e+02, -2.200162055064045941e+00, 1.944198430197576544e+00, 1.944198430197576544e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.889000000000000000e+03, -2.167698930976951210e+00, 1.262593500680913827e+01, 1.262593500680913827e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 6.600000000000000000e+01, -2.135235806889856480e+00, 2.350928821930865098e+01, 2.350928821930865098e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.773000000000000000e+03, -2.102772682802761750e+00, 1.527964730713772701e+00, 1.527964730713772701e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.483000000000000000e+03, -2.070309558715667020e+00, 1.836475631995584124e+01, 1.836475631995584124e+01, 1}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.503000000000000000e+03, -2.037846434628572290e+00, 3.342732789201074866e+02, 3.342732789201074866e+02, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 6.310000000000000000e+02, -2.005383310541477559e+00, 2.444400579802860296e+00, 2.444400579802860296e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 6.710000000000000000e+02, -1.972920186454382829e+00, 1.942925872837638401e+00, 1.942925872837638401e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.552000000000000000e+03, -1.940457062367288099e+00, 2.102770617215973470e+00, 2.102770617215973470e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.843000000000000000e+03, -1.907993938280193369e+00, 5.592211202847906293e+00, 5.592211202847906293e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 7.700000000000000000e+02, -1.875530814193098639e+00, 9.932245748821060261e-01, 9.932245748821060261e-01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 9.200000000000000000e+01, -1.843067690106003909e+00, 2.853228191209232634e+01, 2.853228191209232634e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 4.170000000000000000e+02, -1.810604566018909178e+00, 3.685693310634432152e+01, 3.685693310634432152e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 9.050000000000000000e+02, -1.778141441931814448e+00, 2.000192357631752849e+00, 2.000192357631752849e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 3.670000000000000000e+02, -1.745678317844719718e+00, 2.405536438209896346e+02, 2.405536438209896346e+02, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.965000000000000000e+03, -1.713215193757624988e+00, 3.532277521983465007e+00, 3.532277521983465007e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.808000000000000000e+03, -1.680752069670530258e+00, 3.351207286602512880e+01, 3.351207286602512880e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.162000000000000000e+03, -1.648288945583435527e+00, 2.012393462026044855e+00, 2.012393462026044855e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.780000000000000000e+02, -1.615825821496340797e+00, 2.222882077133689016e+00, 2.222882077133689016e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.743000000000000000e+03, -1.583362697409246067e+00, 1.796087479093972306e+01, 1.796087479093972306e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 5.860000000000000000e+02, -1.550899573322151337e+00, 2.655405911636779237e+01, 2.655405911636779237e+01, 1}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.961000000000000000e+03, -1.518436449235056607e+00, 5.896177669567897084e+01, 5.896177669567897084e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 8.160000000000000000e+02, -1.485973325147961877e+00, 3.416720538579988187e+01, 3.416720538579988187e+01, 1}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.385000000000000000e+03, -1.453510201060867146e+00, 3.377108073963643875e+00, 3.377108073963643875e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.346000000000000000e+03, -1.421047076973772416e+00, 1.370424823742938614e+01, 1.370424823742938614e+01, 1}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 7.330000000000000000e+02, -1.388583952886677686e+00, 3.510214950190343330e+01, 3.510214950190343330e+01, 1}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.040000000000000000e+02, -1.356120828799582956e+00, 3.034365246469118205e+01, 3.034365246469118205e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.223000000000000000e+03, -1.323657704712488226e+00, 2.798260311510538756e+01, 2.798260311510538756e+01, 1}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 7.040000000000000000e+02, -1.291194580625393495e+00, 1.270606110955191381e+00, 1.270606110955191381e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 7.370000000000000000e+02, -1.258731456538298765e+00, 3.655507456712510983e+00, 3.655507456712510983e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.879000000000000000e+03, -1.226268332451204035e+00, 3.113690509203768997e+00, 3.113690509203768997e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 7.270000000000000000e+02, -1.193805208364109305e+00, 1.079589141097831329e+00, 1.079589141097831329e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.255000000000000000e+03, -1.161342084277014575e+00, 1.623241726609736313e+00, 1.623241726609736313e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.498000000000000000e+03, -1.128878960189919844e+00, 1.862213221534218643e+00, 1.862213221534218643e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 8.160000000000000000e+02, -1.096415836102825114e+00, 3.209074538997779058e+00, 3.209074538997779058e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 7.070000000000000000e+02, -1.063952712015730384e+00, 1.545655190243571298e+01, 1.545655190243571298e+01, 1}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 4.090000000000000000e+02, -1.031489587928635654e+00, 7.329444547745226579e+00, 7.329444547745226579e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 2.590000000000000000e+02, -9.990264638415409237e-01, 2.554159844593117956e+00, 2.554159844593117956e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.176000000000000000e+03, -9.665633397544461936e-01, 1.740545307205446868e+00, 1.740545307205446868e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 2.490000000000000000e+02, -9.341002156673514634e-01, 6.468140403375439007e+01, 6.468140403375439007e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 4.900000000000000000e+02, -9.016370915802567332e-01, 2.796637365758305549e+01, 2.796637365758305549e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 8.200000000000000000e+01, -8.691739674931620030e-01, 1.445109205315501466e+00, 1.445109205315501466e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.800000000000000000e+01, -8.367108434060672728e-01, 1.599796702645657209e+00, 1.599796702645657209e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.063000000000000000e+03, -8.042477193189725426e-01, 2.298919684684955111e+00, 2.298919684684955111e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 9.400000000000000000e+01, -7.717845952318778124e-01, 1.448996918990476956e+01, 1.448996918990476956e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.649000000000000000e+03, -7.393214711447830823e-01, 2.149652265881871749e+00, 2.149652265881871749e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.843000000000000000e+03, -7.068583470576883521e-01, 4.110275234093211338e+01, 4.110275234093211338e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.511000000000000000e+03, -6.743952229705936219e-01, 4.021396126504786395e+00, 4.021396126504786395e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.607000000000000000e+03, -6.419320988834988917e-01, 1.420808924521520566e+02, 1.420808924521520566e+02, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 7.700000000000000000e+01, -6.094689747964041615e-01, 2.496973509713194428e+00, 2.496973509713194428e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 2.520000000000000000e+02, -5.770058507093094313e-01, 3.873635243540620365e+01, 3.873635243540620365e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.073000000000000000e+03, -5.445427266222147011e-01, 1.596718017361328679e+00, 1.596718017361328679e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.098000000000000000e+03, -5.120796025351199710e-01, 1.728208146495233066e+01, 1.728208146495233066e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 3.040000000000000000e+02, -4.796164784480252408e-01, 1.712569237300527902e+00, 1.712569237300527902e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.046000000000000000e+03, -4.471533543609305106e-01, 2.984298708434434744e+01, 2.984298708434434744e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 4.570000000000000000e+02, -4.146902302738357804e-01, 2.838230386963193741e+00, 2.838230386963193741e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.942000000000000000e+03, -3.822271061867410502e-01, 1.968798290137359075e+00, 1.968798290137359075e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.934000000000000000e+03, -3.497639820996463200e-01, 2.485267611755486161e+00, 2.485267611755486161e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.537000000000000000e+03, -3.173008580125515898e-01, 9.878855573375568966e+00, 9.878855573375568966e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.539000000000000000e+03, -2.848377339254568597e-01, 2.774105080791446909e+00, 2.774105080791446909e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 6.690000000000000000e+02, -2.523746098383621295e-01, 1.225121218492276398e+02, 1.225121218492276398e+02, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 5.440000000000000000e+02, -2.199114857512673993e-01, 1.775132735625908120e+00, 1.775132735625908120e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.808000000000000000e+03, -1.874483616641726691e-01, 3.117402127072105067e+00, 3.117402127072105067e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.695000000000000000e+03, -1.549852375770779389e-01, 1.315160668462968019e+01, 1.315160668462968019e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.472000000000000000e+03, -1.225221134899832087e-01, 8.880363018132777952e+00, 8.880363018132777952e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 7.460000000000000000e+02, -9.005898940288847854e-02, 2.999455788478646578e+00, 2.999455788478646578e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.418000000000000000e+03, -5.759586531579374835e-02, 1.204908674041459982e+01, 1.204908674041459982e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.152000000000000000e+03, -2.513274122869901817e-02, 1.218173672638984684e+00, 1.218173672638984684e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.373000000000000000e+03, 7.330382858395712020e-03, 2.081704696743619465e+01, 2.081704696743619465e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.209000000000000000e+03, 3.979350694549044221e-02, 4.916436808634734312e+00, 4.916436808634734312e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 3.910000000000000000e+02, 7.225663103258517239e-02, 1.823743071342440913e+01, 1.823743071342440913e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.283000000000000000e+03, 1.047197551196799026e-01, 1.000686569866464737e+02, 1.000686569866464737e+02, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.964000000000000000e+03, 1.371828792067746328e-01, 4.219321715271478723e+01, 4.219321715271478723e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.174000000000000000e+03, 1.696460032938693629e-01, 1.815986135033312632e+00, 1.815986135033312632e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.269000000000000000e+03, 2.021091273809640931e-01, 3.245573272141505150e+00, 3.245573272141505150e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 5.290000000000000000e+02, 2.345722514680588233e-01, 1.931729463388490231e+01, 1.931729463388490231e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.118000000000000000e+03, 2.670353755551535535e-01, 5.063710318499482277e+00, 5.063710318499482277e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.366000000000000000e+03, 2.994984996422482837e-01, 5.319975601889965766e+00, 5.319975601889965766e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 5.000000000000000000e+01, 3.319616237293430139e-01, 2.662013847199401795e+01, 2.662013847199401795e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 8.450000000000000000e+02, 3.644247478164377441e-01, 2.306382448771235616e+01, 2.306382448771235616e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 2.000000000000000000e+01, 3.968878719035324742e-01, 3.002652611639316405e+00, 3.002652611639316405e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 6.190000000000000000e+02, 4.293509959906272044e-01, 1.607490888294559639e+01, 1.607490888294559639e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 3.600000000000000000e+01, 4.618141200777219346e-01, 2.468126908654625140e+00, 2.468126908654625140e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.104000000000000000e+03, 4.942772441648166648e-01, 4.391074864032547964e+01, 4.391074864032547964e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.948000000000000000e+03, 5.267403682519113950e-01, 1.671206877171062644e+00, 1.671206877171062644e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.161000000000000000e+03, 5.592034923390061252e-01, 1.443542734040111419e+01, 1.443542734040111419e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.194000000000000000e+03, 5.916666164261008554e-01, 2.240258332525448992e+01, 2.240258332525448992e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.430000000000000000e+02, 6.241297405131955855e-01, 3.605484427703453321e+01, 3.605484427703453321e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.807000000000000000e+03, 6.565928646002903157e-01, 8.930973292459076163e+01, 8.930973292459076163e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.827000000000000000e+03, 6.890559886873850459e-01, 6.358503952170323714e+00, 6.358503952170323714e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 6.190000000000000000e+02, 7.215191127744797761e-01, 2.749655466819641347e+00, 2.749655466819641347e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.665000000000000000e+03, 7.539822368615745063e-01, 2.830420390295197208e+01, 2.830420390295197208e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 3.630000000000000000e+02, 7.864453609486692365e-01, 1.589931033327494525e+00, 1.589931033327494525e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 8.090000000000000000e+02, 8.189084850357639667e-01, 1.939904064065483169e+01, 1.939904064065483169e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 5.470000000000000000e+02, 8.513716091228586968e-01, 1.711648417376986231e+01, 1.711648417376986231e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 7.380000000000000000e+02, 8.838347332099534270e-01, 1.286452268488032180e+00, 1.286452268488032180e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.274000000000000000e+03, 9.162978572970477131e-01, 1.570396283695466133e+00, 1.570396283695466133e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.773000000000000000e+03, 9.487609813841428874e-01, 1.342835898152888952e+00, 1.342835898152888952e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.896000000000000000e+03, 9.812241054712380617e-01, 4.997778053007959898e+01, 4.997778053007959898e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 3.950000000000000000e+02, 1.013687229558332348e+00, 3.085003975266516463e+01, 3.085003975266516463e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.692000000000000000e+03, 1.046150353645426634e+00, 2.461357339258878341e+00, 2.461357339258878341e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.522000000000000000e+03, 1.078613477732521808e+00, 1.407895642044853268e+01, 1.407895642044853268e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.891000000000000000e+03, 1.111076601819616982e+00, 4.234945395161548554e+00, 4.234945395161548554e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.207000000000000000e+03, 1.143539725906711269e+00, 1.076796225795660922e+00, 1.076796225795660922e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.636000000000000000e+03, 1.176002849993805555e+00, 1.412067502404773967e+00, 1.412067502404773967e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 9.770000000000000000e+02, 1.208465974080900729e+00, 1.887722025205099996e+01, 1.887722025205099996e+01, 1}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.470000000000000000e+03, 1.240929098167995903e+00, 1.755159725377145596e+00, 1.755159725377145596e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 7.800000000000000000e+02, 1.273392222255090189e+00, 3.669181192718615137e+01, 3.669181192718615137e+01, 1}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.964000000000000000e+03, 1.305855346342184475e+00, 2.953525200690035035e+02, 2.953525200690035035e+02, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 5.510000000000000000e+02, 1.338318470429279650e+00, 1.475086669256481819e+01, 1.475086669256481819e+01, 1}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.650000000000000000e+02, 1.370781594516374824e+00, 1.514745198979896834e+01, 1.514745198979896834e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.201000000000000000e+03, 1.403244718603469110e+00, 1.535928216019401837e+01, 1.535928216019401837e+01, 1}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 6.260000000000000000e+02, 1.435707842690563396e+00, 3.033060054527885629e+00, 3.033060054527885629e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.140000000000000000e+03, 1.468170966777658570e+00, 1.257491948638477464e+00, 1.257491948638477464e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 2.600000000000000000e+01, 1.500634090864753745e+00, 1.591980059612582465e+01, 1.591980059612582465e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 2.410000000000000000e+02, 1.533097214951848031e+00, 7.573378744303976617e+00, 7.573378744303976617e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 6.410000000000000000e+02, 1.565560339038942317e+00, 1.159617641887946915e+00, 1.159617641887946915e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 3.000000000000000000e+00, 1.598023463126037491e+00, 4.783766688326164029e+00, 4.783766688326164029e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.600000000000000000e+02, 1.630486587213132665e+00, 2.291950080975525328e+00, 2.291950080975525328e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.463000000000000000e+03, 1.662949711300226951e+00, 1.575753465453069158e+00, 1.575753465453069158e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.740000000000000000e+02, 1.695412835387321238e+00, 2.406451478459961546e+00, 2.406451478459961546e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.732000000000000000e+03, 1.727875959474416412e+00, 1.889279769775920048e+00, 1.889279769775920048e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.370000000000000000e+03, 1.760339083561511586e+00, 1.247236946213509299e+02, 1.247236946213509299e+02, 1}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 5.890000000000000000e+02, 1.792802207648605872e+00, 5.784779830378197651e+00, 5.784779830378197651e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 6.150000000000000000e+02, 1.825265331735700158e+00, 2.512568407028950901e+01, 2.512568407028950901e+01, 1}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.808000000000000000e+03, 1.857728455822795333e+00, 5.256795743690216405e+00, 5.256795743690216405e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.935000000000000000e+03, 1.890191579909890507e+00, 3.075550048931877445e+00, 3.075550048931877445e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 3.060000000000000000e+02, 1.922654703996984793e+00, 1.950984938666307844e+00, 1.950984938666307844e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 7.000000000000000000e+02, 1.955117828084079079e+00, 5.349775279756652679e+00, 5.349775279756652679e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 6.550000000000000000e+02, 1.987580952171174253e+00, 2.465643932119964532e+01, 2.465643932119964532e+01, 1}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.176000000000000000e+03, 2.020044076258269428e+00, 6.818842203522515355e+00, 6.818842203522515355e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.850000000000000000e+03, 2.052507200345363714e+00, 3.931672657612954680e+01, 3.931672657612954680e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.305000000000000000e+03, 2.084970324432458000e+00, 4.120913591177585822e+00, 4.120913591177585822e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.669000000000000000e+03, 2.117433448519553174e+00, 5.901758382041745854e+00, 5.901758382041745854e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 2.090000000000000000e+02, 2.149896572606648348e+00, 5.036680467946733408e+00, 5.036680467946733408e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.929000000000000000e+03, 2.182359696693742634e+00, 1.893367524478577923e+00, 1.893367524478577923e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.659000000000000000e+03, 2.214822820780836921e+00, 1.593925288740647517e+01, 1.593925288740647517e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.752000000000000000e+03, 2.247285944867932095e+00, 2.588869337074477528e+01, 2.588869337074477528e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.816000000000000000e+03, 2.279749068955027269e+00, 4.041590033637751134e+01, 4.041590033637751134e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 8.150000000000000000e+02, 2.312212193042121555e+00, 1.815629033988633978e+01, 1.815629033988633978e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 2.000000000000000000e+02, 2.344675317129215841e+00, 5.001757503618103584e+01, 5.001757503618103584e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.724000000000000000e+03, 2.377138441216311016e+00, 1.696092822989806237e+01, 1.696092822989806237e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.006000000000000000e+03, 2.409601565303406190e+00, 1.167214291305601170e+00, 1.167214291305601170e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 2.110000000000000000e+02, 2.442064689390500476e+00, 1.394389783588127862e+01, 1.394389783588127862e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.757000000000000000e+03, 2.474527813477594762e+00, 9.738571025823040372e+01, 9.738571025823040372e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 5.570000000000000000e+02, 2.506990937564689936e+00, 1.658905994707594189e+01, 1.658905994707594189e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 3.030000000000000000e+02, 2.539454061651785111e+00, 1.443402789392494867e+01, 1.443402789392494867e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 9.720000000000000000e+02, 2.571917185738879397e+00, 1.132858331831478438e+00, 1.132858331831478438e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.914000000000000000e+03, 2.604380309825973683e+00, 2.454729712042381706e+01, 2.454729712042381706e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.674000000000000000e+03, 2.636843433913068857e+00, 2.132541475064759773e+00, 2.132541475064759773e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.153000000000000000e+03, 2.669306558000164031e+00, 1.372210631842134276e+01, 1.372210631842134276e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.128000000000000000e+03, 2.701769682087258317e+00, 1.401645620653246826e+00, 1.401645620653246826e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 7.100000000000000000e+01, 2.734232806174352604e+00, 7.226352718426572608e+01, 7.226352718426572608e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 7.490000000000000000e+02, 2.766695930261447778e+00, 1.040796774358732968e+01, 1.040796774358732968e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 2.670000000000000000e+02, 2.799159054348542952e+00, 3.837624590811352476e+01, 3.837624590811352476e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.236000000000000000e+03, 2.831622178435637238e+00, 2.599858029762944334e+00, 2.599858029762944334e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 8.520000000000000000e+02, 2.864085302522731524e+00, 9.594587594634337790e+01, 9.594587594634337790e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.470000000000000000e+03, 2.896548426609826699e+00, 5.470247810758770157e+01, 5.470247810758770157e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.930000000000000000e+02, 2.929011550696921873e+00, 4.275465937879344480e+00, 4.275465937879344480e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 6.640000000000000000e+02, 2.961474674784016159e+00, 5.581092638661565530e+01, 5.581092638661565530e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.268000000000000000e+03, 2.993937798871110445e+00, 1.808971621873036995e+01, 1.808971621873036995e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 4.080000000000000000e+02, 3.026400922958205619e+00, 1.320913458610780467e+00, 1.320913458610780467e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 1.376000000000000000e+03, 3.058864047045300794e+00, 1.517986080936594151e+00, 1.517986080936594151e+00, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 2.420000000000000000e+02, 3.091327171132395080e+00, 1.694721037541301811e+01, 1.694721037541301811e+01, 0}, + {3.261728279648177420e+01, -9.648202234272204691e+01, 5.320000000000000000e+02, 3.123790295219489366e+00, 3.602828994844336385e+00, 3.602828994844336385e+00, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.589000000000000000e+03, -3.141592653589793116e+00, 8.549465013459982998e+00, 8.549465013459982998e+00, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.617000000000000000e+03, -3.109129529502698386e+00, 5.521042686456880801e+02, 5.521042686456880801e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 4.200000000000000000e+02, -3.076666405415603656e+00, 1.144403139422548676e+01, 1.144403139422548676e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.236000000000000000e+03, -3.044203281328508925e+00, 2.606610629739174101e+02, 2.606610629739174101e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.323000000000000000e+03, -3.011740157241414195e+00, 1.121044011483187042e+01, 1.121044011483187042e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.601000000000000000e+03, -2.979277033154319465e+00, 2.188527678384909336e+01, 2.188527678384909336e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 2.690000000000000000e+02, -2.946813909067224735e+00, 1.168230996082757756e+01, 1.168230996082757756e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.585000000000000000e+03, -2.914350784980130005e+00, 1.079783221435212681e+02, 1.079783221435212681e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.436000000000000000e+03, -2.881887660893035275e+00, 8.700596361117376887e+01, 8.700596361117376887e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.388000000000000000e+03, -2.849424536805940544e+00, 1.280967884021806924e+01, 1.280967884021806924e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.612000000000000000e+03, -2.816961412718845814e+00, 9.937258475052362883e+01, 9.937258475052362883e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 8.860000000000000000e+02, -2.784498288631751084e+00, 9.575250051103017412e+00, 9.575250051103017412e+00, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.362000000000000000e+03, -2.752035164544656354e+00, 9.246944448609223599e+00, 9.246944448609223599e+00, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 5.800000000000000000e+02, -2.719572040457561624e+00, 1.599564343003728339e+01, 1.599564343003728339e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.411000000000000000e+03, -2.687108916370466893e+00, 1.153086600134356985e+02, 1.153086600134356985e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.091000000000000000e+03, -2.654645792283372163e+00, 3.867317311583904882e+01, 3.867317311583904882e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.970000000000000000e+03, -2.622182668196277433e+00, 1.665681525515740589e+02, 1.665681525515740589e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 8.600000000000000000e+02, -2.589719544109182703e+00, 1.237684443325519169e+03, 1.237684443325519169e+03, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 2.100000000000000000e+01, -2.557256420022087973e+00, 9.975892351736430186e+00, 9.975892351736430186e+00, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.965000000000000000e+03, -2.524793295934993242e+00, 7.137943595708095472e+02, 7.137943595708095472e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.704000000000000000e+03, -2.492330171847898512e+00, 3.209495050743841915e+01, 3.209495050743841915e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 7.760000000000000000e+02, -2.459867047760803782e+00, 2.846138818910533885e+01, 2.846138818910533885e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 7.040000000000000000e+02, -2.427403923673709052e+00, 1.038610319143307592e+01, 1.038610319143307592e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 4.730000000000000000e+02, -2.394940799586614322e+00, 1.095751773480679248e+01, 1.095751773480679248e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 7.710000000000000000e+02, -2.362477675499519592e+00, 3.562874737281877913e+01, 3.562874737281877913e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.627000000000000000e+03, -2.330014551412424861e+00, 3.105977666633326066e+02, 3.105977666633326066e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 7.740000000000000000e+02, -2.297551427325330131e+00, 9.004230869636728585e+01, 9.004230869636728585e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.820000000000000000e+03, -2.265088303238235401e+00, 9.011923205756502853e+00, 9.011923205756502853e+00, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 5.580000000000000000e+02, -2.232625179151140671e+00, 1.122082687389445965e+01, 1.122082687389445965e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.925000000000000000e+03, -2.200162055064045941e+00, 8.608235313929111499e+01, 8.608235313929111499e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.779000000000000000e+03, -2.167698930976951210e+00, 1.379585514016256376e+01, 1.379585514016256376e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 8.880000000000000000e+02, -2.135235806889856480e+00, 1.014422428268254883e+01, 1.014422428268254883e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.607000000000000000e+03, -2.102772682802761750e+00, 3.821786579954707008e+02, 3.821786579954707008e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.400000000000000000e+02, -2.070309558715667020e+00, 3.562116753463608916e+02, 3.562116753463608916e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.702000000000000000e+03, -2.037846434628572290e+00, 1.446097677931349956e+01, 1.446097677931349956e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 2.670000000000000000e+02, -2.005383310541477559e+00, 9.758453191411319949e+01, 9.758453191411319949e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 4.350000000000000000e+02, -1.972920186454382829e+00, 1.379401401082600671e+02, 1.379401401082600671e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.439000000000000000e+03, -1.940457062367288099e+00, 2.724984752829232804e+01, 2.724984752829232804e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.510000000000000000e+02, -1.907993938280193369e+00, 5.361312858752974364e+01, 5.361312858752974364e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.157000000000000000e+03, -1.875530814193098639e+00, 1.661406955951788333e+01, 1.661406955951788333e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.616000000000000000e+03, -1.843067690106003909e+00, 1.505720115769851759e+02, 1.505720115769851759e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 4.490000000000000000e+02, -1.810604566018909178e+00, 1.241264602129618311e+02, 1.241264602129618311e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 4.800000000000000000e+02, -1.778141441931814448e+00, 3.202184770573169459e+01, 3.202184770573169459e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.645000000000000000e+03, -1.745678317844719718e+00, 8.312234020750523200e+00, 8.312234020750523200e+00, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 2.830000000000000000e+02, -1.713215193757624988e+00, 1.715739857328656512e+02, 1.715739857328656512e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 8.190000000000000000e+02, -1.680752069670530258e+00, 1.414686379032613956e+02, 1.414686379032613956e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.760000000000000000e+02, -1.648288945583435527e+00, 1.845897557150775299e+02, 1.845897557150775299e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.760000000000000000e+02, -1.615825821496340797e+00, 9.144813585884573826e+00, 9.144813585884573826e+00, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.927000000000000000e+03, -1.583362697409246067e+00, 9.790121463883149033e+01, 9.790121463883149033e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.085000000000000000e+03, -1.550899573322151337e+00, 1.414317950570564619e+02, 1.414317950570564619e+02, 1}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.199000000000000000e+03, -1.518436449235056607e+00, 1.904518335106647555e+02, 1.904518335106647555e+02, 1}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 2.370000000000000000e+02, -1.485973325147961877e+00, 1.310280282337541848e+02, 1.310280282337541848e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 8.650000000000000000e+02, -1.453510201060867146e+00, 1.650222779573176979e+02, 1.650222779573176979e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 5.840000000000000000e+02, -1.421047076973772416e+00, 1.549525270672642137e+02, 1.549525270672642137e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.183000000000000000e+03, -1.388583952886677686e+00, 1.207668069205173254e+02, 1.207668069205173254e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 5.540000000000000000e+02, -1.356120828799582956e+00, 1.502965006523980662e+02, 1.502965006523980662e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 8.400000000000000000e+02, -1.323657704712488226e+00, 4.058230122275306684e+01, 4.058230122275306684e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.775000000000000000e+03, -1.291194580625393495e+00, 1.844441358022109227e+02, 1.844441358022109227e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 4.430000000000000000e+02, -1.258731456538298765e+00, 1.067826480967713643e+01, 1.067826480967713643e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 4.390000000000000000e+02, -1.226268332451204035e+00, 1.103470731066749977e+02, 1.103470731066749977e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 2.640000000000000000e+02, -1.193805208364109305e+00, 1.758668727700204926e+01, 1.758668727700204926e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.356000000000000000e+03, -1.161342084277014575e+00, 1.152591842610255242e+02, 1.152591842610255242e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.527000000000000000e+03, -1.128878960189919844e+00, 1.213632159869798777e+01, 1.213632159869798777e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.876000000000000000e+03, -1.096415836102825114e+00, 1.279065561796617203e+02, 1.279065561796617203e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.035000000000000000e+03, -1.063952712015730384e+00, 1.979923917730173741e+02, 1.979923917730173741e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.332000000000000000e+03, -1.031489587928635654e+00, 9.910623895598097022e+01, 9.910623895598097022e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.558000000000000000e+03, -9.990264638415409237e-01, 2.641196422733185756e+01, 2.641196422733185756e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.908000000000000000e+03, -9.665633397544461936e-01, 1.996486373607393148e+02, 1.996486373607393148e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.283000000000000000e+03, -9.341002156673514634e-01, 2.553500709437971139e+01, 2.553500709437971139e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.044000000000000000e+03, -9.016370915802567332e-01, 3.928448971957107005e+01, 3.928448971957107005e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 4.560000000000000000e+02, -8.691739674931620030e-01, 9.734651855677711296e+01, 9.734651855677711296e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 4.780000000000000000e+02, -8.367108434060672728e-01, 1.102998080429924670e+02, 1.102998080429924670e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 7.660000000000000000e+02, -8.042477193189725426e-01, 8.955719251485410481e+00, 8.955719251485410481e+00, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.186000000000000000e+03, -7.717845952318778124e-01, 2.063122906778028778e+02, 2.063122906778028778e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 5.150000000000000000e+02, -7.393214711447830823e-01, 2.480807177109902000e+02, 2.480807177109902000e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.800000000000000000e+02, -7.068583470576883521e-01, 1.718480528545981656e+02, 1.718480528545981656e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 5.680000000000000000e+02, -6.743952229705936219e-01, 1.377545805404544126e+02, 1.377545805404544126e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 3.620000000000000000e+02, -6.419320988834988917e-01, 1.534032169255761602e+01, 1.534032169255761602e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 3.760000000000000000e+02, -6.094689747964041615e-01, 1.656458487926039652e+03, 1.656458487926039652e+03, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 9.600000000000000000e+02, -5.770058507093094313e-01, 1.374952426225255238e+02, 1.374952426225255238e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.390000000000000000e+02, -5.445427266222147011e-01, 4.987049729048227164e+03, 4.987049729048227164e+03, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 6.660000000000000000e+02, -5.120796025351199710e-01, 3.539556534254492703e+02, 3.539556534254492703e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.409000000000000000e+03, -4.796164784480252408e-01, 1.139813721792198997e+01, 1.139813721792198997e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.630000000000000000e+02, -4.471533543609305106e-01, 2.385170535528057201e+01, 2.385170535528057201e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.179000000000000000e+03, -4.146902302738357804e-01, 1.053482121945355061e+02, 1.053482121945355061e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.528000000000000000e+03, -3.822271061867410502e-01, 6.204760835942832955e+02, 6.204760835942832955e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.151000000000000000e+03, -3.497639820996463200e-01, 8.348902889102802760e+00, 8.348902889102802760e+00, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.790000000000000000e+03, -3.173008580125515898e-01, 8.910858663835337978e+00, 8.910858663835337978e+00, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.813000000000000000e+03, -2.848377339254568597e-01, 8.819504545471819057e+00, 8.819504545471819057e+00, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 8.590000000000000000e+02, -2.523746098383621295e-01, 1.100167102908002619e+02, 1.100167102908002619e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 3.910000000000000000e+02, -2.199114857512673993e-01, 1.987377971096590272e+02, 1.987377971096590272e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 8.240000000000000000e+02, -1.874483616641726691e-01, 1.904350846081260897e+02, 1.904350846081260897e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.188000000000000000e+03, -1.549852375770779389e-01, 1.847586844214550084e+01, 1.847586844214550084e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 8.370000000000000000e+02, -1.225221134899832087e-01, 3.722623818075625479e+01, 3.722623818075625479e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.766000000000000000e+03, -9.005898940288847854e-02, 1.082455517799749032e+02, 1.082455517799749032e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 8.290000000000000000e+02, -5.759586531579374835e-02, 5.381765865213510125e+01, 5.381765865213510125e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.023000000000000000e+03, -2.513274122869901817e-02, 1.135269413150159323e+01, 1.135269413150159323e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.435000000000000000e+03, 7.330382858395712020e-03, 1.145333953484927214e+01, 1.145333953484927214e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.728000000000000000e+03, 3.979350694549044221e-02, 1.463660047720821638e+02, 1.463660047720821638e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 6.360000000000000000e+02, 7.225663103258517239e-02, 1.304325121871731028e+02, 1.304325121871731028e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.634000000000000000e+03, 1.047197551196799026e-01, 1.515246432863373016e+01, 1.515246432863373016e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.130000000000000000e+03, 1.371828792067746328e-01, 1.360055337392724795e+01, 1.360055337392724795e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 2.000000000000000000e+00, 1.696460032938693629e-01, 6.249750807532249155e+02, 6.249750807532249155e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 7.310000000000000000e+02, 2.021091273809640931e-01, 1.232189392199934375e+01, 1.232189392199934375e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 6.290000000000000000e+02, 2.345722514680588233e-01, 1.077542384220713814e+02, 1.077542384220713814e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.117000000000000000e+03, 2.670353755551535535e-01, 1.406374793590416949e+01, 1.406374793590416949e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 5.590000000000000000e+02, 2.994984996422482837e-01, 1.692682924393486488e+01, 1.692682924393486488e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.423000000000000000e+03, 3.319616237293430139e-01, 1.652925655382668083e+03, 1.652925655382668083e+03, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.174000000000000000e+03, 3.644247478164377441e-01, 1.222537495189923540e+01, 1.222537495189923540e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.233000000000000000e+03, 3.968878719035324742e-01, 5.826457849556997814e+01, 5.826457849556997814e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.425000000000000000e+03, 4.293509959906272044e-01, 1.836615729765021570e+02, 1.836615729765021570e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.170000000000000000e+02, 4.618141200777219346e-01, 9.360173996160575882e+00, 9.360173996160575882e+00, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.759000000000000000e+03, 4.942772441648166648e-01, 7.430984154659084595e+01, 7.430984154659084595e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.809000000000000000e+03, 5.267403682519113950e-01, 3.278088521149646084e+01, 3.278088521149646084e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 3.530000000000000000e+02, 5.592034923390061252e-01, 4.041338133225912088e+01, 4.041338133225912088e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.854000000000000000e+03, 5.916666164261008554e-01, 1.108099529781163000e+02, 1.108099529781163000e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.599000000000000000e+03, 6.241297405131955855e-01, 9.199698249062288369e+01, 9.199698249062288369e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 9.320000000000000000e+02, 6.565928646002903157e-01, 9.166632341873631162e+01, 9.166632341873631162e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 6.070000000000000000e+02, 6.890559886873850459e-01, 1.304616483482816136e+02, 1.304616483482816136e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.651000000000000000e+03, 7.215191127744797761e-01, 1.603582909538121442e+02, 1.603582909538121442e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 9.210000000000000000e+02, 7.539822368615745063e-01, 1.774216175953603525e+01, 1.774216175953603525e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.982000000000000000e+03, 7.864453609486692365e-01, 2.126900566745869625e+01, 2.126900566745869625e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.813000000000000000e+03, 8.189084850357639667e-01, 5.536688964657308816e+02, 5.536688964657308816e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 7.310000000000000000e+02, 8.513716091228586968e-01, 1.483054298396328008e+01, 1.483054298396328008e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.058000000000000000e+03, 8.838347332099534270e-01, 9.899835655201554800e+02, 9.899835655201554800e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.077000000000000000e+03, 9.162978572970477131e-01, 4.950047373510681609e+03, 4.950047373510681609e+03, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 7.790000000000000000e+02, 9.487609813841428874e-01, 4.952214151266077806e+02, 4.952214151266077806e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.322000000000000000e+03, 9.812241054712380617e-01, 1.415709139388080189e+02, 1.415709139388080189e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.278000000000000000e+03, 1.013687229558332348e+00, 8.453327331134353528e+00, 8.453327331134353528e+00, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 9.310000000000000000e+02, 1.046150353645426634e+00, 1.847010590979385825e+01, 1.847010590979385825e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 2.000000000000000000e+01, 1.078613477732521808e+00, 1.666006685994320378e+03, 1.666006685994320378e+03, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.648000000000000000e+03, 1.111076601819616982e+00, 2.448724646897072432e+01, 2.448724646897072432e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 9.410000000000000000e+02, 1.143539725906711269e+00, 2.124430788320281138e+01, 2.124430788320281138e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 6.190000000000000000e+02, 1.176002849993805555e+00, 1.652358079298256257e+02, 1.652358079298256257e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 7.730000000000000000e+02, 1.208465974080900729e+00, 1.375652735079192723e+02, 1.375652735079192723e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.412000000000000000e+03, 1.240929098167995903e+00, 1.050490228117060632e+01, 1.050490228117060632e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 9.030000000000000000e+02, 1.273392222255090189e+00, 8.839684154079122891e+01, 8.839684154079122891e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.538000000000000000e+03, 1.305855346342184475e+00, 4.513041387133899889e+02, 4.513041387133899889e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.077000000000000000e+03, 1.338318470429279650e+00, 1.125010766706973158e+02, 1.125010766706973158e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 3.810000000000000000e+02, 1.370781594516374824e+00, 9.762402335750326898e+00, 9.762402335750326898e+00, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 8.570000000000000000e+02, 1.403244718603469110e+00, 1.316696980190000588e+01, 1.316696980190000588e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 5.270000000000000000e+02, 1.435707842690563396e+00, 6.279791232215056596e+01, 6.279791232215056596e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 7.540000000000000000e+02, 1.468170966777658570e+00, 1.031834062297836425e+02, 1.031834062297836425e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 3.630000000000000000e+02, 1.500634090864753745e+00, 1.420057170450168371e+02, 1.420057170450168371e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.948000000000000000e+03, 1.533097214951848031e+00, 4.305976795374863286e+01, 4.305976795374863286e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 4.510000000000000000e+02, 1.565560339038942317e+00, 1.561304287156564996e+01, 1.561304287156564996e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 5.000000000000000000e+01, 1.598023463126037491e+00, 4.162602559630747123e+02, 4.162602559630747123e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 9.990000000000000000e+02, 1.630486587213132665e+00, 1.490887943789782710e+01, 1.490887943789782710e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.664000000000000000e+03, 1.662949711300226951e+00, 1.651816167177010541e+01, 1.651816167177010541e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 7.580000000000000000e+02, 1.695412835387321238e+00, 1.523909220921465213e+01, 1.523909220921465213e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.006000000000000000e+03, 1.727875959474416412e+00, 1.231281030136451804e+01, 1.231281030136451804e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 3.050000000000000000e+02, 1.760339083561511586e+00, 2.925932081698549041e+02, 2.925932081698549041e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 6.220000000000000000e+02, 1.792802207648605872e+00, 4.130799500567521818e+02, 4.130799500567521818e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.545000000000000000e+03, 1.825265331735700158e+00, 1.056324953946256500e+02, 1.056324953946256500e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.996000000000000000e+03, 1.857728455822795333e+00, 1.157315100485781478e+01, 1.157315100485781478e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 6.770000000000000000e+02, 1.890191579909890507e+00, 1.032294693907434713e+01, 1.032294693907434713e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.622000000000000000e+03, 1.922654703996984793e+00, 8.779593806236977827e+00, 8.779593806236977827e+00, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.700000000000000000e+02, 1.955117828084079079e+00, 1.311689784220225192e+02, 1.311689784220225192e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 3.750000000000000000e+02, 1.987580952171174253e+00, 1.868209886555843724e+01, 1.868209886555843724e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.640000000000000000e+02, 2.020044076258269428e+00, 9.370155107049791710e+00, 9.370155107049791710e+00, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.941000000000000000e+03, 2.052507200345363714e+00, 8.700820937466552607e+00, 8.700820937466552607e+00, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.213000000000000000e+03, 2.084970324432458000e+00, 1.157018428278032118e+01, 1.157018428278032118e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 3.220000000000000000e+02, 2.117433448519553174e+00, 9.025247314103600260e+00, 9.025247314103600260e+00, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.503000000000000000e+03, 2.149896572606648348e+00, 8.411034495989893855e+01, 8.411034495989893855e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 6.640000000000000000e+02, 2.182359696693742634e+00, 9.009903183270107974e+00, 9.009903183270107974e+00, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.156000000000000000e+03, 2.214822820780836921e+00, 3.300651282533326025e+02, 3.300651282533326025e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.507000000000000000e+03, 2.247285944867932095e+00, 9.543680527854621687e+01, 9.543680527854621687e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.305000000000000000e+03, 2.279749068955027269e+00, 2.293724151205723416e+01, 2.293724151205723416e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.640000000000000000e+03, 2.312212193042121555e+00, 2.761329328510785786e+02, 2.761329328510785786e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.892000000000000000e+03, 2.344675317129215841e+00, 9.326678862127579350e+00, 9.326678862127579350e+00, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 6.760000000000000000e+02, 2.377138441216311016e+00, 1.457366815984287314e+02, 1.457366815984287314e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 5.740000000000000000e+02, 2.409601565303406190e+00, 1.458501580342507395e+02, 1.458501580342507395e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 3.410000000000000000e+02, 2.442064689390500476e+00, 4.519667306559573490e+02, 4.519667306559573490e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.640000000000000000e+02, 2.474527813477594762e+00, 9.871133696931661206e+00, 9.871133696931661206e+00, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.657000000000000000e+03, 2.506990937564689936e+00, 1.388687621397192018e+01, 1.388687621397192018e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.215000000000000000e+03, 2.539454061651785111e+00, 1.151646997061597517e+02, 1.151646997061597517e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.044000000000000000e+03, 2.571917185738879397e+00, 1.189866755929316078e+01, 1.189866755929316078e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.590000000000000000e+02, 2.604380309825973683e+00, 2.077226257202404440e+02, 2.077226257202404440e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.920000000000000000e+02, 2.636843433913068857e+00, 7.221178870559384677e+01, 7.221178870559384677e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 6.700000000000000000e+01, 2.669306558000164031e+00, 1.468682559373403933e+02, 1.468682559373403933e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.065000000000000000e+03, 2.701769682087258317e+00, 1.151153793716310076e+02, 1.151153793716310076e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.449000000000000000e+03, 2.734232806174352604e+00, 8.671188563327827836e+00, 8.671188563327827836e+00, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.180000000000000000e+02, 2.766695930261447778e+00, 9.520771553641704799e+00, 9.520771553641704799e+00, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 4.770000000000000000e+02, 2.799159054348542952e+00, 2.256156361807758159e+01, 2.256156361807758159e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.047000000000000000e+03, 2.831622178435637238e+00, 9.899718985910661218e+01, 9.899718985910661218e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 9.100000000000000000e+02, 2.864085302522731524e+00, 1.375043616031016711e+02, 1.375043616031016711e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 8.100000000000000000e+01, 2.896548426609826699e+00, 1.313742750256082559e+02, 1.313742750256082559e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.199000000000000000e+03, 2.929011550696921873e+00, 1.375485464243689826e+01, 1.375485464243689826e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.281000000000000000e+03, 2.961474674784016159e+00, 3.155244872539666900e+01, 3.155244872539666900e+01, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 2.130000000000000000e+02, 2.993937798871110445e+00, 2.165622844873544750e+02, 2.165622844873544750e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 9.790000000000000000e+02, 3.026400922958205619e+00, 1.237442549171475576e+02, 1.237442549171475576e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.812000000000000000e+03, 3.058864047045300794e+00, 3.833029646661938727e+02, 3.833029646661938727e+02, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 2.300000000000000000e+02, 3.091327171132395080e+00, 8.512143332829600340e+00, 8.512143332829600340e+00, 0}, + {3.261703997964817603e+01, -9.641582449881775574e+01, 1.704000000000000000e+03, 3.123790295219489366e+00, 1.783052805968801380e+01, 1.783052805968801380e+01, 0}, + +}; diff --git a/src/lib/adsb/CMakeLists.txt b/src/lib/adsb/CMakeLists.txt index 2012ef827d..10a4eaf101 100644 --- a/src/lib/adsb/CMakeLists.txt +++ b/src/lib/adsb/CMakeLists.txt @@ -31,4 +31,8 @@ # ############################################################################ -px4_add_library(adsb adsb.cpp) +px4_add_library(adsb AdsbConflict.cpp) + +target_link_libraries(adsb PUBLIC geo) + +px4_add_functional_gtest(SRC AdsbConflictTest.cpp LINKLIBS adsb) diff --git a/src/lib/adsb/adsb.cpp b/src/lib/adsb/adsb.cpp deleted file mode 100644 index 36bffcc179..0000000000 --- a/src/lib/adsb/adsb.cpp +++ /dev/null @@ -1,32 +0,0 @@ -/**************************************************************************** - * - * Copyright (C) 2022 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ diff --git a/src/lib/adsb/test_adsb_helper.ipynb b/src/lib/adsb/test_adsb_helper.ipynb new file mode 100644 index 0000000000..3702497cb9 --- /dev/null +++ b/src/lib/adsb/test_adsb_helper.ipynb @@ -0,0 +1,646 @@ +{ + "cells": [ + { + "cell_type": "code", + "execution_count": 2340, + "metadata": {}, + "outputs": [], + "source": [ + "from plotly.offline import init_notebook_mode, iplot\n", + "\n", + "import pandas as pd\n", + "import plotly.graph_objects as go\n", + "import math\n", + "import numpy as np\n", + "np.set_printoptions(threshold=sys.maxsize)\n", + "import random\n", + "from decimal import Decimal" + ] + }, + { + "cell_type": "code", + "execution_count": 2341, + "metadata": {}, + "outputs": [], + "source": [ + "\n", + "def to_lonlat(point_xy, origin):\n", + " r = 6371000\n", + "\n", + " o_lat = math.radians(Decimal(origin[0]))\n", + " o_lon = math.radians(Decimal(origin[1]))\n", + " cos_phi = math.cos(o_lat)\n", + " lat = Decimal(point_xy[1])/Decimal(r) + Decimal(o_lat)\n", + " lon = Decimal(point_xy[0])/Decimal((r*cos_phi)) + Decimal(o_lon)\n", + " return {'lon': math.degrees(lon), 'lat': math.degrees(lat)}\n", + "\n", + "\n", + "def seg_lonlat(seg):\n", + " return [to_lonlat(i,origin) for i in seg]\n", + "\n", + "def plot_segment(fig,seg):\n", + "\n", + " df = pd.DataFrame(seg)\n", + " fig.add_trace(go.Scattermapbox(\n", + " mode = \"markers+lines\",\n", + " lon = df['lon'],\n", + " lat = df['lat'],\n", + " marker = {'size': 10}))\n", + "\n", + "def wrap(x, low, high):\n", + " if (low <= x and x < high):\n", + " return x\n", + "\n", + " range = high - low\n", + " inv_range = 1.0/range\n", + " num_wraps = math.floor((x - low) * inv_range)\n", + " return x - (range * num_wraps)\n", + "\n", + "\n", + "def waypoint_from_heading_and_distance(lat_traffic, lon_traffic, bearing, dist):\n", + " r = 6371000\n", + " bearing = wrap(bearing, 0, 2*math.pi)\n", + " radius_ratio = dist / r\n", + "\n", + " lat_traffic_rad = math.radians(lat_traffic)\n", + " lon_traffic_rad = math.radians(lon_traffic)\n", + "\n", + " lat_end = math.asin(math.sin(lat_traffic_rad) * math.cos(radius_ratio) +\n", + " math.cos(lat_traffic_rad) * math.sin(radius_ratio) * math.cos(bearing))\n", + "\n", + " lon_end = lon_traffic_rad + math.atan2(math.sin(bearing) * math.sin(radius_ratio) * math.cos(\n", + " lat_traffic_rad), math.cos(radius_ratio) - math.sin(lat_traffic_rad) * math.sin(lat_end))\n", + "\n", + " lat_end = math.degrees(lat_end)\n", + " lon_end = math.degrees(lon_end)\n", + "\n", + " return lat_end, lon_end, bearing, radius_ratio\n", + "\n", + "\n", + "def get_bearing_to_next_waypoint(lat_start, lon_start, lat_end, lon_end):\n", + "\n", + " lat_start_rad = math.radians(lat_start)\n", + " lat_end_rad = math.radians(lat_end)\n", + "\n", + " cos_lat_end = math.cos(lat_end_rad)\n", + " d_lon = math.radians(lon_end - lon_start)\n", + "\n", + " y = (math.sin(d_lon) * cos_lat_end)\n", + " x = (math.cos(lat_start_rad) * math.sin(lat_end_rad) -\n", + " math.sin(lat_start_rad) * cos_lat_end * math.cos(d_lon))\n", + "\n", + " return wrap(math.atan2(y, x), -math.pi, math.pi)\n", + "\n", + "\n", + "def get_distance_to_next_waypoint(lat_uav, lon_uav, lat_end, lon_end):\n", + "\n", + " r = 6371000\n", + "\n", + " lat_uav_rad = math.radians(lat_uav)\n", + " lat_end_rad = math.radians(lat_end)\n", + "\n", + " d_lat = lat_end_rad - lat_uav_rad\n", + " d_lon = math.radians(lon_end) - math.radians(lon_uav)\n", + "\n", + " a = math.sin(d_lat / 2.0) * math.sin(d_lat / 2.0) + math.sin(d_lon / 2.0) * math.sin(d_lon / 2.0) * math.cos(lat_uav_rad) * math.cos(\n", + " lat_end_rad)\n", + "\n", + " c = math.atan2(math.sqrt(a), math.sqrt(1.0 - a))\n", + "\n", + " return r * 2.0 * c\n", + "\n", + "\n", + "def get_distance_to_line(lat_uav, lon_uav, lat_traffic, lon_traffic, lat_end, lon_end):\n", + "\n", + " return_value = 1\n", + " crosstrack_distance = 0.0\n", + "\n", + " dist_to_end = get_distance_to_next_waypoint(\n", + " lat_uav, lon_uav, lat_end, lon_end)\n", + "\n", + " if (dist_to_end < 0.1):\n", + " return_value = 0 \n", + "\n", + " bearing_end = get_bearing_to_next_waypoint(\n", + " lat_uav, lon_uav, lat_end, lon_end)\n", + " bearing_track = get_bearing_to_next_waypoint(\n", + " lat_traffic, lon_traffic, lat_end, lon_end)\n", + " bearing_diff = wrap(bearing_track - bearing_end, -math.pi, math.pi)\n", + "\n", + " if (bearing_diff > math.pi/2 or bearing_diff < -math.pi/2):\n", + " return_value = 0\n", + "\n", + " crosstrack_distance = (dist_to_end) * math.sin(bearing_diff)\n", + "\n", + " return return_value, crosstrack_distance \n" + ] + }, + { + "cell_type": "code", + "execution_count": 2342, + "metadata": {}, + "outputs": [], + "source": [ + "#uav location \n", + "origin=[32.617013,-96.490564]\n", + "h = 0 #x\n", + "k = 0 #y\n", + "uav_z = 1000\n", + "\n", + "vx_now = 0\n", + "vy_now = 0\n", + "vz_now = 0\n", + "\n", + "crosstrack_separation = 500\n", + "vertical_separation = 500\n", + "collision_time_threshold = 60.0\n", + "\n", + "rot_step = 1.86\n", + "\n" + ] + }, + { + "cell_type": "code", + "execution_count": 2343, + "metadata": {}, + "outputs": [], + "source": [ + "lines=[\n", + " [[10000,10000],[h,k]],\n", + " [[1000,-1000],[h,k]],\n", + " [[-5000,-4000],[h,k]],\n", + " [[-3000,3000],[h,k]],\n", + " [[-200,200],[h,k]],\n", + " [[0,0],[h,k]],\n", + " [[50,100],[h,k]],\n", + " [[1000000,9000000],[h,k]],\n", + " [[800,30],[h,k]],\n", + " [[7000,3],[h,k]],\n", + "]\n", + "\n", + "fig = go.Figure()\n", + " \n", + "[plot_segment(fig,seg_lonlat(i)) for i in lines]\n", + "\n", + "fig.update_layout(\n", + " margin ={'l':0,'t':0,'b':0,'r':0},\n", + " mapbox = {\n", + " 'center': {'lon': origin[1], 'lat': origin[0]},\n", + " 'style': \"stamen-terrain\",\n", + " 'zoom': 13})\n", + "\n", + "fig.write_html('traffic.html', auto_open=True)" + ] + }, + { + "cell_type": "code", + "execution_count": 2344, + "metadata": {}, + "outputs": [], + "source": [ + "\n", + "dist_xy = []\n", + "\n", + "for i in range(len(lines)):\n", + " r = math.sqrt(lines[i][0][0]*lines[i][0][0] + lines[i][0][1]*lines[i][0][1])\n", + " dist_xy.append(r) " + ] + }, + { + "cell_type": "code", + "execution_count": 2345, + "metadata": {}, + "outputs": [], + "source": [ + "a = [seg_lonlat(i) for i in lines]\n", + "\n", + "lat = []\n", + "lon = []\n", + "address = []\n", + "\n", + "for i in range(0,len(a)):\n", + " #print(str(a[i][0]['lat'])+\",\"+str(a[i][0]['lon']))\n", + " lat.append(a[i][0]['lat'])\n", + " lon.append(a[i][0]['lon'])\n", + " address.append(random.randint(1000,9999))\n" + ] + }, + { + "cell_type": "code", + "execution_count": 2364, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "[6751, 2839, 2431, 3222, 2171, 7666, 4249, 8438, 4110, 5798]\n" + ] + } + ], + "source": [ + "print(address)" + ] + }, + { + "cell_type": "code", + "execution_count": 2346, + "metadata": {}, + "outputs": [], + "source": [ + "heading = np.arange(-math.pi, math.pi, math.radians(rot_step)) " + ] + }, + { + "cell_type": "code", + "execution_count": 2347, + "metadata": {}, + "outputs": [], + "source": [ + "headings = []\n", + "\n", + "ct_dist = []\n", + "ct_distance_conflict_threshold = []\n", + "\n", + "vertical_arr = []\n", + "vertical_check = []\n", + "\n", + "dist_xyz = []\n", + "traffic_vel = []\n", + "time_check = []\n", + "collision_times = []" + ] + }, + { + "cell_type": "code", + "execution_count": 2348, + "metadata": {}, + "outputs": [], + "source": [ + "for j in range(len(dist_xy)):\n", + "\n", + " prediction_dist = dist_xy[j] + 1000 \n", + "\n", + " for i in heading:\n", + "\n", + " headings.append(i) \n", + "\n", + " lat_end, lon_end, bearing, radius_ratio = waypoint_from_heading_and_distance(lat[j],lon[j],i,prediction_dist)\n", + " \n", + "\n", + " return_value, ct = get_distance_to_line(origin[0],origin[1],lat[j],lon[j],lat_end, lon_end)\n", + "\n", + " ct = abs(ct)\n", + "\n", + " #print(lat_end,lon_end, bearing, radius_ratio, return_value, ct)\n", + "\n", + " ct_dist.append(ct)\n", + " if(ct < crosstrack_separation and return_value):\n", + " ct_distance_conflict_threshold.append(True)\n", + " else:\n", + " ct_distance_conflict_threshold.append(False)\n", + "\n", + " vertical_separation_check = random.choice([True, False])\n", + " if (vertical_separation_check):\n", + " z_diff = random.randrange(0, vertical_separation-1)\n", + " vertical_check.append(True)\n", + " else:\n", + " z_diff = random.randrange(vertical_separation+1, 1000)\n", + " vertical_check.append(False)\n", + " \n", + " sign = random.choice([-1, 1])\n", + " vertical_arr.append(sign*z_diff+uav_z)\n", + "\n", + " xyz = math.sqrt(z_diff*z_diff + dist_xy[j]*dist_xy[j])\n", + " dist_xyz.append(xyz)\n", + "\n", + " collision_time_check = random.choice([True, False])\n", + " if (collision_time_check):\n", + " time_to_collision = random.randrange(1, collision_time_threshold)\n", + " time_check.append(True)\n", + " collision_times.append(time_to_collision)\n", + " else:\n", + " time_to_collision = random.randrange(collision_time_threshold+1, 10*collision_time_threshold)\n", + " time_check.append(False)\n", + " collision_times.append(time_to_collision)\n", + "\n", + " vel = xyz/time_to_collision\n", + " traffic_vel.append(math.sqrt((vel*vel)/2))\n", + "\n", + " " + ] + }, + { + "cell_type": "code", + "execution_count": 2349, + "metadata": {}, + "outputs": [], + "source": [ + "lat_traffic = np.array([])\n", + "\n", + "for i in lat:\n", + " for j in range(len(heading)):\n", + " lat_now = np.array([i])\n", + " lat_traffic = np.concatenate([lat_traffic, lat_now])\n", + "\n", + "\n", + "lon_traffic = np.array([])\n", + "\n", + "for i in lon:\n", + " for j in range(len(heading)):\n", + " lon_now = np.array([i])\n", + " lon_traffic = np.concatenate([lon_traffic, lon_now])\n" + ] + }, + { + "cell_type": "code", + "execution_count": 2350, + "metadata": {}, + "outputs": [], + "source": [ + "in_conflict = []\n", + "\n", + "for i in range(len(time_check)):\n", + " if((time_check[i]== True) and (vertical_check[i] == True) and (ct_distance_conflict_threshold[i] == True)):\n", + " in_conflict.append(True)\n", + " else:\n", + " in_conflict.append(False)" + ] + }, + { + "cell_type": "code", + "execution_count": 2351, + "metadata": {}, + "outputs": [], + "source": [ + "#print(vertical_check)" + ] + }, + { + "cell_type": "code", + "execution_count": 2352, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "946\n" + ] + } + ], + "source": [ + "print(vertical_arr[78])" + ] + }, + { + "cell_type": "code", + "execution_count": 2353, + "metadata": {}, + "outputs": [], + "source": [ + "#print(headings)" + ] + }, + { + "cell_type": "code", + "execution_count": 2354, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "13903.21572374496\n" + ] + } + ], + "source": [ + "print(ct_dist[78])" + ] + }, + { + "cell_type": "code", + "execution_count": 2355, + "metadata": {}, + "outputs": [], + "source": [ + "#print(ct_distance_conflict_threshold)" + ] + }, + { + "cell_type": "code", + "execution_count": 2356, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "False\n" + ] + } + ], + "source": [ + "print(time_check[78])" + ] + }, + { + "cell_type": "code", + "execution_count": 2357, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "456" + ] + }, + "execution_count": 2357, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "collision_times[78]" + ] + }, + { + "cell_type": "code", + "execution_count": 2358, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "21.929984429241845" + ] + }, + "execution_count": 2358, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "traffic_vel[78]" + ] + }, + { + "cell_type": "code", + "execution_count": 2359, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "False\n" + ] + } + ], + "source": [ + "print(in_conflict[78])" + ] + }, + { + "cell_type": "code", + "execution_count": 2360, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "158\n" + ] + } + ], + "source": [ + "print(np.count_nonzero(in_conflict))" + ] + }, + { + "cell_type": "code", + "execution_count": 2361, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "dist_xy 10\n", + "lat_traffic 1940\n", + "lon_traffic 1940\n" + ] + } + ], + "source": [ + "print(\"dist_xy\", len(dist_xy))\n", + "print(\"lat_traffic\", len(lat_traffic))\n", + "print(\"lon_traffic\", len(lon_traffic))\n", + "\n" + ] + }, + { + "cell_type": "code", + "execution_count": 2362, + "metadata": {}, + "outputs": [], + "source": [ + "\"\"\" \t\n", + "\tstruct traffic_data_s {\n", + "\tdouble lat_traffic\n", + "\tdouble lon_traffic\n", + "\tfloat alt_traffic\n", + "\tfloat heading_traffic\n", + "\tfloat vxy_traffic\n", + "\tfloat vz_traffic\n", + "\tbool in_conflict\n", + "\"\"\"\n", + "\n", + "traffic_data = np.zeros(shape=(7, len(lat_traffic)))\n", + "\n", + "traffic_data = np.concatenate([traffic_data,[lat_traffic]])\n", + "\n", + "traffic_data = np.concatenate([traffic_data,[lon_traffic]])\n", + "\n", + "\n", + "alt_traffic = np.asarray(vertical_arr)\n", + "traffic_data = np.concatenate([traffic_data,[alt_traffic]])\n", + "\n", + "headings_arr = np.asarray(headings)\n", + "traffic_data = np.concatenate([traffic_data,[headings_arr]])\n", + "\n", + "vxy_traffic = np.asarray(traffic_vel)\n", + "traffic_data = np.concatenate([traffic_data,[vxy_traffic]])\n", + "\n", + "vz_traffic = np.asarray(traffic_vel)\n", + "traffic_data = np.concatenate([traffic_data,[vz_traffic]])\n", + "\n", + "in_conflict_arr = np.asarray(in_conflict)\n", + "traffic_data = np.concatenate([traffic_data,[in_conflict_arr]])\n", + "\n", + "for i in range(7):\n", + "\ttraffic_data = np.delete(traffic_data,0,0)\n", + "\n" + ] + }, + { + "cell_type": "code", + "execution_count": 2363, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "(1940, 7)\n" + ] + } + ], + "source": [ + "np.savetxt(\"foo.csv\", traffic_data.transpose(), delimiter=\",\",newline='}, \\n {')\n", + "print(traffic_data.transpose().shape)" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 3.8.10 64-bit", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.8.10" + }, + "toc": { + "base_numbering": 1, + "nav_menu": {}, + "number_sections": true, + "sideBar": true, + "skip_h1_title": false, + "title_cell": "Table of Contents", + "title_sidebar": "Contents", + "toc_cell": false, + "toc_position": {}, + "toc_section_display": true, + "toc_window_display": false + }, + "vscode": { + "interpreter": { + "hash": "e7370f93d1d0cde622a1f8e1c04877d8463912d04d973331ad4851f04de6915a" + } + } + }, + "nbformat": 4, + "nbformat_minor": 4 +} diff --git a/src/lib/geo/geo.cpp b/src/lib/geo/geo.cpp index 631a8c35cb..bbbb7d0782 100644 --- a/src/lib/geo/geo.cpp +++ b/src/lib/geo/geo.cpp @@ -49,10 +49,6 @@ using matrix::wrap_pi; using matrix::wrap_2pi; -#ifndef hrt_absolute_time -# define hrt_absolute_time() (0) -#endif - /* * Azimuthal Equidistant Projection * formulas according to: http://mathworld.wolfram.com/AzimuthalEquidistantProjection.html @@ -146,6 +142,7 @@ void waypoint_from_heading_and_distance(double lat_start, double lon_start, floa double *lat_target, double *lon_target) { bearing = wrap_2pi(bearing); + double radius_ratio = static_cast(dist) / CONSTANTS_RADIUS_OF_EARTH; double lat_start_rad = math::radians(lat_start); @@ -218,7 +215,7 @@ void add_vector_to_global_position(double lat_now, double lon_now, float v_n, fl // Additional functions - @author Doug Weibel -int get_distance_to_line(struct crosstrack_error_s *crosstrack_error, double lat_now, double lon_now, +int get_distance_to_line(struct crosstrack_error_s &crosstrack_error, double lat_now, double lon_now, double lat_start, double lon_start, double lat_end, double lon_end) { // This function returns the distance to the nearest point on the track line. Distance is positive if current @@ -226,9 +223,9 @@ int get_distance_to_line(struct crosstrack_error_s *crosstrack_error, double lat // headed towards the end point. int return_value = -1; // Set error flag, cleared when valid result calculated. - crosstrack_error->past_end = false; - crosstrack_error->distance = 0.0f; - crosstrack_error->bearing = 0.0f; + crosstrack_error.past_end = false; + crosstrack_error.distance = 0.0f; + crosstrack_error.bearing = 0.0f; float dist_to_end = get_distance_to_next_waypoint(lat_now, lon_now, lat_end, lon_end); @@ -243,18 +240,18 @@ int get_distance_to_line(struct crosstrack_error_s *crosstrack_error, double lat // Return past_end = true if past end point of line if (bearing_diff > M_PI_2_F || bearing_diff < -M_PI_2_F) { - crosstrack_error->past_end = true; + crosstrack_error.past_end = true; return_value = 0; return return_value; } - crosstrack_error->distance = (dist_to_end) * sinf(bearing_diff); + crosstrack_error.distance = (dist_to_end) * sinf(bearing_diff); if (sinf(bearing_diff) >= 0) { - crosstrack_error->bearing = wrap_pi(bearing_track - M_PI_2_F); + crosstrack_error.bearing = wrap_pi(bearing_track - M_PI_2_F); } else { - crosstrack_error->bearing = wrap_pi(bearing_track + M_PI_2_F); + crosstrack_error.bearing = wrap_pi(bearing_track + M_PI_2_F); } return_value = 0; diff --git a/src/lib/geo/geo.h b/src/lib/geo/geo.h index cb93e99be5..8d38bd2632 100644 --- a/src/lib/geo/geo.h +++ b/src/lib/geo/geo.h @@ -136,7 +136,7 @@ void get_vector_to_next_waypoint_fast(double lat_now, double lon_now, double lat void add_vector_to_global_position(double lat_now, double lon_now, float v_n, float v_e, double *lat_res, double *lon_res); -int get_distance_to_line(struct crosstrack_error_s *crosstrack_error, double lat_now, double lon_now, +int get_distance_to_line(struct crosstrack_error_s &crosstrack_error, double lat_now, double lon_now, double lat_start, double lon_start, double lat_end, double lon_end); int get_distance_to_arc(struct crosstrack_error_s *crosstrack_error, double lat_now, double lon_now, diff --git a/src/modules/navigator/CMakeLists.txt b/src/modules/navigator/CMakeLists.txt index 08eb898a74..30725a05d0 100644 --- a/src/modules/navigator/CMakeLists.txt +++ b/src/modules/navigator/CMakeLists.txt @@ -52,6 +52,7 @@ px4_add_module( vtol_takeoff.cpp DEPENDS geo + adsb geofence_breach_avoidance motion_planning mission_feasibility_checker diff --git a/src/modules/navigator/navigator.h b/src/modules/navigator/navigator.h index 2eee56cebb..d80beb9333 100644 --- a/src/modules/navigator/navigator.h +++ b/src/modules/navigator/navigator.h @@ -55,6 +55,7 @@ #include "GeofenceBreachAvoidance/geofence_breach_avoidance.h" +#include #include #include #include @@ -129,29 +130,14 @@ public: */ void publish_vehicle_cmd(vehicle_command_s *vcmd); - /** - * Generate an artificial traffic indication - * - * @param distance Horizontal distance to this vehicle - * @param direction Direction in earth frame from this vehicle in radians - * @param traffic_heading Travel direction of the traffic in earth frame in radians - * @param altitude_diff Altitude difference, positive is up - * @param hor_velocity Horizontal velocity of traffic, in m/s - * @param ver_velocity Vertical velocity of traffic, in m/s - * @param emitter_type, Type of vehicle, as a number - */ - void fake_traffic(const char *callsign, float distance, float direction, float traffic_heading, float altitude_diff, - float hor_velocity, float ver_velocity, int emitter_type); - /** * Check nearby traffic for potential collisions */ void check_traffic(); - /** - * Buffer for air traffic to control the amount of messages sent to a user - */ - bool buffer_air_traffic(uint32_t icao_address); + void take_traffic_conflict_action(); + + void run_fake_traffic(); /** * Setters @@ -327,11 +313,6 @@ public: private: - struct traffic_buffer_s { - uint32_t icao_address; - hrt_abstime timestamp; - }; - int _local_pos_sub{-1}; int _mission_sub{-1}; int _vehicle_status_sub{-1}; @@ -395,6 +376,7 @@ private: Land _land; /**< class for handling land commands */ PrecLand _precland; /**< class for handling precision land commands */ RTL _rtl; /**< class that handles RTL */ + AdsbConflict _adsb_conflict; /**< class that handles ADSB conflict avoidance */ NavigatorMode *_navigation_mode{nullptr}; /**< abstract pointer to current navigation mode class */ NavigatorMode *_navigation_mode_array[NAVIGATOR_MODE_ARRAY_SIZE] {}; /**< array of navigation modes */ @@ -445,8 +427,9 @@ private: (ParamFloat) _param_nav_mc_alt_rad, /**< acceptance rad for multicopter alt */ (ParamInt) _param_nav_force_vt, /**< acceptance radius for multicopter alt */ (ParamInt) _param_nav_traff_avoid, /**< avoiding other aircraft is enabled */ - (ParamFloat) _param_nav_traff_a_radu, /**< avoidance Distance Unmanned*/ - (ParamFloat) _param_nav_traff_a_radm, /**< avoidance Distance Manned*/ + (ParamFloat) _param_nav_traff_a_hor_ct, /**< avoidance Distance Crosstrack*/ + (ParamFloat) _param_nav_traff_a_ver, /**< avoidance Distance Vertical*/ + (ParamInt) _param_nav_traff_collision_time, (ParamFloat) _param_min_ltr_alt, /**< minimum altitude in Loiter mode*/ // non-navigator parameters: Mission (MIS_*) diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index 7cc4f130f9..10349a6cb8 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -51,6 +51,7 @@ #include #include #include +#include #include #include #include @@ -107,6 +108,10 @@ Navigator::Navigator() : // Update the timeout used in mission_block (which can't hold it's own parameters) _mission.set_payload_deployment_timeout(_param_mis_payload_delivery_timeout.get()); + _adsb_conflict.set_conflict_detection_params(_param_nav_traff_a_hor_ct.get(), + _param_nav_traff_a_ver.get(), + _param_nav_traff_collision_time.get(), _param_nav_traff_avoid.get()); + reset_triplets(); } @@ -1202,281 +1207,68 @@ void Navigator::load_fence_from_file(const char *filename) _geofence.loadFromFile(filename); } -void Navigator::fake_traffic(const char *callsign, float distance, float direction, float traffic_heading, - float altitude_diff, float hor_velocity, float ver_velocity, int emitter_type) +void Navigator::take_traffic_conflict_action() { - double lat{0.0}; - double lon{0.0}; - waypoint_from_heading_and_distance(get_global_position()->lat, get_global_position()->lon, direction, distance, &lat, - &lon); - float alt = get_global_position()->alt + altitude_diff; + vehicle_command_s vcmd = {}; - // float vel_n = get_global_position()->vel_n; - // float vel_e = get_global_position()->vel_e; - // float vel_d = get_global_position()->vel_d; + switch (_adsb_conflict._conflict_detection_params.traffic_avoidance_mode) { - transponder_report_s tr{}; - tr.timestamp = hrt_absolute_time(); - tr.icao_address = 1234; - tr.lat = lat; // Latitude, expressed as degrees - tr.lon = lon; // Longitude, expressed as degrees - tr.altitude_type = 0; - tr.altitude = alt; - tr.heading = traffic_heading; //-atan2(vel_e, vel_n); // Course over ground in radians - tr.hor_velocity = hor_velocity; //sqrtf(vel_e * vel_e + vel_n * vel_n); // The horizontal velocity in m/s - tr.ver_velocity = ver_velocity; //-vel_d; // The vertical velocity in m/s, positive is up - strncpy(&tr.callsign[0], callsign, sizeof(tr.callsign) - 1); - tr.callsign[sizeof(tr.callsign) - 1] = 0; - tr.emitter_type = emitter_type; // Type from ADSB_EMITTER_TYPE enum - tr.tslc = 2; // Time since last communication in seconds - tr.flags = transponder_report_s::PX4_ADSB_FLAGS_VALID_COORDS | transponder_report_s::PX4_ADSB_FLAGS_VALID_HEADING | - transponder_report_s::PX4_ADSB_FLAGS_VALID_VELOCITY | - transponder_report_s::PX4_ADSB_FLAGS_VALID_ALTITUDE | - (transponder_report_s::ADSB_EMITTER_TYPE_UAV & emitter_type ? 0 : - transponder_report_s::PX4_ADSB_FLAGS_VALID_CALLSIGN); // Flags to indicate various statuses including valid data fields - tr.squawk = 6667; + case 2: { + _rtl.set_return_alt_min(true); + vcmd.command = vehicle_command_s::VEHICLE_CMD_NAV_RETURN_TO_LAUNCH; + publish_vehicle_cmd(&vcmd); + break; + } -#ifndef BOARD_HAS_NO_UUID - px4_guid_t px4_guid; - board_get_px4_guid(px4_guid); - memcpy(tr.uas_id, px4_guid, sizeof(px4_guid_t)); //simulate own GUID -#else + case 3: { + vcmd.command = vehicle_command_s::VEHICLE_CMD_NAV_LAND; + publish_vehicle_cmd(&vcmd); + break; - for (int i = 0; i < PX4_GUID_BYTE_LENGTH ; i++) { - tr.uas_id[i] = 0xe0 + i; //simulate GUID + } + + case 4: { + + vcmd.command = vehicle_command_s::VEHICLE_CMD_NAV_LOITER_UNLIM; + publish_vehicle_cmd(&vcmd); + break; + + } } -#endif /* BOARD_HAS_NO_UUID */ +} - uORB::Publication tr_pub{ORB_ID(transponder_report)}; - tr_pub.publish(tr); +void Navigator::run_fake_traffic() +{ + + _adsb_conflict.run_fake_traffic(get_global_position()->lat, get_global_position()->lon, + get_global_position()->alt); } void Navigator::check_traffic() { - double lat = get_global_position()->lat; - double lon = get_global_position()->lon; - float alt = get_global_position()->alt; - // TODO for non-multirotors predicting the future - // position as accurately as possible will become relevant - // float vel_n = get_global_position()->vel_n; - // float vel_e = get_global_position()->vel_e; - // float vel_d = get_global_position()->vel_d; + if (_traffic_sub.updated()) { - bool changed = _traffic_sub.updated(); - - char uas_id[11]; //GUID of incoming UTM messages - - float NAVTrafficAvoidUnmanned = _param_nav_traff_a_radu.get(); - float NAVTrafficAvoidManned = _param_nav_traff_a_radm.get(); - float horizontal_separation = NAVTrafficAvoidManned; - float vertical_separation = NAVTrafficAvoidManned; - - while (changed) { - - //vehicle_status_s vs{}; - transponder_report_s tr{}; - _traffic_sub.copy(&tr); + _traffic_sub.copy(&_adsb_conflict._transponder_report); uint16_t required_flags = transponder_report_s::PX4_ADSB_FLAGS_VALID_COORDS | transponder_report_s::PX4_ADSB_FLAGS_VALID_HEADING | transponder_report_s::PX4_ADSB_FLAGS_VALID_VELOCITY | transponder_report_s::PX4_ADSB_FLAGS_VALID_ALTITUDE; - if ((tr.flags & required_flags) != required_flags) { - changed = _traffic_sub.updated(); - continue; - } + if ((_adsb_conflict._transponder_report.flags & required_flags) == required_flags) { - //convert UAS_id byte array to char array for User Warning - for (int i = 0; i < 5; i++) { - snprintf(&uas_id[i * 2], sizeof(uas_id) - i * 2, "%02x", tr.uas_id[PX4_GUID_BYTE_LENGTH - 5 + i]); - } + _adsb_conflict.detect_traffic_conflict(get_global_position()->lat, get_global_position()->lon, + get_global_position()->alt, _local_pos.vx, _local_pos.vy, _local_pos.vz); - uint64_t uas_id_int = 0; - - for (int i = 0; i < 8; i++) { - uas_id_int |= (uint64_t)(tr.uas_id[PX4_GUID_BYTE_LENGTH - i - 1]) << (i * 8); - } - - //Manned/Unmanned Vehicle Seperation Distance - if (tr.emitter_type == transponder_report_s::ADSB_EMITTER_TYPE_UAV) { - horizontal_separation = NAVTrafficAvoidUnmanned; - vertical_separation = NAVTrafficAvoidUnmanned; - } - - float d_hor, d_vert; - get_distance_to_point_global_wgs84(lat, lon, alt, - tr.lat, tr.lon, tr.altitude, &d_hor, &d_vert); - - - // predict final altitude (positive is up) in prediction time frame - float end_alt = tr.altitude + (d_vert / tr.hor_velocity) * tr.ver_velocity; - - // Predict until the vehicle would have passed this system at its current speed - float prediction_distance = d_hor + 1000.0f; - - // If the altitude is not getting close to us, do not calculate - // the horizontal separation. - // Since commercial flights do most of the time keep flight levels - // check for the current and for the predicted flight level. - // we also make the implicit assumption that this system is on the lowest - // flight level close to ground in the - // (end_alt - horizontal_separation < alt) condition. If this system should - // ever be used in normal airspace this implementation would anyway be - // inappropriate as it should be replaced with a TCAS compliant solution. - - if ((fabsf(alt - tr.altitude) < vertical_separation) || ((end_alt - horizontal_separation) < alt)) { - - double end_lat, end_lon; - waypoint_from_heading_and_distance(tr.lat, tr.lon, tr.heading, prediction_distance, &end_lat, &end_lon); - - struct crosstrack_error_s cr; - - if (!get_distance_to_line(&cr, lat, lon, tr.lat, tr.lon, end_lat, end_lon)) { - - if (!cr.past_end && (fabsf(cr.distance) < horizontal_separation)) { - - bool action_needed = buffer_air_traffic(tr.icao_address); - - if (action_needed) { - // direction of traffic in human-readable 0..360 degree in earth frame - int traffic_direction = math::degrees(tr.heading) + 180; - int traffic_seperation = (int)fabsf(cr.distance); - - switch (_param_nav_traff_avoid.get()) { - - case 0: { - /* Ignore */ - PX4_WARN("TRAFFIC %s! dst %d, hdg %d", - tr.flags & transponder_report_s::PX4_ADSB_FLAGS_VALID_CALLSIGN ? tr.callsign : uas_id, - traffic_seperation, - traffic_direction); - break; - } - - case 1: { - /* Warn only */ - mavlink_log_critical(&_mavlink_log_pub, "Warning TRAFFIC %s! dst %d, hdg %d\t", - tr.flags & transponder_report_s::PX4_ADSB_FLAGS_VALID_CALLSIGN ? tr.callsign : uas_id, - traffic_seperation, - traffic_direction); - /* EVENT - * @description - * - ID: {1} - * - Distance: {2m} - * - Direction: {3} degrees - */ - events::send(events::ID("navigator_traffic"), events::Log::Critical, "Traffic alert", - uas_id_int, traffic_seperation, traffic_direction); - break; - } - - case 2: { - /* RTL Mode */ - mavlink_log_critical(&_mavlink_log_pub, "TRAFFIC: %s Returning home! dst %d, hdg %d\t", - tr.flags & transponder_report_s::PX4_ADSB_FLAGS_VALID_CALLSIGN ? tr.callsign : uas_id, - traffic_seperation, - traffic_direction); - /* EVENT - * @description - * - ID: {1} - * - Distance: {2m} - * - Direction: {3} degrees - */ - events::send(events::ID("navigator_traffic_rtl"), events::Log::Critical, - "Traffic alert, returning home", - uas_id_int, traffic_seperation, traffic_direction); - - // set the return altitude to minimum - _rtl.set_return_alt_min(true); - - // ask the commander to execute an RTL - vehicle_command_s vcmd = {}; - vcmd.command = vehicle_command_s::VEHICLE_CMD_NAV_RETURN_TO_LAUNCH; - publish_vehicle_cmd(&vcmd); - break; - } - - case 3: { - /* Land Mode */ - mavlink_log_critical(&_mavlink_log_pub, "TRAFFIC: %s Landing! dst %d, hdg % d\t", - tr.flags & transponder_report_s::PX4_ADSB_FLAGS_VALID_CALLSIGN ? tr.callsign : uas_id, - traffic_seperation, - traffic_direction); - /* EVENT - * @description - * - ID: {1} - * - Distance: {2m} - * - Direction: {3} degrees - */ - events::send(events::ID("navigator_traffic_land"), events::Log::Critical, - "Traffic alert, landing", - uas_id_int, traffic_seperation, traffic_direction); - - // ask the commander to land - vehicle_command_s vcmd = {}; - vcmd.command = vehicle_command_s::VEHICLE_CMD_NAV_LAND; - publish_vehicle_cmd(&vcmd); - break; - - } - - case 4: { - /* Position hold */ - mavlink_log_critical(&_mavlink_log_pub, "TRAFFIC: %s Holding position! dst %d, hdg %d\t", - tr.flags & transponder_report_s::PX4_ADSB_FLAGS_VALID_CALLSIGN ? tr.callsign : uas_id, - traffic_seperation, - traffic_direction); - /* EVENT - * @description - * - ID: {1} - * - Distance: {2m} - * - Direction: {3} degrees - */ - events::send(events::ID("navigator_traffic_hold"), events::Log::Critical, - "Traffic alert, holding position", - uas_id_int, traffic_seperation, traffic_direction); - - // ask the commander to Loiter - vehicle_command_s vcmd = {}; - vcmd.command = vehicle_command_s::VEHICLE_CMD_NAV_LOITER_UNLIM; - publish_vehicle_cmd(&vcmd); - break; - - } - } - } - } + if (_adsb_conflict.handle_traffic_conflict()) { + take_traffic_conflict_action(); } } - - changed = _traffic_sub.updated(); } } -bool Navigator::buffer_air_traffic(uint32_t icao_address) -{ - bool action_needed = true; - - if (_traffic_buffer.icao_address == icao_address) { - - if (hrt_elapsed_time(&_traffic_buffer.timestamp) > 60_s) { - _traffic_buffer.timestamp = hrt_absolute_time(); - - } else { - action_needed = false; - } - - } else { - _traffic_buffer.timestamp = hrt_absolute_time(); - _traffic_buffer.icao_address = icao_address; - } - - return action_needed; -} - bool Navigator::abort_landing() { // only abort if currently landing and position controller status updated @@ -1519,12 +1311,9 @@ int Navigator::custom_command(int argc, char *argv[]) return 0; } else if (!strcmp(argv[0], "fake_traffic")) { - get_instance()->fake_traffic("LX007", 500, 1.0f, -1.0f, 100.0f, 90.0f, 0.001f, - transponder_report_s::ADSB_EMITTER_TYPE_LIGHT); - get_instance()->fake_traffic("LX55", 1000, 0, 0, 100.0f, 90.0f, 0.001f, transponder_report_s::ADSB_EMITTER_TYPE_SMALL); - get_instance()->fake_traffic("LX20", 15000, 1.0f, -1.0f, 280.0f, 90.0f, 0.001f, - transponder_report_s::ADSB_EMITTER_TYPE_LARGE); - get_instance()->fake_traffic("UAV", 10, 1.0f, -2.0f, 10.0f, 10.0f, 0.01f, transponder_report_s::ADSB_EMITTER_TYPE_UAV); + + get_instance()->run_fake_traffic(); + return 0; } diff --git a/src/modules/navigator/navigator_params.c b/src/modules/navigator/navigator_params.c index 1beed87bac..7ef16df6f4 100644 --- a/src/modules/navigator/navigator_params.c +++ b/src/modules/navigator/navigator_params.c @@ -128,23 +128,20 @@ PARAM_DEFINE_FLOAT(NAV_MC_ALT_RAD, 0.8f); PARAM_DEFINE_INT32(NAV_TRAFF_AVOID, 1); /** - * Set NAV TRAFFIC AVOID RADIUS MANNED + * Set NAV TRAFFIC AVOID horizontal distance * - * Defines the Radius where NAV TRAFFIC AVOID is Called - * For Manned Aviation + * Defines a crosstrack horizontal distance * * @unit m * @min 500 * * @group Mission */ -PARAM_DEFINE_FLOAT(NAV_TRAFF_A_RADM, 500); +PARAM_DEFINE_FLOAT(NAV_TRAFF_A_HOR, 500); /** - * Set NAV TRAFFIC AVOID RADIUS + * Set NAV TRAFFIC AVOID vertical distance * - * Defines the Radius where NAV TRAFFIC AVOID is Called - * For Unmanned Aviation * * @unit m * @min 10 @@ -152,7 +149,20 @@ PARAM_DEFINE_FLOAT(NAV_TRAFF_A_RADM, 500); * * @group Mission */ -PARAM_DEFINE_FLOAT(NAV_TRAFF_A_RADU, 10); +PARAM_DEFINE_FLOAT(NAV_TRAFF_A_VER, 500); + +/** + * Estimated time until collision + * + * Minimum acceptable time until collsion. + * Assumes constant speed over 3d distance. + * + * @unit s + * @min 1 + * @max 900000000 + * @group Mission + */ +PARAM_DEFINE_INT32(NAV_TRAFF_COLL_T, 60); /** * Force VTOL mode takeoff and land