From 99150c8956fb3db9415cc22d29be01368f63eb9f Mon Sep 17 00:00:00 2001 From: PhileasL Date: Mon, 1 Feb 2021 11:22:35 +0100 Subject: [PATCH 01/67] add service adjust_odometry --- src/modules/drive/include/drive.hpp | 6 ++++++ src/modules/drive/src/drive.cpp | 12 ++++++++++++ 2 files changed, 18 insertions(+) diff --git a/src/modules/drive/include/drive.hpp b/src/modules/drive/include/drive.hpp index 9c8cc39f..ab8947de 100644 --- a/src/modules/drive/include/drive.hpp +++ b/src/modules/drive/include/drive.hpp @@ -10,6 +10,7 @@ #include #endif #include "std_srvs/srv/set_bool.hpp" +#include "std_srvs/srv/trigger.hpp" #include "actuators_srvs/srv/slider.hpp" #include "nav_msgs/msg/odometry.hpp" #include "sensor_msgs/msg/joint_state.hpp" @@ -102,6 +103,9 @@ class Drive : public rclcpp::Node { // Sliders service rclcpp::Service::SharedPtr _set_slider_postion; + // Odometric adjustment + rclcpp::Service::SharedPtr _adjust_odometry; + rclcpp::TimerBase::SharedPtr diagnostics_timer_; #ifdef USE_TIMER @@ -165,6 +169,8 @@ class Drive : public rclcpp::Node { const std_srvs::srv::SetBool::Response::SharedPtr response); void handle_set_slider_position(const std::shared_ptr request_header, const actuators_srvs::srv::Slider::Request::SharedPtr request, const actuators_srvs::srv::Slider::Response::SharedPtr response); + void adjust_odometry(const std::shared_ptr request_header, const std_srvs::srv::Trigger::Request::SharedPtr request, + const std_srvs::srv::Trigger::Response::SharedPtr response); #ifdef SIMULATION void sim_step(); diff --git a/src/modules/drive/src/drive.cpp b/src/modules/drive/src/drive.cpp index f9c7e056..1c6c29bd 100644 --- a/src/modules/drive/src/drive.cpp +++ b/src/modules/drive/src/drive.cpp @@ -60,6 +60,9 @@ Drive::Drive() : Node("drive_node") { _set_slider_postion = this->create_service( "slider_position", std::bind(&Drive::handle_set_slider_position, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3)); + _adjust_odometry = this->create_service( + "adjust_odometry", std::bind(&Drive::adjust_odometry, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3)); + diagnostics_timer_ = this->create_wall_timer(1s, std::bind(&Drive::update_diagnostic, this)); #ifdef USE_TIMER @@ -315,6 +318,15 @@ rclcpp::Time Drive::get_sim_time() { void Drive::sim_step() { this->wb_robot->step(timestep); } #endif /* SIMULATION */ +void Drive::adjust_odometry(const std::shared_ptr request_header, const std_srvs::srv::Trigger::Request::SharedPtr request, + const std_srvs::srv::Trigger::Response::SharedPtr response) { + + odom_pose_.x = 0; + odom_pose_.y = 0; + odom_pose_.thetha = 0; + response->success = true; +} + Drive::~Drive() { #ifndef SIMULATION this->i2c_mutex.lock(); From d152d24cee0939dddd5c83b9c9333e513d40ed51 Mon Sep 17 00:00:00 2001 From: PhileasL Date: Mon, 1 Feb 2021 11:26:47 +0100 Subject: [PATCH 02/67] add service caller adjust odometry + update tf map->odom on readjust --- .../localisation/localisation_node.py | 34 ++++++++++++++++--- 1 file changed, 30 insertions(+), 4 deletions(-) diff --git a/src/modules/localisation/localisation/localisation_node.py b/src/modules/localisation/localisation/localisation_node.py index a873cd1e..4b6fa9fe 100644 --- a/src/modules/localisation/localisation/localisation_node.py +++ b/src/modules/localisation/localisation/localisation_node.py @@ -9,7 +9,9 @@ import rclpy from geometry_msgs.msg import TransformStamped from rcl_interfaces.msg import SetParametersResult +from visualization_msgs.msg import MarkerArray from tf2_ros import StaticTransformBroadcaster +from std_srvs.srv import Trigger class Localisation(rclpy.node.Node): @@ -23,11 +25,18 @@ def __init__(self): self._x, self._y, self._theta = self.fetchStartPosition() self._tf_brodcaster = StaticTransformBroadcaster(self) self._tf = TransformStamped() - self._tf.header.frame_id = "map" - self._tf.child_frame_id = "odom" + self._tf.header.frame_id = 'map' + self._tf.child_frame_id = 'odom' + self.update_transform() + self.subscription_ = self.create_subscription( + MarkerArray, '/allies_positions_markers', self.allies_subscription_callback, 10) + self.subscription_ # prevent unused variable warning + self.last_odom_update = self.get_clock().now().to_msg().sec; self.create_timer(1, self.update_transform) - self.get_logger().info(f"Default side is {self.side.value}") - self.get_logger().info("Localisation node is ready") + self._get_trigger_adjust_odometry_request = Trigger.Request() + self._get_trigger_adjust_odometry_client = self.create_client(Trigger, 'adjust_odometry') + self.get_logger().info(f'Default side is {self.side.value}') + self.get_logger().info('Localisation node is ready') def _on_set_parameters(self, params): """Handle Parameter events especially for side.""" @@ -88,7 +97,24 @@ def update_transform(self): self._tf.transform.rotation.z = float(qz) self._tf.transform.rotation.w = float(qw) self._tf_brodcaster.sendTransform(self._tf) + #self.get_logger().info(f'tf: x={self.get_clock().now().to_msg().sec}') + def _service_call(self, client, request): + """Call service synchronously.""" + client.call_async(request) + + def allies_subscription_callback(self, msg): + for allie_marker in msg.markers: + if allie_marker.text.lower() == self.robot and (self.get_clock().now().to_msg().sec - self.last_odom_update) > 5: + self._x = allie_marker.pose.position.x + self._y = allie_marker.pose.position.y + self._theta = allie_marker.pose.orientation.z + self._service_call( + self._get_trigger_adjust_odometry_client, + self._get_trigger_adjust_odometry_request, + ) + self.update_transform() + self.last_odom_update = self.get_clock().now().to_msg().sec def main(args=None): """Entrypoint.""" From 34ceda05c3acb6e5ff21158e7919f3cf23b896ba Mon Sep 17 00:00:00 2001 From: PhileasL Date: Tue, 2 Feb 2021 20:10:47 +0100 Subject: [PATCH 03/67] rework on robot_param controller and adding inflation layer costmap --- src/modules/robot/param/robot.in.yml | 46 +++++++++++++++++++--------- 1 file changed, 31 insertions(+), 15 deletions(-) diff --git a/src/modules/robot/param/robot.in.yml b/src/modules/robot/param/robot.in.yml index 8f929922..a43e95ab 100644 --- a/src/modules/robot/param/robot.in.yml +++ b/src/modules/robot/param/robot.in.yml @@ -57,41 +57,50 @@ controller_server: ros__parameters: use_sim_time: !Var use_sim_time controller_frequency: 40.0 + min_x_velocity_threshold: 0.001 + min_y_velocity_threshold: 0.5 + min_theta_velocity_threshold: 0.001 + progress_checker_plugin: "progress_checker" + goal_checker_plugin: "goal_checker" controller_plugins: ["DynamicFollowPath"] - + progress_checker: + plugin: "nav2_controller::SimpleProgressChecker" + required_movement_radius: 0.5 + movement_time_allowance: 10.0 + goal_checker: + plugin: "nav2_controller::SimpleGoalChecker" + xy_goal_tolerance: 0.02 + yaw_goal_tolerance: 0.02 + stateful: True DynamicFollowPath: plugin: "teb_local_planner::TebLocalPlannerROS" # Robot footprint footprint_model.type: polygon - # Goal tolerance - xy_goal_tolerance: 0.02 - yaw_goal_tolerance: 0.05 - # Obstacles min_obstacle_dist: 0.01 inflation_dist: 0.1 costmap_converter_plugin: costmap_converter::CostmapToPolygonsDBSMCCH costmap_converter_spin_thread: True - costmap_converter_rate: 2 + costmap_converter_rate: 5 # Homotopy Class Planner enable_homotopy_class_planning: True enable_multithreading: True - visualize_hc_graph: False + delete_detours_backwards: True # Optimisation optimization_activate: True optimization_verbose: False + #weight_shortest_path: 500.0 # Trajectory teb_autoresize: True exact_arc_length: False min_samples: 3 - max_samples: 20 + max_samples: 100 max_global_plan_lookahead_dist: 1.0 - allow_init_with_backwards_motion: True - global_plan_overwrite_orientation: True + allow_init_with_backwards_motion: true controller_server_rclcpp_node: @@ -102,23 +111,30 @@ controller_server_rclcpp_node: global_costmap: global_costmap: ros__parameters: - update_frequency: 2.0 - publish_frequency: 2.0 + update_frequency: 5.0 + publish_frequency: 5.0 global_frame: map robot_base_frame: base_link use_sim_time: !Var use_sim_time resolution: 0.02 - plugins: ["static_layer", "gradient_layer"] + plugins: ["static_layer", "gradient_layer", "inflation_layer"] static_layer: #subscribe to map plugin: "nav2_costmap_2d::StaticLayer" map_subscribe_transient_local: True gradient_layer: #draw radians circle around ennemies plugin: "gradient_costmap_layer_plugin/GradientLayer" enabled: true - gradient_size: 15 + gradient_size: 7 gradient_factor: 100 markers_topic: /ennemies_positions_markers - always_send_full_costmap: True + inflation_layer: + plugin: "nav2_costmap_2d::InflationLayer" + enabled: true + inflation_radius: 0.2 + cost_scaling_factor: 5.0 + inflate_unknown: false + inflate_around_unknown: false + always_send_full_costmap: true local_costmap: #just enough parameters to disable it local_costmap: From efa6e5401bb5a2db3c4f977d284777fe253c75cd Mon Sep 17 00:00:00 2001 From: PhileasL Date: Tue, 2 Feb 2021 20:18:38 +0100 Subject: [PATCH 04/67] storing 20 tf + retrieve the tf near the stamp of the tf in callback The idea is to re-adjust odometry considering the stamp of the adjust odometry tf given in the callback --- src/modules/drive/include/drive.hpp | 5 +++++ src/modules/drive/src/drive.cpp | 21 +++++++++++++++++++++ 2 files changed, 26 insertions(+) diff --git a/src/modules/drive/include/drive.hpp b/src/modules/drive/include/drive.hpp index ab8947de..95c4cec4 100644 --- a/src/modules/drive/include/drive.hpp +++ b/src/modules/drive/include/drive.hpp @@ -117,6 +117,10 @@ class Drive : public rclcpp::Node { diagnostic_msgs::msg::DiagnosticArray diagnostics_array_; diagnostic_msgs::msg::DiagnosticStatus diagnostics_status_; + /* Odometry re-adjustement */ + std::vector _previous_tf; + rclcpp::Subscription::SharedPtr _adjust_odometry_sub; + double _accel; double _wheel_separation; double _wheel_radius; @@ -171,6 +175,7 @@ class Drive : public rclcpp::Node { const actuators_srvs::srv::Slider::Response::SharedPtr response); void adjust_odometry(const std::shared_ptr request_header, const std_srvs::srv::Trigger::Request::SharedPtr request, const std_srvs::srv::Trigger::Response::SharedPtr response); + void adjust_odometry_callback(const geometry_msgs::msg::TransformStamped::SharedPtr tf_stamped_msg); #ifdef SIMULATION void sim_step(); diff --git a/src/modules/drive/src/drive.cpp b/src/modules/drive/src/drive.cpp index 1c6c29bd..da5bb47c 100644 --- a/src/modules/drive/src/drive.cpp +++ b/src/modules/drive/src/drive.cpp @@ -63,6 +63,9 @@ Drive::Drive() : Node("drive_node") { _adjust_odometry = this->create_service( "adjust_odometry", std::bind(&Drive::adjust_odometry, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3)); + _adjust_odometry_sub = this->create_subscription( + "adjust_odometry", qos, std::bind(&Drive::adjust_odometry_callback, this, std::placeholders::_1)); + diagnostics_timer_ = this->create_wall_timer(1s, std::bind(&Drive::update_diagnostic, this)); #ifdef USE_TIMER @@ -259,6 +262,9 @@ void Drive::update_tf() { tf2_msgs::msg::TFMessage odom_tf_msg; odom_tf_msg.transforms.push_back(odom_tf); tf_pub_->publish(odom_tf_msg); + + _previous_tf.insert(_previous_tf.begin(), odom_tf); + if (_previous_tf.size() > 20) _previous_tf.pop_back(); } void Drive::update_joint_states() { @@ -327,6 +333,21 @@ void Drive::adjust_odometry(const std::shared_ptr request_head response->success = true; } +void Drive::adjust_odometry_callback(const geometry_msgs::msg::TransformStamped::SharedPtr tf_stamped_msg){ + rclcpp::Time stamp_msg = tf_stamped_msg->header.stamp; + int right_stamp_index = 0; + while (right_stamp_index < _previous_tf.size() && stamp_msg < _previous_tf[right_stamp_index].header.stamp){ + right_stamp_index++; + if (right_stamp_index == _previous_tf.size()) { + RCLCPP_WARN(this->get_logger(), "Not enough tf stored to readjust odometry"); + return; + } + } + + +} + + Drive::~Drive() { #ifndef SIMULATION this->i2c_mutex.lock(); From 2b933cc558270476a12c7d3ab1f6690c3c33da69 Mon Sep 17 00:00:00 2001 From: PhileasL Date: Wed, 3 Feb 2021 23:38:03 +0100 Subject: [PATCH 05/67] simulation get_sim_time + true quaternion from sim --- .../include/assurancetourix.hpp | 4 ++++ .../assurancetourix/src/assurancetourix.cpp | 24 ++++++++++++++++--- 2 files changed, 25 insertions(+), 3 deletions(-) diff --git a/src/assurancetourix/assurancetourix/include/assurancetourix.hpp b/src/assurancetourix/assurancetourix/include/assurancetourix.hpp index 98fa4836..3827f008 100644 --- a/src/assurancetourix/assurancetourix/include/assurancetourix.hpp +++ b/src/assurancetourix/assurancetourix/include/assurancetourix.hpp @@ -114,6 +114,10 @@ class Assurancetourix : public rclcpp::Node { std::string base_frame, header_frame_id, topic_for_gradient_layer, side, allies_positions_topic; rclcpp::Client::SharedPtr transformClient; + +#ifdef SIMULATION + rclcpp::Time get_sim_time(std::shared_ptr wb_robot); +#endif /* SIMULATION */ }; #endif /* ONBOARD_VISION_NODE_HPP */ diff --git a/src/assurancetourix/assurancetourix/src/assurancetourix.cpp b/src/assurancetourix/assurancetourix/src/assurancetourix.cpp index 0784ba4f..51cda057 100644 --- a/src/assurancetourix/assurancetourix/src/assurancetourix.cpp +++ b/src/assurancetourix/assurancetourix/src/assurancetourix.cpp @@ -135,10 +135,17 @@ void Assurancetourix::simulation_marker_callback() { x = wb_supervisor->getFromDef(robot)->getPosition()[0]; y = 2 - wb_supervisor->getFromDef(robot)->getPosition()[2]; - webots_marker.header.stamp = this->get_clock()->now(); + webots_marker.header.stamp = get_sim_time(wb_supervisor); + tf2::Quaternion q; + q.setRPY(0, 0, theta); + + webots_marker.pose.orientation.x = q.x(); + webots_marker.pose.orientation.y = q.y(); + webots_marker.pose.orientation.z = q.z(); + webots_marker.pose.orientation.w = q.w(); + webots_marker.pose.position.x = x; webots_marker.pose.position.y = y; - webots_marker.pose.orientation.z = theta; webots_marker.text = robot; webots_marker.id = id; @@ -147,7 +154,10 @@ void Assurancetourix::simulation_marker_callback() { id++; } id = 6; - webots_marker.pose.orientation.z = 0; + webots_marker.pose.orientation.x = 0.0; + webots_marker.pose.orientation.y = 0.0; + webots_marker.pose.orientation.z = 0.0; + webots_marker.pose.orientation.w = 1.0; webots_marker.header.stamp = this->get_clock()->now(); if (comeback) { comeback_x += 0.1; @@ -477,6 +487,14 @@ void Assurancetourix::_anotate_image(Mat img) { } } +#ifdef SIMULATION +rclcpp::Time Assurancetourix::get_sim_time(std::shared_ptr wb_robot) { + double seconds = 0; + double nanosec = modf(wb_robot->getTime(), &seconds) * 1e9; + return rclcpp::Time((uint32_t)seconds, (uint32_t)nanosec); +} +#endif /* SIMULATION */ + Assurancetourix::~Assurancetourix() { #ifdef MIPI_CAMERA arducam::arducam_close_camera(camera_instance); From 417dbab8de9169bc50867c280a36bbe5a84e6b95 Mon Sep 17 00:00:00 2001 From: PhileasL Date: Wed, 3 Feb 2021 23:40:41 +0100 Subject: [PATCH 06/67] condition change + managing extreme indexes --- src/modules/drive/src/drive.cpp | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/src/modules/drive/src/drive.cpp b/src/modules/drive/src/drive.cpp index da5bb47c..8c49841b 100644 --- a/src/modules/drive/src/drive.cpp +++ b/src/modules/drive/src/drive.cpp @@ -336,15 +336,18 @@ void Drive::adjust_odometry(const std::shared_ptr request_head void Drive::adjust_odometry_callback(const geometry_msgs::msg::TransformStamped::SharedPtr tf_stamped_msg){ rclcpp::Time stamp_msg = tf_stamped_msg->header.stamp; int right_stamp_index = 0; - while (right_stamp_index < _previous_tf.size() && stamp_msg < _previous_tf[right_stamp_index].header.stamp){ + while (stamp_msg < (rclcpp::Time)_previous_tf.at(right_stamp_index).header.stamp){ right_stamp_index++; if (right_stamp_index == _previous_tf.size()) { RCLCPP_WARN(this->get_logger(), "Not enough tf stored to readjust odometry"); return; } } - + if (right_stamp_index != 0){ + if (stamp_msg - (rclcpp::Time)_previous_tf[right_stamp_index].header.stamp + > (rclcpp::Time)_previous_tf[right_stamp_index - 1].header.stamp - stamp_msg) right_stamp_index--; + } } From c329478955e992c593daa5eff3f1c9a96bf9b9d9 Mon Sep 17 00:00:00 2001 From: PhileasL Date: Wed, 3 Feb 2021 23:42:15 +0100 Subject: [PATCH 07/67] extract_pose_from_transform + set_transform_from_pose functions --- src/modules/drive/include/drive.hpp | 2 ++ src/modules/drive/src/drive.cpp | 16 ++++++++++++++++ 2 files changed, 18 insertions(+) diff --git a/src/modules/drive/include/drive.hpp b/src/modules/drive/include/drive.hpp index 95c4cec4..3538c159 100644 --- a/src/modules/drive/include/drive.hpp +++ b/src/modules/drive/include/drive.hpp @@ -176,6 +176,8 @@ class Drive : public rclcpp::Node { void adjust_odometry(const std::shared_ptr request_header, const std_srvs::srv::Trigger::Request::SharedPtr request, const std_srvs::srv::Trigger::Response::SharedPtr response); void adjust_odometry_callback(const geometry_msgs::msg::TransformStamped::SharedPtr tf_stamped_msg); + void extract_pose_from_transform(geometry_msgs::msg::TransformStamped &transform_in, geometry_msgs::msg::PoseStamped &pose_out); + void set_transform_from_pose(geometry_msgs::msg::PoseStamped &pose_in, geometry_msgs::msg::TransformStamped &transform_out, rclcpp::Time &stamp); #ifdef SIMULATION void sim_step(); diff --git a/src/modules/drive/src/drive.cpp b/src/modules/drive/src/drive.cpp index 8c49841b..dfe7628a 100644 --- a/src/modules/drive/src/drive.cpp +++ b/src/modules/drive/src/drive.cpp @@ -348,6 +348,22 @@ void Drive::adjust_odometry_callback(const geometry_msgs::msg::TransformStamped: if (stamp_msg - (rclcpp::Time)_previous_tf[right_stamp_index].header.stamp > (rclcpp::Time)_previous_tf[right_stamp_index - 1].header.stamp - stamp_msg) right_stamp_index--; } +void Drive::extract_pose_from_transform(geometry_msgs::msg::TransformStamped &transform_in, geometry_msgs::msg::PoseStamped &pose_out){ + pose_out.header = transform_in.header; + pose_out.pose.position.x = transform_in.transform.translation.x; + pose_out.pose.position.y = transform_in.transform.translation.y; + pose_out.pose.position.z = transform_in.transform.translation.z; + pose_out.pose.orientation = transform_in.transform.rotation; +} + +void Drive::set_transform_from_pose(geometry_msgs::msg::PoseStamped &pose_in, geometry_msgs::msg::TransformStamped &transform_out, rclcpp::Time &stamp){ + transform_out.header.stamp = stamp; + transform_out.header.frame_id = odom_.header.frame_id; + transform_out.child_frame_id = odom_.child_frame_id; + transform_out.transform.translation.x = pose_in.pose.position.x; + transform_out.transform.translation.y = pose_in.pose.position.y; + transform_out.transform.translation.z = pose_in.pose.position.z; + transform_out.transform.rotation = pose_in.pose.orientation; } From baff0c65c1c57cad9538020e9241fbb449b80b97 Mon Sep 17 00:00:00 2001 From: PhileasL Date: Wed, 3 Feb 2021 23:44:57 +0100 Subject: [PATCH 08/67] algorithm to get base_link_relative_to_new_odom tf --- src/modules/drive/include/drive.hpp | 2 ++ src/modules/drive/src/drive.cpp | 15 +++++++++++++++ 2 files changed, 17 insertions(+) diff --git a/src/modules/drive/include/drive.hpp b/src/modules/drive/include/drive.hpp index 3538c159..d6c0e721 100644 --- a/src/modules/drive/include/drive.hpp +++ b/src/modules/drive/include/drive.hpp @@ -19,6 +19,8 @@ #include #include #include +#include +#include #include #include diff --git a/src/modules/drive/src/drive.cpp b/src/modules/drive/src/drive.cpp index dfe7628a..d1614584 100644 --- a/src/modules/drive/src/drive.cpp +++ b/src/modules/drive/src/drive.cpp @@ -348,6 +348,21 @@ void Drive::adjust_odometry_callback(const geometry_msgs::msg::TransformStamped: if (stamp_msg - (rclcpp::Time)_previous_tf[right_stamp_index].header.stamp > (rclcpp::Time)_previous_tf[right_stamp_index - 1].header.stamp - stamp_msg) right_stamp_index--; } + + //stamp_msg = this->get_clock()->now(); + geometry_msgs::msg::TransformStamped base_link_odom_tf, + tf_msg = *tf_stamped_msg, + nearest_tf = _previous_tf[right_stamp_index]; + //tf_msg.header.stamp = this->get_clock()->now(); + + geometry_msgs::msg::PoseStamped base_link_relative_to_old_odom, base_link_relative_to_new_odom; + extract_pose_from_transform(_previous_tf[0], base_link_relative_to_old_odom); + + tf2::doTransform(base_link_relative_to_old_odom, base_link_relative_to_new_odom, nearest_tf); + + //rclcpp::Time base_link_odom_tf_stamp = (rclcpp::Time)_previous_tf[right_stamp_index].header.stamp; + set_transform_from_pose(base_link_relative_to_new_odom, base_link_odom_tf, stamp_msg); + void Drive::extract_pose_from_transform(geometry_msgs::msg::TransformStamped &transform_in, geometry_msgs::msg::PoseStamped &pose_out){ pose_out.header = transform_in.header; pose_out.pose.position.x = transform_in.transform.translation.x; From 7129137c2aa9f5a6a3c0f68f0de831a6b8e01888 Mon Sep 17 00:00:00 2001 From: PhileasL Date: Wed, 3 Feb 2021 23:46:57 +0100 Subject: [PATCH 09/67] sending new tf and new odom with readjustement --- src/modules/drive/include/drive.hpp | 3 ++- src/modules/drive/src/drive.cpp | 25 +++++++++++++++++++++++-- 2 files changed, 25 insertions(+), 3 deletions(-) diff --git a/src/modules/drive/include/drive.hpp b/src/modules/drive/include/drive.hpp index d6c0e721..84820db2 100644 --- a/src/modules/drive/include/drive.hpp +++ b/src/modules/drive/include/drive.hpp @@ -19,6 +19,7 @@ #include #include #include +#include #include #include #include @@ -163,7 +164,7 @@ class Drive : public rclcpp::Node { void init_variables(); void update_tf(); void update_joint_states(); - void update_odometry(); + void update_odometry(rclcpp::Time stamp = rclcpp::Time(0)); void update_velocity(); void update_diagnostic(); void read_from_serial(); diff --git a/src/modules/drive/src/drive.cpp b/src/modules/drive/src/drive.cpp index d1614584..76c4d5e5 100644 --- a/src/modules/drive/src/drive.cpp +++ b/src/modules/drive/src/drive.cpp @@ -230,7 +230,7 @@ void Drive::compute_pose_velocity(TinyData steps_returned) { odom_pose_.thetha += instantaneous_move_.angular; } -void Drive::update_odometry() { +void Drive::update_odometry(rclcpp::Time stamp) { odom_.pose.pose.position.x = odom_pose_.x; odom_.pose.pose.position.y = odom_pose_.y; odom_.pose.pose.position.z = 0; @@ -246,7 +246,8 @@ void Drive::update_odometry() { // We should update the twist of the odometry odom_.twist.twist.linear.x = instantaneous_speed_.linear; odom_.twist.twist.angular.z = instantaneous_speed_.angular; - odom_.header.stamp = time_since_last_sync_; + if (stamp.nanoseconds() == 0) odom_.header.stamp = time_since_last_sync_; + else odom_.header.stamp = stamp; odom_pub_->publish(odom_); } @@ -363,6 +364,26 @@ void Drive::adjust_odometry_callback(const geometry_msgs::msg::TransformStamped: //rclcpp::Time base_link_odom_tf_stamp = (rclcpp::Time)_previous_tf[right_stamp_index].header.stamp; set_transform_from_pose(base_link_relative_to_new_odom, base_link_odom_tf, stamp_msg); + tf2_msgs::msg::TFMessage odom_tf_msg; + odom_tf_msg.transforms.push_back(tf_msg); + odom_tf_msg.transforms.push_back(base_link_odom_tf); + + tf2::Quaternion q( + base_link_odom_tf.transform.rotation.x, + base_link_odom_tf.transform.rotation.y, + base_link_odom_tf.transform.rotation.z, + base_link_odom_tf.transform.rotation.w + ); + tf2::Matrix3x3 m(q); + double roll, pitch, yaw; + m.getRPY(roll, pitch, yaw); + odom_pose_.thetha = yaw; + odom_pose_.x = base_link_odom_tf.transform.translation.x; + odom_pose_.y = base_link_odom_tf.transform.translation.y; + update_odometry(stamp_msg); + tf_pub_->publish(odom_tf_msg); +} + void Drive::extract_pose_from_transform(geometry_msgs::msg::TransformStamped &transform_in, geometry_msgs::msg::PoseStamped &pose_out){ pose_out.header = transform_in.header; pose_out.pose.position.x = transform_in.transform.translation.x; From b4eddf0c0c368cdf375a3843bbac4d0bd2e1dbc8 Mon Sep 17 00:00:00 2001 From: PhileasL Date: Wed, 3 Feb 2021 23:48:22 +0100 Subject: [PATCH 10/67] Init _previous_tf vector + adding dependency to cmakelist --- src/modules/drive/CMakeLists.txt | 2 ++ src/modules/drive/src/drive.cpp | 5 +++++ 2 files changed, 7 insertions(+) diff --git a/src/modules/drive/CMakeLists.txt b/src/modules/drive/CMakeLists.txt index 8aa634e2..80d48993 100644 --- a/src/modules/drive/CMakeLists.txt +++ b/src/modules/drive/CMakeLists.txt @@ -20,6 +20,7 @@ find_package(rclcpp REQUIRED) find_package(sensor_msgs REQUIRED) find_package(tf2 REQUIRED) find_package(tf2_msgs REQUIRED) +find_package(tf2_geometry_msgs REQUIRED) find_package(std_srvs REQUIRED) find_package(diagnostic_msgs REQUIRED) find_package(actuators_srvs REQUIRED) @@ -39,6 +40,7 @@ set(dependencies "sensor_msgs" "tf2" "tf2_msgs" + "tf2_geometry_msgs" "std_srvs" "diagnostic_msgs" "actuators_srvs" diff --git a/src/modules/drive/src/drive.cpp b/src/modules/drive/src/drive.cpp index 76c4d5e5..a3ef66e2 100644 --- a/src/modules/drive/src/drive.cpp +++ b/src/modules/drive/src/drive.cpp @@ -135,6 +135,11 @@ void Drive::init_variables() { #else time_since_last_sync_ = get_sim_time(); #endif /* SIMULATION */ + geometry_msgs::msg::TransformStamped init_vector; + init_vector.header.stamp = this->get_clock()->now(); + init_vector.header.frame_id = odom_.header.frame_id; + init_vector.child_frame_id = odom_.child_frame_id; + for (int i = 0; i<20; i++) _previous_tf.push_back(init_vector); } int8_t Drive::compute_velocity_cmd(double velocity) { From 2367bf538a392a0ba7b6290e8d4e145e0907e815 Mon Sep 17 00:00:00 2001 From: PhileasL Date: Wed, 3 Feb 2021 23:51:33 +0100 Subject: [PATCH 11/67] TransformBroadcaster + 'adjust_odometry' publisher + quaternion_to_euler --- .../localisation/localisation_node.py | 18 ++++++++++++++++++ 1 file changed, 18 insertions(+) diff --git a/src/modules/localisation/localisation/localisation_node.py b/src/modules/localisation/localisation/localisation_node.py index 4b6fa9fe..3372c8a7 100644 --- a/src/modules/localisation/localisation/localisation_node.py +++ b/src/modules/localisation/localisation/localisation_node.py @@ -11,6 +11,7 @@ from rcl_interfaces.msg import SetParametersResult from visualization_msgs.msg import MarkerArray from tf2_ros import StaticTransformBroadcaster +from tf2_ros import TransformBroadcaster from std_srvs.srv import Trigger @@ -24,6 +25,7 @@ def __init__(self): self.add_on_set_parameters_callback(self._on_set_parameters) self._x, self._y, self._theta = self.fetchStartPosition() self._tf_brodcaster = StaticTransformBroadcaster(self) + self._tf_brodcaster = TransformBroadcaster(self) self._tf = TransformStamped() self._tf.header.frame_id = 'map' self._tf.child_frame_id = 'odom' @@ -35,6 +37,8 @@ def __init__(self): self.create_timer(1, self.update_transform) self._get_trigger_adjust_odometry_request = Trigger.Request() self._get_trigger_adjust_odometry_client = self.create_client(Trigger, 'adjust_odometry') + self.tf_publisher_ = self.create_publisher(TransformStamped, 'adjust_odometry', 10) + self.update_transform() self.get_logger().info(f'Default side is {self.side.value}') self.get_logger().info('Localisation node is ready') @@ -86,6 +90,20 @@ def euler_to_quaternion(self, yaw, pitch=0, roll=0): ) * np.sin(pitch / 2) * np.sin(yaw / 2) return [qx, qy, qz, qw] + def quaternion_to_euler(self, x, y, z, w): + """Conversion between quaternions and euler angles.""" + t0 = +2.0 * (w * x + y * z) + t1 = +1.0 - 2.0 * (x * x + y * y) + X = math.atan2(t0, t1) + t2 = +2.0 * (w * y - z * x) + t2 = +1.0 if t2 > +1.0 else t2 + t2 = -1.0 if t2 < -1.0 else t2 + Y = math.asin(t2) + t3 = +2.0 * (w * z + x * y) + t4 = +1.0 - 2.0 * (y * y + z * z) + Z = math.atan2(t3, t4) + return (X, Y, Z) + def update_transform(self): """Update and publish transform callback.""" self._tf.header.stamp = self.get_clock().now().to_msg() From d7ba7a70c37dde6fe9e0d932a8dd0c6d80fa6595 Mon Sep 17 00:00:00 2001 From: PhileasL Date: Thu, 4 Feb 2021 22:26:08 +0100 Subject: [PATCH 12/67] Changing odometry_readjustement strategy, removing service --- src/modules/drive/src/drive.cpp | 12 ------------ .../localisation/localisation/localisation_node.py | 4 ---- 2 files changed, 16 deletions(-) diff --git a/src/modules/drive/src/drive.cpp b/src/modules/drive/src/drive.cpp index a3ef66e2..bc444db1 100644 --- a/src/modules/drive/src/drive.cpp +++ b/src/modules/drive/src/drive.cpp @@ -60,9 +60,6 @@ Drive::Drive() : Node("drive_node") { _set_slider_postion = this->create_service( "slider_position", std::bind(&Drive::handle_set_slider_position, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3)); - _adjust_odometry = this->create_service( - "adjust_odometry", std::bind(&Drive::adjust_odometry, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3)); - _adjust_odometry_sub = this->create_subscription( "adjust_odometry", qos, std::bind(&Drive::adjust_odometry_callback, this, std::placeholders::_1)); @@ -330,15 +327,6 @@ rclcpp::Time Drive::get_sim_time() { void Drive::sim_step() { this->wb_robot->step(timestep); } #endif /* SIMULATION */ -void Drive::adjust_odometry(const std::shared_ptr request_header, const std_srvs::srv::Trigger::Request::SharedPtr request, - const std_srvs::srv::Trigger::Response::SharedPtr response) { - - odom_pose_.x = 0; - odom_pose_.y = 0; - odom_pose_.thetha = 0; - response->success = true; -} - void Drive::adjust_odometry_callback(const geometry_msgs::msg::TransformStamped::SharedPtr tf_stamped_msg){ rclcpp::Time stamp_msg = tf_stamped_msg->header.stamp; int right_stamp_index = 0; diff --git a/src/modules/localisation/localisation/localisation_node.py b/src/modules/localisation/localisation/localisation_node.py index 3372c8a7..742e12e9 100644 --- a/src/modules/localisation/localisation/localisation_node.py +++ b/src/modules/localisation/localisation/localisation_node.py @@ -12,8 +12,6 @@ from visualization_msgs.msg import MarkerArray from tf2_ros import StaticTransformBroadcaster from tf2_ros import TransformBroadcaster -from std_srvs.srv import Trigger - class Localisation(rclpy.node.Node): """Robot localisation node.""" @@ -35,8 +33,6 @@ def __init__(self): self.subscription_ # prevent unused variable warning self.last_odom_update = self.get_clock().now().to_msg().sec; self.create_timer(1, self.update_transform) - self._get_trigger_adjust_odometry_request = Trigger.Request() - self._get_trigger_adjust_odometry_client = self.create_client(Trigger, 'adjust_odometry') self.tf_publisher_ = self.create_publisher(TransformStamped, 'adjust_odometry', 10) self.update_transform() self.get_logger().info(f'Default side is {self.side.value}') From 6bb8e494890f70be216953d822ff8b0c6b4c890d Mon Sep 17 00:00:00 2001 From: PhileasL Date: Thu, 4 Feb 2021 22:30:06 +0100 Subject: [PATCH 13/67] Re-basculing to static map to odom transform --- src/modules/localisation/localisation/localisation_node.py | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/modules/localisation/localisation/localisation_node.py b/src/modules/localisation/localisation/localisation_node.py index 742e12e9..36c36fe3 100644 --- a/src/modules/localisation/localisation/localisation_node.py +++ b/src/modules/localisation/localisation/localisation_node.py @@ -11,7 +11,6 @@ from rcl_interfaces.msg import SetParametersResult from visualization_msgs.msg import MarkerArray from tf2_ros import StaticTransformBroadcaster -from tf2_ros import TransformBroadcaster class Localisation(rclpy.node.Node): """Robot localisation node.""" @@ -23,7 +22,6 @@ def __init__(self): self.add_on_set_parameters_callback(self._on_set_parameters) self._x, self._y, self._theta = self.fetchStartPosition() self._tf_brodcaster = StaticTransformBroadcaster(self) - self._tf_brodcaster = TransformBroadcaster(self) self._tf = TransformStamped() self._tf.header.frame_id = 'map' self._tf.child_frame_id = 'odom' From d40ed7c226706d68e98ce8ea2bbf5fa9b2cea458 Mon Sep 17 00:00:00 2001 From: PhileasL Date: Thu, 4 Feb 2021 22:31:49 +0100 Subject: [PATCH 14/67] Getting the static map to odom transform --- src/modules/drive/CMakeLists.txt | 2 ++ src/modules/drive/include/drive.hpp | 4 ++++ src/modules/drive/src/drive.cpp | 9 +++++++++ 3 files changed, 15 insertions(+) diff --git a/src/modules/drive/CMakeLists.txt b/src/modules/drive/CMakeLists.txt index 80d48993..1adadcc7 100644 --- a/src/modules/drive/CMakeLists.txt +++ b/src/modules/drive/CMakeLists.txt @@ -20,6 +20,7 @@ find_package(rclcpp REQUIRED) find_package(sensor_msgs REQUIRED) find_package(tf2 REQUIRED) find_package(tf2_msgs REQUIRED) +find_package(tf2_ros REQUIRED) find_package(tf2_geometry_msgs REQUIRED) find_package(std_srvs REQUIRED) find_package(diagnostic_msgs REQUIRED) @@ -40,6 +41,7 @@ set(dependencies "sensor_msgs" "tf2" "tf2_msgs" + "tf2_ros" "tf2_geometry_msgs" "std_srvs" "diagnostic_msgs" diff --git a/src/modules/drive/include/drive.hpp b/src/modules/drive/include/drive.hpp index 84820db2..5f74dbc3 100644 --- a/src/modules/drive/include/drive.hpp +++ b/src/modules/drive/include/drive.hpp @@ -20,7 +20,10 @@ #include #include #include +#include +#include #include +#include #include #include #include @@ -121,6 +124,7 @@ class Drive : public rclcpp::Node { diagnostic_msgs::msg::DiagnosticStatus diagnostics_status_; /* Odometry re-adjustement */ + geometry_msgs::msg::TransformStamped _map_to_odom_tf; std::vector _previous_tf; rclcpp::Subscription::SharedPtr _adjust_odometry_sub; diff --git a/src/modules/drive/src/drive.cpp b/src/modules/drive/src/drive.cpp index bc444db1..26326e80 100644 --- a/src/modules/drive/src/drive.cpp +++ b/src/modules/drive/src/drive.cpp @@ -132,6 +132,15 @@ void Drive::init_variables() { #else time_since_last_sync_ = get_sim_time(); #endif /* SIMULATION */ + + tf2_ros::Buffer tfBuffer(std::make_shared(), tf2::Duration(tf2::BUFFER_CORE_DEFAULT_CACHE_TIME)); + tf2_ros::TransformListener tfListener(tfBuffer); + std::string errorMsg; + if(tfBuffer.canTransform(odom_.header.frame_id, "map", std::chrono::system_clock::now(), std::chrono::milliseconds(10000))) + { + _map_to_odom_tf = tfBuffer.lookupTransform(odom_.header.frame_id, "map", std::chrono::system_clock::now(), std::chrono::milliseconds(10000)); + } + geometry_msgs::msg::TransformStamped init_vector; init_vector.header.stamp = this->get_clock()->now(); init_vector.header.frame_id = odom_.header.frame_id; From 2af55cacc8a305a9ce0ddbf486b14f85413c7352 Mon Sep 17 00:00:00 2001 From: PhileasL Date: Thu, 4 Feb 2021 22:36:41 +0100 Subject: [PATCH 15/67] use sim time + clean all traces of service 'ajust_odometry' --- src/modules/drive/include/drive.hpp | 11 ++++------- src/modules/drive/src/drive.cpp | 5 ++--- 2 files changed, 6 insertions(+), 10 deletions(-) diff --git a/src/modules/drive/include/drive.hpp b/src/modules/drive/include/drive.hpp index 5f74dbc3..ac629675 100644 --- a/src/modules/drive/include/drive.hpp +++ b/src/modules/drive/include/drive.hpp @@ -109,9 +109,6 @@ class Drive : public rclcpp::Node { // Sliders service rclcpp::Service::SharedPtr _set_slider_postion; - // Odometric adjustment - rclcpp::Service::SharedPtr _adjust_odometry; - rclcpp::TimerBase::SharedPtr diagnostics_timer_; #ifdef USE_TIMER @@ -168,7 +165,7 @@ class Drive : public rclcpp::Node { void init_variables(); void update_tf(); void update_joint_states(); - void update_odometry(rclcpp::Time stamp = rclcpp::Time(0)); + void update_odometry(); void update_velocity(); void update_diagnostic(); void read_from_serial(); @@ -180,11 +177,11 @@ class Drive : public rclcpp::Node { const std_srvs::srv::SetBool::Response::SharedPtr response); void handle_set_slider_position(const std::shared_ptr request_header, const actuators_srvs::srv::Slider::Request::SharedPtr request, const actuators_srvs::srv::Slider::Response::SharedPtr response); - void adjust_odometry(const std::shared_ptr request_header, const std_srvs::srv::Trigger::Request::SharedPtr request, - const std_srvs::srv::Trigger::Response::SharedPtr response); void adjust_odometry_callback(const geometry_msgs::msg::TransformStamped::SharedPtr tf_stamped_msg); void extract_pose_from_transform(geometry_msgs::msg::TransformStamped &transform_in, geometry_msgs::msg::PoseStamped &pose_out); - void set_transform_from_pose(geometry_msgs::msg::PoseStamped &pose_in, geometry_msgs::msg::TransformStamped &transform_out, rclcpp::Time &stamp); + void set_transform_from_pose(geometry_msgs::msg::PoseStamped &pose_in, geometry_msgs::msg::TransformStamped &transform_out); + void get_pose_in_another_frame(geometry_msgs::msg::PoseStamped &pose_in, geometry_msgs::msg::PoseStamped &pose_out, geometry_msgs::msg::TransformStamped &transform); + tf2::Quaternion get_tf2_quaternion(geometry_msgs::msg::Quaternion &q); #ifdef SIMULATION void sim_step(); diff --git a/src/modules/drive/src/drive.cpp b/src/modules/drive/src/drive.cpp index 26326e80..346429b8 100644 --- a/src/modules/drive/src/drive.cpp +++ b/src/modules/drive/src/drive.cpp @@ -241,7 +241,7 @@ void Drive::compute_pose_velocity(TinyData steps_returned) { odom_pose_.thetha += instantaneous_move_.angular; } -void Drive::update_odometry(rclcpp::Time stamp) { +void Drive::update_odometry() { odom_.pose.pose.position.x = odom_pose_.x; odom_.pose.pose.position.y = odom_pose_.y; odom_.pose.pose.position.z = 0; @@ -257,8 +257,7 @@ void Drive::update_odometry(rclcpp::Time stamp) { // We should update the twist of the odometry odom_.twist.twist.linear.x = instantaneous_speed_.linear; odom_.twist.twist.angular.z = instantaneous_speed_.angular; - if (stamp.nanoseconds() == 0) odom_.header.stamp = time_since_last_sync_; - else odom_.header.stamp = stamp; + odom_.header.stamp = time_since_last_sync_; odom_pub_->publish(odom_); } From 925dfb1a27d3a979fd983bbaa90932d809b035ed Mon Sep 17 00:00:00 2001 From: PhileasL Date: Thu, 4 Feb 2021 22:40:59 +0100 Subject: [PATCH 16/67] The key is to update variables instead of tf ! --- src/modules/drive/src/drive.cpp | 9 +++------ 1 file changed, 3 insertions(+), 6 deletions(-) diff --git a/src/modules/drive/src/drive.cpp b/src/modules/drive/src/drive.cpp index 346429b8..accf7436 100644 --- a/src/modules/drive/src/drive.cpp +++ b/src/modules/drive/src/drive.cpp @@ -379,10 +379,8 @@ void Drive::adjust_odometry_callback(const geometry_msgs::msg::TransformStamped: double roll, pitch, yaw; m.getRPY(roll, pitch, yaw); odom_pose_.thetha = yaw; - odom_pose_.x = base_link_odom_tf.transform.translation.x; - odom_pose_.y = base_link_odom_tf.transform.translation.y; - update_odometry(stamp_msg); - tf_pub_->publish(odom_tf_msg); + odom_pose_.x = base_link_relative_to_odom_corrected.pose.position.x; + odom_pose_.y = base_link_relative_to_odom_corrected.pose.position.y; } void Drive::extract_pose_from_transform(geometry_msgs::msg::TransformStamped &transform_in, geometry_msgs::msg::PoseStamped &pose_out){ @@ -393,8 +391,7 @@ void Drive::extract_pose_from_transform(geometry_msgs::msg::TransformStamped &tr pose_out.pose.orientation = transform_in.transform.rotation; } -void Drive::set_transform_from_pose(geometry_msgs::msg::PoseStamped &pose_in, geometry_msgs::msg::TransformStamped &transform_out, rclcpp::Time &stamp){ - transform_out.header.stamp = stamp; +void Drive::set_transform_from_pose(geometry_msgs::msg::PoseStamped &pose_in, geometry_msgs::msg::TransformStamped &transform_out){ transform_out.header.frame_id = odom_.header.frame_id; transform_out.child_frame_id = odom_.child_frame_id; transform_out.transform.translation.x = pose_in.pose.position.x; From 8a6166dff2be5e75cb20875dda3915787d2301f4 Mon Sep 17 00:00:00 2001 From: PhileasL Date: Thu, 4 Feb 2021 22:44:13 +0100 Subject: [PATCH 17/67] strange behavior of tf2::doTransform, need my own functions --- src/modules/drive/src/drive.cpp | 4 ---- 1 file changed, 4 deletions(-) diff --git a/src/modules/drive/src/drive.cpp b/src/modules/drive/src/drive.cpp index accf7436..44af840e 100644 --- a/src/modules/drive/src/drive.cpp +++ b/src/modules/drive/src/drive.cpp @@ -360,14 +360,10 @@ void Drive::adjust_odometry_callback(const geometry_msgs::msg::TransformStamped: geometry_msgs::msg::PoseStamped base_link_relative_to_old_odom, base_link_relative_to_new_odom; extract_pose_from_transform(_previous_tf[0], base_link_relative_to_old_odom); - tf2::doTransform(base_link_relative_to_old_odom, base_link_relative_to_new_odom, nearest_tf); //rclcpp::Time base_link_odom_tf_stamp = (rclcpp::Time)_previous_tf[right_stamp_index].header.stamp; set_transform_from_pose(base_link_relative_to_new_odom, base_link_odom_tf, stamp_msg); - tf2_msgs::msg::TFMessage odom_tf_msg; - odom_tf_msg.transforms.push_back(tf_msg); - odom_tf_msg.transforms.push_back(base_link_odom_tf); tf2::Quaternion q( base_link_odom_tf.transform.rotation.x, From 7e4ccd9bd0b36f433040a01f8bcf08624737c6ac Mon Sep 17 00:00:00 2001 From: PhileasL Date: Thu, 4 Feb 2021 22:51:35 +0100 Subject: [PATCH 18/67] It might be all the functions i need --- src/modules/drive/include/drive.hpp | 3 +++ src/modules/drive/src/drive.cpp | 17 +++++++++++++++++ 2 files changed, 20 insertions(+) diff --git a/src/modules/drive/include/drive.hpp b/src/modules/drive/include/drive.hpp index ac629675..dc05bc54 100644 --- a/src/modules/drive/include/drive.hpp +++ b/src/modules/drive/include/drive.hpp @@ -182,6 +182,9 @@ class Drive : public rclcpp::Node { void set_transform_from_pose(geometry_msgs::msg::PoseStamped &pose_in, geometry_msgs::msg::TransformStamped &transform_out); void get_pose_in_another_frame(geometry_msgs::msg::PoseStamped &pose_in, geometry_msgs::msg::PoseStamped &pose_out, geometry_msgs::msg::TransformStamped &transform); tf2::Quaternion get_tf2_quaternion(geometry_msgs::msg::Quaternion &q); + tf2::Vector3 get_tf2_vector(geometry_msgs::msg::Point &p); + tf2::Vector3 get_tf2_vector(geometry_msgs::msg::Vector3 &p); + void set_pose_from_tf_t_q(tf2::Vector3 &t, tf2::Quaternion &q, geometry_msgs::msg::PoseStamped &pose_out); #ifdef SIMULATION void sim_step(); diff --git a/src/modules/drive/src/drive.cpp b/src/modules/drive/src/drive.cpp index 44af840e..8e6ed4da 100644 --- a/src/modules/drive/src/drive.cpp +++ b/src/modules/drive/src/drive.cpp @@ -396,6 +396,23 @@ void Drive::set_transform_from_pose(geometry_msgs::msg::PoseStamped &pose_in, ge transform_out.transform.rotation = pose_in.pose.orientation; } +void Drive::get_pose_in_another_frame(geometry_msgs::msg::PoseStamped &pose_in, geometry_msgs::msg::PoseStamped &pose_out, geometry_msgs::msg::TransformStamped &transform){ +} + +tf2::Quaternion Drive::get_tf2_quaternion(geometry_msgs::msg::Quaternion &q){ + return tf2::Quaternion(q.x,q.y,q.z,q.w); +} + +tf2::Vector3 Drive::get_tf2_vector(geometry_msgs::msg::Point &p){ + return tf2::Vector3(p.x, p.y, p.z); +} + +tf2::Vector3 Drive::get_tf2_vector(geometry_msgs::msg::Vector3 &p){ + return tf2::Vector3(p.x, p.y, p.z); +} + +void Drive::set_pose_from_tf_t_q(tf2::Vector3 &t, tf2::Quaternion &q, geometry_msgs::msg::PoseStamped &pose_out){ +} Drive::~Drive() { #ifndef SIMULATION From 3e0476ce1c3c87f96f908c14903b84eba7d046c5 Mon Sep 17 00:00:00 2001 From: PhileasL Date: Thu, 4 Feb 2021 22:53:05 +0100 Subject: [PATCH 19/67] setting up the idea, need to fill the functions now --- src/modules/drive/src/drive.cpp | 29 +++++++++++++++++------------ 1 file changed, 17 insertions(+), 12 deletions(-) diff --git a/src/modules/drive/src/drive.cpp b/src/modules/drive/src/drive.cpp index 8e6ed4da..83ef6cee 100644 --- a/src/modules/drive/src/drive.cpp +++ b/src/modules/drive/src/drive.cpp @@ -351,25 +351,30 @@ void Drive::adjust_odometry_callback(const geometry_msgs::msg::TransformStamped: > (rclcpp::Time)_previous_tf[right_stamp_index - 1].header.stamp - stamp_msg) right_stamp_index--; } - //stamp_msg = this->get_clock()->now(); - geometry_msgs::msg::TransformStamped base_link_odom_tf, - tf_msg = *tf_stamped_msg, + geometry_msgs::msg::TransformStamped msg_received_relative_to_odom_tf, nearest_tf = _previous_tf[right_stamp_index]; - //tf_msg.header.stamp = this->get_clock()->now(); - geometry_msgs::msg::PoseStamped base_link_relative_to_old_odom, base_link_relative_to_new_odom; - extract_pose_from_transform(_previous_tf[0], base_link_relative_to_old_odom); + geometry_msgs::msg::PoseStamped msg_received_relative_to_map, msg_received_relative_to_odom, + base_link_relative_to_odom_estim, base_link_relative_to_near, + base_link_relative_to_odom_corrected; + /* Getting msg_received_relative_to_odom */ + extract_pose_from_transform(*tf_stamped_msg, msg_received_relative_to_map); + get_pose_in_another_frame(msg_received_relative_to_map, msg_received_relative_to_odom, _map_to_odom_tf); - //rclcpp::Time base_link_odom_tf_stamp = (rclcpp::Time)_previous_tf[right_stamp_index].header.stamp; - set_transform_from_pose(base_link_relative_to_new_odom, base_link_odom_tf, stamp_msg); + /* Getting base_link_relative_to_near */ + extract_pose_from_transform(_previous_tf[0], base_link_relative_to_odom_estim); + get_pose_in_another_frame(base_link_relative_to_odom_estim, base_link_relative_to_near, nearest_tf); + /* Getting base_link_relative_to_odom_corrected */ + set_transform_from_pose(msg_received_relative_to_odom, msg_received_relative_to_odom_tf); + get_pose_in_another_frame(base_link_relative_to_near, base_link_relative_to_odom_corrected, msg_received_relative_to_odom_tf); tf2::Quaternion q( - base_link_odom_tf.transform.rotation.x, - base_link_odom_tf.transform.rotation.y, - base_link_odom_tf.transform.rotation.z, - base_link_odom_tf.transform.rotation.w + base_link_relative_to_odom_corrected.pose.orientation.x, + base_link_relative_to_odom_corrected.pose.orientation.y, + base_link_relative_to_odom_corrected.pose.orientation.z, + base_link_relative_to_odom_corrected.pose.orientation.w ); tf2::Matrix3x3 m(q); double roll, pitch, yaw; From fc3a017f5d80931a824e5b18605487bc3f845fa0 Mon Sep 17 00:00:00 2001 From: PhileasL Date: Thu, 4 Feb 2021 23:00:48 +0100 Subject: [PATCH 20/67] almost working, adding a dummy function to avoid odom sliding In fact there is a little error at each stage that amplifies slowly, but we can get rid of it by manipulating troncated double. A precision of about a millimeter is still remaining which is acceptable. --- src/modules/drive/include/drive.hpp | 1 + src/modules/drive/src/drive.cpp | 25 +++++++++++++++++++++++++ 2 files changed, 26 insertions(+) diff --git a/src/modules/drive/include/drive.hpp b/src/modules/drive/include/drive.hpp index dc05bc54..598a74b2 100644 --- a/src/modules/drive/include/drive.hpp +++ b/src/modules/drive/include/drive.hpp @@ -185,6 +185,7 @@ class Drive : public rclcpp::Node { tf2::Vector3 get_tf2_vector(geometry_msgs::msg::Point &p); tf2::Vector3 get_tf2_vector(geometry_msgs::msg::Vector3 &p); void set_pose_from_tf_t_q(tf2::Vector3 &t, tf2::Quaternion &q, geometry_msgs::msg::PoseStamped &pose_out); + double dummy_tree_digits_precision(double a); #ifdef SIMULATION void sim_step(); diff --git a/src/modules/drive/src/drive.cpp b/src/modules/drive/src/drive.cpp index 83ef6cee..8f298a45 100644 --- a/src/modules/drive/src/drive.cpp +++ b/src/modules/drive/src/drive.cpp @@ -402,6 +402,19 @@ void Drive::set_transform_from_pose(geometry_msgs::msg::PoseStamped &pose_in, ge } void Drive::get_pose_in_another_frame(geometry_msgs::msg::PoseStamped &pose_in, geometry_msgs::msg::PoseStamped &pose_out, geometry_msgs::msg::TransformStamped &transform){ + pose_out.header = pose_in.header; + pose_out.header.frame_id = transform.child_frame_id; + + tf2::Vector3 t_in_new_frame, + t_pose_in = get_tf2_vector(pose_in.pose.position), + t_transform = get_tf2_vector(transform.transform.translation); + tf2::Quaternion q_in_new_frame, + q_pose_in = get_tf2_quaternion(pose_in.pose.orientation), + q_transform = get_tf2_quaternion(transform.transform.rotation); + + t_in_new_frame = t_pose_in - t_transform; + q_in_new_frame = q_pose_in * q_transform.inverse(); + set_pose_from_tf_t_q(t_in_new_frame, q_in_new_frame, pose_out); } tf2::Quaternion Drive::get_tf2_quaternion(geometry_msgs::msg::Quaternion &q){ @@ -417,6 +430,18 @@ tf2::Vector3 Drive::get_tf2_vector(geometry_msgs::msg::Vector3 &p){ } void Drive::set_pose_from_tf_t_q(tf2::Vector3 &t, tf2::Quaternion &q, geometry_msgs::msg::PoseStamped &pose_out){ + pose_out.pose.position.x = dummy_tree_digits_precision(t.x()); + pose_out.pose.position.y = dummy_tree_digits_precision(t.y()); + pose_out.pose.position.z = 0; + pose_out.pose.orientation.x = q.x(); + pose_out.pose.orientation.y = q.y(); + pose_out.pose.orientation.z = q.z(); + pose_out.pose.orientation.w = q.w(); +} + +double Drive::dummy_tree_digits_precision(double a){ + int dummy = (int)(a*1000); + return (double)(dummy)/1000; } Drive::~Drive() { From 92b18990d3f188269c2388fa5aad092753b1081e Mon Sep 17 00:00:00 2001 From: PhileasL Date: Thu, 4 Feb 2021 23:02:13 +0100 Subject: [PATCH 21/67] Little tweaking on tf, working good now ! --- src/modules/drive/src/drive.cpp | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/src/modules/drive/src/drive.cpp b/src/modules/drive/src/drive.cpp index 8f298a45..99a975ee 100644 --- a/src/modules/drive/src/drive.cpp +++ b/src/modules/drive/src/drive.cpp @@ -412,8 +412,19 @@ void Drive::get_pose_in_another_frame(geometry_msgs::msg::PoseStamped &pose_in, q_pose_in = get_tf2_quaternion(pose_in.pose.orientation), q_transform = get_tf2_quaternion(transform.transform.rotation); + if (pose_in.header.frame_id == transform.header.frame_id){ t_in_new_frame = t_pose_in - t_transform; + } else { + t_in_new_frame = t_pose_in + t_transform; + } + + if (pose_in.header.frame_id == odom_.child_frame_id){ + q_in_new_frame = q_transform * q_pose_in.inverse(); + } else { q_in_new_frame = q_pose_in * q_transform.inverse(); + } + + set_pose_from_tf_t_q(t_in_new_frame, q_in_new_frame, pose_out); } From f16543b59feeeccb09d25f94cb6cdbbc82fe8dd8 Mon Sep 17 00:00:00 2001 From: PhileasL Date: Thu, 4 Feb 2021 23:04:53 +0100 Subject: [PATCH 22/67] A static transformation need to be publish only once + little fixes --- .../localisation/localisation/localisation_node.py | 9 +-------- 1 file changed, 1 insertion(+), 8 deletions(-) diff --git a/src/modules/localisation/localisation/localisation_node.py b/src/modules/localisation/localisation/localisation_node.py index 36c36fe3..9a552126 100644 --- a/src/modules/localisation/localisation/localisation_node.py +++ b/src/modules/localisation/localisation/localisation_node.py @@ -4,6 +4,7 @@ """Robot localisation node.""" +import math import numpy as np import rclpy @@ -29,10 +30,7 @@ def __init__(self): self.subscription_ = self.create_subscription( MarkerArray, '/allies_positions_markers', self.allies_subscription_callback, 10) self.subscription_ # prevent unused variable warning - self.last_odom_update = self.get_clock().now().to_msg().sec; - self.create_timer(1, self.update_transform) self.tf_publisher_ = self.create_publisher(TransformStamped, 'adjust_odometry', 10) - self.update_transform() self.get_logger().info(f'Default side is {self.side.value}') self.get_logger().info('Localisation node is ready') @@ -109,11 +107,6 @@ def update_transform(self): self._tf.transform.rotation.z = float(qz) self._tf.transform.rotation.w = float(qw) self._tf_brodcaster.sendTransform(self._tf) - #self.get_logger().info(f'tf: x={self.get_clock().now().to_msg().sec}') - - def _service_call(self, client, request): - """Call service synchronously.""" - client.call_async(request) def allies_subscription_callback(self, msg): for allie_marker in msg.markers: From d96d9a8b5f4043e646d8a46540ad421d5da35c92 Mon Sep 17 00:00:00 2001 From: PhileasL Date: Thu, 4 Feb 2021 23:07:02 +0100 Subject: [PATCH 23/67] Publishing the robot transformation for drive to readjust odometry --- .../localisation/localisation_node.py | 17 +++++++++++------ 1 file changed, 11 insertions(+), 6 deletions(-) diff --git a/src/modules/localisation/localisation/localisation_node.py b/src/modules/localisation/localisation/localisation_node.py index 9a552126..2b4a2cff 100644 --- a/src/modules/localisation/localisation/localisation_node.py +++ b/src/modules/localisation/localisation/localisation_node.py @@ -31,6 +31,7 @@ def __init__(self): MarkerArray, '/allies_positions_markers', self.allies_subscription_callback, 10) self.subscription_ # prevent unused variable warning self.tf_publisher_ = self.create_publisher(TransformStamped, 'adjust_odometry', 10) + self.last_odom_update = 0 self.get_logger().info(f'Default side is {self.side.value}') self.get_logger().info('Localisation node is ready') @@ -109,16 +110,20 @@ def update_transform(self): self._tf_brodcaster.sendTransform(self._tf) def allies_subscription_callback(self, msg): + """Identity the robot marker in assurancetourix marker_array detection + publish the transformation for drive to readjust odometry""" for allie_marker in msg.markers: if allie_marker.text.lower() == self.robot and (self.get_clock().now().to_msg().sec - self.last_odom_update) > 5: self._x = allie_marker.pose.position.x self._y = allie_marker.pose.position.y - self._theta = allie_marker.pose.orientation.z - self._service_call( - self._get_trigger_adjust_odometry_client, - self._get_trigger_adjust_odometry_request, - ) - self.update_transform() + q = allie_marker.pose.orientation + self._theta = self.quaternion_to_euler(q.x, q.y, q.z, q.w)[2] + self._tf.header.stamp = allie_marker.header.stamp + self._tf.transform.translation.x = allie_marker.pose.position.x + self._tf.transform.translation.y = allie_marker.pose.position.y + self._tf.transform.translation.z = float(0) + self._tf.transform.rotation = q + self.tf_publisher_.publish(self._tf) self.last_odom_update = self.get_clock().now().to_msg().sec def main(args=None): From abe9844f2f50e514a04bf43ff4028e811e5209b3 Mon Sep 17 00:00:00 2001 From: PhileasL Date: Fri, 5 Feb 2021 10:24:21 +0100 Subject: [PATCH 24/67] small fix, can now recalibrate even if the information is .75s from past --- src/modules/drive/src/drive.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/modules/drive/src/drive.cpp b/src/modules/drive/src/drive.cpp index 99a975ee..e403c796 100644 --- a/src/modules/drive/src/drive.cpp +++ b/src/modules/drive/src/drive.cpp @@ -145,7 +145,7 @@ void Drive::init_variables() { init_vector.header.stamp = this->get_clock()->now(); init_vector.header.frame_id = odom_.header.frame_id; init_vector.child_frame_id = odom_.child_frame_id; - for (int i = 0; i<20; i++) _previous_tf.push_back(init_vector); + for (int i = 0; i<30; i++) _previous_tf.push_back(init_vector); } int8_t Drive::compute_velocity_cmd(double velocity) { @@ -275,7 +275,7 @@ void Drive::update_tf() { tf_pub_->publish(odom_tf_msg); _previous_tf.insert(_previous_tf.begin(), odom_tf); - if (_previous_tf.size() > 20) _previous_tf.pop_back(); + if (_previous_tf.size() > 30) _previous_tf.pop_back(); } void Drive::update_joint_states() { @@ -418,7 +418,7 @@ void Drive::get_pose_in_another_frame(geometry_msgs::msg::PoseStamped &pose_in, t_in_new_frame = t_pose_in + t_transform; } - if (pose_in.header.frame_id == odom_.child_frame_id){ + if (pose_in.header.frame_id == odom_.child_frame_id || pose_in.header.frame_id == transform.header.frame_id){ q_in_new_frame = q_transform * q_pose_in.inverse(); } else { q_in_new_frame = q_pose_in * q_transform.inverse(); From 1e9f406847ba078e4b82c9d8f84b9aab66393af3 Mon Sep 17 00:00:00 2001 From: PhileasL Date: Fri, 5 Feb 2021 21:42:10 +0100 Subject: [PATCH 25/67] =?UTF-8?q?teb=5Flocal=5Fplanner=20no=20longer=20tur?= =?UTF-8?q?n=202*180=C2=B0=20for=20a=20simple=20backward=20drive?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- src/modules/robot/param/robot.in.yml | 23 ++++++++++------------- 1 file changed, 10 insertions(+), 13 deletions(-) diff --git a/src/modules/robot/param/robot.in.yml b/src/modules/robot/param/robot.in.yml index a43e95ab..e42f76cd 100644 --- a/src/modules/robot/param/robot.in.yml +++ b/src/modules/robot/param/robot.in.yml @@ -92,14 +92,15 @@ controller_server: # Optimisation optimization_activate: True optimization_verbose: False - #weight_shortest_path: 500.0 + weight_kinematics_forward_drive: 0.0 # Trajectory teb_autoresize: True exact_arc_length: False min_samples: 3 max_samples: 100 - max_global_plan_lookahead_dist: 1.0 + max_global_plan_lookahead_dist: 3.7 + global_plan_overwrite_orientation: true allow_init_with_backwards_motion: true @@ -139,19 +140,15 @@ global_costmap: local_costmap: #just enough parameters to disable it local_costmap: ros__parameters: - update_frequency: 2.0 - publish_frequency: 2.0 - global_frame: odom + update_frequency: 0.1 + publish_frequency: 0.1 + global_frame: map robot_base_frame: base_link - use_sim_time: !Var use_sim_time + use_sim_time: false rolling_window: true - width: 3 - height: 3 - resolution: 0.02 - plugins: ["static_layer"] - static_layer: - plugin: "nav2_costmap_2d::StaticLayer" - map_subscribe_transient_local: True + width: 6 + height: 6 + resolution: 1.0 map_server: ros__parameters: From d5c14eb7e7931de12f3c253d787ad09e9400c183 Mon Sep 17 00:00:00 2001 From: PhileasL Date: Mon, 8 Feb 2021 20:21:32 +0100 Subject: [PATCH 26/67] Remove things that needed to be delete in merge of PR #27 #28 --- src/assurancetourix/assurancetourix/src/assurancetourix.cpp | 1 - src/modules/drive/include/drive.hpp | 1 - 2 files changed, 2 deletions(-) diff --git a/src/assurancetourix/assurancetourix/src/assurancetourix.cpp b/src/assurancetourix/assurancetourix/src/assurancetourix.cpp index 51cda057..c4d3d373 100644 --- a/src/assurancetourix/assurancetourix/src/assurancetourix.cpp +++ b/src/assurancetourix/assurancetourix/src/assurancetourix.cpp @@ -72,7 +72,6 @@ Assurancetourix::Assurancetourix() : Node("assurancetourix") { timer_ = this->create_wall_timer(std::chrono::milliseconds(1000 / refresh_frequency), std::bind(&Assurancetourix::simulation_marker_callback, this)); #endif - //timer_ = this->create_wall_timer(0.3s, std::bind(&Assurancetourix::detect, this)); // to remove for PR RCLCPP_INFO(this->get_logger(), "Assurancetourix has been started"); } diff --git a/src/modules/drive/include/drive.hpp b/src/modules/drive/include/drive.hpp index 598a74b2..1a8bc8fa 100644 --- a/src/modules/drive/include/drive.hpp +++ b/src/modules/drive/include/drive.hpp @@ -10,7 +10,6 @@ #include #endif #include "std_srvs/srv/set_bool.hpp" -#include "std_srvs/srv/trigger.hpp" #include "actuators_srvs/srv/slider.hpp" #include "nav_msgs/msg/odometry.hpp" #include "sensor_msgs/msg/joint_state.hpp" From 7ef6151d5b67a64b6bdbf490a5bd4670b7dc12ca Mon Sep 17 00:00:00 2001 From: PhileasL Date: Mon, 8 Feb 2021 20:24:02 +0100 Subject: [PATCH 27/67] Global planner works now at 2Hz, drive's garbage log not showing anymore --- src/modules/robot/behavior_trees/navigate_w_replanning_time.xml | 2 +- src/modules/robot/robot/interfaces.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/robot/behavior_trees/navigate_w_replanning_time.xml b/src/modules/robot/behavior_trees/navigate_w_replanning_time.xml index 7ceb1c0f..27a16821 100644 --- a/src/modules/robot/behavior_trees/navigate_w_replanning_time.xml +++ b/src/modules/robot/behavior_trees/navigate_w_replanning_time.xml @@ -5,7 +5,7 @@ - + diff --git a/src/modules/robot/robot/interfaces.py b/src/modules/robot/robot/interfaces.py index 685c6d3f..de765453 100644 --- a/src/modules/robot/robot/interfaces.py +++ b/src/modules/robot/robot/interfaces.py @@ -40,7 +40,7 @@ def generate_launch_description(): Node( package="drive", executable="drive", - output="screen", + output={'both': 'log'}, parameters=[params], remappings=remappings, ), From d17a54939bdfe711a0677240020e84db677c72eb Mon Sep 17 00:00:00 2001 From: PhileasL Date: Mon, 8 Feb 2021 21:09:21 +0100 Subject: [PATCH 28/67] Local_costmap contains obstacles for teb_local_planner In fact, the planner takes care of the global_costmap and the teb_local_planner only of the local_costmap. Here, the local_costmap is just representing the static map without inflation and gradient_layer that need a specific treatement. --- src/modules/robot/param/robot.in.yml | 30 ++++++++++++++++++++++------ 1 file changed, 24 insertions(+), 6 deletions(-) diff --git a/src/modules/robot/param/robot.in.yml b/src/modules/robot/param/robot.in.yml index e42f76cd..99d740d5 100644 --- a/src/modules/robot/param/robot.in.yml +++ b/src/modules/robot/param/robot.in.yml @@ -137,18 +137,36 @@ global_costmap: inflate_around_unknown: false always_send_full_costmap: true -local_costmap: #just enough parameters to disable it +local_costmap: local_costmap: ros__parameters: - update_frequency: 0.1 - publish_frequency: 0.1 + lethal_cost_threshold: 253 + trinary_costmap: false + update_frequency: 5.0 + publish_frequency: 5.0 global_frame: map robot_base_frame: base_link use_sim_time: false - rolling_window: true - width: 6 - height: 6 + rolling_window: false resolution: 1.0 + static_map: true + plugins: ["static_layer", "gradient_layer", "inflation_layer"] + static_layer: + plugin: nav2_costmap_2d::StaticLayer + gradient_layer: #draw radians circle around ennemies + plugin: "gradient_costmap_layer_plugin/GradientLayer" + enabled: false + gradient_size: 7 + gradient_factor: 100 + markers_topic: /ennemies_positions_markers + inflation_layer: + plugin: nav2_costmap_2d::InflationLayer + enabled: false + inflation_radius: 0.01 + cost_scaling_factor: 5.0 + inflate_unknown: false + inflate_around_unknown: false + always_send_full_costmap: true map_server: ros__parameters: From 88833b5451f2d04efe182f33ed4afdeb1c222958 Mon Sep 17 00:00:00 2001 From: PhileasL Date: Mon, 8 Feb 2021 21:12:33 +0100 Subject: [PATCH 29/67] Tweak of the global_costmap for an acceptable global_planning --- src/modules/robot/param/robot.in.yml | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/src/modules/robot/param/robot.in.yml b/src/modules/robot/param/robot.in.yml index 99d740d5..3754d9fc 100644 --- a/src/modules/robot/param/robot.in.yml +++ b/src/modules/robot/param/robot.in.yml @@ -112,12 +112,13 @@ controller_server_rclcpp_node: global_costmap: global_costmap: ros__parameters: + lethal_cost_threshold: 253 update_frequency: 5.0 publish_frequency: 5.0 global_frame: map robot_base_frame: base_link use_sim_time: !Var use_sim_time - resolution: 0.02 + resolution: 0.01 plugins: ["static_layer", "gradient_layer", "inflation_layer"] static_layer: #subscribe to map plugin: "nav2_costmap_2d::StaticLayer" @@ -131,8 +132,8 @@ global_costmap: inflation_layer: plugin: "nav2_costmap_2d::InflationLayer" enabled: true - inflation_radius: 0.2 - cost_scaling_factor: 5.0 + inflation_radius: 0.3 + cost_scaling_factor: 10.0 inflate_unknown: false inflate_around_unknown: false always_send_full_costmap: true From c472520ad002ccd7e0da51bd71f14ae0ac445727 Mon Sep 17 00:00:00 2001 From: PhileasL Date: Mon, 8 Feb 2021 21:20:21 +0100 Subject: [PATCH 30/67] Teb_local_planner tweak: - Decreasing controller_frequency which were way too high, - Made the progress checker more accurate on progress detection, - Raise of the min_obstacle_distance and inflation radius to avoid navigation abort due to trajectory collision with an obstacle, - Include static costmap obstacles. Next step: create a node for computing and sending dynamic obstacles to teb_local_planner. --- src/modules/robot/param/robot.in.yml | 24 +++++++++++++++++------- 1 file changed, 17 insertions(+), 7 deletions(-) diff --git a/src/modules/robot/param/robot.in.yml b/src/modules/robot/param/robot.in.yml index 3754d9fc..3c70b1c5 100644 --- a/src/modules/robot/param/robot.in.yml +++ b/src/modules/robot/param/robot.in.yml @@ -56,33 +56,40 @@ cetautomatix: controller_server: ros__parameters: use_sim_time: !Var use_sim_time - controller_frequency: 40.0 + controller_frequency: 20.0 min_x_velocity_threshold: 0.001 - min_y_velocity_threshold: 0.5 + min_y_velocity_threshold: 0.001 min_theta_velocity_threshold: 0.001 progress_checker_plugin: "progress_checker" goal_checker_plugin: "goal_checker" controller_plugins: ["DynamicFollowPath"] progress_checker: plugin: "nav2_controller::SimpleProgressChecker" - required_movement_radius: 0.5 + required_movement_radius: 0.005 movement_time_allowance: 10.0 goal_checker: plugin: "nav2_controller::SimpleGoalChecker" - xy_goal_tolerance: 0.02 - yaw_goal_tolerance: 0.02 + xy_goal_tolerance: 0.01 + yaw_goal_tolerance: 0.01 stateful: True DynamicFollowPath: plugin: "teb_local_planner::TebLocalPlannerROS" # Robot footprint footprint_model.type: polygon + # Goal tolerance + xy_goal_tolerance: 0.01 + yaw_goal_tolerance: 0.01 + # Obstacles - min_obstacle_dist: 0.01 - inflation_dist: 0.1 + min_obstacle_dist: 0.03 + inflation_dist: 0.25 costmap_converter_plugin: costmap_converter::CostmapToPolygonsDBSMCCH costmap_converter_spin_thread: True costmap_converter_rate: 5 + include_costmap_obstacles: true + costmap_obstacles_behind_robot_dist: 3.0 + include_dynamic_obstacles: false # Homotopy Class Planner enable_homotopy_class_planning: True @@ -103,6 +110,9 @@ controller_server: global_plan_overwrite_orientation: true allow_init_with_backwards_motion: true + # Miscellaneous + map_frame: "map" + controller_server_rclcpp_node: ros__parameters: From 9b4ab3686ce757fc7378faf4e186ec2b07987fd1 Mon Sep 17 00:00:00 2001 From: PhileasL Date: Mon, 8 Feb 2021 21:27:19 +0100 Subject: [PATCH 31/67] Hello teb_obstacles node ! The goal of this node is to compute and send to the teb_local_planner the dynamic obstacles. With theses obstacles, the teb_local_planner might be able to make better decisions. The dynamic obstacles are (for the moment in my mind): - Ennemies - The other allie --- src/navigation/teb_obstacles/package.xml | 15 +++++++++ .../teb_obstacles/resource/teb_obstacles | 0 src/navigation/teb_obstacles/setup.cfg | 4 +++ src/navigation/teb_obstacles/setup.py | 33 +++++++++++++++++++ .../teb_obstacles/teb_obstacles/__init__.py | 0 .../teb_obstacles/teb_obstacles.py | 28 ++++++++++++++++ 6 files changed, 80 insertions(+) create mode 100644 src/navigation/teb_obstacles/package.xml create mode 100644 src/navigation/teb_obstacles/resource/teb_obstacles create mode 100644 src/navigation/teb_obstacles/setup.cfg create mode 100644 src/navigation/teb_obstacles/setup.py create mode 100644 src/navigation/teb_obstacles/teb_obstacles/__init__.py create mode 100644 src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py diff --git a/src/navigation/teb_obstacles/package.xml b/src/navigation/teb_obstacles/package.xml new file mode 100644 index 00000000..f1bf23e6 --- /dev/null +++ b/src/navigation/teb_obstacles/package.xml @@ -0,0 +1,15 @@ + + + + teb_obstacles + 0.8.3 + teb_obstacles node compute and send dynamic teb_obstacles + Philéas LAMBERT + ECAM Makers :: CDFR 2021 + + rclpy + + + ament_python + + diff --git a/src/navigation/teb_obstacles/resource/teb_obstacles b/src/navigation/teb_obstacles/resource/teb_obstacles new file mode 100644 index 00000000..e69de29b diff --git a/src/navigation/teb_obstacles/setup.cfg b/src/navigation/teb_obstacles/setup.cfg new file mode 100644 index 00000000..b166fdb2 --- /dev/null +++ b/src/navigation/teb_obstacles/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script-dir=$base/lib/teb_obstacles +[install] +install-scripts=$base/lib/teb_obstacles diff --git a/src/navigation/teb_obstacles/setup.py b/src/navigation/teb_obstacles/setup.py new file mode 100644 index 00000000..bdcc7740 --- /dev/null +++ b/src/navigation/teb_obstacles/setup.py @@ -0,0 +1,33 @@ +#!/usr/bin/env python3 + + +"""Teb_obstacles package.""" + + +from os import path +from setuptools import setup, find_packages + +package_name = 'teb_obstacles' + +setup( + name=package_name, + version='0.8.3', + packages=find_packages(), + data_files=[ + (path.join("share", package_name), ["package.xml"]), + ('share/ament_index/resource_index/packages', ['resource/' + package_name]), + ], + install_requires=['setuptools'], + zip_safe=True, + author="Philéas LAMBERT", + maintainer='Phileas LAMBERT', + maintainer_email='phileas.lambert@gmail.com', + keywords=["ROS2", "teb_obstacles", "CDFR"], + description='teb_obstacles node compute and send dynamic teb_obstacles', + license="ECAM Makers :: CDFR 2021", + entry_points={ + 'console_scripts': [ + 'teb_obstacles = teb_obstacles.teb_obstacles:main' + ], + }, +) diff --git a/src/navigation/teb_obstacles/teb_obstacles/__init__.py b/src/navigation/teb_obstacles/teb_obstacles/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py b/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py new file mode 100644 index 00000000..3c2fe773 --- /dev/null +++ b/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py @@ -0,0 +1,28 @@ +#!/usr/bin/env python3 + + +"""Teb_obstacles localisation node.""" + + +import rclpy + +from rclpy.node import Node + +class Teb_obstacles(Node): + + def __init__(self): + super().__init__("teb_dynamic_obstacles_node") + self.allie = "obelix" if self.get_namespace().strip("/") == "asterix" else "asterix" + self.get_logger().info('teb_dynamic_obstacles node is ready') + + +def main(args=None): + """Entrypoint.""" + rclpy.init(args=args) + teb_obstacles = Teb_obstacles() + try: + rclpy.spin(teb_obstacles) + except KeyboardInterrupt: + pass + teb_obstacles.destroy_node() + rclpy.shutdown() From 9994d674f7e89e866b4f979ac7e14ca465911a8a Mon Sep 17 00:00:00 2001 From: PhileasL Date: Mon, 8 Feb 2021 21:35:20 +0100 Subject: [PATCH 32/67] teb_obstales node launching with nav --- src/modules/robot/robot/launcher.py | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/src/modules/robot/robot/launcher.py b/src/modules/robot/robot/launcher.py index 8aa83290..667cd745 100644 --- a/src/modules/robot/robot/launcher.py +++ b/src/modules/robot/robot/launcher.py @@ -126,6 +126,13 @@ def generate_robot_launch_description(robot_namespace: str, simulation=False): parameters=[params.name], remappings=remappings, ), + Node( + package='teb_obstacles', + executable='teb_obstacles', + output='screen', + parameters=[], + remappings=remappings + ), IncludeLaunchDescription( PythonLaunchDescriptionSource( [nav2_launch_file_dir, "/navigation_launch.py"] From 7a9e9e5f0a5eb2b02971c6434e6c8bb5d210c0f4 Mon Sep 17 00:00:00 2001 From: PhileasL Date: Tue, 9 Feb 2021 20:45:36 +0100 Subject: [PATCH 33/67] Subscribing + callback to allies and ennemies topics --- .../teb_obstacles/teb_obstacles/teb_obstacles.py | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py b/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py index 3c2fe773..e3218b42 100644 --- a/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py +++ b/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py @@ -7,14 +7,23 @@ import rclpy from rclpy.node import Node +from visualization_msgs.msg import MarkerArray class Teb_obstacles(Node): def __init__(self): super().__init__("teb_dynamic_obstacles_node") self.allie = "obelix" if self.get_namespace().strip("/") == "asterix" else "asterix" + self.allies_subscription_ = self.create_subscription( + MarkerArray, '/allies_positions_markers', self.allies_subscription_callback, 10) + self.ennemies_subscription_ = self.create_subscription( + MarkerArray, '/ennemies_positions_markers', self.ennemies_subscription_callback, 10) + self.allies_subscription_ + self.ennemies_subscription_ self.get_logger().info('teb_dynamic_obstacles node is ready') + def allies_subscription_callback(self, msg): + def ennemies_subscription_callback(self, msg): def main(args=None): """Entrypoint.""" From 58e688865f9d5b6d8a270ee8a13eaf1af0f183d9 Mon Sep 17 00:00:00 2001 From: PhileasL Date: Tue, 9 Feb 2021 20:48:26 +0100 Subject: [PATCH 34/67] Initialisation of obstacles array This ObstacleArrayMsg object is the object to send to the topic 'obstacle' in order to tell the teb_local_planner that theses obstacles are dynamic obstacles --- .../teb_obstacles/teb_obstacles/teb_obstacles.py | 15 +++++++++++++++ 1 file changed, 15 insertions(+) diff --git a/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py b/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py index e3218b42..b200a1bd 100644 --- a/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py +++ b/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py @@ -20,8 +20,23 @@ def __init__(self): MarkerArray, '/ennemies_positions_markers', self.ennemies_subscription_callback, 10) self.allies_subscription_ self.ennemies_subscription_ + self.initObstaclesArray() self.get_logger().info('teb_dynamic_obstacles node is ready') + def initObstaclesArray(self): + """ObstacleArray index 0: allie, index 1-2: ennemies""" + self.obstacles = ObstacleArrayMsg() + self.obstacles.header.frame_id = "map" + self.obstacles.obstacles.append(ObstacleMsg()) + self.obstacles.obstacles.append(ObstacleMsg()) + self.obstacles.obstacles.append(ObstacleMsg()) + for i in range(3): + self.obstacles.obstacles[i].header.frame_id = "map" + self.obstacles.obstacles[i].polygon.points = [Point32()] + self.obstacles.obstacles[i].polygon.points[0].x = -1.0 + self.obstacles.obstacles[i].polygon.points[0].y = -1.0 + self.obstacles.obstacles[i].radius = 0.15 + self.previous_obstacles = copy.deepcopy(self.obstacles) def allies_subscription_callback(self, msg): def ennemies_subscription_callback(self, msg): From 7c8dd54886a93e3a1216985fb4d3efe975ba0d5f Mon Sep 17 00:00:00 2001 From: PhileasL Date: Tue, 9 Feb 2021 20:51:46 +0100 Subject: [PATCH 35/67] dictionnary_index_id: The purpose of this dictionnary is to track which marker id of the obstaclesArray is at which index in order to update the array instead of re-create it in case of new markers detection from assurancetourix --- src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py | 1 + 1 file changed, 1 insertion(+) diff --git a/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py b/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py index b200a1bd..3fb5b812 100644 --- a/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py +++ b/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py @@ -20,6 +20,7 @@ def __init__(self): MarkerArray, '/ennemies_positions_markers', self.ennemies_subscription_callback, 10) self.allies_subscription_ self.ennemies_subscription_ + self.dictionary_index_id = {"0":0, "1":0, "2":0} self.initObstaclesArray() self.get_logger().info('teb_dynamic_obstacles node is ready') From ef09df5fd3afe897c7e43209bb35a421f033cabe Mon Sep 17 00:00:00 2001 From: PhileasL Date: Tue, 9 Feb 2021 21:00:48 +0100 Subject: [PATCH 36/67] ennemies_subscription_callback function of teb_obstacles This function dissociate the predicted markers (id > 10) from the true positions of the ennemie. At first call, it will just put the marker id in a availible slot of the dictionary. Other callbacks will set the dynamic obstacles --- .../teb_obstacles/teb_obstacles.py | 23 +++++++++++++++++++ 1 file changed, 23 insertions(+) diff --git a/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py b/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py index 3fb5b812..19c087fa 100644 --- a/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py +++ b/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py @@ -7,7 +7,9 @@ import rclpy from rclpy.node import Node +from costmap_converter_msgs.msg import ObstacleArrayMsg, ObstacleMsg from visualization_msgs.msg import MarkerArray +from geometry_msgs.msg import Point32 class Teb_obstacles(Node): @@ -38,8 +40,29 @@ def initObstaclesArray(self): self.obstacles.obstacles[i].polygon.points[0].y = -1.0 self.obstacles.obstacles[i].radius = 0.15 self.previous_obstacles = copy.deepcopy(self.obstacles) + def set_obstacle(self, index, marker): + + def allies_subscription_callback(self, msg): + def ennemies_subscription_callback(self, msg): + """Identity the ennemie marker in assurancetourix marker_array detection + set the dynamic obstacle for teb_local_planner""" + for ennemie_marker in msg.markers: + if ennemie_marker.id <= 10: + in_dict = False + for index in range(1,2): + if self.dictionary_index_id[f"{index}"] == ennemie_marker.id: + self.set_obstacle(index, ennemie_marker) + in_dict = True + if not in_dict: + if self.dictionary_index_id["1"] == 0: + self.dictionary_index_id["1"] = ennemie_marker.id + elif self.dictionary_index_id["2"] == 0: + self.dictionary_index_id["2"] = ennemie_marker.id + else: + self.get_logger().info('obstacleArray index limit, is there 3 ennemies, or is it a bad marker detection') + def main(args=None): """Entrypoint.""" From 421869cd1bd09bc126dbe3aa50ec8a48a302a73b Mon Sep 17 00:00:00 2001 From: PhileasL Date: Tue, 9 Feb 2021 21:02:21 +0100 Subject: [PATCH 37/67] WIP on allies_subscription_callback for teb_obstacles --- .../teb_obstacles/teb_obstacles/teb_obstacles.py | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py b/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py index 19c087fa..d6bc7aa7 100644 --- a/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py +++ b/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py @@ -44,6 +44,14 @@ def set_obstacle(self, index, marker): def allies_subscription_callback(self, msg): + """Identity the allie marker in assurancetourix marker_array detection + set the dynamic obstacle for teb_local_planner""" + for allie_marker in msg.markers: + if allie_marker.text.lower() == self.allie: + if self.dictionary_index_id["0"] == 0: + self.dictionary_index_id["0"] = allie_marker.id + self.obstacles.obstacles[0].id = self.dictionary_index_id["0"] + self.set_obstacle(0, allie_marker) def ennemies_subscription_callback(self, msg): """Identity the ennemie marker in assurancetourix marker_array detection From 6f63d31752977d045c7b28d85dffb235726d8e58 Mon Sep 17 00:00:00 2001 From: PhileasL Date: Tue, 9 Feb 2021 21:04:55 +0100 Subject: [PATCH 38/67] Set_obstacles function for teb_obstacles Set the position of the obstacle + compute its x and y linear velocity for the teb_local_planner in order to predict the movement of the dynamic obstacle --- .../teb_obstacles/teb_obstacles.py | 20 +++++++++++++++++++ 1 file changed, 20 insertions(+) diff --git a/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py b/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py index d6bc7aa7..6e5f5c6d 100644 --- a/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py +++ b/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py @@ -5,6 +5,7 @@ import rclpy +import copy from rclpy.node import Node from costmap_converter_msgs.msg import ObstacleArrayMsg, ObstacleMsg @@ -40,7 +41,26 @@ def initObstaclesArray(self): self.obstacles.obstacles[i].polygon.points[0].y = -1.0 self.obstacles.obstacles[i].radius = 0.15 self.previous_obstacles = copy.deepcopy(self.obstacles) + + def get_diff_time(self, t1, t2): + return float(t1.sec - t2.sec + (t1.nanosec - t2.nanosec)*1e-9) + def set_obstacle(self, index, marker): + self.previous_obstacles.obstacles[index] = copy.deepcopy(self.obstacles.obstacles[index]) + self.obstacles.obstacles[index].header = marker.header + self.obstacles.obstacles[index].polygon.points[0].x = marker.pose.position.x + self.obstacles.obstacles[index].polygon.points[0].y = marker.pose.position.y + + dt = float(self.get_diff_time(marker.header.stamp, self.previous_obstacles.obstacles[index].header.stamp)) + + if dt != 0.0: + self.obstacles.obstacles[index].velocities.twist.linear.x = ( + marker.pose.position.x - self.previous_obstacles.obstacles[index].polygon.points[0].x + ) / dt + + self.obstacles.obstacles[index].velocities.twist.linear.y = ( + marker.pose.position.y - self.previous_obstacles.obstacles[index].polygon.points[0].y + ) / dt def allies_subscription_callback(self, msg): From 3528e587a97470d0aca0b0fdebdb85c7cbfbf8af Mon Sep 17 00:00:00 2001 From: PhileasL Date: Tue, 9 Feb 2021 21:08:06 +0100 Subject: [PATCH 39/67] Publishing dynamic obstacles each .5s + including them in teb config --- src/modules/robot/param/robot.in.yml | 2 +- .../teb_obstacles/teb_obstacles/teb_obstacles.py | 8 ++++++++ 2 files changed, 9 insertions(+), 1 deletion(-) diff --git a/src/modules/robot/param/robot.in.yml b/src/modules/robot/param/robot.in.yml index 3c70b1c5..aa4a14a0 100644 --- a/src/modules/robot/param/robot.in.yml +++ b/src/modules/robot/param/robot.in.yml @@ -89,7 +89,7 @@ controller_server: costmap_converter_rate: 5 include_costmap_obstacles: true costmap_obstacles_behind_robot_dist: 3.0 - include_dynamic_obstacles: false + include_dynamic_obstacles: true # Homotopy Class Planner enable_homotopy_class_planning: True diff --git a/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py b/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py index 6e5f5c6d..afee8920 100644 --- a/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py +++ b/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py @@ -23,8 +23,14 @@ def __init__(self): MarkerArray, '/ennemies_positions_markers', self.ennemies_subscription_callback, 10) self.allies_subscription_ self.ennemies_subscription_ + + self.obstacles_publisher_ = self.create_publisher(ObstacleArrayMsg, 'obstacles', 10) + self.dictionary_index_id = {"0":0, "1":0, "2":0} self.initObstaclesArray() + + self.create_timer(0.5, self.send_obstacles) + self.get_logger().info('teb_dynamic_obstacles node is ready') def initObstaclesArray(self): @@ -91,6 +97,8 @@ def ennemies_subscription_callback(self, msg): else: self.get_logger().info('obstacleArray index limit, is there 3 ennemies, or is it a bad marker detection') + def send_obstacles(self): + self.obstacles_publisher_.publish(self.obstacles) def main(args=None): """Entrypoint.""" From 691dfe95fff309b40f80758d440e83fc958d4cfd Mon Sep 17 00:00:00 2001 From: PhileasL Date: Wed, 10 Feb 2021 23:41:04 +0100 Subject: [PATCH 40/67] /robot/get_odom_map_tf service that returns the initial map->odom tf --- .../localisation/localisation/localisation_node.py | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/src/modules/localisation/localisation/localisation_node.py b/src/modules/localisation/localisation/localisation_node.py index 2b4a2cff..0e9714b5 100644 --- a/src/modules/localisation/localisation/localisation_node.py +++ b/src/modules/localisation/localisation/localisation_node.py @@ -12,6 +12,7 @@ from rcl_interfaces.msg import SetParametersResult from visualization_msgs.msg import MarkerArray from tf2_ros import StaticTransformBroadcaster +from transformix_msgs.srv import TransformixParametersTransformStamped class Localisation(rclpy.node.Node): """Robot localisation node.""" @@ -27,6 +28,8 @@ def __init__(self): self._tf.header.frame_id = 'map' self._tf.child_frame_id = 'odom' self.update_transform() + self.get_initial_tf_srv = self.create_service(TransformixParametersTransformStamped, + 'get_odom_map_tf', self.get_initial_tf_srv_callback) self.subscription_ = self.create_subscription( MarkerArray, '/allies_positions_markers', self.allies_subscription_callback, 10) self.subscription_ # prevent unused variable warning @@ -107,6 +110,7 @@ def update_transform(self): self._tf.transform.rotation.y = float(qy) self._tf.transform.rotation.z = float(qz) self._tf.transform.rotation.w = float(qw) + self._initial_tf = self._tf self._tf_brodcaster.sendTransform(self._tf) def allies_subscription_callback(self, msg): @@ -126,6 +130,11 @@ def allies_subscription_callback(self, msg): self.tf_publisher_.publish(self._tf) self.last_odom_update = self.get_clock().now().to_msg().sec + def get_initial_tf_srv_callback(self, request, response): + self.get_logger().info(f"incoming request for {self.robot} odom -> map tf") + response.transform_stamped = self._initial_tf + return response + def main(args=None): """Entrypoint.""" rclpy.init(args=args) From b230aba6a86c7f74eb92fbd4314dc507726b9baa Mon Sep 17 00:00:00 2001 From: PhileasL Date: Wed, 10 Feb 2021 23:43:46 +0100 Subject: [PATCH 41/67] Client of /robot/get_odom_map_tf for future pose transform --- .../teb_obstacles/teb_obstacles.py | 26 +++++++++++++++++++ 1 file changed, 26 insertions(+) diff --git a/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py b/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py index afee8920..5faf5299 100644 --- a/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py +++ b/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py @@ -11,12 +11,19 @@ from costmap_converter_msgs.msg import ObstacleArrayMsg, ObstacleMsg from visualization_msgs.msg import MarkerArray from geometry_msgs.msg import Point32 +from platform import machine +from transformix_msgs.srv import TransformixParametersTransformStamped class Teb_obstacles(Node): def __init__(self): super().__init__("teb_dynamic_obstacles_node") + self.simulation = True if machine() != "aarch64" else False + self.allie = "obelix" if self.get_namespace().strip("/") == "asterix" else "asterix" + + self.get_allie_odom_transformation() + self.allies_subscription_ = self.create_subscription( MarkerArray, '/allies_positions_markers', self.allies_subscription_callback, 10) self.ennemies_subscription_ = self.create_subscription( @@ -33,6 +40,25 @@ def __init__(self): self.get_logger().info('teb_dynamic_obstacles node is ready') + def get_allie_odom_transformation(self): + if self.simulation: + return + + get_tf_client = self.create_client(TransformixParametersTransformStamped, f'/{self.allie}/get_odom_map_tf') + + if not get_tf_client.wait_for_service(timeout_sec=15.0): + self.get_logger().info(f'No service /{self.allie}/get_odom_map_tf availible, is there ony one robot?') + return + get_tf_request = TransformixParametersTransformStamped.Request() + future = get_tf_client.call_async(get_tf_request) + rclpy.spin_until_future_complete(self, future) + try: + response = future.result() + except Exception as e: + self.get_logger().info( + 'Service call failed %r' % (e,)) + else: + self.odom_map_tf = response.transform_stamped def initObstaclesArray(self): """ObstacleArray index 0: allie, index 1-2: ennemies""" self.obstacles = ObstacleArrayMsg() From 803b68d4efb5608aa2bb1c1189181db53a36c663 Mon Sep 17 00:00:00 2001 From: PhileasL Date: Wed, 10 Feb 2021 23:49:22 +0100 Subject: [PATCH 42/67] Different allie tracking strategy for dynamic obstacle By subscribing to the odometry of the allie, we can get the position of the allie relative to its odom frame. With the odom->map transform, we can have these coordinates in the map frame. Then we can set the allie dynamic obstacle by the same way as for ennemies. Cooldown of 0.3s between each update of allie dynamic obstacle --- .../teb_obstacles/teb_obstacles.py | 25 ++++++++++++------- 1 file changed, 16 insertions(+), 9 deletions(-) diff --git a/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py b/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py index 5faf5299..d98bb576 100644 --- a/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py +++ b/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py @@ -9,7 +9,8 @@ from rclpy.node import Node from costmap_converter_msgs.msg import ObstacleArrayMsg, ObstacleMsg -from visualization_msgs.msg import MarkerArray +from visualization_msgs.msg import MarkerArray, Marker +from nav_msgs.msg import Odometry from geometry_msgs.msg import Point32 from platform import machine from transformix_msgs.srv import TransformixParametersTransformStamped @@ -25,7 +26,7 @@ def __init__(self): self.get_allie_odom_transformation() self.allies_subscription_ = self.create_subscription( - MarkerArray, '/allies_positions_markers', self.allies_subscription_callback, 10) + Odometry, f'/{self.allie}/odom', self.allies_subscription_callback, 10) self.ennemies_subscription_ = self.create_subscription( MarkerArray, '/ennemies_positions_markers', self.ennemies_subscription_callback, 10) self.allies_subscription_ @@ -34,6 +35,9 @@ def __init__(self): self.obstacles_publisher_ = self.create_publisher(ObstacleArrayMsg, 'obstacles', 10) self.dictionary_index_id = {"0":0, "1":0, "2":0} + + self.last_time_allie_callback = self.get_clock().now().to_msg() + self.initObstaclesArray() self.create_timer(0.5, self.send_obstacles) @@ -96,14 +100,17 @@ def set_obstacle(self, index, marker): def allies_subscription_callback(self, msg): - """Identity the allie marker in assurancetourix marker_array detection + """Determine the pose of base_link in map set the dynamic obstacle for teb_local_planner""" - for allie_marker in msg.markers: - if allie_marker.text.lower() == self.allie: - if self.dictionary_index_id["0"] == 0: - self.dictionary_index_id["0"] = allie_marker.id - self.obstacles.obstacles[0].id = self.dictionary_index_id["0"] - self.set_obstacle(0, allie_marker) + if self.get_diff_time(self.get_clock().now().to_msg(), self.last_time_allie_callback) > 0.3: + pose = msg.pose.pose + x = pose.position.x + self.odom_map_tf.transform.translation.x + y = pose.position.y + self.odom_map_tf.transform.translation.y + tmp_marker = Marker() + tmp_marker.pose.position.x = x + tmp_marker.pose.position.y = y + self.set_obstacle(0, tmp_marker) + self.last_time_allie_callback = self.get_clock().now().to_msg() def ennemies_subscription_callback(self, msg): """Identity the ennemie marker in assurancetourix marker_array detection From df97f05db9c2e0c195e5a429f65fefa3d7a93d37 Mon Sep 17 00:00:00 2001 From: PhileasL Date: Wed, 10 Feb 2021 23:51:05 +0100 Subject: [PATCH 43/67] removing useless remapping + commentaries on teb_obstacles functions --- src/modules/robot/robot/launcher.py | 3 +-- src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py | 3 +++ 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/src/modules/robot/robot/launcher.py b/src/modules/robot/robot/launcher.py index 667cd745..174b5fab 100644 --- a/src/modules/robot/robot/launcher.py +++ b/src/modules/robot/robot/launcher.py @@ -130,8 +130,7 @@ def generate_robot_launch_description(robot_namespace: str, simulation=False): package='teb_obstacles', executable='teb_obstacles', output='screen', - parameters=[], - remappings=remappings + parameters=[] ), IncludeLaunchDescription( PythonLaunchDescriptionSource( diff --git a/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py b/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py index d98bb576..3e9cec52 100644 --- a/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py +++ b/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py @@ -79,9 +79,12 @@ def initObstaclesArray(self): self.previous_obstacles = copy.deepcopy(self.obstacles) def get_diff_time(self, t1, t2): + """Returns the nb of seconds between the two Time object""" return float(t1.sec - t2.sec + (t1.nanosec - t2.nanosec)*1e-9) def set_obstacle(self, index, marker): + """Set the marker as obstacle in ObstacleArrayMsg at the given index, + compute the linear velocities relative to the previous state""" self.previous_obstacles.obstacles[index] = copy.deepcopy(self.obstacles.obstacles[index]) self.obstacles.obstacles[index].header = marker.header self.obstacles.obstacles[index].polygon.points[0].x = marker.pose.position.x From 422108ab45381b30ca22e64fd8d4a22fd5bf7207 Mon Sep 17 00:00:00 2001 From: PhileasL Date: Thu, 18 Feb 2021 19:33:20 +0100 Subject: [PATCH 44/67] Robot position extrapolation: The idea is to get a banch of VLX and robot position/orientation data using the simulator, and then establish a model to extrapolate the position of the robot using theses data (using linear regression, stochastic gradient descent...). The goal is to apply this model in the localisation_node to get and extra confidence of the real position of the robot (especially near walls) --- .../data_obtention.py | 57 +++++++++++++++++++ 1 file changed, 57 insertions(+) create mode 100644 tools/localisation_machine_learning/data_obtention.py diff --git a/tools/localisation_machine_learning/data_obtention.py b/tools/localisation_machine_learning/data_obtention.py new file mode 100644 index 00000000..f0a978a0 --- /dev/null +++ b/tools/localisation_machine_learning/data_obtention.py @@ -0,0 +1,57 @@ +""" +Do not forget to hit supervisor: TRUE in asterix description in webots +Need export PYTHONPATH=${WEBOTS_HOME}/lib/controller/python38 in order to work +""" + +from controller import Supervisor +from controller import Field +from os import environ + +import numpy as np +import math +import time + +x = 0.2 +y = 2 - 1.5 + +full_turn = [ + [1.0, 0.0, 0.0, -1.57], + [0.982902, -0.130198, -0.130198, -1.58804], + [-0.934738, 0.251261, 0.251261, 1.63823], + [-0.862359, 0.358006, 0.358006, 1.71834], + [0.775, -0.447, -0.447, -1.82], + [0.678, -0.52, -0.52, -1.95], + [0.577, -0.577, -0.577, -2.09], + [0.477, -0.622, -0.622, -2.25], + [0.378, -0.655, -0.655, -2.42], + [0.281, -0.679, -0.679, -2.59], + [0.186, -0.695, -0.695, -2.77], + [0.0927, -0.704, -0.704, -2.96], + [0.0, -0.707, -0.707, -3.14], + [0.0927, 0.704, 0.704, -2.96], + [0.186, 0.695, 0.695, -2.77], + [0.281, 0.679, 0.679, -2.59], + [0.378, 0.655, 0.655, -2.42], + [0.477, 0.622, 0.622, -2.25], + [0.577, 0.577, 0.577, -2.09], + [0.678, 0.52, 0.52, -1.95], + [0.775, 0.447, 0.447, -1.82], + [0.863, 0.357, 0.357, -1.72], + [0.935, 0.251, 0.251, -1.64], + [0.983, 0.129, 0.129, -1.59] +] + +environ["WEBOTS_ROBOT_NAME"] = "asterix" +robot = Supervisor() +vlx = robot.getDevice('vlx_0x30') +vlx.enable(1) +asterix = robot.getFromDef('ASTERIX') +translationtion_field = asterix.getField('translation') +rotation_field = asterix.getField('rotation') + +for i in range(len(full_turn)): + rotation_field.setSFRotation(full_turn[i]) + translationtion_field.setSFVec3f([x + i/len(full_turn), 0.17, y]) + robot.step(1) + time.sleep(0.1) + print(round(vlx.getValue(), 4)) From d619826308dc93dee8ef42a7003111f2cf9b64f9 Mon Sep 17 00:00:00 2001 From: PhileasL Date: Fri, 19 Feb 2021 23:27:37 +0100 Subject: [PATCH 45/67] Repositionning of vlx in webots + asterix supervisor: TRUE --- tools/localisation_machine_learning/data_obtention.py | 3 +-- tools/simulation/protos/Asterix.proto | 6 +++--- 2 files changed, 4 insertions(+), 5 deletions(-) diff --git a/tools/localisation_machine_learning/data_obtention.py b/tools/localisation_machine_learning/data_obtention.py index f0a978a0..9ddafbbd 100644 --- a/tools/localisation_machine_learning/data_obtention.py +++ b/tools/localisation_machine_learning/data_obtention.py @@ -1,6 +1,5 @@ """ -Do not forget to hit supervisor: TRUE in asterix description in webots -Need export PYTHONPATH=${WEBOTS_HOME}/lib/controller/python38 in order to work +Need export PYTHONPATH=${WEBOTS_HOME}/lib/controller/python38 """ from controller import Supervisor diff --git a/tools/simulation/protos/Asterix.proto b/tools/simulation/protos/Asterix.proto index 914c8332..9edf73b8 100644 --- a/tools/simulation/protos/Asterix.proto +++ b/tools/simulation/protos/Asterix.proto @@ -11,7 +11,7 @@ PROTO Asterix [ field SFString controller "" # Is `Robot.controller`. field MFString controllerArgs [] # Is `Robot.controllerArgs`. field SFString customData "" # Is `Robot.customData`. - field SFBool supervisor FALSE # Is `Robot.supervisor`. + field SFBool supervisor TRUE # Is `Robot.supervisor`. field SFBool synchronization FALSE # Is `Robot.synchronization`. field MFNode arucoTag [ Aruco { } ] # Is `Robot.arucoTag`. ] @@ -141,7 +141,7 @@ PROTO Asterix [ VL53L1X { name "vlx_0x30" translation 0.08 -0.13 -0.14 - rotation 0 0 1 1.5708 + rotation 0 0 1 -1.5708 } VL53L1X { name "vlx_0x31" @@ -156,7 +156,7 @@ PROTO Asterix [ VL53L1X { name "vlx_0x33" translation 0.08 0.13 -0.14 - rotation 0 0 1 -1.5708 + rotation 0 0 1 1.5708 } VL53L1X { name "vlx_0x34" From bcc1be7dbe40a3f04158f58acf0cf189648ff9af Mon Sep 17 00:00:00 2001 From: PhileasL Date: Fri, 19 Feb 2021 23:28:45 +0100 Subject: [PATCH 46/67] Gobelets removing --- .../data_obtention.py | 4 + tools/simulation/worlds/cdr2020.wbt | 100 +++++++++--------- 2 files changed, 54 insertions(+), 50 deletions(-) diff --git a/tools/localisation_machine_learning/data_obtention.py b/tools/localisation_machine_learning/data_obtention.py index 9ddafbbd..94edcf61 100644 --- a/tools/localisation_machine_learning/data_obtention.py +++ b/tools/localisation_machine_learning/data_obtention.py @@ -48,6 +48,10 @@ translationtion_field = asterix.getField('translation') rotation_field = asterix.getField('rotation') +for i in range(1,51): + gob = robot.getFromDef(f'GOB{i}') + gob.remove() + for i in range(len(full_turn)): rotation_field.setSFRotation(full_turn[i]) translationtion_field.setSFVec3f([x + i/len(full_turn), 0.17, y]) diff --git a/tools/simulation/worlds/cdr2020.wbt b/tools/simulation/worlds/cdr2020.wbt index 3121721c..26cc2531 100644 --- a/tools/simulation/worlds/cdr2020.wbt +++ b/tools/simulation/worlds/cdr2020.wbt @@ -48,223 +48,223 @@ DEF ASTERIX Asterix { DEF PHARAON Pharaon { translation 2.78 0.07 -0.11 } -RedSignal { +DEF GOB2 RedSignal { translation 0.3 0 0.4 name "GOB2" } -RedSignal { +DEF GOB3 RedSignal { translation 0.45 0 1.08 name "GOB3" } -RedSignal { +DEF GOB5 RedSignal { translation 0.67 0 0.1 name "GOB5" } -RedSignal { +DEF GOB7 RedSignal { translation 1.005 0 1.955 name "GOB7" } -RedSignal { +DEF GOB9 RedSignal { translation 1.1 0 0.8 name "GOB9" } -RedSignal { +DEF GOB11 RedSignal { translation 1.335 0 1.65 name "GOB11" } -RedSignal { +DEF GOB13 RedSignal { translation 1.605 0 1.955 name "GOB13" } -RedSignal { +DEF GOB15 RedSignal { translation 1.73 0 1.2 name "GOB15" } -RedSignal { +DEF GOB17 RedSignal { translation 1.935 0 1.65 name "GOB17" } -RedSignal { +DEF GOB19 RedSignal { translation 2.05 0 0.4 name "GOB19" } -RedSignal { +DEF GOB22 RedSignal { translation 2.55 0 0.51 name "GOB22" } -RedSignal { +DEF GOB23 RedSignal { translation 2.7 0 1.2 name "GOB23" } -RedSignal { +DEF GOB25 RedSignal { translation -0.067 0.132 1.45 rotation 1 0 0 3.1415 name "GOB25" } -RedSignal { +DEF GOB27 RedSignal { translation -0.067 0.132 1.6 rotation 1 0 0 3.1415 name "GOB27" } -RedSignal { +DEF GOB29 RedSignal { translation -0.067 0.132 1.75 rotation 1 0 0 3.1415 name "GOB29" } -RedSignal { +DEF GOB31 RedSignal { translation 3.067 0.132 1.525 rotation 1 0 0 3.1415 name "GOB31" } -RedSignal { +DEF GOB33 RedSignal { translation 3.067 0.132 1.675 rotation 1 0 0 3.1415 name "GOB33" } -RedSignal { +DEF GOB36 RedSignal { translation 0.775 0.132 -0.067 rotation 1 0 0 3.1415 name "GOB36" } -RedSignal { +DEF GOB39 RedSignal { translation 1 0.132 -0.067 rotation 1 0 0 3.1415 name "GOB39" } -RedSignal { +DEF GOB41 RedSignal { translation 2.075 0.132 -0.067 rotation 1 0 0 3.1415 name "GOB41" } -RedSignal { +DEF GOB42 RedSignal { translation 2.15 0.132 -0.067 rotation 1 0 0 3.1415 name "GOB42" } -RedSignal { +DEF GOB44 RedSignal { translation 2.3 0.132 -0.067 rotation 1 0 0 3.1415 name "GOB44" } -GreenSignal { +DEF GOB1 GreenSignal { translation 0.3 0 1.2 name "GOB1" } -GreenSignal { +DEF GOB4 GreenSignal { translation 0.45 0 0.51 name "GOB4" } -GreenSignal { +DEF GOB6 GreenSignal { translation 0.95 0 0.4 name "GOB6" } -GreenSignal { +DEF GOB8 GreenSignal { translation 1.065 0 1.65 name "GOB8" } -GreenSignal { +DEF GOB10 GreenSignal { translation 1.27 0 1.2 name "GOB10" } -GreenSignal { +DEF GOB12 GreenSignal { translation 1.395 0 1.955 name "GOB12" } -GreenSignal { +DEF GOB14 GreenSignal { translation 1.665 0 1.65 name "GOB14" } -GreenSignal { +DEF GOB16 GreenSignal { translation 1.9 0 0.8 name "GOB16" } -GreenSignal { +DEF GOB18 GreenSignal { translation 1.995 0 1.955 name "GOB18" } -GreenSignal { +DEF GOB20 GreenSignal { translation 2.33 0 0.1 name "GOB20" } -GreenSignal { +DEF GOB21 GreenSignal { translation 2.55 0 1.08 name "GOB21" } -GreenSignal { +DEF GOB24 GreenSignal { translation 2.7 0 0.4 name "GOB24" } -GreenSignal { +DEF GOB26 GreenSignal { translation -0.067 0.132 1.525 rotation 1 0 0 3.1415 name "GOB26" } -GreenSignal { +DEF GOB28 GreenSignal { translation -0.067 0.132 1.675 rotation 1 0 0 3.1415 name "GOB28" } -GreenSignal { +DEF GOB30 GreenSignal { translation 3.067 0.132 1.45 rotation 1 0 0 3.1415 name "GOB30" } -GreenSignal { +DEF GOB32 GreenSignal { translation 3.067 0.132 1.6 rotation 1 0 0 3.1415 name "GOB32" } -GreenSignal { +DEF GOB34 GreenSignal { translation 3.067 0.132 1.75 rotation 1 0 0 3.1415 name "GOB34" } -GreenSignal { +DEF GOB35 GreenSignal { translation 0.7 0.132 -0.067 rotation 1 0 0 3.1415 name "GOB35" } -GreenSignal { +DEF GOB37 GreenSignal { translation 0.85 0.132 -0.067 rotation 1 0 0 3.1415 name "GOB37" } -GreenSignal { +DEF GOB38 GreenSignal { translation 0.925 0.132 -0.067 rotation 1 0 0 3.1415 name "GOB38" } -GreenSignal { +DEF GOB40 GreenSignal { translation 2 0.132 -0.067 rotation 1 0 0 3.1415 name "GOB40" } -GreenSignal { +DEF GOB43 GreenSignal { translation 2.225 0.132 -0.067 rotation 1 0 0 3.1415 name "GOB43" } -GreenSignal { +DEF GOB45 GreenSignal { translation 1.73 0 0.35 name "GOB45" } -GreenSignal { +DEF GOB46 GreenSignal { translation 1.6 0 0.14 name "GOB46" } -GreenSignal { +DEF GOB47 GreenSignal { translation 1.22 0 0.33 name "GOB47" } -RedSignal { +DEF GOB48 RedSignal { translation 1.12 0 0.13 name "GOB48" } -RedSignal { +DEF GOB49 RedSignal { translation 1.45 0 0.4 name "GOB49" } -RedSignal { +DEF GOB50 RedSignal { translation 1.91 0 0.16 name "GOB50" } From 08552526a445b092db9c174a912c8e5b7d6d94b8 Mon Sep 17 00:00:00 2001 From: PhileasL Date: Fri, 19 Feb 2021 23:32:28 +0100 Subject: [PATCH 47/67] Min x and y from the walls for a full turn without collisions Maybe get the dimensions of the robot and compute them in the future ? --- tools/localisation_machine_learning/data_obtention.py | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/tools/localisation_machine_learning/data_obtention.py b/tools/localisation_machine_learning/data_obtention.py index 94edcf61..f53cc96a 100644 --- a/tools/localisation_machine_learning/data_obtention.py +++ b/tools/localisation_machine_learning/data_obtention.py @@ -10,8 +10,8 @@ import math import time -x = 0.2 -y = 2 - 1.5 +x = 0.171 +y = 0.171 full_turn = [ [1.0, 0.0, 0.0, -1.57], @@ -52,9 +52,11 @@ gob = robot.getFromDef(f'GOB{i}') gob.remove() +translationtion_field.setSFVec3f([x, 0.17, y]) + for i in range(len(full_turn)): rotation_field.setSFRotation(full_turn[i]) - translationtion_field.setSFVec3f([x + i/len(full_turn), 0.17, y]) + #translationtion_field.setSFVec3f([x + i/len(full_turn), 0.17, y]) robot.step(1) time.sleep(0.1) print(round(vlx.getValue(), 4)) From c984fed43dc15653391aa670a698aa230e76f5f7 Mon Sep 17 00:00:00 2001 From: PhileasL Date: Fri, 19 Feb 2021 23:35:08 +0100 Subject: [PATCH 48/67] Tweak of the laser response noise + sleep time between samples --- .../data_obtention.py | 24 +++++++++++++++++-- tools/simulation/protos/VL53L1X.proto | 6 ++--- 2 files changed, 25 insertions(+), 5 deletions(-) diff --git a/tools/localisation_machine_learning/data_obtention.py b/tools/localisation_machine_learning/data_obtention.py index f53cc96a..6318be75 100644 --- a/tools/localisation_machine_learning/data_obtention.py +++ b/tools/localisation_machine_learning/data_obtention.py @@ -54,9 +54,29 @@ translationtion_field.setSFVec3f([x, 0.17, y]) +test1 = [] +test2 = [] + for i in range(len(full_turn)): rotation_field.setSFRotation(full_turn[i]) #translationtion_field.setSFVec3f([x + i/len(full_turn), 0.17, y]) robot.step(1) - time.sleep(0.1) - print(round(vlx.getValue(), 4)) + time.sleep(0.0005) + vlx_value = round(vlx.getValue(), 1) + test1.append(vlx_value) + print(vlx_value) + +for i in range(len(full_turn)): + rotation_field.setSFRotation(full_turn[i]) + #translationtion_field.setSFVec3f([x + i/len(full_turn), 0.17, y]) + robot.step(1) + time.sleep(0.0005) + vlx_value = round(vlx.getValue(), 1) + test2.append(vlx_value) + print(vlx_value) + +avg_error = 0 +for i in range(len(test1)): + avg_error += abs(test1[i] - test2[i]) +avg_error = avg_error/len(test1) +print(avg_error) diff --git a/tools/simulation/protos/VL53L1X.proto b/tools/simulation/protos/VL53L1X.proto index 911d9002..86802d70 100644 --- a/tools/simulation/protos/VL53L1X.proto +++ b/tools/simulation/protos/VL53L1X.proto @@ -10,9 +10,9 @@ PROTO VL53L1X [ translation IS translation rotation IS rotation lookupTable [ 0 0 0 , - 0.02 0.01 0.005, - 3000 3000 0.01 , - 3500 0 0 ] + 0.02 20 0.0001, + 3.5 3500 0.0001, + 4.0 0 0 ] type "laser" numberOfRays 1 resolution -1 From 5d7a74fe4b94b6ab7623d5addf5b370657a92f50 Mon Sep 17 00:00:00 2001 From: PhileasL Date: Sat, 20 Feb 2021 23:41:44 +0100 Subject: [PATCH 49/67] vlx_array + function to get all distances --- .../data_obtention.py | 14 ++++++++++++-- 1 file changed, 12 insertions(+), 2 deletions(-) diff --git a/tools/localisation_machine_learning/data_obtention.py b/tools/localisation_machine_learning/data_obtention.py index 6318be75..6ac2dc66 100644 --- a/tools/localisation_machine_learning/data_obtention.py +++ b/tools/localisation_machine_learning/data_obtention.py @@ -42,12 +42,22 @@ environ["WEBOTS_ROBOT_NAME"] = "asterix" robot = Supervisor() -vlx = robot.getDevice('vlx_0x30') -vlx.enable(1) + +vlx_array = [] +for i in range(6): + vlx = robot.getDevice(f'vlx_0x3{i}') + vlx.enable(1) + vlx_array.append(vlx) + asterix = robot.getFromDef('ASTERIX') translationtion_field = asterix.getField('translation') rotation_field = asterix.getField('rotation') +def get_vlx_values(): + values = [] + for i in vlx_array: + values.append(round(i.getValue(), 1)) + for i in range(1,51): gob = robot.getFromDef(f'GOB{i}') gob.remove() From 59cd70ab7030f6903fed959b6d9fd0c0e5606b3f Mon Sep 17 00:00:00 2001 From: PhileasL Date: Sat, 20 Feb 2021 23:43:52 +0100 Subject: [PATCH 50/67] full path and distance getting for sector 1 --- .../data_obtention.py | 35 ++++++------------- 1 file changed, 10 insertions(+), 25 deletions(-) diff --git a/tools/localisation_machine_learning/data_obtention.py b/tools/localisation_machine_learning/data_obtention.py index 6ac2dc66..f9b7b9f1 100644 --- a/tools/localisation_machine_learning/data_obtention.py +++ b/tools/localisation_machine_learning/data_obtention.py @@ -64,29 +64,14 @@ def get_vlx_values(): translationtion_field.setSFVec3f([x, 0.17, y]) -test1 = [] -test2 = [] +for j in range(14): + for k in range(9): + for i in range(len(full_turn)): + rotation_field.setSFRotation(full_turn[i]) + translationtion_field.setSFVec3f([x + (j/10), 0.17, y + (k/10)]) + robot.step(1) + time.sleep(0.0005) + get_vlx_values() -for i in range(len(full_turn)): - rotation_field.setSFRotation(full_turn[i]) - #translationtion_field.setSFVec3f([x + i/len(full_turn), 0.17, y]) - robot.step(1) - time.sleep(0.0005) - vlx_value = round(vlx.getValue(), 1) - test1.append(vlx_value) - print(vlx_value) - -for i in range(len(full_turn)): - rotation_field.setSFRotation(full_turn[i]) - #translationtion_field.setSFVec3f([x + i/len(full_turn), 0.17, y]) - robot.step(1) - time.sleep(0.0005) - vlx_value = round(vlx.getValue(), 1) - test2.append(vlx_value) - print(vlx_value) - -avg_error = 0 -for i in range(len(test1)): - avg_error += abs(test1[i] - test2[i]) -avg_error = avg_error/len(test1) -print(avg_error) +position = asterix.getPosition() +orientation = asterix.getOrientation() From c2c2e665bf3c797b6802ae6079871ebd8aae29d2 Mon Sep 17 00:00:00 2001 From: PhileasL Date: Sun, 21 Feb 2021 23:46:47 +0100 Subject: [PATCH 51/67] csv ready --- .../data_obtention.py | 28 +++++++------------ 1 file changed, 10 insertions(+), 18 deletions(-) diff --git a/tools/localisation_machine_learning/data_obtention.py b/tools/localisation_machine_learning/data_obtention.py index f9b7b9f1..116dbf8d 100644 --- a/tools/localisation_machine_learning/data_obtention.py +++ b/tools/localisation_machine_learning/data_obtention.py @@ -9,6 +9,16 @@ import numpy as np import math import time +import os +import csv + +folder_for_CSV = "/data" + + +fullPath = os.getcwd() + folder_for_CSV + +if not os.path.isdir("." + folder_for_CSV): + os.mkdir(fullPath) x = 0.171 y = 0.171 @@ -57,21 +67,3 @@ def get_vlx_values(): values = [] for i in vlx_array: values.append(round(i.getValue(), 1)) - -for i in range(1,51): - gob = robot.getFromDef(f'GOB{i}') - gob.remove() - -translationtion_field.setSFVec3f([x, 0.17, y]) - -for j in range(14): - for k in range(9): - for i in range(len(full_turn)): - rotation_field.setSFRotation(full_turn[i]) - translationtion_field.setSFVec3f([x + (j/10), 0.17, y + (k/10)]) - robot.step(1) - time.sleep(0.0005) - get_vlx_values() - -position = asterix.getPosition() -orientation = asterix.getOrientation() From 55b91e1b6093854691dfe7fddfb13ba3abc50408 Mon Sep 17 00:00:00 2001 From: PhileasL Date: Sun, 21 Feb 2021 23:48:17 +0100 Subject: [PATCH 52/67] acquire_data function --- .../data_obtention.py | 39 +++++++++++++++++++ 1 file changed, 39 insertions(+) diff --git a/tools/localisation_machine_learning/data_obtention.py b/tools/localisation_machine_learning/data_obtention.py index 116dbf8d..9ba580a7 100644 --- a/tools/localisation_machine_learning/data_obtention.py +++ b/tools/localisation_machine_learning/data_obtention.py @@ -50,6 +50,10 @@ [0.983, 0.129, 0.129, -1.59] ] +angular_orientation = [] +for i in range(24): + angular_orientation.append(math.pi * i/12) + environ["WEBOTS_ROBOT_NAME"] = "asterix" robot = Supervisor() @@ -67,3 +71,38 @@ def get_vlx_values(): values = [] for i in vlx_array: values.append(round(i.getValue(), 1)) +def acquire_data(): + translationtion_field.setSFVec3f([x, 0.17, y]) + + for orien in range(0,4): + for sector in range(1,5): + with open(f'data/sector{sector}_orient{orien}.csv', 'w') as f: + writer = csv.writer(f, delimiter=',') + for j in range(13): + for k in range(8): + for i in range(int(len(full_turn)/4)): + if sector == 1: + tr_x = x + (j/10) + tr_y = y + (k/10) + if sector == 2: + tr_x = x + (j/10) + tr_y = 2.0 - y - (k/10) + if hitting_obstacle(tr_x, tr_y): + tr_x = x + tr_y = 2.0 - y + if sector == 3: + tr_x = 3.0 - x - (j/10) + tr_y = 2.0 - y - (k/10) + if hitting_obstacle(tr_x, tr_y): + tr_x = 3.0 - x + tr_y = 2.0 - y + if sector == 4: + tr_x = 3.0 - x - (j/10) + tr_y = y + (k/10) + rotation_field.setSFRotation(full_turn[orien*int(len(full_turn)/4) + i]) + translationtion_field.setSFVec3f([tr_x, 0.17, tr_y]) + robot.step(1) + time.sleep(0.0005) + values = get_vlx_values() + position = [asterix.getPosition()[0], 2 - asterix.getPosition()[2]] + writer.writerow(np.concatenate([position, [angular_orientation[orien*int(len(full_turn)/4) + i]], values])) From 0b725dedf4d3c678383dd92d915faba6f74ea050 Mon Sep 17 00:00:00 2001 From: PhileasL Date: Sun, 21 Feb 2021 23:48:56 +0100 Subject: [PATCH 53/67] obstacle avoidance --- .../localisation_machine_learning/data_obtention.py | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/tools/localisation_machine_learning/data_obtention.py b/tools/localisation_machine_learning/data_obtention.py index 9ba580a7..6edb7b18 100644 --- a/tools/localisation_machine_learning/data_obtention.py +++ b/tools/localisation_machine_learning/data_obtention.py @@ -15,6 +15,10 @@ folder_for_CSV = "/data" +obstacle_1 = [0.9, 1.85] +obstacle_2 = [1.5, 1.7] +obstacle_3 = [2.1, 1.85] + fullPath = os.getcwd() + folder_for_CSV if not os.path.isdir("." + folder_for_CSV): @@ -71,6 +75,14 @@ def get_vlx_values(): values = [] for i in vlx_array: values.append(round(i.getValue(), 1)) +def hitting_obstacle(t_x, t_y): + if t_x > (obstacle_1[0] - 0.2) and t_x < (obstacle_1[0] + 0.2) and t_y > obstacle_1[1] - 0.2: + return True + if t_x > (obstacle_2[0] - 0.2) and t_x < (obstacle_2[0] + 0.2) and t_y > obstacle_2[1] - 0.2: + return True + if t_x > (obstacle_3[0] - 0.2) and t_x < (obstacle_3[0] + 0.2) and t_y > obstacle_3[1] - 0.2: + return True + return False def acquire_data(): translationtion_field.setSFVec3f([x, 0.17, y]) From a06597f22aa9c4ec9d0b9bcf407b82448655327b Mon Sep 17 00:00:00 2001 From: PhileasL Date: Sun, 21 Feb 2021 23:49:39 +0100 Subject: [PATCH 54/67] vlx + remove_gobelets functions --- tools/localisation_machine_learning/data_obtention.py | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/tools/localisation_machine_learning/data_obtention.py b/tools/localisation_machine_learning/data_obtention.py index 6edb7b18..ef0d3b7f 100644 --- a/tools/localisation_machine_learning/data_obtention.py +++ b/tools/localisation_machine_learning/data_obtention.py @@ -75,6 +75,8 @@ def get_vlx_values(): values = [] for i in vlx_array: values.append(round(i.getValue(), 1)) + return values + def hitting_obstacle(t_x, t_y): if t_x > (obstacle_1[0] - 0.2) and t_x < (obstacle_1[0] + 0.2) and t_y > obstacle_1[1] - 0.2: return True @@ -83,6 +85,12 @@ def hitting_obstacle(t_x, t_y): if t_x > (obstacle_3[0] - 0.2) and t_x < (obstacle_3[0] + 0.2) and t_y > obstacle_3[1] - 0.2: return True return False + +def remove_gobelets(): + for i in range(1,51): + gob = robot.getFromDef(f'GOB{i}') + gob.remove() + def acquire_data(): translationtion_field.setSFVec3f([x, 0.17, y]) From 4019c1c70302e4fc80b63e597d425e7cb2669591 Mon Sep 17 00:00:00 2001 From: PhileasL Date: Sun, 21 Feb 2021 23:50:49 +0100 Subject: [PATCH 55/67] reading csv --- .../data_treatment.py | 18 ++++++++++++++++++ 1 file changed, 18 insertions(+) create mode 100644 tools/localisation_machine_learning/data_treatment.py diff --git a/tools/localisation_machine_learning/data_treatment.py b/tools/localisation_machine_learning/data_treatment.py new file mode 100644 index 00000000..62b06971 --- /dev/null +++ b/tools/localisation_machine_learning/data_treatment.py @@ -0,0 +1,18 @@ +import numpy as np +import math +import os +import time +import pandas as pd + +colnames = ["x", "y", "thetha", "vlx_0x30", "vlx_0x31", "vlx_0x32", "vlx_0x33", "vlx_0x34", "vlx_0x35"] + +data = pd.read_csv('data/sector1_orient0.csv', names=colnames) +x = data.x.tolist() +y = data.y.tolist() +theta = data.thetha.tolist() +vlx_0x30 = data.vlx_0x30.tolist() +vlx_0x31 = data.vlx_0x31.tolist() +vlx_0x32 = data.vlx_0x32.tolist() +vlx_0x33 = data.vlx_0x33.tolist() +vlx_0x34 = data.vlx_0x34.tolist() +vlx_0x35 = data.vlx_0x35.tolist() From 63cf1d2af3473801568eca818d98d2e6d2c34d2c Mon Sep 17 00:00:00 2001 From: PhileasL Date: Sun, 21 Feb 2021 23:53:04 +0100 Subject: [PATCH 56/67] regression test using NuSVR from sklearn --- .../localisation_machine_learning/data_treatment.py | 13 +++++++++++++ 1 file changed, 13 insertions(+) diff --git a/tools/localisation_machine_learning/data_treatment.py b/tools/localisation_machine_learning/data_treatment.py index 62b06971..7b12444a 100644 --- a/tools/localisation_machine_learning/data_treatment.py +++ b/tools/localisation_machine_learning/data_treatment.py @@ -3,6 +3,10 @@ import os import time import pandas as pd +from sklearn.svm import NuSVR +from sklearn.pipeline import make_pipeline +from sklearn.preprocessing import StandardScaler +import joblib colnames = ["x", "y", "thetha", "vlx_0x30", "vlx_0x31", "vlx_0x32", "vlx_0x33", "vlx_0x34", "vlx_0x35"] @@ -16,3 +20,12 @@ vlx_0x33 = data.vlx_0x33.tolist() vlx_0x34 = data.vlx_0x34.tolist() vlx_0x35 = data.vlx_0x35.tolist() +target = x +vlx_array = np.array([vlx_0x30, vlx_0x31, vlx_0x32, vlx_0x33, vlx_0x34, vlx_0x35]).T +clf = make_pipeline(StandardScaler(), NuSVR(C=200.0, nu=1.0)) + +clf.fit(vlx_array, target) + +joblib.dump(clf, 'test.sav') + +print(clf.score(vlx_array, target)) From bda036d13d89d23638e18f890142bbfdfdaea2cd Mon Sep 17 00:00:00 2001 From: PhileasL Date: Sun, 21 Feb 2021 23:54:25 +0100 Subject: [PATCH 57/67] testing model function --- .../data_obtention.py | 29 +++++++++++++++++++ 1 file changed, 29 insertions(+) diff --git a/tools/localisation_machine_learning/data_obtention.py b/tools/localisation_machine_learning/data_obtention.py index ef0d3b7f..59934997 100644 --- a/tools/localisation_machine_learning/data_obtention.py +++ b/tools/localisation_machine_learning/data_obtention.py @@ -11,6 +11,7 @@ import time import os import csv +import joblib folder_for_CSV = "/data" @@ -126,3 +127,31 @@ def acquire_data(): values = get_vlx_values() position = [asterix.getPosition()[0], 2 - asterix.getPosition()[2]] writer.writerow(np.concatenate([position, [angular_orientation[orien*int(len(full_turn)/4) + i]], values])) + +def test_regression(): + regr = joblib.load('first_test_6_sector1.sav') + difftot = 0 + nb = 0 + max = 0 + nbmax = -1 + + for j in range(13): + for k in range(8): + for i in range(int(len(full_turn)/4)): + tr_x = x + (j/10) + tr_y = y + (k/10) + rotation_field.setSFRotation(full_turn[i]) + translationtion_field.setSFVec3f([tr_x, 0.17, tr_y]) + robot.step(1) + time.sleep(0.0005) + values = get_vlx_values() + predicted_position = regr.predict([values]) + position = [asterix.getPosition()[0], 2 - asterix.getPosition()[2]] + difftot += abs(predicted_position-position[0]) + nb += 1 + if abs(predicted_position-position[0])>max: + nbmax += 1 + max = abs(predicted_position-position[0]) + print(difftot/nb) + print(max) + print(nbmax) From 063cee7756f8146585cb86be81f7257e05f0e76f Mon Sep 17 00:00:00 2001 From: PhileasL Date: Mon, 22 Feb 2021 22:57:09 +0100 Subject: [PATCH 58/67] Testing a new splitting strategy --- .../data_obtention.py | 70 ++++++++++++++++++- 1 file changed, 69 insertions(+), 1 deletion(-) diff --git a/tools/localisation_machine_learning/data_obtention.py b/tools/localisation_machine_learning/data_obtention.py index 59934997..55fa3567 100644 --- a/tools/localisation_machine_learning/data_obtention.py +++ b/tools/localisation_machine_learning/data_obtention.py @@ -28,6 +28,9 @@ x = 0.171 y = 0.171 +x_sample = 30 +y_sample = 20 + full_turn = [ [1.0, 0.0, 0.0, -1.57], [0.982902, -0.130198, -0.130198, -1.58804], @@ -128,8 +131,73 @@ def acquire_data(): position = [asterix.getPosition()[0], 2 - asterix.getPosition()[2]] writer.writerow(np.concatenate([position, [angular_orientation[orien*int(len(full_turn)/4) + i]], values])) +def right_first_diag(x,y): + if x > 1.5 * y: + return True + return False + +def right_second_diag(x,y): + if x > 1.5 * (2- y): + return True + return False + +def check_for_sample(sector, x, y): + if sector in [1,6]: + return right_first_diag(x,y) + if sector in [2,5]: + return not right_first_diag(x,y) + if sector in [3,8]: + return not right_second_diag(x,y) + if sector in [4,7]: + return right_second_diag(x,y) + + +def acquire_data_rework(): + translationtion_field.setSFVec3f([x, 0.17, y]) + + for sector in range(1,9): + with open(f'data/sector{sector}.csv', 'w') as f: + writer = csv.writer(f, delimiter=',') + for k in range(y_sample): + for j in range(x_sample): + hit = False + angle = False + if sector in [1,2]: + tr_x = x + j*((1.5-x)/x_sample) + tr_y = y + k*((1.0-y)/y_sample) + if tr_x < 0.3 and tr_y < 0.3: + angle = True + if sector in [3,4]: + tr_x = x + j*((1.5-x)/x_sample) + tr_y = 2.0 - y - k*((1.0-y)/y_sample) + if hitting_obstacle(tr_x, tr_y): + hit = True + if tr_x < 0.3 and tr_y > 1.7: + angle = True + if sector in [5,6]: + tr_x = 3.0 - x - j*((1.5-x)/x_sample) + tr_y = 2.0 - y - k*((1.0-y)/y_sample) + if hitting_obstacle(tr_x, tr_y): + hit = True + if tr_x > 1.7 and tr_y > 1.7: + angle = True + if sector in [7,8]: + tr_x = 3.0 - x - j*((1.5-x)/x_sample) + tr_y = y + k*((1.0-y)/y_sample) + if tr_x > 1.7 and tr_y < 0.3: + angle = True + if check_for_sample(sector, tr_x, tr_y) and not hit and not angle: + translationtion_field.setSFVec3f([tr_x, 0.17, tr_y]) + for i in range(len(full_turn)): + rotation_field.setSFRotation(full_turn[i]) + robot.step(1) + time.sleep(0.0005) + values = get_vlx_values() + position = [asterix.getPosition()[0], 2 - asterix.getPosition()[2]] + writer.writerow(np.concatenate([position, [angular_orientation[i]], values])) + def test_regression(): - regr = joblib.load('first_test_6_sector1.sav') + regr = joblib.load('test.sav') difftot = 0 nb = 0 max = 0 From 8a94cb9a9c8f4dc3a8c0a6c04a6633c0271951bb Mon Sep 17 00:00:00 2001 From: PhileasL Date: Mon, 22 Feb 2021 22:58:27 +0100 Subject: [PATCH 59/67] Testing the new strategy Still not good enough for me, thinking of just using vlx near walls considering the orientation given by the odometry to choose which vlx to use in order to extrapolate position --- .../data_obtention.py | 43 +++++++++++++++++++ 1 file changed, 43 insertions(+) diff --git a/tools/localisation_machine_learning/data_obtention.py b/tools/localisation_machine_learning/data_obtention.py index 55fa3567..a65cb6d2 100644 --- a/tools/localisation_machine_learning/data_obtention.py +++ b/tools/localisation_machine_learning/data_obtention.py @@ -220,6 +220,49 @@ def test_regression(): if abs(predicted_position-position[0])>max: nbmax += 1 max = abs(predicted_position-position[0]) + print(position) print(difftot/nb) print(max) print(nbmax) + +def test_regression_rework(): + regr = joblib.load('test.sav') + difftot = 0 + nb = 0 + max = 0 + nbmax = -1 + + for k in range(y_sample): + for j in range(x_sample): + for i in range(len(full_turn)): + angle = False + tr_x = x + j*((1.5-x)/x_sample) + tr_y = y + k*((1.0-y)/y_sample) + if tr_x < 0.3 and tr_y < 0.3: + angle = True + if check_for_sample(1, tr_x, tr_y) and not angle: + rotation_field.setSFRotation(full_turn[i]) + translationtion_field.setSFVec3f([tr_x, 0.17, tr_y]) + robot.step(1) + time.sleep(0.0005) + values = get_vlx_values() + predicted_position = regr.predict([values]) + position = [asterix.getPosition()[0], 2 - asterix.getPosition()[2]] + difftot += abs(predicted_position-position[0]) + nb += 1 + if abs(predicted_position-position[0])>max: + nbmax += 1 + max = abs(predicted_position-position[0]) + print(position) + print(difftot/nb) + print(max) + print(nbmax) + + +def print_actual_vlx_states(): + print([asterix.getPosition()[0], 2 - asterix.getPosition()[2]]) + print(math.acos(asterix.getOrientation()[0])) + robot.step(1) + print(get_vlx_values()) + +test_regression_rework() From 3bac8c8601f6a79ff790c29e54c7a927e0903359 Mon Sep 17 00:00:00 2001 From: PhileasL Date: Thu, 25 Feb 2021 09:30:18 +0100 Subject: [PATCH 60/67] Data from machine learning before deleting the unused method --- .../data/sector1.csv | 2496 +++++++++++++++++ .../data/sector2.csv | 2496 +++++++++++++++++ .../data/sector3.csv | 2496 +++++++++++++++++ .../data/sector4.csv | 2496 +++++++++++++++++ .../data/sectors.md | 29 + 5 files changed, 10013 insertions(+) create mode 100644 tools/localisation_machine_learning/data/sector1.csv create mode 100644 tools/localisation_machine_learning/data/sector2.csv create mode 100644 tools/localisation_machine_learning/data/sector3.csv create mode 100644 tools/localisation_machine_learning/data/sector4.csv create mode 100644 tools/localisation_machine_learning/data/sectors.md diff --git a/tools/localisation_machine_learning/data/sector1.csv b/tools/localisation_machine_learning/data/sector1.csv new file mode 100644 index 00000000..51f82f1e --- /dev/null +++ b/tools/localisation_machine_learning/data/sector1.csv @@ -0,0 +1,2496 @@ +0.17092194841810554,1.829207465725712,0.0,1720.8,2750.5,2751.0,40.9,71.0,71.0 +0.17096226623644847,1.828944035105113,0.1308996938995747,1808.8,1049.3,148.9,25.5,47.4,106.8 +0.17095143362032808,1.8290935759243316,0.2617993877991494,2055.7,430.7,51.2,21.3,33.9,161.4 +0.17101085015601797,1.8289812912716459,0.39269908169872414,2572.4,251.1,31.8,32.0,31.9,252.5 +0.17099868966830156,1.8289990419772488,0.5235987755982988,3120.1,161.2,33.5,72.2,50.8,711.8 +0.17084437272556974,1.829115506103378,0.6544984694978736,2800.3,106.5,47.5,68.5,149.6,969.0 +0.1710385852631262,1.8290178054394233,0.7853981633974483,2721.6,70.9,70.4,40.9,1751.8,1751.2 +0.17074105016221489,1.8291807519809502,0.916297857297023,232.0,47.5,106.3,25.4,1786.5,1845.7 +0.17101689265651487,1.8291223577750664,1.0471975511965976,73.2,34.0,51.5,21.4,1974.8,2102.1 +0.17099355760776588,1.8290320788711976,1.1780972450961724,31.8,31.6,31.3,31.1,2403.1,2622.0 +0.17067222541365637,1.828965386969519,1.3089969389957472,21.2,51.1,33.4,72.2,3258.5,3132.3 +0.17090033775471775,1.8291231991687675,1.4398966328953218,25.7,106.5,48.0,697.2,2878.3,2820.4 +0.17100750483107735,1.829008742533505,1.5707963267948966,40.9,71.0,70.7,1720.6,2751.2,2750.8 +0.17098345637569926,1.8289999473008447,1.7016960206944713,68.2,47.4,105.8,1764.1,980.7,152.2 +0.1708952404794647,1.8289803300067213,1.832595714594046,73.6,34.3,162.0,1963.7,430.2,51.0 +0.17104254152315035,1.8290026590520727,1.9634954084936205,32.2,32.4,253.3,2413.1,250.7,31.6 +0.17110862087463477,1.8290650605586949,2.0943951023931953,21.2,51.2,710.9,3210.0,161.2,34.0 +0.171009929363068,1.8290361319052317,2.2252947962927703,25.8,151.4,974.5,2842.1,106.3,47.5 +0.17103547426331028,1.829027115045187,2.356194490192345,41.6,1751.1,1751.6,2720.2,70.4,70.9 +0.17128977565664666,1.8291925114005771,2.4870941840919194,68.6,1786.9,1845.7,828.6,47.5,106.5 +0.17092827544161085,1.8290394691854306,2.6179938779914944,114.3,1976.9,2104.6,347.9,33.5,51.5 +0.17111613270017226,1.8291252543682692,2.748893571891069,191.7,2407.8,2627.1,192.2,32.2,31.7 +0.17089797234302156,1.8288907850802376,2.8797932657906435,349.1,3258.4,3130.9,114.3,51.8,33.8 +0.171000026419977,1.8290042372255524,3.010692959690218,916.0,2880.4,2821.9,68.7,106.4,47.6 +0.1709693381657898,1.728777201501448,0.0,1621.2,2751.2,2750.9,140.8,71.0,71.0 +0.17099888754949527,1.7292689278218094,0.1308996938995747,1705.3,1433.3,532.8,129.1,47.4,106.8 +0.1710593145903002,1.728885586493453,0.2617993877991494,1939.8,630.3,250.6,136.9,33.9,161.4 +0.1709885717143409,1.7290194234427751,0.39269908169872414,2430.5,392.2,173.0,173.6,31.9,252.6 +0.17100114876952657,1.7290018386142028,0.5235987755982988,3253.8,276.8,149.1,113.9,50.7,596.2 +0.1708494214949743,1.7291145649180737,0.6544984694978736,2801.0,210.1,151.0,68.5,632.5,968.8 +0.1710421220977605,1.729017016483805,0.7853981633974483,2721.1,170.9,170.4,40.9,1651.6,1651.1 +0.17074633822355512,1.7291814496691673,0.916297857297023,618.8,151.0,149.6,25.4,1683.4,1742.2 +0.1710204040634571,1.7291230613199402,1.0471975511965976,272.9,149.5,51.5,21.4,1859.3,1986.6 +0.17099408137467847,1.7290319072022104,1.1780972450961724,173.5,172.7,31.3,31.1,2261.5,2481.4 +0.17065554164532645,1.72894080967735,1.3089969389957472,136.8,160.9,33.4,72.2,3201.5,3132.3 +0.17088423410172762,1.7291081327477675,1.4398966328953218,129.2,106.5,48.0,571.0,2878.1,2820.3 +0.17100255586749505,1.729010122090229,1.5707963267948966,140.9,71.0,70.7,1621.0,2750.9,2751.3 +0.17098146587049415,1.729000301998672,1.7016960206944713,171.7,47.4,105.8,1660.5,1370.4,542.0 +0.1708900167399209,1.728979266208476,1.832595714594046,73.6,34.3,161.9,1848.3,629.3,250.2 +0.1711891275345699,1.7288644368175115,1.9634954084936205,32.2,32.4,253.1,2269.9,392.2,172.8 +0.17101965027541308,1.729075586297348,2.0943951023931953,21.2,51.2,595.4,3184.3,276.8,149.5 +0.17100195977079,1.7290225447332614,2.2252947962927703,25.8,632.2,974.6,2842.2,209.8,151.0 +0.17115748901708158,1.7289849489953233,2.356194490192345,41.6,1651.1,1651.4,2721.0,170.4,170.9 +0.17125352594321863,1.7290261632332844,2.4870941840919194,68.6,1683.3,1742.3,1213.2,151.1,150.0 +0.1709525173806403,1.72897962875142,2.6179938779914944,114.4,1861.0,1988.8,547.0,149.1,51.5 +0.17112735569093285,1.7290956691832515,2.748893571891069,191.7,2265.7,2485.7,333.7,173.7,31.7 +0.17087308522107897,1.7288473127443813,2.8797932657906435,608.0,3203.0,3130.8,229.9,161.2,33.8 +0.17099322890799384,1.7289913940232329,3.010692959690218,831.0,2880.4,2822.2,172.2,106.4,47.6 +0.1709650524321688,1.6287718004684846,0.0,1521.5,2751.0,2751.1,240.8,71.0,71.0 +0.17099647356560058,1.6292669158201158,0.1308996938995747,1601.8,1732.5,916.8,232.6,47.5,106.8 +0.17105795725758718,1.628885475018302,0.2617993877991494,1824.8,829.8,450.1,252.4,33.9,161.4 +0.17098644823784617,1.6290222620126693,0.39269908169872414,2289.2,533.5,314.2,191.2,31.9,252.6 +0.17100147753197023,1.629001699591175,0.5235987755982988,3119.7,392.3,264.7,113.9,50.8,473.6 +0.17085318353711848,1.629112331547199,0.6544984694978736,2801.0,313.6,254.5,68.5,529.1,1360.2 +0.17104528535824895,1.6290156893089864,0.7853981633974483,2721.4,270.9,270.3,40.9,1551.3,1550.8 +0.17075134296823472,1.629181672616631,0.916297857297023,1090.7,254.5,149.6,25.4,1579.7,1638.6 +0.1710237260380022,1.6291235549182401,1.0471975511965976,472.5,265.0,51.5,21.4,1744.0,1870.9 +0.17099400897825562,1.6290313608949145,1.1780972450961724,315.2,252.2,31.3,31.1,2121.0,2340.1 +0.17067365515814675,1.6289723014633521,1.3089969389957472,252.4,160.9,33.4,72.2,3002.9,3131.8 +0.1709035585286119,1.629130581793253,1.4398966328953218,232.6,106.4,48.0,490.3,2878.6,2820.3 +0.17101550212464775,1.6288577506521782,1.5707963267948966,240.9,71.0,70.6,1521.1,2751.5,2751.6 +0.17099317905591904,1.6290435018288614,1.7016960206944713,233.8,47.4,105.8,1557.0,1760.0,931.6 +0.17090267246094487,1.628983543126705,1.832595714594046,73.6,34.3,161.9,1732.2,828.6,449.5 +0.17120116312306505,1.6288677680824806,1.9634954084936205,32.2,32.4,253.1,2128.5,533.4,314.0 +0.17101960634525737,1.6290819704121668,2.0943951023931953,21.2,51.2,431.4,3028.5,392.3,265.0 +0.1708995524618737,1.6290973845633885,2.2252947962927703,25.8,528.9,1359.6,2841.9,313.3,254.4 +0.17117831828466576,1.6289998170853282,2.356194490192345,41.6,1551.1,1552.0,2720.3,270.3,270.9 +0.1712494707837472,1.628984600205581,2.4870941840919194,68.6,1580.0,1639.0,1598.5,254.6,150.0 +0.17099713666591002,1.6289963447528253,2.6179938779914944,114.4,1745.6,1873.0,746.3,264.7,51.5 +0.1711355299675771,1.6290967908312912,2.748893571891069,191.7,2124.5,2343.9,475.1,251.7,31.7 +0.1709042230401793,1.6288741490107321,2.8797932657906435,393.0,3004.1,3130.9,345.4,161.2,33.8 +0.1708832411043868,1.6288045742448751,3.010692959690218,830.8,2880.5,2822.0,275.8,106.4,47.5 +0.17103095556378153,1.528839175782786,0.0,1421.0,2750.8,2751.5,340.9,71.0,71.0 +0.17101801567547892,1.5291376862807957,0.1308996938995747,1498.0,2116.9,1300.9,336.3,47.5,106.8 +0.1710611349663433,1.5288555078061243,0.2617993877991494,1708.9,1029.2,649.5,349.1,33.9,161.4 +0.17091959318208702,1.5291291187132425,0.39269908169872414,2147.1,674.6,455.3,191.2,31.8,456.6 +0.17111571202689288,1.528902296182917,0.5235987755982988,3098.7,508.0,380.4,113.9,50.8,429.9 +0.17087503136133497,1.529085475310672,0.6544984694978736,2800.7,417.1,358.1,68.5,425.5,1256.4 +0.17115384352466398,1.5289814918160385,0.7853981633974483,2720.8,370.9,370.4,40.9,1451.5,1451.1 +0.1707698193777327,1.5291594540165687,0.916297857297023,1477.3,358.0,149.6,25.4,1476.4,1535.0 +0.17102426371801308,1.529113227396771,1.0471975511965976,672.4,380.6,51.5,21.4,1628.1,1755.9 +0.17090530704201956,1.528988174433866,1.1780972450961724,456.9,252.3,31.3,31.1,1978.9,2198.0 +0.17096639830337948,1.5290602221549667,1.3089969389957472,368.0,161.0,33.4,72.1,2801.5,3132.9 +0.17069199010188096,1.528918833895617,1.4398966328953218,336.1,106.4,48.1,236.8,2878.8,2819.9 +0.17093446740300658,1.529097704406047,1.5707963267948966,340.8,71.0,70.7,1420.9,2751.5,2751.1 +0.17094852532957813,1.5289126679031524,1.7016960206944713,233.8,47.4,105.8,1453.5,2149.9,1407.0 +0.17089513604143863,1.529149772088103,1.832595714594046,73.6,34.3,161.9,1617.0,1071.6,648.6 +0.17123119896890784,1.5288821218431154,1.9634954084936205,32.2,32.4,457.2,1987.3,674.4,455.1 +0.17102998085998697,1.5290882584854768,2.0943951023931953,21.2,51.2,431.4,2828.3,507.8,380.6 +0.1709056961712029,1.5291000997630086,2.2252947962927703,25.8,425.4,1256.5,2842.5,416.9,358.0 +0.1711799656045049,1.5290014972867332,2.356194490192345,41.6,1451.1,1451.8,2720.4,370.4,370.9 +0.17124568941681023,1.5290383191140742,2.4870941840919194,68.6,1476.3,1535.2,1984.1,358.2,150.0 +0.17084332495900065,1.5289535163598926,2.6179938779914944,114.3,1629.3,1757.7,945.4,380.4,51.5 +0.1711049589611337,1.5290992065989033,2.748893571891069,191.7,1982.7,2202.9,616.4,251.6,31.7 +0.17090287355209652,1.5288880183807645,2.8797932657906435,349.1,2804.2,3131.1,461.0,161.2,33.8 +0.1708814063666045,1.5288126754939806,3.010692959690218,1233.7,2880.5,2821.8,379.3,106.4,47.5 +0.17087266045300065,1.428567351688384,0.0,1321.3,2751.3,2751.0,440.8,71.0,71.0 +0.17095376941209128,1.4293031844398025,0.1308996938995747,1394.4,2499.2,1683.9,439.7,47.4,106.7 +0.17103585462376497,1.4289087187549263,0.2617993877991494,1593.3,1228.5,848.9,349.1,33.9,161.4 +0.17092586205373111,1.4291209974323653,0.39269908169872414,2005.5,816.0,596.6,191.1,31.8,252.6 +0.17111983616471668,1.428897343501793,0.5235987755982988,2899.7,623.6,495.9,113.9,50.8,473.8 +0.17087414302119727,1.4290848635088627,0.6544984694978736,2800.4,520.7,461.7,68.5,319.3,1130.1 +0.17115304725141955,1.4289812991370927,0.7853981633974483,2721.6,470.9,470.3,40.9,1351.6,1351.0 +0.17070262310723455,1.4290910785577942,0.916297857297023,1780.2,461.5,149.7,25.4,1372.8,1431.6 +0.17103326805318514,1.4290925417523337,1.0471975511965976,871.9,431.6,51.5,21.4,1512.5,1640.0 +0.17104995140501206,1.4290643311524045,1.1780972450961724,598.6,252.3,31.3,31.1,1838.7,2057.4 +0.17083106223339947,1.4289048019810053,1.3089969389957472,483.6,161.0,33.4,354.6,2601.9,2981.7 +0.17095124415290866,1.429074252780305,1.4398966328953218,439.6,106.5,48.0,236.3,2878.8,2820.2 +0.1711702498534188,1.429025639853649,1.5707963267948966,440.9,70.9,70.6,1321.1,2751.7,2750.8 +0.17105493706316233,1.4289702385539906,1.7016960206944713,233.8,47.4,105.8,1350.0,2540.2,1710.8 +0.17084340313876237,1.4291327077477078,1.832595714594046,73.8,34.4,161.9,1500.7,1228.4,848.6 +0.1710886167539638,1.428843473448831,1.9634954084936205,32.2,32.4,253.2,1845.6,815.5,596.2 +0.17102502340367887,1.4290671736004439,2.0943951023931953,21.2,51.2,431.4,2629.1,623.4,496.1 +0.17089960189781306,1.4290914305542137,2.2252947962927703,25.8,321.6,1129.9,2842.5,520.2,461.5 +0.17117838987866668,1.4289969904164297,2.356194490192345,41.6,1351.0,1351.8,2720.2,470.3,470.9 +0.171241166063334,1.4290353652310328,2.4870941840919194,68.6,1372.9,1432.2,2370.0,461.6,149.9 +0.1708425319822258,1.4289524697267002,2.6179938779914944,114.3,1514.2,1641.8,1144.6,430.5,51.5 +0.17110532791931635,1.4290991120356382,2.748893571891069,191.7,1841.5,2061.9,757.9,251.7,31.7 +0.17090305923101198,1.428887981965163,2.8797932657906435,349.1,2604.0,2983.6,576.6,161.2,33.8 +0.17088331210244273,1.428815673275263,3.010692959690218,1130.1,2880.4,2821.3,482.8,106.4,47.5 +0.17087399525927194,1.3285694986933607,0.0,1221.3,2751.0,2751.2,540.9,71.0,71.0 +0.1709544644427907,1.32930318945927,0.1308996938995747,1290.9,2823.1,2067.9,543.3,47.4,106.8 +0.17103622584115266,1.3289085667260032,0.2617993877991494,1477.8,1428.2,1048.3,349.1,33.9,161.4 +0.17092599140921694,1.3291210146190853,0.39269908169872414,1864.1,957.0,737.9,191.2,31.8,252.6 +0.17111986164134116,1.3288973895574459,0.5235987755982988,2700.4,739.3,611.6,113.9,286.8,429.9 +0.17087415697398675,1.32908488400943,0.6544984694978736,2800.5,624.1,565.2,68.5,149.6,1138.6 +0.17115304953621785,1.328981309264413,0.7853981633974483,2721.2,570.9,570.4,40.9,1251.9,1250.8 +0.17076972858454,1.3291594360002208,0.916297857297023,2165.3,565.1,149.5,25.4,1269.3,1328.3 +0.1710298309149586,1.329114597795626,1.0471975511965976,1071.5,431.6,51.5,21.4,1397.4,1524.7 +0.1710511448232365,1.3290789745454274,1.1780972450961724,740.3,252.2,31.3,31.1,1697.4,1916.7 +0.1708284206778974,1.3289102615432626,1.3089969389957472,599.1,161.0,33.4,239.1,2402.9,2782.0 +0.17095082294002864,1.3290772367015702,1.4398966328953218,543.1,106.5,48.0,236.3,2878.6,2820.3 +0.17117068915344621,1.3290284253271816,1.5707963267948966,540.9,70.9,70.6,1221.2,2751.3,2751.2 +0.171055245168651,1.328969500886958,1.7016960206944713,233.9,47.4,105.8,1246.7,2820.5,2100.7 +0.17085927843402288,1.3289081624774972,1.832595714594046,73.8,34.4,187.5,1385.8,1426.5,1091.3 +0.17095573699843553,1.3290030671382165,1.9634954084936205,32.2,32.4,253.3,1704.3,956.3,737.4 +0.171222237364476,1.3289663876439626,2.0943951023931953,21.2,286.0,430.9,2427.9,739.2,611.8 +0.17086678988996162,1.3291234642449172,2.2252947962927703,25.8,151.2,974.2,2842.1,623.8,565.0 +0.17115813113673306,1.329013429399277,2.356194490192345,41.6,1251.2,1251.7,2720.9,570.3,570.9 +0.1713358170534425,1.3292221936963027,2.4870941840919194,68.6,1269.2,1328.2,2800.7,565.2,150.4 +0.17080094764556006,1.3290242049672103,2.6179938779914944,280.8,1398.7,1526.3,1344.2,430.7,51.5 +0.1710804515807799,1.3291307848523375,2.748893571891069,191.7,1700.3,1920.5,899.3,251.6,31.7 +0.17089261460697616,1.328904605866622,2.8797932657906435,392.9,2404.3,2784.2,692.0,161.2,33.8 +0.17087671022278686,1.3288274316266102,3.010692959690218,1004.0,2880.3,2821.6,586.4,106.4,47.5 +0.17086804320669646,1.2285798052566204,0.0,1121.2,2750.6,2750.6,640.9,71.0,71.0 +0.1709518322094097,1.22930406433152,0.1308996938995747,1187.5,2822.9,2451.4,646.9,47.4,106.8 +0.17103521621145945,1.228907955424528,0.2617993877991494,1362.2,1627.3,1291.8,349.1,33.9,161.4 +0.17092551851252288,1.2291207017041414,0.39269908169872414,1722.2,1098.3,878.9,191.1,231.3,252.6 +0.17111962256925659,1.228897252367299,0.5235987755982988,2501.0,854.8,727.3,113.9,94.6,429.9 +0.1708740779168281,1.2290847950755088,0.6544984694978736,2800.7,727.8,668.7,68.5,149.6,969.0 +0.1711530289606126,1.2289812610907607,0.7853981633974483,2721.6,670.9,670.5,40.9,1151.7,1151.2 +0.17076973721150868,1.2291594030902173,0.916297857297023,2551.8,668.6,149.5,25.4,1165.8,1224.6 +0.1710326433025023,1.2291152741400455,1.0471975511965976,1271.1,431.8,51.5,21.4,1281.8,1408.8 +0.17105376914455897,1.229079936953899,1.1780972450961724,882.0,252.2,31.3,204.3,1555.9,1775.3 +0.1708289418946401,1.2289099660663707,1.3089969389957472,714.8,161.0,33.4,72.1,2203.4,2582.5 +0.17101033010830183,1.2291817353096621,1.4398966328953218,646.4,106.4,48.1,322.1,2878.4,2820.2 +0.1710627279202285,1.2287708342236399,1.5707963267948966,640.9,71.0,70.6,1121.2,2751.3,2750.8 +0.17102207843807207,1.2291632806579549,1.7016960206944713,234.0,47.4,105.8,1143.0,2820.6,2491.2 +0.17093936228482648,1.2287575206447454,1.832595714594046,73.6,34.3,162.1,1270.1,1624.4,1245.7 +0.17095221255390405,1.2290429265876501,1.9634954084936205,32.2,231.3,284.5,1562.7,1097.4,878.3 +0.17124078429972212,1.2289821940824788,2.0943951023931953,21.2,95.0,431.0,2227.8,854.9,727.4 +0.17087244791962028,1.229133236059123,2.2252947962927703,25.8,151.2,974.0,2842.7,727.5,668.6 +0.17116005402690088,1.2290183477991121,2.356194490192345,41.6,1151.2,1151.6,2720.1,670.4,671.0 +0.171225322453083,1.2290477253989502,2.4870941840919194,68.6,1165.7,1225.0,2801.1,668.7,149.9 +0.17084087982586846,1.2289596761694428,2.6179938779914944,114.3,1282.9,1410.9,1543.2,430.5,51.5 +0.17110541792058132,1.2291030630567192,2.748893571891069,191.7,1558.7,1778.8,1040.9,251.7,31.7 +0.17090239677964364,1.228889206729106,2.8797932657906435,349.1,2205.3,2585.6,807.6,161.2,33.8 +0.17088651042480074,1.228822627070987,3.010692959690218,915.9,2880.6,2821.4,689.8,106.4,47.5 +0.17087612570810592,1.128574642454336,0.0,1021.2,2750.8,2750.5,740.8,71.0,71.0 +0.17095560753953046,1.1293032670867929,0.1308996938995747,1083.7,2823.2,2882.3,750.4,47.4,106.8 +0.1710368712896355,1.1289082154636259,0.2617993877991494,1246.6,1826.7,1447.3,349.1,33.9,161.4 +0.17092620454042506,1.129121021331882,0.39269908169872414,1580.7,1239.4,1020.0,191.2,31.8,252.5 +0.17111989091144172,1.1288974704155312,0.5235987755982988,2301.8,970.6,842.8,113.9,50.8,429.9 +0.17087417852958992,1.129084915138964,0.6544984694978736,2800.3,831.3,772.2,68.5,234.5,969.0 +0.17115305107256037,1.1289813265751134,0.7853981633974483,2721.0,770.9,770.4,40.9,1051.7,1051.1 +0.17076973844246826,1.1291594497505688,0.916297857297023,2842.8,772.0,149.6,25.4,1062.3,1121.3 +0.1710353184057938,1.129115948949896,1.0471975511965976,1470.9,431.7,51.5,21.4,1166.1,1293.4 +0.1710562712983801,1.1290808743387093,1.1780972450961724,1023.8,252.3,31.3,31.1,1415.0,1634.0 +0.1708294353675978,1.1289096921612056,1.3089969389957472,830.4,161.0,33.4,72.0,2004.0,2384.0 +0.17101041900085598,1.129181357577397,1.4398966328953218,749.9,106.4,48.1,236.4,2878.5,2819.9 +0.1710628982355852,1.1287706714733692,1.5707963267948966,740.9,71.0,70.7,1021.1,2751.5,2751.4 +0.17102215948927518,1.1291633071632048,1.7016960206944713,233.9,47.4,105.8,1039.5,2820.8,2879.4 +0.17093942104593796,1.1287575715607452,1.832595714594046,73.6,34.3,187.6,1154.7,1823.4,1444.9 +0.17095208867834805,1.1290460381675733,1.9634954084936205,32.2,32.4,253.4,1421.0,1238.5,1019.4 +0.17124050118235457,1.1289862996907951,2.0943951023931953,21.2,51.1,430.9,2028.4,970.2,842.9 +0.170872529362083,1.1291350824203938,2.2252947962927703,25.8,236.4,974.0,2843.0,830.8,772.1 +0.17116059143991658,1.1290190837009795,2.356194490192345,41.6,1051.0,1051.6,2720.2,770.3,770.9 +0.17122160689323002,1.1290482368287151,2.4870941840919194,68.6,1062.4,1121.5,2800.4,772.4,149.9 +0.17083992713412396,1.12896009932856,2.6179938779914944,114.3,1167.4,1295.1,1742.3,430.5,51.5 +0.17110550392425236,1.1291035625209727,2.748893571891069,191.7,1417.1,1637.4,1182.2,251.6,31.7 +0.1709023939391514,1.1288894031595984,2.8797932657906435,349.1,2006.0,2385.9,923.1,161.2,33.8 +0.17088824669554495,1.1288257313068115,3.010692959690218,830.7,2881.3,2822.2,793.3,106.4,47.5 +0.2709389649875579,1.829194537367861,0.0,1720.7,2651.2,2650.9,41.0,171.0,171.0 +0.27096927161083223,1.8289115357711418,0.1308996938995747,1808.6,964.8,148.9,25.6,151.0,210.3 +0.27112650773081653,1.8289613400156406,0.2617993877991494,2056.0,431.0,51.3,21.3,149.4,276.9 +0.2710323992075201,1.829030838669132,0.39269908169872414,2572.2,251.1,31.8,32.0,173.5,394.2 +0.2710190348287386,1.8290177810255612,0.5235987755982988,3004.4,161.2,33.5,72.1,250.0,737.3 +0.2708518619624328,1.8291284177474938,0.6544984694978736,2697.0,106.6,47.5,172.1,736.2,1567.1 +0.27117009251775537,1.8289939629088392,0.7853981633974483,2621.5,70.9,70.4,140.9,1751.8,1751.1 +0.2707773333005617,1.8291639654297887,0.916297857297023,232.0,47.5,106.3,128.9,1787.1,1845.8 +0.27103618643934035,1.8291171182560635,1.0471975511965976,73.2,33.9,161.2,136.9,1974.6,2101.9 +0.2710572616314036,1.8290818353285845,1.1780972450961724,31.7,31.5,173.0,172.3,2403.3,2622.6 +0.2708294170652326,1.828909722437329,1.3089969389957472,21.2,51.0,149.0,271.4,3144.5,3016.4 +0.2710103445943455,1.8291812511191567,1.4398966328953218,25.7,152.1,151.5,626.0,2775.2,2717.0 +0.27106289642123343,1.8287706562137906,1.5707963267948966,40.9,171.0,170.7,1721.2,2651.7,2651.0 +0.27102215549857955,1.82916331974553,1.7016960206944713,68.2,150.9,209.2,1763.8,1067.0,152.2 +0.2709394184015474,1.8287575809590204,1.832595714594046,114.1,150.0,277.7,1964.2,429.7,50.9 +0.2710968309349378,1.828997182850595,1.9634954084936205,173.3,174.2,395.1,2412.9,250.6,31.6 +0.2712284583998348,1.8291423148678976,2.0943951023931953,136.7,250.8,631.0,3184.0,161.3,34.0 +0.27108047294564447,1.8290919569861646,2.2252947962927703,129.3,735.9,1566.6,2738.5,106.3,47.4 +0.2710733903177761,1.8290612527966408,2.356194490192345,141.6,1751.5,1751.7,2620.1,70.3,70.9 +0.271206066785063,1.8290674452545506,2.4870941840919194,172.2,1787.1,1845.7,826.9,47.5,106.6 +0.27084180430506966,1.8289715515395175,2.6179938779914944,230.0,1976.8,2104.5,347.9,33.5,161.2 +0.2711056063073363,1.8291086391696956,2.748893571891069,333.2,2407.4,2627.2,192.2,32.2,173.1 +0.27090123020810075,1.828890684693416,2.8797932657906435,723.6,3143.3,3015.2,114.3,51.8,149.4 +0.2709484688492395,1.828834564697893,3.010692959690218,1521.9,2777.0,2717.8,68.8,151.7,151.0 +0.2709091914476188,1.7286036705756835,0.0,1621.1,2651.0,2651.2,140.8,171.0,171.0 +0.2709754808272247,1.72929618092982,0.1308996938995747,1704.7,1348.4,532.7,129.1,151.0,210.3 +0.2710461897851685,1.7289051191517888,0.2617993877991494,1940.2,630.3,250.6,136.9,149.5,277.0 +0.2710519159037479,1.7289089232999866,0.39269908169872414,2430.7,392.3,173.0,173.7,173.6,394.2 +0.2708586935324108,1.7291269356756722,0.5235987755982988,3004.8,276.7,149.1,229.5,250.0,629.1 +0.2708226874495069,1.7291449130956367,0.6544984694978736,2697.1,210.1,151.0,172.0,620.1,1463.5 +0.2711437925789047,1.7289577100082907,0.7853981633974483,2620.3,170.9,170.4,140.9,1651.5,1651.0 +0.27077022270912643,1.729122284684844,0.916297857297023,618.7,151.0,209.8,128.9,1683.5,1742.3 +0.27115951534258986,1.7291443836432423,1.0471975511965976,272.8,149.5,251.1,136.9,1859.5,1986.9 +0.2708735992392601,1.7289490984722913,1.1780972450961724,173.5,172.7,173.0,172.2,2261.8,2480.9 +0.2707049065616731,1.7291044810992726,1.3089969389957472,136.8,250.3,149.1,271.4,3144.8,3017.3 +0.27087290256563773,1.7291366233521066,1.4398966328953218,129.2,209.9,151.5,625.9,2775.4,2716.4 +0.2710866057500448,1.729088827235892,1.5707963267948966,140.9,170.9,170.6,1620.9,2651.1,2651.3 +0.2710200593381259,1.7289642542734456,1.7016960206944713,171.7,150.8,209.3,1660.2,1370.8,542.0 +0.2708256538853389,1.7289032812780625,1.832595714594046,229.6,150.0,277.7,1848.1,629.3,250.2 +0.27093734469347724,1.728992806574243,1.9634954084936205,173.3,174.1,395.0,2271.5,391.8,172.7 +0.2710765514287949,1.7291455219333018,2.0943951023931953,136.7,250.7,630.9,3095.1,276.8,149.6 +0.27104580284925694,1.7290302152969508,2.2252947962927703,129.3,623.8,1447.0,2738.5,209.7,151.0 +0.2710451587436101,1.7290275082094289,2.356194490192345,141.6,1651.0,1651.7,2620.4,170.4,170.9 +0.271201505704856,1.7290473933481487,2.4870941840919194,172.1,1683.3,1742.6,1297.6,151.1,210.1 +0.2708440257617808,1.7289631739130946,2.6179938779914944,229.9,1861.0,1988.6,547.0,149.1,250.6 +0.27110743033642637,1.7291050391585276,2.748893571891069,333.1,2266.3,2486.2,333.6,173.7,173.1 +0.27090232251624186,1.7288891637583532,2.8797932657906435,548.6,3143.3,3015.7,229.8,251.3,149.4 +0.27089222604451285,1.7288324089296614,3.010692959690218,1440.9,2777.3,2718.7,172.3,209.9,151.1 +0.2708800683153245,1.6285816851763726,0.0,1521.3,2650.4,2650.7,240.8,171.0,171.0 +0.2709576749301276,1.6292216523397183,0.1308996938995747,1601.7,1731.9,916.3,232.6,151.0,210.3 +0.271050683073762,1.6288325600350615,0.2617993877991494,1824.6,829.7,450.1,252.5,149.5,277.0 +0.27090248474317435,1.6291395484279354,0.39269908169872414,2289.3,533.5,314.1,315.2,173.5,598.2 +0.27111119581438275,1.6289033555197376,0.5235987755982988,3054.4,392.4,264.7,229.5,250.1,673.0 +0.27087570449001375,1.629084244308163,0.6544984694978736,2696.8,313.7,254.6,172.0,535.3,1354.6 +0.2711540956912581,1.628980923779331,0.7853981633974483,2621.0,270.9,270.4,140.9,1551.5,1551.1 +0.2707698273450156,1.6291590441573445,0.916297857297023,1005.6,254.5,313.4,128.9,1579.8,1638.8 +0.2711682756142472,1.6291652602183058,1.0471975511965976,472.2,265.1,251.1,137.0,1743.9,1871.4 +0.2708722732694751,1.6289560814759998,1.1780972450961724,315.2,313.8,173.0,172.2,2120.5,2339.9 +0.2707049390074784,1.6291101905414305,1.3089969389957472,252.4,276.8,149.1,271.4,3000.0,3136.1 +0.27087124774266264,1.629136721515268,1.4398966328953218,232.6,209.9,151.5,711.6,2775.0,2717.3 +0.2710852270908924,1.6290888595772903,1.5707963267948966,240.9,170.9,170.6,1521.1,2651.5,2651.3 +0.2710195282170736,1.6289643982840323,1.7016960206944713,275.2,150.9,209.3,1556.6,1760.1,931.8 +0.2708251683824264,1.6289034376183542,1.832595714594046,273.1,150.0,277.6,1732.6,872.5,449.4 +0.27093717392366484,1.6289926402811978,1.9634954084936205,173.3,174.1,599.1,2129.5,532.9,313.8 +0.2710763934513774,1.6291453685779116,2.0943951023931953,136.6,250.7,630.9,3027.7,392.4,265.1 +0.27105264007467983,1.6290422522912271,2.2252947962927703,129.3,538.7,1361.8,2738.9,313.3,254.5 +0.27105074002048035,1.6290340657338587,2.356194490192345,141.6,1551.2,1551.6,2620.2,270.3,270.9 +0.2712028345033109,1.6290512816304918,2.4870941840919194,172.1,1579.9,1639.1,1598.3,254.6,313.6 +0.2708436177117515,1.6289647515520744,2.6179938779914944,229.9,1745.8,1873.0,746.2,264.8,250.7 +0.2711070465091727,1.6291056896588463,2.748893571891069,333.1,2124.6,2344.6,475.1,315.1,173.1 +0.27090211386844754,1.6288894508473049,2.8797932657906435,548.6,3003.1,3140.1,345.4,276.8,149.4 +0.2708939089221579,1.628835708534444,3.010692959690218,1337.3,2777.3,2718.0,275.8,209.9,151.0 +0.2708812010903275,1.528584086445759,0.0,1421.2,2651.3,2651.1,340.8,171.0,171.0 +0.2709582786631376,1.5293033781163379,0.1308996938995747,1498.1,2116.1,1384.8,336.2,151.0,210.4 +0.27103832275854733,1.5289075651625934,0.2617993877991494,1708.9,1073.0,649.5,368.1,149.5,277.0 +0.2710452376014155,1.5289121000353099,0.39269908169872414,2147.2,674.7,455.4,332.4,173.5,394.2 +0.27085709556802184,1.5291266325932387,0.5235987755982988,3005.0,508.0,380.3,229.5,518.1,629.0 +0.27082820100998384,1.5291404557495532,0.6544984694978736,2696.8,417.2,358.1,172.1,620.0,1354.6 +0.2711831831274259,1.5289929010111991,0.7853981633974483,2621.6,370.9,370.4,140.9,1451.8,1451.2 +0.27078367893704464,1.529159538811958,0.916297857297023,1392.2,358.0,416.9,128.9,1476.4,1534.9 +0.27081246507908124,1.5290694678662806,1.0471975511965976,671.7,380.6,250.9,136.9,1628.6,1756.0 +0.2711311023900046,1.5291684719074277,1.1780972450961724,456.7,393.7,173.0,172.4,1980.4,2200.0 +0.2707163348840079,1.5289713956876207,1.3089969389957472,368.0,276.6,149.0,470.1,2803.4,3016.6 +0.27079133007460127,1.5289325290273161,1.4398966328953218,336.2,209.8,151.5,626.7,2774.6,2716.8 +0.2709836314820744,1.5290759236656355,1.5707963267948966,340.9,170.9,170.7,1421.0,2651.3,2651.5 +0.2709675520064994,1.52882136991859,1.7016960206944713,378.7,150.9,209.2,1453.3,2150.0,1321.4 +0.2708936251587138,1.529151632663589,1.832595714594046,272.9,149.9,277.6,1616.8,1027.8,648.7 +0.27122149011558877,1.5288898724604043,1.9634954084936205,173.4,174.1,394.8,1986.7,674.3,455.2 +0.27094343869335813,1.5291739341627837,2.0943951023931953,136.7,517.1,631.0,2828.7,507.8,380.6 +0.2709163351602167,1.529121349777276,2.2252947962927703,129.3,624.0,1361.9,2739.0,416.7,358.0 +0.27120285304746616,1.5290149506401332,2.356194490192345,141.6,1451.1,1451.8,2620.1,370.3,370.9 +0.2712225959413515,1.5290529218817435,2.4870941840919194,172.2,1476.5,1535.4,1983.1,358.1,417.2 +0.2708347657924829,1.5289605564679125,2.6179938779914944,229.9,1630.3,1757.3,945.6,380.3,250.7 +0.2711045154791966,1.5291045751080719,2.748893571891069,333.1,1982.8,2203.2,616.5,393.1,173.1 +0.27090231199772924,1.5288902581854533,2.8797932657906435,548.6,2803.7,3016.3,461.0,276.8,149.4 +0.27089507858247175,1.5288380925737006,3.010692959690218,1217.8,2777.5,2718.8,379.3,209.9,151.0 +0.27088197912191303,1.4285858661182025,0.0,1321.2,2651.3,2650.8,440.8,171.0,171.0 +0.2709586949885709,1.4293033867191531,0.1308996938995747,1394.8,2499.9,1684.2,439.8,151.0,210.4 +0.2710385542001287,1.4289074441320109,0.2617993877991494,1593.4,1228.6,849.0,483.5,149.5,422.1 +0.27104544148792475,1.4289119622078208,0.39269908169872414,2005.6,815.8,596.7,332.3,173.5,394.3 +0.27105350392238814,1.4289226841020728,0.5235987755982988,2899.8,623.7,496.0,229.5,402.3,629.1 +0.2708303184252421,1.4291004059374983,0.6544984694978736,2697.4,520.7,461.6,172.0,535.3,1350.0 +0.27115513572456257,1.428982036295412,0.7853981633974483,2620.9,470.9,470.4,140.9,1351.2,1350.8 +0.2707758349250428,1.429157335813989,0.916297857297023,1778.9,461.6,520.5,128.9,1372.8,1431.7 +0.2708051177877577,1.4290657624722354,1.0471975511965976,871.2,496.2,250.8,136.9,1512.7,1640.4 +0.2711303233055466,1.4291686031261475,1.1780972450961724,598.3,393.8,173.0,172.3,1839.3,2058.8 +0.2707167436186807,1.4289720233149463,1.3089969389957472,483.5,276.6,149.0,271.5,2603.2,2983.2 +0.27079167471294474,1.428933189418316,1.4398966328953218,439.5,209.8,151.5,626.7,2774.8,2716.6 +0.27098374329747704,1.4292141883253144,1.5707963267948966,440.9,170.9,170.7,1321.2,2651.0,2651.1 +0.27097121728583373,1.4288538719335981,1.7016960206944713,482.0,150.9,209.3,1350.1,2539.4,1711.0 +0.2709041979394162,1.4291305990975478,1.832595714594046,272.9,149.9,422.0,1501.3,1227.2,848.1 +0.27122996952773537,1.4288849579538163,1.9634954084936205,173.4,174.1,394.9,1845.8,815.7,596.3 +0.27094263329565166,1.4291767765909038,2.0943951023931953,136.7,401.4,631.2,2628.9,623.3,496.1 +0.27091515858180704,1.4291234905151264,2.2252947962927703,129.3,538.7,1350.1,2738.8,520.3,461.4 +0.2712028894954585,1.4290159430593778,2.356194490192345,141.6,1350.9,1351.7,2620.4,470.3,470.9 +0.2712195448384496,1.4290537344965037,2.4870941840919194,172.1,1372.8,1432.0,2368.8,461.7,520.7 +0.27083403127976946,1.42896108657976,2.6179938779914944,230.0,1514.1,1641.6,1144.6,496.1,250.6 +0.27110457059975424,1.4291050523975388,2.748893571891069,333.1,1841.6,2061.7,757.9,393.1,173.1 +0.2709022881467447,1.4288904375873481,2.8797932657906435,548.6,2604.2,2984.2,576.5,276.8,149.4 +0.27091781656876,1.4286829753465085,3.010692959690218,1218.1,2777.6,2718.5,482.7,209.9,151.0 +0.2710439090990391,1.3288052676802389,0.0,1221.1,2651.0,2651.1,540.9,171.0,171.0 +0.2710255793241709,1.329129868680052,0.1308996938995747,1291.0,2719.2,2069.1,543.3,151.0,210.3 +0.271003267843256,1.329122771911328,0.2617993877991494,1477.9,1472.1,1048.5,548.7,149.5,276.9 +0.2711215593680672,1.3288481850477991,0.39269908169872414,1863.9,956.9,737.6,332.4,372.4,394.4 +0.2711311262642516,1.3288606382637287,0.5235987755982988,2700.4,739.3,611.5,229.5,250.1,629.3 +0.27084070816676825,1.329087841691048,0.6544984694978736,2696.8,624.3,565.1,172.0,535.4,1269.4 +0.2708345522486544,1.3290648001596774,0.7853981633974483,2621.2,570.9,570.4,140.8,1251.6,1251.2 +0.2707767793161179,1.3290646194334337,0.916297857297023,2168.4,565.2,537.0,128.9,1269.0,1328.0 +0.27078948321357255,1.3290270237514763,1.0471975511965976,1071.6,611.6,251.1,136.8,1397.2,1524.4 +0.27113815006083003,1.3291444011569005,1.1780972450961724,740.1,393.8,173.0,203.4,1697.7,1917.2 +0.27072978061667646,1.3289644669795981,1.3089969389957472,599.2,276.5,149.0,271.6,2404.6,2784.3 +0.2708003707335944,1.3289279322083813,1.4398966328953218,543.0,209.8,151.5,1046.2,2774.3,2716.8 +0.27098900637214735,1.329211770632246,1.5707963267948966,540.9,170.9,170.7,1221.1,2651.0,2651.0 +0.27095546577765156,1.3292099681888434,1.7016960206944713,585.7,150.8,209.3,1246.5,2717.9,2096.6 +0.2710199733140488,1.3288237770010543,1.832595714594046,272.8,150.0,277.6,1385.5,1426.2,1047.0 +0.2712332071398093,1.328960535580943,1.9634954084936205,173.2,372.3,426.3,1704.3,956.2,737.3 +0.27105839613632954,1.3290968900992297,2.0943951023931953,136.7,250.8,631.1,2429.0,738.8,611.6 +0.27096244720736756,1.3289131395698637,2.2252947962927703,129.4,538.8,1269.3,2738.3,623.8,564.8 +0.2712381274750242,1.3289300110550428,2.356194490192345,141.7,1251.2,1251.7,2620.3,570.3,570.9 +0.2713413423857288,1.3291937229953001,2.4870941840919194,172.1,1269.3,1328.0,2697.0,565.2,536.6 +0.27079154770841596,1.3290070538274708,2.6179938779914944,229.9,1398.5,1526.4,1344.1,611.7,250.7 +0.2710806804839036,1.329125055947248,2.748893571891069,333.1,1700.4,1920.6,899.3,393.0,173.1 +0.27089462005846926,1.3289036257925702,2.8797932657906435,548.5,2404.9,2784.2,692.2,276.8,149.4 +0.2709134023866092,1.3288942271004203,3.010692959690218,1246.8,2777.3,2718.4,586.2,209.9,151.0 +0.2708920456262257,1.2286286146975072,0.0,1121.0,2651.1,2651.0,640.8,171.0,171.0 +0.27096217570592995,1.2293057975020476,0.1308996938995747,1187.4,2719.5,2452.0,647.0,151.0,210.3 +0.2710412476220784,1.228904776491642,0.2617993877991494,1362.3,1627.5,1247.8,548.5,149.5,277.0 +0.2710479796199744,1.2289092050537174,0.39269908169872414,1722.4,1098.1,879.1,332.4,173.5,394.3 +0.2710562629360409,1.2289201772089053,0.5235987755982988,2501.1,854.9,727.2,229.5,250.0,629.1 +0.27083052435372723,1.2290998272162907,0.6544984694978736,2696.8,727.8,668.7,172.0,1004.8,1165.9 +0.2708236105653016,1.2290735047135661,0.7853981633974483,2621.3,670.9,670.3,140.8,1151.6,1151.1 +0.27077539888424934,1.22906967374321,0.916297857297023,2556.1,668.5,537.0,128.9,1165.8,1224.3 +0.27078839643653574,1.229031133016503,1.0471975511965976,1271.2,631.3,251.1,136.8,1281.8,1409.1 +0.27113763470509605,1.2291464369945206,1.1780972450961724,881.7,393.8,173.0,172.3,1556.8,1775.5 +0.2707290794470259,1.2289653260063607,1.3089969389957472,714.6,276.5,149.0,271.5,2204.8,2584.1 +0.27079995175478355,1.2289286409481426,1.4398966328953218,646.4,209.8,151.5,965.5,2775.2,2716.2 +0.27098869975662515,1.2292119560670638,1.5707963267948966,641.0,170.9,170.7,1121.0,2651.2,2651.2 +0.2709552063893951,1.2292101548589112,1.7016960206944713,622.1,150.8,209.3,1143.1,2717.4,2485.6 +0.2709136297057444,1.2291962277001072,1.832595714594046,272.6,149.9,277.7,1270.2,1668.2,1245.5 +0.27113778878824807,1.228876705298793,1.9634954084936205,173.3,205.4,395.2,1562.8,1128.4,878.3 +0.271297950860524,1.2290532887346985,2.0943951023931953,136.7,250.8,631.2,2229.8,854.6,727.2 +0.27082532936641057,1.229178629831161,2.2252947962927703,129.3,1004.4,1165.5,2738.6,727.2,668.4 +0.27116201338023316,1.2290342306916235,2.356194490192345,141.6,1151.4,1151.6,2620.5,670.3,670.8 +0.2713090586402624,1.2292446349141863,2.4870941840919194,172.1,1165.4,1224.8,2696.4,668.7,536.6 +0.27079012218548204,1.2290353682512771,2.6179938779914944,229.9,1282.9,1410.7,1543.6,629.9,250.7 +0.27107932366350923,1.2291383016811432,2.748893571891069,364.3,1558.9,1779.2,1040.6,393.0,173.1 +0.27089159626030257,1.2289077190343165,2.8797932657906435,548.5,2205.3,2584.6,807.6,276.8,149.4 +0.2709115645565183,1.2288976826278728,3.010692959690218,1143.2,2777.1,2718.4,689.7,209.8,151.0 +0.27089035931930766,1.128631737676965,0.0,1021.3,2651.3,2651.0,740.8,170.9,171.0 +0.2709612903593327,1.1293061265990243,0.1308996938995747,1083.8,2719.5,2779.2,750.5,151.0,210.3 +0.2710410256301089,1.1289043992871708,0.2617993877991494,1246.6,1826.6,1447.3,548.5,149.5,277.0 +0.27104788356116993,1.1289089074434284,0.39269908169872414,1580.6,1270.5,1020.2,332.4,173.5,394.3 +0.271056212759162,1.128919929184132,0.5235987755982988,2301.8,970.4,842.7,229.5,293.8,629.2 +0.2708304564543895,1.1290997110957899,0.6544984694978736,2697.1,831.4,772.3,172.0,901.3,1062.2 +0.27082354792746816,1.1290734103312408,0.7853981633974483,2621.3,770.8,770.3,140.8,1051.6,1051.1 +0.2707777802926265,1.1290695185941373,0.916297857297023,2739.3,772.1,537.2,128.9,1062.2,1121.2 +0.27079069391620936,1.1290312396344877,1.0471975511965976,1470.7,631.2,251.0,136.8,1166.2,1293.6 +0.27113809629376,1.1291460966582259,1.1780972450961724,1023.4,393.8,173.0,172.3,1415.5,1634.4 +0.2707291691768218,1.1289649572167462,1.3089969389957472,830.4,276.5,149.0,271.6,2005.5,2385.2 +0.2707999803273099,1.1289283049593037,1.4398966328953218,749.8,209.8,151.5,862.1,2774.7,2717.0 +0.27098876106705955,1.1292118826288453,1.5707963267948966,740.9,170.9,170.7,1021.0,2651.4,2651.2 +0.2709552633436781,1.1292100815348978,1.7016960206944713,622.1,150.8,209.3,1039.7,2717.7,2776.0 +0.27091368961816426,1.1291961558970331,1.832595714594046,272.6,149.9,277.7,1154.8,1823.5,1444.6 +0.2711377998344142,1.1288766978395774,1.9634954084936205,173.3,174.2,395.2,1421.5,1238.4,1019.3 +0.27129796485373936,1.1290532845054786,2.0943951023931953,136.7,294.7,631.0,2030.0,970.1,842.7 +0.2708253301301111,1.1291786258867917,2.2252947962927703,129.3,878.0,1062.1,2739.1,830.8,772.0 +0.27116200753231756,1.1290342288467463,2.356194490192345,141.6,1051.0,1051.7,2620.1,770.3,770.9 +0.2711501079646094,1.1292653867003002,2.4870941840919194,172.2,1062.4,1121.5,2697.1,772.5,535.2 +0.27074220121260206,1.1290221248117285,2.6179938779914944,230.0,1167.3,1295.1,1741.8,629.5,250.6 +0.2710862725635541,1.1291498917997034,2.748893571891069,333.2,1417.6,1637.4,1182.1,393.0,173.1 +0.2708946306362496,1.1289130968229517,2.8797932657906435,548.5,2005.7,2385.9,923.4,276.8,149.4 +0.2709144795320088,1.1289031081427487,3.010692959690218,1039.8,2777.3,2718.7,793.3,209.9,151.0 +0.3709560370272465,1.8292033722081653,0.0,1721.1,2551.1,2550.9,40.9,271.0,271.0 +0.3709771281180925,1.8289188591656678,0.1308996938995747,1808.8,964.7,148.9,25.6,254.6,313.9 +0.37113045693247443,1.8289674445239155,0.2617993877991494,2055.7,430.9,51.3,21.3,265.0,392.5 +0.3709141322316646,1.8292146021646998,0.39269908169872414,2572.5,251.0,31.7,31.9,315.2,536.0 +0.3711431147509891,1.8289167002778335,0.5235987755982988,2888.4,161.1,33.5,72.2,449.4,828.5 +0.3708891821929592,1.829091854716181,0.6544984694978736,2593.3,106.6,47.5,231.3,1005.8,1787.1 +0.3708824358778367,1.8290667728410914,0.7853981633974483,2521.3,70.9,70.4,240.8,1751.5,1751.2 +0.3708274307427325,1.8291179485172118,0.916297857297023,232.3,47.5,106.3,232.4,1786.7,1845.7 +0.3708454509949016,1.8290624775297193,1.0471975511965976,73.2,33.9,161.3,252.4,1974.7,2102.3 +0.3711400631221659,1.8291525526945391,1.1780972450961724,31.7,31.5,250.7,313.6,2403.9,2623.1 +0.37072177649768506,1.8289628179673492,1.3089969389957472,21.2,51.1,264.6,471.0,3157.8,2901.3 +0.37079453354187636,1.8289251444785803,1.4398966328953218,25.8,152.6,254.9,1017.2,2671.2,2612.9 +0.3709862460968821,1.8292122526428685,1.5707963267948966,40.9,270.9,270.7,1721.0,2551.8,2551.4 +0.3709532309548635,1.8292104683855381,1.7016960206944713,68.2,254.3,312.8,1764.0,978.7,151.6 +0.37091178561781646,1.829196570679533,1.832595714594046,114.0,265.6,393.3,1964.4,429.6,50.8 +0.37113704505793066,1.8288766578989861,1.9634954084936205,192.5,315.9,536.9,2413.0,250.6,31.6 +0.37129721644336194,1.8290532464485554,2.0943951023931953,252.3,450.5,830.8,2979.2,161.3,34.1 +0.3708251887352648,1.8291784775774536,2.2252947962927703,232.8,926.5,1786.3,2635.1,106.2,47.5 +0.3711620052126641,1.8290341362497184,2.356194490192345,241.6,1751.0,1751.8,2520.4,70.3,70.9 +0.3711462830347968,1.829305439375017,2.4870941840919194,275.7,1786.9,1846.3,911.8,47.6,106.7 +0.3707731060311675,1.8290450182952076,2.6179938779914944,345.7,1976.9,2104.4,347.6,33.5,161.2 +0.3710888811670482,1.8291545740481108,2.748893571891069,474.6,2407.6,2627.5,192.2,32.2,252.3 +0.3708920437476835,1.8289116549936213,2.8797932657906435,748.0,3159.2,2900.3,114.3,51.8,264.9 +0.37091240334450476,1.8289013989593013,3.010692959690218,1604.7,2673.7,2615.5,68.7,151.8,254.5 +0.37089089153561683,1.7286350723185737,0.0,1621.3,2550.9,2551.1,140.8,271.0,271.0 +0.3709615422573938,1.7293060434873577,0.1308996938995747,1705.4,1347.8,532.4,129.1,254.6,313.9 +0.37093784688881865,1.7292981581987297,0.2617993877991494,1940.6,630.1,250.4,136.8,265.0,392.5 +0.3711210390921074,1.7288770682376007,0.39269908169872414,2430.7,392.3,173.0,173.7,315.3,739.9 +0.3711264762261649,1.728884893411303,0.5235987755982988,2888.4,276.7,149.1,271.5,723.7,828.6 +0.3708465270256524,1.7290951898937108,0.6544984694978736,2593.3,210.1,151.0,275.6,921.2,1683.5 +0.3708399127282425,1.729070259617549,0.7853981633974483,2521.5,170.9,170.4,240.8,1651.9,1650.9 +0.37078813431216584,1.7290692892424646,0.916297857297023,619.6,151.0,209.8,232.4,1683.3,1741.6 +0.37080048256699477,1.7290327762427515,1.0471975511965976,272.9,149.5,276.8,252.4,1859.1,1986.4 +0.37113990973121325,1.7291447966856177,1.1780972450961724,173.4,172.7,314.7,313.5,2262.4,2481.3 +0.3707293991376938,1.7289635124927205,1.3089969389957472,136.8,250.4,264.6,701.3,3028.0,2900.9 +0.37080000773369276,1.7289269691876834,1.4398966328953218,129.2,313.2,254.9,1483.0,2671.5,2613.3 +0.3709889492115474,1.7292116176795769,1.5707963267948966,140.9,270.9,270.7,1621.1,2551.2,2551.0 +0.37095543955575916,1.7292098170508279,1.7016960206944713,171.7,254.3,312.8,1660.2,1367.9,540.7 +0.3709138804070665,1.7291958977969577,1.832595714594046,229.7,265.5,393.3,1848.9,628.7,249.9 +0.3711378307123948,1.728876664130805,1.9634954084936205,314.5,315.9,740.9,2271.2,391.8,172.7 +0.371298007056304,1.7290532632312463,2.0943951023931953,252.2,738.2,830.8,2978.5,276.8,149.6 +0.37082533017099545,1.7291786159166833,2.2252947962927703,232.8,926.6,1683.2,2635.9,209.7,151.0 +0.3711619950906497,1.7290342236907223,2.356194490192345,241.6,1651.2,1651.6,2520.6,170.3,170.9 +0.3711500957036174,1.7292653802634903,2.4870941840919194,275.8,1683.4,1742.5,1212.5,151.1,210.3 +0.37074221227120674,1.729022114588893,2.6179938779914944,345.7,1861.0,1988.9,546.9,149.1,276.9 +0.3710862737691908,1.7291498781657264,2.748893571891069,474.6,2266.2,2486.5,333.6,173.6,314.4 +0.3708946429961134,1.728913088855367,2.8797932657906435,748.1,3028.0,2899.4,229.8,251.3,264.9 +0.3709144907876616,1.728903100701112,3.010692959690218,1661.1,2673.5,2614.7,172.3,313.4,254.5 +0.3708924717587221,1.628636399396263,0.0,1521.5,2550.9,2551.2,240.8,271.0,270.9 +0.37096239067027326,1.6293058590532654,0.1308996938995747,1601.8,1731.8,1000.8,232.6,254.6,313.9 +0.37093855727778735,1.6292979323282266,0.2617993877991494,1824.8,829.4,449.8,252.4,265.1,392.5 +0.3711213120618656,1.628877084924187,0.39269908169872414,2289.1,533.4,314.1,315.3,315.3,536.0 +0.3711267183446416,1.6288848776185387,0.5235987755982988,3011.9,392.3,264.8,345.1,608.1,828.6 +0.3708465845097716,1.6290952183616432,0.6544984694978736,2594.2,313.7,254.6,275.6,921.0,1579.8 +0.3708399678924572,1.6290702787707827,0.7853981633974483,2521.5,270.9,270.3,240.8,1551.7,1551.0 +0.3707904867097966,1.6290692438198393,0.916297857297023,1007.0,254.4,313.3,232.4,1579.6,1638.3 +0.3708027524892265,1.6290329875650869,1.0471975511965976,472.6,265.0,392.3,252.4,1743.9,1871.3 +0.37114035647431154,1.6291445010740442,1.1780972450961724,315.0,313.8,314.7,313.5,2121.6,2340.8 +0.370729471375917,1.6289631645792082,1.3089969389957472,252.3,392.1,264.6,514.9,3002.4,2901.0 +0.37080002580335736,1.6289266503447,1.4398966328953218,232.7,313.3,254.9,1356.5,2671.1,2613.5 +0.37089335238274185,1.6289057610178492,1.5707963267948966,241.0,270.8,270.6,1521.1,2551.1,2551.1 +0.3708934163260513,1.6289057211383866,1.7016960206944713,275.2,254.3,312.7,1557.0,1757.5,1015.8 +0.37089171806897975,1.6289045973701695,1.832595714594046,345.3,265.5,393.2,1732.6,828.0,449.2 +0.37094775785993095,1.6289404205146434,1.9634954084936205,314.1,315.8,568.2,2130.7,532.7,313.8 +0.3709652755834427,1.6289606715466847,2.0943951023931953,252.1,606.8,831.2,2978.8,392.3,265.0 +0.3709562323557974,1.6289413788567475,2.2252947962927703,232.7,926.9,1579.7,2635.0,313.3,254.5 +0.3709621651775824,1.628964331532052,2.356194490192345,241.5,1550.8,1551.7,2520.2,270.4,271.0 +0.37113338345552555,1.6290200683731184,2.4870941840919194,275.6,1579.9,1638.8,1598.9,254.6,313.7 +0.3711309415739109,1.6290306772402814,2.6179938779914944,345.5,1745.4,1872.8,746.4,264.8,392.4 +0.3711077101341771,1.629062835648487,2.748893571891069,474.4,2124.0,2344.2,475.2,315.1,314.5 +0.370869976018808,1.6288433904738917,2.8797932657906435,748.0,3003.5,2900.3,345.4,392.4,264.9 +0.3708866637047351,1.628835243588909,3.010692959690218,1557.0,2673.6,2614.8,275.8,313.4,254.6 +0.3708731329019683,1.5285797908394005,0.0,1421.2,2550.9,2550.8,340.8,271.0,271.0 +0.370952667944828,1.5293068594704895,0.1308996938995747,1498.3,2115.1,1300.1,336.3,254.5,313.9 +0.3709307648680721,1.529299525457247,0.2617993877991494,1709.3,1028.9,649.2,367.9,265.0,392.6 +0.37111789925319943,1.5288770437969865,0.39269908169872414,2147.8,674.5,455.3,457.0,315.3,536.0 +0.3711236440105934,1.528885191286875,0.5235987755982988,2888.8,508.0,380.3,345.2,449.4,828.6 +0.37084590905093473,1.5290948640885018,0.6544984694978736,2593.6,417.1,358.1,275.6,1315.3,1476.5 +0.3708393169042924,1.5290700258170042,0.7853981633974483,2521.4,370.8,370.3,240.9,1451.7,1450.8 +0.3707917786933266,1.529068925655971,0.916297857297023,1394.3,358.0,416.9,232.4,1476.2,1535.2 +0.3708040000934584,1.5290328088709986,1.0471975511965976,672.2,380.6,450.7,252.4,1628.5,1755.5 +0.3711406321533291,1.5291442306792618,1.1780972450961724,456.8,455.0,314.7,313.5,1980.4,2199.7 +0.37072955653174083,1.5289629291990547,1.3089969389957472,368.0,392.1,264.6,471.0,2803.1,2939.2 +0.3708000640952255,1.5289264399535565,1.4398966328953218,336.2,313.3,254.9,1276.0,2671.3,2613.4 +0.370893393034161,1.528905550760563,1.5707963267948966,340.9,270.8,270.7,1421.0,2551.1,2551.4 +0.3708934751591356,1.5289055121654251,1.7016960206944713,378.6,254.3,312.7,1453.5,2146.8,1319.2 +0.37089179795586313,1.5289043953361605,1.832595714594046,461.0,265.5,393.2,1617.4,1027.3,648.3 +0.37094785635816563,1.528940231094123,1.9634954084936205,314.2,315.9,536.9,1988.6,673.7,454.7 +0.37096538786637945,1.5289604982310894,2.0943951023931953,252.1,450.6,831.1,2830.3,507.8,380.5 +0.37095635330857357,1.5289412229798638,2.2252947962927703,232.7,1314.9,1476.1,2634.7,416.6,358.1 +0.3709622897600149,1.5289641934326448,2.356194490192345,241.5,1451.0,1451.4,2520.5,370.3,371.0 +0.371133403658246,1.5290199873710584,2.4870941840919194,275.6,1476.4,1535.5,1984.8,358.1,417.2 +0.3711309577654271,1.5290306095492117,2.6179938779914944,345.5,1629.8,1757.6,945.8,380.4,450.0 +0.3711077237848032,1.5290627726372843,2.748893571891069,474.4,1983.0,2202.7,616.6,456.6,314.4 +0.37086998832146006,1.528843367234986,2.8797932657906435,748.1,2803.7,2939.9,461.0,392.4,265.0 +0.3708866716341632,1.5288352227496271,3.010692959690218,1453.7,2673.4,2614.7,379.3,313.4,254.5 +0.3708731418851279,1.4285797733869823,0.0,1321.1,2550.9,2551.0,440.9,271.0,271.0 +0.37095267288078365,1.4293068474329118,0.1308996938995747,1394.4,2499.4,1684.0,439.7,254.6,313.9 +0.37093076873147657,1.4292995132248918,0.2617993877991494,1593.6,1228.2,848.7,483.6,265.0,392.6 +0.3711178988139992,1.4288770398370496,0.39269908169872414,2005.7,815.7,596.4,473.5,513.6,536.0 +0.3711236440603325,1.4288851879042286,0.5235987755982988,2863.1,623.6,496.0,345.1,449.4,828.5 +0.3708459105743925,1.4290948610663967,0.6544984694978736,2593.7,520.7,461.7,275.6,1211.9,1372.7 +0.37083931827921424,1.4290700225467123,0.7853981633974483,2520.9,470.8,470.4,240.8,1351.6,1351.2 +0.37079328125537797,1.4290688801448046,0.916297857297023,1781.4,461.5,520.4,232.4,1372.7,1431.4 +0.37080544994865217,1.4290329273301194,1.0471975511965976,871.9,496.1,450.6,252.4,1512.7,1639.8 +0.3711409214353173,1.4291440364640748,1.1780972450961724,598.4,535.5,314.7,344.5,1838.4,2058.4 +0.3707296046690259,1.4289627053299343,1.3089969389957472,483.6,392.1,264.6,470.9,2603.5,2900.6 +0.37080007714287705,1.428926234839653,1.4398966328953218,439.6,313.3,254.9,1172.3,2671.4,2613.3 +0.37089341320975955,1.4289053446550426,1.5707963267948966,440.9,270.9,270.7,1320.7,2551.1,2551.1 +0.3708935156150097,1.4289053073639344,1.7016960206944713,482.2,254.2,312.7,1349.9,2614.7,1708.5 +0.37089186059711354,1.428904197765834,1.832595714594046,471.7,265.5,393.2,1501.4,1226.2,847.4 +0.37094793837755025,1.4289400465005397,1.9634954084936205,314.2,513.3,537.0,1846.9,814.8,595.9 +0.370965484240368,1.4289603301660314,2.0943951023931953,252.0,450.6,831.2,2630.4,623.2,496.1 +0.3709564587473267,1.4289410728640248,2.2252947962927703,232.7,1211.4,1372.4,2635.6,520.3,461.5 +0.37096239907157375,1.4289640616531174,2.356194490192345,241.5,1351.1,1352.1,2520.5,470.4,471.1 +0.3711334046904501,1.429019910030466,2.4870941840919194,275.6,1372.8,1432.0,2370.6,461.7,520.7 +0.3711309550451929,1.4290305450695433,2.6179938779914944,370.9,1514.0,1641.7,1145.0,496.0,450.0 +0.37110771861963965,1.4290627128583904,2.748893571891069,474.4,1841.4,2061.5,758.0,534.5,314.5 +0.370869991168084,1.4288433487045435,2.8797932657906435,748.2,2603.8,2899.9,576.5,392.4,265.0 +0.37088667152292754,1.428835205862224,3.010692959690218,1350.1,2673.3,2614.5,482.8,313.4,254.5 +0.37087314353364853,1.328579760013988,0.0,1221.1,2551.0,2551.2,540.9,271.0,271.0 +0.37095267453946756,1.3293068370336303,0.1308996938995747,1290.9,2615.8,2067.7,543.3,254.6,313.9 +0.3709307699666536,1.3292995028250612,0.2617993877991494,1478.1,1427.5,1091.9,599.1,265.0,392.6 +0.37111789755711844,1.328877035873127,0.39269908169872414,1864.7,956.9,737.5,473.5,315.2,536.0 +0.3711236433719156,1.328885184599753,0.5235987755982988,2701.0,739.1,611.6,345.1,493.2,828.7 +0.37084591191733884,1.3290948579739843,0.6544984694978736,2593.3,624.2,565.2,275.6,1085.4,1269.4 +0.37083931947870846,1.32907001922695,0.7853981633974483,2521.2,570.9,570.3,240.8,1251.6,1251.2 +0.37079585855032254,1.329068689546932,0.916297857297023,2168.8,565.0,623.8,232.4,1269.3,1327.7 +0.37080794447814885,1.3290329956280527,1.0471975511965976,1071.5,611.6,450.8,252.4,1397.3,1524.7 +0.37114145642220303,1.3291436372247898,1.1780972450961724,740.2,535.5,314.7,313.5,1697.9,1917.0 +0.3707297204665086,1.3289622885519994,1.3089969389957472,599.0,392.1,264.6,471.0,2404.6,2783.7 +0.3708001180596589,1.3289258580813597,1.4398966328953218,543.0,313.3,255.0,1017.1,2671.6,2613.4 +0.37089346198258427,1.3289049673833813,1.5707963267948966,541.0,270.9,270.7,1221.0,2551.3,2551.1 +0.37089359839609104,1.3289049324795732,1.7016960206944713,585.7,254.2,312.7,1246.5,2613.8,2097.3 +0.37089198176356936,1.3289038355092289,1.832595714594046,471.6,265.5,393.3,1385.8,1425.5,1046.7 +0.3709480933239611,1.3289397070739488,1.9634954084936205,314.2,347.1,536.8,1705.2,955.8,737.0 +0.3709656641725412,1.3289600198223388,2.0943951023931953,252.1,450.6,831.0,2431.3,738.8,611.6 +0.3709566544109771,1.3289407939649167,2.2252947962927703,232.7,1085.0,1268.9,2634.6,623.7,565.0 +0.3709626013925913,1.3289638148510765,2.356194490192345,241.5,1251.0,1251.7,2520.5,570.3,570.9 +0.3711334141119887,1.3290197644404609,2.4870941840919194,275.6,1269.4,1328.3,2593.1,565.2,624.3 +0.3711309572585776,1.329030423740996,2.6179938779914944,345.5,1398.5,1526.0,1344.2,611.5,450.0 +0.3711077165003931,1.3290625997267886,2.748893571891069,505.5,1700.2,1920.0,899.4,534.7,314.5 +0.3708699990837243,1.3288433103825543,2.8797932657906435,748.0,2404.5,2784.5,692.1,392.4,264.9 +0.37088667327020103,1.3288351709318698,3.010692959690218,1246.6,2673.1,2614.9,586.2,313.4,254.6 +0.3708731477649606,1.2285797308671298,0.0,1121.1,2551.1,2551.3,640.8,271.0,270.9 +0.37095267743715377,1.2293068255800026,0.1308996938995747,1187.6,2616.3,2451.4,646.8,254.6,313.9 +0.3709307722849694,1.22929949132785,0.2617993877991494,1362.7,1627.1,1247.7,714.9,431.5,392.6 +0.3711178965185813,1.2288770319228661,0.39269908169872414,1722.5,1129.3,878.8,473.5,315.2,536.1 +0.3711236428769734,1.228885181283403,0.5235987755982988,2501.5,854.7,727.2,345.2,449.4,828.5 +0.3708459132849635,1.229094854920479,0.6544984694978736,2593.8,727.9,668.8,275.6,1090.7,1165.6 +0.37083932070101,1.2290700159375727,0.7853981633974483,2521.4,670.8,670.5,240.8,1151.7,1151.1 +0.3708405012010982,1.229071862740288,0.916297857297023,2635.7,668.4,727.3,232.4,1165.7,1224.3 +0.370850670479944,1.229042147028212,1.0471975511965976,1270.9,727.1,450.6,252.4,1281.7,1409.3 +0.3708727604764598,1.2290055081230116,1.1780972450961724,882.0,535.6,314.6,313.4,1556.7,1775.7 +0.3708630493572548,1.2290145396356271,1.3089969389957472,714.7,392.2,264.6,470.6,2203.8,2583.0 +0.3708699623351171,1.2290115690346022,1.4398966328953218,646.4,313.3,255.0,1015.9,2671.8,2613.5 +0.3709355114582546,1.2289964415595132,1.5707963267948966,640.9,270.9,270.7,1121.2,2551.3,2551.1 +0.37092191928440843,1.2289955043797987,1.7016960206944713,689.0,254.2,312.7,1143.0,2614.1,2488.9 +0.37091203190457267,1.228991673152434,1.832595714594046,472.0,432.0,393.2,1270.2,1625.2,1246.4 +0.37096250054792274,1.2290236587513754,1.9634954084936205,314.3,315.8,536.8,1562.9,1097.2,878.2 +0.37097627530269006,1.2290394866106173,2.0943951023931953,252.1,450.5,1036.2,2229.7,854.4,727.2 +0.3709648467668503,1.2290157048523949,2.2252947962927703,232.7,1096.7,1165.6,2635.0,727.2,668.4 +0.3709696442271367,1.2290341077426654,2.356194490192345,241.5,1151.0,1151.7,2520.7,670.4,671.0 +0.371169076681097,1.229057949672122,2.4870941840919194,275.7,1165.9,1224.8,2594.1,668.8,727.8 +0.37116859791343176,1.229061345432569,2.6179938779914944,345.6,1282.9,1410.6,1542.8,727.3,449.9 +0.371146167575274,1.2290915852451847,2.748893571891069,474.5,1558.8,1778.7,1040.8,534.5,314.5 +0.37088541439911105,1.228846223494311,2.8797932657906435,748.2,2205.4,2585.5,807.7,392.4,264.9 +0.37090118812560013,1.2288385435202462,3.010692959690218,1143.3,2673.4,2614.6,689.8,313.4,254.5 +0.3708858288617225,1.1285815526421903,0.0,1021.2,2550.7,2551.5,740.9,270.9,271.0 +0.37095832430527614,1.1293044291764578,0.1308996938995747,1083.8,2616.4,2675.4,750.5,254.6,313.9 +0.37093524237170505,1.1292967402671514,0.2617993877991494,1246.9,1826.7,1447.1,747.7,265.1,392.6 +0.37111945396104407,1.1288769644099892,0.39269908169872414,1580.8,1239.1,1020.0,473.5,315.3,536.0 +0.3711250683452595,1.1288849777426435,0.5235987755982988,2302.2,970.4,842.9,345.2,449.4,896.2 +0.37084619342544184,1.129095002927441,0.6544984694978736,2593.2,831.3,772.2,275.5,921.1,1062.1 +0.37083958990606763,1.1290701187314696,0.7853981633974483,2521.7,770.9,770.3,240.8,1051.6,1051.0 +0.3708064976739175,1.1290640016226865,0.916297857297023,2635.4,772.0,830.9,232.4,1062.1,1120.8 +0.3708174351392026,1.1290318920254645,1.0471975511965976,1515.0,830.9,450.8,252.4,1166.3,1293.3 +0.37114254801098673,1.1291452871713368,1.1780972450961724,1023.5,535.5,314.7,313.5,1415.5,1634.9 +0.37072666299901585,1.1289593104619138,1.3089969389957472,830.3,392.1,264.6,471.0,2005.9,2385.1 +0.370798390809006,1.1289221847057274,1.4398966328953218,749.9,313.3,254.9,1081.8,2671.3,2613.7 +0.37089246198798237,1.128901151743214,1.5707963267948966,741.1,270.8,270.7,1021.0,2551.2,2551.3 +0.3708930692817346,1.12890115012745,1.7016960206944713,792.6,254.2,312.7,1039.6,2613.9,2672.8 +0.3708918031531443,1.1289001662436298,1.832595714594046,471.6,265.5,393.2,1154.6,1823.8,1444.7 +0.37094818139723734,1.1289362209414078,1.9634954084936205,314.2,347.0,537.0,1421.5,1237.9,1019.0 +0.3709659389584705,1.1289567563113816,2.0943951023931953,252.1,450.6,920.4,2031.2,969.8,842.4 +0.37095704922511236,1.1289377599405284,2.2252947962927703,232.7,926.9,1061.9,2635.0,830.7,772.0 +0.37096305092225856,1.1289610147595734,2.356194490192345,241.5,1051.3,1051.7,2520.5,770.3,770.9 +0.37113241905628636,1.1290182590316007,2.4870941840919194,275.6,1062.2,1121.3,2593.3,772.3,831.3 +0.37112987918613444,1.1290292148196355,2.6179938779914944,345.5,1167.3,1294.9,1742.9,829.1,450.1 +0.37110659984205463,1.1290614738152573,2.748893571891069,474.4,1417.0,1637.2,1182.5,534.6,314.5 +0.37086957883767235,1.1288431199004136,2.8797932657906435,907.9,2005.8,2385.5,923.3,392.4,264.9 +0.3708862649444937,1.1288349749503541,3.010692959690218,1039.8,2673.6,2614.9,793.4,313.4,254.5 +0.4709552322112855,1.8290530812283567,0.0,1720.8,2451.1,2451.2,41.0,371.0,371.0 +0.47098038706489415,1.8289349291958372,0.1308996938995747,1808.6,965.0,148.9,25.5,358.2,417.5 +0.4711307614955159,1.8289825894831957,0.2617993877991494,2055.9,431.0,51.3,21.3,380.6,508.1 +0.4710567343300485,1.8289360506667711,0.39269908169872414,2571.9,251.1,31.8,32.0,456.8,881.4 +0.4710468671604634,1.8289272515338635,0.5235987755982988,2773.3,161.2,33.5,72.2,839.6,1027.4 +0.47082391036514043,1.8291045708711777,0.6544984694978736,2489.9,106.5,47.5,231.5,1626.1,1786.6 +0.47081661712448913,1.8290764901704681,0.7853981633974483,2421.4,70.9,70.4,340.8,1751.6,1751.3 +0.47081796265835835,1.8290750261866926,0.916297857297023,232.2,47.4,106.3,335.9,1786.7,1845.3 +0.47082910392829674,1.829042302256832,1.0471975511965976,73.2,33.9,161.2,367.9,1974.8,2102.3 +0.4708528018130051,1.8290032047602724,1.1780972450961724,31.7,31.5,250.7,454.5,2403.3,2622.5 +0.4708450794843813,1.8290104182639615,1.3089969389957472,21.1,50.9,380.2,817.1,2913.3,2785.2 +0.47085420694379837,1.8290062682304689,1.4398966328953218,25.7,152.2,358.4,1563.5,2568.3,2509.7 +0.47092204368350965,1.8289906342708175,1.5707963267948966,40.9,370.9,370.7,1721.5,2451.4,2451.7 +0.4709105828706892,1.8289897567242779,1.7016960206944713,68.2,357.8,416.2,1764.1,1065.8,151.9 +0.47090260008428436,1.8289864521272492,1.832595714594046,114.0,381.1,508.8,1964.0,429.9,50.8 +0.470954667914855,1.8290193893879385,1.9634954084936205,192.4,457.5,882.7,2413.3,250.5,31.5 +0.4709696451879907,1.8290364435796125,2.0943951023931953,349.9,838.1,1030.4,2863.4,161.2,33.9 +0.4709590205541456,1.829047567490738,2.2252947962927703,336.3,1625.7,1786.6,2531.4,106.2,47.4 +0.47096692221755526,1.8290403547196985,2.356194490192345,341.5,1751.1,1751.7,2420.2,70.3,70.9 +0.4711375198280126,1.829062360429365,2.4870941840919194,379.2,1787.1,1846.2,826.9,47.5,106.6 +0.47113771555055983,1.8290640843735237,2.6179938779914944,461.3,1976.7,2104.6,347.7,33.5,161.2 +0.4711160890370959,1.829093280196037,2.748893571891069,616.0,2407.5,2627.3,192.2,32.3,252.3 +0.47087235066671446,1.8288528650745437,2.8797932657906435,991.4,2911.6,2784.5,114.3,51.8,380.5 +0.4708902287062958,1.8288440623757418,3.010692959690218,1764.4,2570.2,2511.0,68.7,151.9,358.1 +0.47087585067086296,1.7285871185967676,0.0,1621.3,2451.3,2451.2,140.8,371.0,371.0 +0.47095382667563773,1.7293065638275573,0.1308996938995747,1705.2,1347.5,532.4,129.1,358.1,417.5 +0.47093162902117996,1.7292991397587232,0.2617993877991494,1940.1,630.1,250.5,136.8,380.6,508.2 +0.4711182650994262,1.7288769964375457,0.39269908169872414,2431.0,392.2,173.0,173.7,456.9,677.8 +0.47112398528182714,1.7288851189451286,0.5235987755982988,2772.7,276.8,149.1,271.5,692.5,1027.8 +0.4708459844555141,1.7290948796018049,0.6544984694978736,2490.2,210.1,151.0,379.2,1522.4,1683.3 +0.4708393891569459,1.7290700301927022,0.7853981633974483,2421.1,170.9,170.4,340.8,1651.6,1650.9 +0.47084056926284057,1.729071877245225,0.916297857297023,619.5,150.9,209.8,335.9,1683.2,1742.4 +0.4708507371114359,1.7290421648379255,1.0471975511965976,272.8,149.5,276.8,367.9,1859.0,1986.6 +0.470847108797591,1.7290465344868786,1.1780972450961724,173.4,172.7,391.8,454.6,2262.1,2481.5 +0.47086160308822567,1.729032986466874,1.3089969389957472,136.8,250.2,380.2,669.9,2956.9,2785.9 +0.4708750425434583,1.7290265579613635,1.4398966328953218,129.2,416.8,358.5,1405.7,2568.2,2509.7 +0.47093989684502036,1.7290116054307414,1.5707963267948966,140.9,370.8,370.7,1621.2,2451.6,2451.1 +0.4709232724840784,1.7290105766825383,1.7016960206944713,171.6,357.8,416.2,1660.5,1369.8,541.5 +0.4709099394790301,1.7290057079311567,1.832595714594046,229.6,381.2,508.8,1848.1,629.2,250.1 +0.4709573211894581,1.7290357644092786,1.9634954084936205,334.2,457.5,709.9,2271.8,391.7,172.6 +0.4709687587502133,1.7290490872944546,2.0943951023931953,367.6,650.1,1030.5,2984.8,276.8,149.5 +0.47095583605482927,1.7290225146937528,2.2252947962927703,336.2,1521.8,1683.0,2531.2,209.7,151.0 +0.47095996260974965,1.7290380271832357,2.356194490192345,341.5,1651.3,1651.5,2420.6,170.3,170.9 +0.4711777352706784,1.729059186829084,2.4870941840919194,379.2,1683.6,1742.8,1212.2,151.0,210.1 +0.4711774703830008,1.7290616668591636,2.6179938779914944,461.4,1860.8,1989.0,547.0,149.1,276.7 +0.4711251529736613,1.7291402901756048,2.748893571891069,616.1,2266.0,2486.3,333.7,173.7,393.8 +0.47090024058417274,1.7288834164049725,2.8797932657906435,947.9,2959.4,2784.4,229.8,251.4,380.5 +0.47092124905611804,1.7288728824093136,3.010692959690218,1660.9,2570.1,2511.5,172.2,416.8,358.1 +0.4709019512835838,1.6286089142237807,0.0,1521.1,2450.8,2451.2,240.8,371.0,371.0 +0.4709395712218054,1.6292860562358014,0.1308996938995747,1601.7,1732.0,916.4,232.6,358.2,417.5 +0.47092884111235617,1.6292822233903217,0.2617993877991494,1824.4,829.5,449.9,252.4,380.7,508.1 +0.4711124949422483,1.6288730457545406,0.39269908169872414,2288.9,533.4,314.2,315.3,457.0,677.7 +0.4711189974868486,1.6288820137399154,0.5235987755982988,2772.8,392.5,264.7,460.7,648.7,1027.7 +0.47084400096258117,1.6290931855664996,0.6544984694978736,2489.9,313.6,254.6,379.1,1419.1,1579.5 +0.470837525336123,1.6290688337383912,0.7853981633974483,2421.3,270.9,270.4,340.9,1551.2,1551.2 +0.4708387099092094,1.6290706955431102,0.916297857297023,1006.5,254.5,313.3,335.9,1579.6,1638.5 +0.4708489241617131,1.6290408559086047,1.0471975511965976,472.4,265.0,392.3,367.9,1744.1,1871.1 +0.47087111177759927,1.6290040826544094,1.1780972450961724,315.1,313.8,456.4,454.5,2120.9,2340.1 +0.4708615285269671,1.629013006883063,1.3089969389957472,252.3,449.6,380.2,670.0,2913.1,2785.6 +0.47086858543374654,1.6290099660920783,1.4398966328953218,232.6,416.8,358.4,1405.7,2568.6,2510.3 +0.470934282384997,1.6289948165114154,1.5707963267948966,240.9,370.9,370.7,1521.1,2451.8,2451.0 +0.4708764521071589,1.6289890300201129,1.7016960206944713,275.1,357.7,416.2,1557.1,1759.2,931.1 +0.4708962174429718,1.6289943047693716,1.832595714594046,345.2,381.1,508.8,1732.7,828.5,449.3 +0.4709531465488985,1.629030379900305,1.9634954084936205,455.4,457.5,678.5,2130.3,532.9,313.8 +0.4709670546273815,1.6290463728209228,2.0943951023931953,367.6,650.2,1030.6,2863.3,392.3,265.0 +0.47095468239103694,1.6290208290896677,2.2252947962927703,336.2,1398.7,1579.9,2531.7,313.2,254.5 +0.4709588979329078,1.6290367045407101,2.356194490192345,341.4,1551.2,1551.5,2420.7,270.4,270.9 +0.4711766266538561,1.6290585408238607,2.4870941840919194,379.2,1580.2,1639.2,1597.5,254.6,313.7 +0.4711763235013165,1.6290611677447335,2.6179938779914944,461.3,1745.6,1872.9,790.1,264.7,392.4 +0.4711541124987809,1.6290909697793399,2.748893571891069,616.1,2124.9,2344.5,475.1,315.1,455.9 +0.47088962776404564,1.628844617816322,2.8797932657906435,947.7,2911.6,2783.8,345.4,450.8,380.5 +0.4709048483184096,1.628837232726592,3.010692959690218,1557.1,2570.3,2511.1,275.8,416.9,358.1 +0.4708891465182756,1.5285801084461998,0.0,1421.2,2451.0,2451.0,340.8,371.0,371.0 +0.47095980414724153,1.5293037157514318,0.1308996938995747,1498.1,2115.7,1300.3,336.2,358.1,417.5 +0.47093642138664654,1.529295936975503,0.2617993877991494,1708.8,1028.9,649.4,368.0,380.7,508.1 +0.4711198408345022,1.5288769383564627,0.39269908169872414,2147.5,674.6,455.3,457.0,654.7,677.7 +0.47112542345134234,1.5288849191688967,0.5235987755982988,2856.6,507.8,380.3,460.7,648.7,1028.0 +0.47084626562333964,1.5290950326295414,0.6544984694978736,2489.7,417.2,358.1,379.1,1306.7,1476.6 +0.47083965890769264,1.5290701362093133,0.7853981633974483,2421.1,370.9,370.4,340.8,1451.7,1450.9 +0.4708408379452453,1.529071989135074,0.916297857297023,1393.8,358.0,416.9,335.9,1476.1,1535.2 +0.4708509984180252,1.529042297271428,1.0471975511965976,672.2,380.5,507.9,367.9,1628.1,1756.1 +0.4708730711029846,1.5290056821762144,1.1780972450961724,456.8,455.0,456.4,629.3,1979.8,2198.8 +0.47086333800271696,1.5290147320940575,1.3089969389957472,367.9,507.9,380.2,713.9,2802.6,2927.1 +0.4708702264368557,1.5290117734754718,1.4398966328953218,336.1,416.8,358.4,1405.8,2568.3,2509.7 +0.4709357501950625,1.5289966500509795,1.5707963267948966,340.9,370.9,370.6,1421.2,2451.3,2451.2 +0.47092213510357395,1.5289957110365535,1.7016960206944713,378.6,357.6,416.2,1453.6,2148.5,1320.7 +0.47091222755455153,1.5289918736451773,1.832595714594046,460.8,381.1,621.3,1616.8,1027.6,648.6 +0.4709626793654114,1.5290238483852097,1.9634954084936205,455.5,654.7,678.4,1988.2,673.9,454.8 +0.47097644176542786,1.5290396626933365,2.0943951023931953,367.7,650.2,1030.6,2829.0,507.7,380.5 +0.4709650048329309,1.5290158668940639,2.2252947962927703,336.2,1313.6,1476.2,2531.8,416.7,358.0 +0.4709697978000149,1.529034255003781,2.356194490192345,341.5,1451.2,1451.5,2420.3,370.3,370.9 +0.4711693447628588,1.529058012172434,2.4870941840919194,379.2,1476.5,1535.5,1983.0,358.1,417.2 +0.4711688702090531,1.5290613895078786,2.6179938779914944,461.3,1629.9,1757.7,945.3,380.3,508.0 +0.4711464406077511,1.5290916255156377,2.748893571891069,616.0,1983.3,2203.1,616.5,456.6,455.9 +0.47084812950180915,1.5288103696953605,2.8797932657906435,947.7,2804.5,2925.2,460.9,507.9,380.5 +0.47086918070733186,1.5287999809547637,3.010692959690218,1453.6,2570.5,2511.5,379.3,416.9,358.1 +0.4708621396425053,1.4285505214132999,0.0,1321.1,2450.8,2451.3,440.9,371.0,371.0 +0.4709457107245003,1.4293065017961308,0.1308996938995747,1394.5,2512.7,1684.1,439.8,358.1,417.5 +0.4709247746947627,1.4292994633567546,0.2617993877991494,1593.6,1228.1,848.7,483.6,380.6,508.2 +0.47111525383013364,1.428876698283326,0.39269908169872414,2006.0,815.8,596.6,598.6,456.9,677.7 +0.4711213370408464,1.4288852045756684,0.5235987755982988,2773.2,623.6,495.9,460.8,648.7,1027.9 +0.470845349544097,1.4290945001583282,0.6544984694978736,2489.7,520.7,461.6,379.1,1306.7,1372.9 +0.4708387787990052,1.4290697526054215,0.7853981633974483,2421.2,470.9,470.3,340.9,1351.5,1351.2 +0.4708399610441523,1.429071580587237,0.916297857297023,1780.9,461.4,520.3,336.0,1372.7,1431.4 +0.4708501469511142,1.4290418160337768,1.0471975511965976,871.7,496.0,623.4,367.9,1512.7,1640.2 +0.47087227010282645,1.429005129589068,1.1780972450961724,598.4,596.0,456.4,454.5,1838.7,2057.7 +0.4708626018987606,1.4290141238877538,1.3089969389957472,483.6,507.9,380.2,670.0,2602.3,2786.0 +0.4708695630906541,1.4290111289624572,1.4398966328953218,439.6,416.8,358.4,1392.8,2568.4,2510.0 +0.47093516168323746,1.4289959930343228,1.5707963267948966,440.8,370.9,370.7,1321.2,2451.1,2450.8 +0.4709216152735135,1.4289950590932456,1.7016960206944713,482.1,357.7,416.1,1350.1,2510.9,1710.1 +0.4709117684118407,1.4289912401353482,1.832595714594046,576.4,381.1,508.8,1501.3,1226.9,847.8 +0.47096227022840603,1.4290232471487174,1.9634954084936205,455.4,488.7,678.4,1846.5,815.1,596.0 +0.4709760695759755,1.429039102022412,2.0943951023931953,367.7,650.2,1030.6,2629.7,623.4,496.1 +0.4709646579441328,1.4290153489581359,2.2252947962927703,336.2,1313.3,1372.7,2531.5,520.2,461.5 +0.4709694641827523,1.4290337816533858,2.356194490192345,341.5,1351.2,1351.4,2420.8,470.2,470.9 +0.47116872594810827,1.4290577943579958,2.4870941840919194,379.2,1373.0,1432.0,2368.6,461.6,520.7 +0.4711682373600978,1.4290612307690091,2.6179938779914944,461.2,1514.3,1641.9,1144.7,496.1,623.8 +0.47114580159878977,1.4290914843403342,2.748893571891069,616.1,1841.5,2061.5,757.9,598.1,456.0 +0.47088525678398374,1.4288462614764468,2.8797932657906435,947.8,2604.3,2784.3,576.6,507.9,380.5 +0.4709010506974423,1.4288385709154028,3.010692959690218,1350.2,2569.7,2510.8,482.7,417.0,358.1 +0.4708857103013378,1.3285815921338417,0.0,1221.1,2450.7,2451.0,540.8,371.0,371.0 +0.4709582705026704,1.3293044166003773,0.1308996938995747,1290.9,2512.5,2067.8,543.3,358.1,417.4 +0.47093519820727214,1.329296731105151,0.2617993877991494,1478.0,1427.5,1048.0,599.1,380.6,508.1 +0.4711194316942222,1.328876945581246,0.39269908169872414,1864.4,987.9,737.8,614.7,457.0,677.6 +0.4711250505793145,1.3288849638604234,0.5235987755982988,2700.7,739.2,611.6,460.7,648.6,1152.7 +0.47084619438833103,1.3290949870261977,0.6544984694978736,2489.6,624.2,565.2,379.1,1305.5,1269.2 +0.4708395904196895,1.3290701025218574,0.7853981633974483,2420.7,570.9,570.4,340.8,1251.6,1251.0 +0.4708407696428388,1.3290719521797116,0.916297857297023,2168.4,565.0,623.7,335.9,1269.3,1328.4 +0.47085093250488136,1.3290422529852548,1.0471975511965976,1071.3,611.7,650.4,521.3,1397.1,1524.5 +0.4708730099760879,1.3290056307996576,1.1780972450961724,740.1,677.2,456.3,454.5,1697.6,1916.8 +0.4708632831515691,1.329014675142815,1.3089969389957472,599.2,507.8,380.2,670.0,2403.4,2782.8 +0.4708701786708854,1.3290117128839898,1.4398966328953218,543.1,416.8,358.4,1289.3,2568.2,2509.9 +0.47093570968399273,1.3289965881155923,1.5707963267948966,540.9,370.9,370.7,1221.1,2451.3,2451.2 +0.4709221013887298,1.3289956495117194,1.7016960206944713,585.6,357.7,416.1,1246.7,2510.8,2099.7 +0.47091219987498867,1.3289918139418075,1.832595714594046,671.1,381.1,508.7,1385.6,1425.9,1046.9 +0.4709626566010978,1.3290237918272148,1.9634954084936205,455.4,457.5,678.5,1704.8,956.3,737.1 +0.4709764226697689,1.329039610123211,2.0943951023931953,367.7,650.1,1151.7,2430.0,738.8,611.5 +0.4709649882467781,1.3290158186446082,2.2252947962927703,336.3,1305.2,1268.9,2531.6,623.8,565.1 +0.47096978248334037,1.3290342112160922,2.356194490192345,341.4,1251.2,1251.7,2420.6,570.4,570.8 +0.4711693076410029,1.3290579901709538,2.4870941840919194,379.1,1269.2,1328.4,2490.3,565.1,624.2 +0.4711688317558605,1.329061373002364,2.6179938779914944,461.2,1398.6,1526.3,1343.9,611.6,649.1 +0.4711464011590485,1.3290916112900115,2.748893571891069,616.1,1700.4,1920.4,899.3,675.8,455.9 +0.4708855271951138,1.3288461938810638,2.8797932657906435,1113.4,2404.8,2759.1,692.0,507.9,380.5 +0.47090128870935677,1.3288385205008546,3.010692959690218,1246.7,2569.9,2511.3,586.4,416.9,358.1 +0.4708859242483963,1.2285815307753265,0.0,1121.1,2451.1,2451.0,640.8,370.9,371.0 +0.4709583660532525,1.2293043669516588,0.1308996938995747,1187.4,2511.9,2451.7,646.9,358.1,417.5 +0.4709352742636299,1.2292966756874024,0.2617993877991494,1362.3,1627.1,1247.3,714.8,380.6,508.1 +0.47111945613199313,1.2288769416681455,0.39269908169872414,1722.7,1098.1,878.9,614.6,456.9,677.8 +0.47112507324600594,1.2288849581688395,0.5235987755982988,2501.6,854.7,727.2,460.8,648.7,1141.8 +0.4708461995735179,1.2290949871313626,0.6544984694978736,2489.9,727.7,668.7,379.0,1224.8,1165.5 +0.4708395953401602,1.229070101772611,0.7853981633974483,2421.1,670.8,670.4,340.8,1151.7,1151.3 +0.4708407745098014,1.2290719508686947,0.916297857297023,2532.1,668.5,727.4,336.0,1165.5,1224.6 +0.4708509374311642,1.2290422512493775,1.0471975511965976,1270.7,727.2,650.3,368.0,1281.7,1409.2 +0.4708730150413902,1.2290056287153717,1.1780972450961724,881.8,677.3,456.4,485.5,1556.5,1775.5 +0.4708632884515774,1.2290146727630349,1.3089969389957472,714.7,507.8,380.3,670.0,2203.9,2583.7 +0.47087018425681015,1.2290117103084555,1.4398966328953218,646.4,416.8,358.4,1185.6,2568.0,2510.0 +0.4709357155468749,1.228996585437093,1.5707963267948966,640.9,370.9,370.7,1121.1,2451.1,2450.8 +0.47092210757390557,1.2289956468164696,1.7016960206944713,689.0,357.7,416.2,1143.1,2510.4,2568.6 +0.4709122063605357,1.2289918113301819,1.832595714594046,671.2,381.1,508.7,1270.0,1625.1,1245.9 +0.47096266330277714,1.2290237893453957,1.9634954084936205,455.4,488.7,678.4,1563.1,1097.4,878.3 +0.4709764295487601,1.229039607822525,2.0943951023931953,367.7,650.1,1140.7,2230.2,854.4,727.1 +0.47096499525042196,1.229015816588932,2.2252947962927703,336.2,1224.4,1165.7,2531.3,727.3,668.5 +0.4709697895315631,1.2290342093935163,2.356194490192345,341.4,1151.1,1151.7,2421.0,670.3,671.0 +0.471169316764427,1.2290579884113602,2.4870941840919194,379.3,1166.0,1224.7,2490.4,668.6,727.9 +0.4711688408037763,1.2290613714828371,2.6179938779914944,461.3,1283.2,1410.6,1543.3,727.2,649.1 +0.471146409964992,1.2290916101649936,2.748893571891069,616.1,1559.0,1779.2,1040.7,675.9,456.0 +0.47088553212615425,1.2288461923865222,2.8797932657906435,1023.2,2205.7,2585.3,807.8,507.9,380.5 +0.47090129318211116,1.2288385192679923,3.010692959690218,1143.2,2570.1,2511.2,689.8,416.8,358.1 +0.4708859288875784,1.1285815300878765,0.0,1021.3,2451.3,2451.2,740.8,371.0,371.1 +0.4709583678621134,1.1293043599101065,0.1308996938995747,1084.0,2512.5,2572.3,750.5,358.1,417.5 +0.470935275525545,1.1292966685646082,0.2617993877991494,1246.9,1826.4,1446.7,830.2,380.6,508.2 +0.4711194554172585,1.1288769386266662,0.39269908169872414,1580.8,1239.3,1020.0,614.8,456.9,677.8 +0.4711250729456512,1.1288849556021314,0.5235987755982988,2302.2,970.3,842.7,460.6,648.7,1028.0 +0.4708462002751709,1.1290949847429783,0.6544984694978736,2490.2,831.4,772.2,379.1,1121.4,1062.4 +0.47083959595543134,1.1290700992717093,0.7853981633974483,2420.9,770.9,770.3,340.8,1051.5,1051.1 +0.470840775087563,1.129071947686208,0.916297857297023,2532.5,772.2,830.9,335.9,1062.2,1120.8 +0.4708509381929813,1.1290422472854038,1.0471975511965976,1470.5,842.8,650.3,368.0,1166.5,1293.6 +0.47087301618978034,1.1290056240515083,1.1780972450961724,1023.7,677.3,456.4,454.5,1415.3,1634.2 +0.47086329015347916,1.1290146675297468,1.3089969389957472,830.4,507.8,380.2,670.0,2004.8,2383.8 +0.4708701866023378,1.1290117047007457,1.4398966328953218,749.9,416.8,358.4,1082.0,2568.0,2510.0 +0.47093571853755467,1.1289965796636028,1.5707963267948966,740.8,371.0,370.7,1021.2,2451.3,2451.3 +0.4709221112249249,1.1289956410503572,1.7016960206944713,792.5,357.7,416.2,1039.7,2511.0,2569.1 +0.4709122106106781,1.1289918057383725,1.832595714594046,671.1,381.2,508.8,1154.6,1824.7,1445.5 +0.47096266801571296,1.129023784041849,1.9634954084936205,455.4,457.5,678.5,1421.3,1238.3,1019.3 +0.4709764346214633,1.12903960289932,2.0943951023931953,367.6,650.1,1030.3,2030.5,969.8,842.5 +0.47096500057227364,1.1290158121213019,2.2252947962927703,336.2,1120.8,1062.5,2531.8,830.7,772.1 +0.4709697949631279,1.129034205378792,2.356194490192345,341.5,1051.0,1051.7,2420.1,770.4,770.8 +0.47116932284848423,1.1290579856442111,2.4870941840919194,379.2,1062.3,1121.3,2490.1,772.3,831.3 +0.47116884674785253,1.129061369230576,2.6179938779914944,461.3,1167.6,1295.3,1742.5,842.7,649.1 +0.4711464156392723,1.129091608388931,2.748893571891069,615.9,1417.6,1637.6,1182.2,675.9,455.9 +0.4708855356432317,1.1288461912524421,2.8797932657906435,947.6,2006.0,2386.1,923.1,507.9,380.5 +0.4709012964116665,1.12883851830511,3.010692959690218,1039.8,2570.2,2511.6,793.4,416.9,358.1 +0.570968152500873,1.82905000105298,0.0,1720.7,2350.5,2351.1,41.0,471.0,470.9 +0.5709850833717504,1.8289344316266543,0.1308996938995747,1808.4,1049.2,148.9,25.5,461.6,521.1 +0.5711346861092487,1.8289818642382603,0.2617993877991494,2055.7,431.0,51.3,21.3,496.0,623.7 +0.5710597859346717,1.8289347832829475,0.39269908169872414,2572.2,251.1,31.8,32.0,598.4,819.1 +0.5710498941165464,1.8289259700858205,0.5235987755982988,2658.0,161.2,33.5,72.2,847.7,1226.8 +0.5708245551952956,1.829104668246837,0.6544984694978736,2386.4,106.5,47.5,231.5,1692.7,1786.9 +0.57081726915729,1.8290766279420991,0.7853981633974483,2320.8,70.9,70.4,440.8,1751.8,1751.0 +0.5708186104312741,1.8290752204786482,0.916297857297023,232.2,47.4,106.3,439.4,1786.9,1845.6 +0.5708297320922157,1.8290425514798836,1.0471975511965976,73.2,33.9,161.2,483.5,1975.1,2102.6 +0.570853397420756,1.8290034979600809,1.1780972450961724,31.7,31.5,250.7,595.5,2403.6,2622.8 +0.5708456364113768,1.8290107437108247,1.3089969389957472,21.1,50.9,430.2,869.4,2797.8,2670.0 +0.5708547216924829,1.8290066147949162,1.4398966328953218,25.7,152.1,461.8,1783.5,2464.7,2406.1 +0.5709225150816176,1.8289909871384813,1.5707963267948966,40.9,470.8,470.7,1720.8,2351.2,2351.4 +0.5709110152551125,1.8289901063991851,1.7016960206944713,68.2,461.1,519.7,1764.1,980.1,151.9 +0.5709029979345766,1.8289867921116718,1.832595714594046,114.0,496.9,624.4,1964.0,429.9,50.8 +0.5709550370071323,1.8290197110355317,1.9634954084936205,192.4,599.2,882.5,2413.6,250.5,31.5 +0.5709699931900025,1.8290367419556273,2.0943951023931953,349.8,849.9,1230.1,2747.9,161.2,33.9 +0.570959353646871,1.8290142886934675,2.2252947962927703,439.8,1701.1,1786.3,2427.7,106.2,47.4 +0.5709645463115035,1.8290340874342572,2.356194490192345,441.4,1751.1,1751.6,2320.8,70.3,70.9 +0.5711514381582679,1.829060775095223,2.4870941840919194,482.8,1787.2,1846.1,826.7,47.5,106.6 +0.5711508367004351,1.8290649493307178,2.6179938779914944,576.9,1977.2,2104.2,347.7,33.5,161.2 +0.5711282897709882,1.8290955195207288,2.748893571891069,757.4,2407.8,2627.2,192.2,32.3,252.3 +0.5708766112740429,1.8288508902175984,2.8797932657906435,1147.0,2796.2,2669.0,114.3,51.8,431.6 +0.570893805698639,1.8288424511771262,3.010692959690218,1763.9,2465.9,2408.0,68.7,151.9,461.6 +0.5708791033191414,1.7285855275429756,0.0,1621.3,2351.1,2350.7,140.8,471.0,471.0 +0.5709552954881931,1.7293058067253197,0.1308996938995747,1705.0,1347.8,532.4,129.0,461.7,521.1 +0.5709328098541059,1.7292982971329045,0.2617993877991494,1940.2,630.1,250.5,136.8,496.3,623.8 +0.5711227679533732,1.7288751720410798,0.39269908169872414,2430.9,392.2,173.0,173.6,598.5,819.3 +0.5711291394893557,1.7288840177214744,0.5235987755982988,2657.1,276.7,149.1,271.6,848.1,1227.3 +0.570846914951253,1.7290950336967665,0.6544984694978736,2385.9,210.1,151.0,482.6,1742.6,1683.5 +0.5708402900971323,1.72907006229472,0.7853981633974483,2321.4,170.9,170.4,440.8,1651.9,1651.4 +0.5708414659389957,1.7290719538273487,0.916297857297023,704.6,151.0,209.8,439.4,1683.3,1742.0 +0.5708516037574081,1.7290423300329198,1.0471975511965976,272.9,149.5,276.8,483.5,1859.5,1986.7 +0.5708736338529221,1.7290057800974712,1.1780972450961724,173.4,172.7,391.8,595.6,2262.2,2481.1 +0.5708638455726235,1.729014879921446,1.3089969389957472,136.7,250.2,495.8,869.4,2913.6,2670.3 +0.5708706716282883,1.7290119535441675,1.4398966328953218,129.2,520.3,461.9,1702.8,2465.3,2406.5 +0.5709361306473411,1.7289968445630364,1.5707963267948966,140.9,470.9,470.7,1620.8,2351.6,2351.0 +0.5709224554791141,1.728995903577145,1.7016960206944713,171.6,461.2,519.7,1660.6,1369.6,541.6 +0.5709124945500591,1.7289920504554175,1.832595714594046,229.6,496.7,624.4,1848.4,629.2,250.1 +0.5709629013315648,1.7290239980706128,1.9634954084936205,334.2,599.2,820.2,2272.1,391.7,172.6 +0.5709766299289339,1.7290397779618991,2.0943951023931953,483.3,849.8,1230.5,2747.9,276.7,149.5 +0.5709651709207672,1.7290159439689035,2.2252947962927703,439.7,1742.1,1683.2,2428.3,209.7,150.9 +0.5709699529377283,1.7290342920373547,2.356194490192345,441.5,1651.1,1651.5,2320.5,170.3,170.9 +0.5711661794658001,1.7290592084515861,2.4870941840919194,482.7,1683.2,1742.8,1212.2,151.0,210.1 +0.5711656458484835,1.729062846122,2.6179938779914944,576.9,1861.2,1989.0,546.9,149.1,276.8 +0.5711431802004691,1.7290931547316772,2.748893571891069,757.4,2266.1,2485.4,333.6,173.7,393.7 +0.5708839314333384,1.7288473091179255,2.8797932657906435,1147.1,2915.4,2669.1,229.9,251.3,496.1 +0.5709000030682027,1.7288394696770182,3.010692959690218,1660.8,2466.5,2407.7,172.2,520.4,461.5 +0.5708847449723776,1.628582452963712,0.0,1521.3,2351.3,2350.7,240.8,471.1,471.0 +0.5709578286402497,1.629304604149044,0.1308996938995747,1601.8,1731.3,916.3,232.7,461.6,521.0 +0.5709348391348599,1.6292969437390874,0.2617993877991494,1824.9,829.3,449.9,252.4,496.2,623.7 +0.5711251780463252,1.6288739349821248,0.39269908169872414,2289.6,533.4,314.1,315.3,795.9,819.4 +0.5711317767642242,1.6288830377966175,0.5235987755982988,2657.5,392.4,264.7,470.8,848.0,1227.1 +0.5708473119978269,1.6290950328299352,0.6544984694978736,2386.0,313.6,254.6,482.7,1638.8,1579.9 +0.5708406828480922,1.6290700444613557,0.7853981633974483,2321.1,270.9,270.4,440.9,1551.8,1551.3 +0.570841856508225,1.629071968382243,0.916297857297023,1091.8,254.5,313.3,439.4,1579.5,1638.6 +0.5708519799343129,1.6290423880069165,1.0471975511965976,472.4,265.0,392.3,483.5,1744.1,1871.3 +0.5708739839743381,1.6290058773673732,1.1780972450961724,315.1,313.8,532.9,771.0,2120.8,2340.1 +0.5708641625051544,1.6290150070290288,1.3089969389957472,252.3,449.5,495.8,869.3,2798.0,2670.1 +0.5708709512951177,1.629012099994573,1.4398966328953218,232.6,520.3,461.9,1599.4,2464.6,2406.5 +0.5709363717865288,1.628996999174878,1.5707963267948966,240.9,470.9,470.6,1521.1,2351.0,2351.4 +0.5709226608598676,1.6289960568011672,1.7016960206944713,275.1,461.2,519.6,1557.2,1759.2,1016.8 +0.5709126681223425,1.628992194457009,1.832595714594046,345.2,496.8,624.3,1732.6,828.5,449.3 +0.5709630482535184,1.629024125878219,1.9634954084936205,475.8,795.9,820.2,2129.9,532.8,313.8 +0.5709767568785006,1.6290398851420411,2.0943951023931953,483.2,893.8,1230.3,2785.1,392.3,265.0 +0.5709652845862058,1.6290160285136963,2.2252947962927703,439.8,1638.1,1579.7,2428.3,313.2,254.4 +0.5709700599109383,1.6290343528627589,2.356194490192345,441.4,1550.9,1551.5,2320.7,270.3,271.0 +0.5711641794479145,1.629059679514777,2.4870941840919194,482.8,1580.0,1639.1,1597.4,254.5,313.7 +0.5711636348155087,1.629063393075365,2.6179938779914944,576.9,1745.4,1873.0,746.1,264.7,392.4 +0.5711411715254169,1.6290937107588546,2.748893571891069,757.3,2125.0,2344.9,475.0,315.1,535.2 +0.5708829699782783,1.6288478874763004,2.8797932657906435,1147.3,2796.3,2668.9,345.4,450.9,496.0 +0.5709381434604213,1.6288229421004494,3.010692959690218,1557.5,2466.8,2407.9,275.7,520.4,461.5 +0.5708972108232659,1.5285924043507306,0.0,1421.3,2350.9,2351.0,340.8,471.0,471.0 +0.5709619764872343,1.5292975130071618,0.1308996938995747,1498.2,2115.1,1300.1,336.2,461.7,521.1 +0.5709376037755056,1.5292894361204932,0.2617993877991494,1709.0,1028.7,649.3,368.0,496.3,623.7 +0.570866708148878,1.5292417314558036,0.39269908169872414,2147.6,674.4,455.3,456.9,598.6,819.4 +0.570860420688985,1.529235914308257,0.5235987755982988,2657.4,507.9,380.2,576.3,848.0,1384.0 +0.5708544374514962,1.5292208969459775,0.6544984694978736,2386.4,417.2,358.1,482.7,1535.6,1476.5 +0.5708304110035479,1.529118423918121,0.7853981633974483,2321.1,370.8,370.3,440.8,1451.7,1451.2 +0.5708302761886025,1.529147788250593,0.916297857297023,1393.1,357.9,416.7,439.5,1476.2,1535.2 +0.5708403136603443,1.5291169896054635,1.0471975511965976,671.8,380.5,507.8,483.7,1628.6,1755.5 +0.5708669801914441,1.5290720921068717,1.1780972450961724,456.7,454.8,598.2,595.8,1980.2,2199.3 +0.5708651585506186,1.5290729243905705,1.3089969389957472,367.8,623.6,495.9,869.6,2772.1,2670.4 +0.5708819312166415,1.5290639565581374,1.4398966328953218,335.9,520.3,461.9,1496.1,2464.9,2406.6 +0.5709582198216636,1.5290457625502891,1.5707963267948966,340.8,471.0,470.8,1421.1,2351.8,2351.1 +0.570954953288872,1.5290446076609179,1.7016960206944713,378.5,461.2,519.7,1453.7,2148.1,1319.7 +0.5709544528684309,1.5290430912790847,1.832595714594046,460.7,496.7,624.6,1616.8,1027.4,648.4 +0.5710128654548277,1.5290796314337995,1.9634954084936205,596.7,685.8,820.3,1988.2,673.8,454.6 +0.571032559446513,1.5291015153120915,2.0943951023931953,483.3,849.9,1382.7,2747.8,507.7,380.4 +0.5710248717287026,1.5290845596874272,2.2252947962927703,439.7,1535.3,1476.2,2428.0,416.7,357.9 +0.5710209934416458,1.5290617200165717,2.356194490192345,441.5,1451.0,1451.7,2320.6,370.2,370.7 +0.5710080129467394,1.5293281161119965,2.4870941840919194,482.7,1476.3,1535.7,1982.7,358.0,417.2 +0.5707047675715183,1.52908253573831,2.6179938779914944,643.7,1629.6,1757.4,946.0,380.2,507.7 +0.5710807450764211,1.5291844383701947,2.748893571891069,757.7,1983.7,2203.6,616.3,456.5,597.1 +0.570888825406708,1.5289266283917078,2.8797932657906435,1146.9,2771.5,2668.8,461.0,623.5,496.1 +0.5709115100596956,1.5289151062523967,3.010692959690218,1453.7,2467.4,2407.8,379.3,520.4,461.6 +0.570889352778243,1.4286470415730839,0.0,1321.4,2350.7,2350.7,440.8,471.0,471.0 +0.5709607955694019,1.429306541201488,0.1308996938995747,1394.8,2408.7,1684.1,439.8,461.7,521.1 +0.5709371854485114,1.4292986805015957,0.2617993877991494,1593.6,1228.2,848.9,483.5,496.2,623.8 +0.5709038503304664,1.429277013606895,0.39269908169872414,2006.3,815.8,596.5,598.6,598.5,819.2 +0.570874844749654,1.429246769953434,0.5235987755982988,2657.5,623.5,495.8,576.3,848.0,1373.1 +0.5708647260141791,1.429223916909899,0.6544984694978736,2386.4,520.6,461.5,482.6,1431.7,1372.6 +0.5708530341218899,1.4291779534675852,0.7853981633974483,2320.8,470.7,470.4,440.8,1351.7,1351.2 +0.570854350555259,1.4291681317183975,0.916297857297023,1780.3,461.4,520.3,439.5,1373.0,1431.6 +0.5708664919422255,1.4291305626687265,1.0471975511965976,871.6,496.1,623.4,483.6,1513.0,1640.3 +0.5708916669111314,1.4290880325336375,1.1780972450961724,598.4,596.0,598.1,595.7,1839.1,2057.9 +0.5708858092709456,1.4290926358683984,1.3089969389957472,483.4,623.3,495.9,869.6,2602.9,2739.1 +0.5708971844202526,1.429086548944519,1.4398966328953218,439.4,520.2,461.9,1392.6,2464.5,2406.2 +0.5709675702679441,1.42906968054737,1.5707963267948966,440.8,471.0,470.8,1321.1,2351.5,2351.0 +0.570958702817196,1.4290683213644688,1.7016960206944713,481.9,461.2,519.7,1350.4,2407.3,1709.5 +0.5709084219259141,1.4292067121311132,1.832595714594046,576.4,496.8,624.4,1501.2,1227.3,848.2 +0.5711108565410827,1.4293361070827593,1.9634954084936205,596.7,599.1,820.0,1845.8,846.5,596.1 +0.5713324707880758,1.4288892503653363,2.0943951023931953,483.3,849.8,1372.0,2628.3,623.5,496.2 +0.5709162435742914,1.4290884171168852,2.2252947962927703,439.8,1431.5,1372.6,2428.5,520.3,461.5 +0.5709144864701989,1.4290798877584923,2.356194490192345,441.6,1351.1,1351.6,2320.6,470.4,470.9 +0.571193114718247,1.4290709694924955,2.4870941840919194,482.7,1373.1,1431.8,2386.4,461.7,520.8 +0.5711947524943158,1.4290668657052332,2.6179938779914944,576.9,1514.5,1641.8,1188.4,496.1,623.6 +0.5711733726686148,1.4290952029388873,2.748893571891069,757.4,1841.7,2061.7,758.0,598.0,597.3 +0.5708969212248125,1.4288432266609585,2.8797932657906435,1229.1,2605.1,2741.1,576.6,623.4,496.0 +0.5709109116968226,1.428836490993326,3.010692959690218,1350.3,2466.4,2407.2,482.8,520.4,461.6 +0.5708944376777487,1.3285791396849667,0.0,1221.0,2350.6,2351.0,540.8,471.0,470.9 +0.5709623075589185,1.3293026600329092,0.1308996938995747,1290.9,2409.0,2068.1,543.3,461.6,521.1 +0.5709384587665698,1.3292947424187154,0.2617993877991494,1478.1,1427.6,1048.2,599.2,496.3,649.2 +0.5709054012523983,1.32927326185547,0.39269908169872414,1864.1,956.8,737.6,740.2,598.5,819.3 +0.5708767221737094,1.3292433824917627,0.5235987755982988,2657.0,739.1,611.5,576.3,847.9,1227.0 +0.5708668338722055,1.3292209780027813,0.6544984694978736,2386.1,624.1,565.1,482.7,1328.6,1269.6 +0.570855247664933,1.329175494138279,0.7853981633974483,2321.0,570.8,570.2,440.8,1251.7,1251.1 +0.5708565461578046,1.3291661286693062,0.916297857297023,2167.0,564.9,623.7,439.4,1269.4,1328.1 +0.5708685627448051,1.3291289686408798,1.0471975511965976,1071.1,611.5,738.9,483.6,1397.4,1524.5 +0.570893530160066,1.32908677733178,1.1780972450961724,740.1,737.2,598.2,626.8,1697.9,1916.7 +0.5708874113029653,1.3290916336454868,1.3089969389957472,599.0,623.4,495.8,869.5,2403.9,2669.9 +0.5708984917146726,1.329085713151549,1.4398966328953218,543.0,520.4,461.9,1289.2,2464.2,2406.3 +0.5709685697492608,1.3290689267612326,1.5707963267948966,540.8,470.9,470.6,1221.3,2350.8,2350.9 +0.5709594112659184,1.3290675698434953,1.7016960206944713,585.3,461.2,519.8,1246.9,2407.1,2099.1 +0.5709536493325827,1.3290644691431928,1.832595714594046,691.9,602.1,624.4,1386.0,1425.9,1046.8 +0.5710076779781231,1.3290982609038242,1.9634954084936205,596.7,599.3,820.4,1705.0,955.9,736.9 +0.5710241315881311,1.3291166586949463,2.0943951023931953,483.2,850.0,1230.2,2429.6,738.8,611.4 +0.5710143793065094,1.3290958657519294,2.2252947962927703,439.7,1328.1,1269.2,2428.2,623.6,564.9 +0.5710198125142317,1.3291174305523823,2.356194490192345,441.6,1251.2,1251.8,2320.8,570.2,570.8 +0.5710169458292136,1.3291467860375146,2.4870941840919194,482.7,1269.5,1328.6,2386.5,565.2,624.2 +0.5710208913270615,1.3291367869516502,2.6179938779914944,576.8,1398.8,1526.7,1343.5,611.5,739.2 +0.5710078562276544,1.3291521470466177,2.748893571891069,757.3,1700.5,1921.0,899.1,739.4,597.2 +0.5708258436693835,1.3289113527850454,2.8797932657906435,1233.7,2403.8,2669.4,692.2,623.7,496.1 +0.5708514301998613,1.3288983366682974,3.010692959690218,1246.9,2466.3,2407.7,586.3,520.5,461.6 +0.5708373953440382,1.228637560060832,0.0,1121.1,2351.2,2351.1,640.7,471.0,470.9 +0.5709551067638597,1.2292982244462551,0.1308996938995747,1187.4,2408.9,2468.3,646.9,461.7,521.1 +0.5709249946052073,1.2292882795956714,0.2617993877991494,1362.5,1627.0,1247.4,714.7,496.2,623.7 +0.5708912039149284,1.229266272221875,0.39269908169872414,1722.7,1098.0,878.7,755.8,598.6,819.4 +0.5708631616440024,1.2292369649196475,0.5235987755982988,2501.6,854.7,727.1,576.4,848.0,1227.1 +0.5708539714978526,1.2292156717843845,0.6544984694978736,2386.0,727.7,668.7,482.7,1225.1,1165.9 +0.5708428168193218,1.229171550197884,0.7853981633974483,2321.1,670.8,670.2,440.9,1151.7,1151.4 +0.5708441809684685,1.2291635564875492,0.916297857297023,2428.4,668.5,727.3,439.5,1165.8,1224.5 +0.5708559207560823,1.2291276802330464,1.0471975511965976,1270.7,727.1,850.0,483.6,1281.7,1409.1 +0.5708803257017278,1.2290865997514424,1.1780972450961724,881.7,819.0,598.2,595.8,1556.9,1776.1 +0.5708734310337992,1.229092303031574,1.3089969389957472,714.7,623.4,495.7,869.4,2204.1,2584.3 +0.570883591312721,1.2290869380915634,1.4398966328953218,646.4,520.4,461.8,1185.5,2464.7,2406.3 +0.5709526856047556,1.229070429938694,1.5707963267948966,640.8,470.9,470.7,1121.2,2351.3,2351.2 +0.5709425914479479,1.229069057599154,1.7016960206944713,688.9,461.2,519.7,1143.1,2407.1,2465.4 +0.5709360033997334,1.2290656777649263,1.832595714594046,807.5,496.7,624.5,1270.2,1625.0,1246.0 +0.5709893612413199,1.2290989992500179,1.9634954084936205,596.5,599.2,820.4,1563.3,1097.1,877.9 +0.571005350300206,1.2291168096970178,2.0943951023931953,483.2,850.0,1230.2,2230.3,854.1,726.9 +0.5709953583674608,1.2290953702246652,2.2252947962927703,439.8,1224.7,1165.7,2428.1,727.2,668.4 +0.571000752218814,1.229116297679823,2.356194490192345,441.5,1151.1,1151.9,2320.0,670.3,670.8 +0.5709980080523668,1.229145090372685,2.4870941840919194,482.8,1165.9,1225.2,2386.8,668.7,727.8 +0.5710022115362187,1.2291346289778726,2.6179938779914944,576.9,1283.2,1411.1,1542.8,727.1,848.1 +0.5709894967146834,1.22914965169483,2.748893571891069,757.4,1559.4,1779.3,1040.5,817.1,597.2 +0.5708181787127877,1.2289140015318365,2.8797932657906435,1146.1,2203.8,2583.3,807.9,623.6,496.1 +0.5708448938212792,1.2289003833831638,3.010692959690218,1143.2,2466.9,2408.3,689.9,520.4,461.6 +0.5708315490841225,1.1286398123592876,0.0,1021.1,2350.9,2350.9,740.8,471.0,470.9 +0.5709355972041673,1.1293187232026973,0.1308996938995747,1083.9,2409.4,2468.2,750.6,461.6,521.0 +0.5709173039131987,1.1293124639555316,0.2617993877991494,1247.2,1826.1,1446.6,830.3,496.3,623.7 +0.571119207950172,1.1288746071944862,0.39269908169872414,1580.8,1239.3,1051.1,756.0,598.6,819.3 +0.5711260183870013,1.1288839087161817,0.5235987755982988,2302.3,970.4,842.9,576.4,1023.8,1167.1 +0.5708462734268878,1.129094464314451,0.6544984694978736,2386.4,831.3,772.3,482.6,1121.4,1062.2 +0.5708396869877591,1.1290696554333994,0.7853981633974483,2320.7,770.8,770.3,440.8,1051.5,1051.2 +0.5708408641974129,1.1290715498920796,0.916297857297023,2428.4,772.1,830.8,439.4,1062.2,1121.2 +0.5708510175619707,1.1290418826120368,1.0471975511965976,1470.4,842.8,849.9,509.0,1166.0,1293.7 +0.5708730813186266,1.1290052860026107,1.1780972450961724,1023.5,819.0,598.2,595.8,1415.2,1634.3 +0.5708633372323642,1.1290143485262933,1.3089969389957472,830.3,623.4,495.8,1001.6,2004.5,2384.1 +0.5708702130551653,1.1290113977332532,1.4398966328953218,750.0,520.3,461.9,1082.2,2464.8,2406.3 +0.5709357231198986,1.1289962809950531,1.5707963267948966,740.9,470.8,470.7,1021.3,2351.3,2351.3 +0.57093476040301,1.1291953786820828,1.7016960206944713,792.5,461.3,519.6,1039.5,2406.9,2465.8 +0.5709017279650053,1.1291843176948246,1.832595714594046,870.2,522.3,624.5,1154.4,1824.0,1445.3 +0.5709234667121256,1.1291981260978852,1.9634954084936205,596.6,599.3,820.4,1421.4,1238.1,1019.1 +0.5709135050336418,1.1291883938326377,2.0943951023931953,483.2,1047.8,1165.9,2030.9,969.8,842.6 +0.5708865093098724,1.1291353251465424,2.2252947962927703,439.8,1121.0,1062.3,2428.0,830.6,771.9 +0.5708842164174625,1.129123166331144,2.356194490192345,441.6,1051.2,1051.8,2320.3,770.4,770.9 +0.5711963048162797,1.1291081982449254,2.4870941840919194,482.9,1062.2,1121.6,2386.4,772.3,831.4 +0.5711982432007072,1.129103084128689,2.6179938779914944,577.0,1167.6,1295.3,1741.5,842.9,848.0 +0.5711765653926784,1.1291315193292268,2.748893571891069,757.7,1417.7,1638.2,1181.6,817.0,597.2 +0.5708955950598186,1.1288543650109528,2.8797932657906435,1128.1,2005.9,2386.2,923.3,623.5,496.0 +0.5709116237538863,1.1288465218931845,3.010692959690218,1039.7,2466.5,2407.8,793.3,520.4,461.5 +0.670976269824446,1.829051038502581,0.0,1721.0,2251.3,2251.2,41.0,571.0,571.0 +0.670988051480694,1.8289343994505607,0.1308996938995747,1808.5,964.9,148.9,25.5,565.3,624.6 +0.6709881327649007,1.828934417215431,0.2617993877991494,2055.8,430.9,51.3,21.3,611.8,739.2 +0.6709777440390003,1.829006688446965,0.39269908169872414,2572.5,251.1,31.8,32.0,740.0,960.8 +0.6709803729235737,1.8290106811299607,0.5235987755982988,2542.2,161.2,33.5,72.2,1046.9,1426.0 +0.6709885038834534,1.8290229384095673,0.6544984694978736,2282.9,106.6,47.5,231.4,1846.1,1787.1 +0.6709846396200229,1.8290118758963154,0.7853981633974483,2220.8,70.9,70.4,540.8,1751.6,1751.0 +0.6707929771677344,1.8290425318132884,0.916297857297023,232.3,47.5,106.3,543.0,1786.8,1845.7 +0.6708031891008726,1.8290128235297014,1.0471975511965976,73.2,34.0,161.3,599.0,1975.0,2102.3 +0.6708284079310698,1.8289714656265883,1.1780972450961724,31.7,31.5,250.7,736.7,2403.5,2622.4 +0.6708238508085238,1.8289758871495772,1.3089969389957472,21.1,50.9,430.2,1068.7,2683.0,2554.4 +0.6708370097163495,1.828969765205853,1.4398966328953218,25.7,152.2,565.3,1806.1,2361.2,2302.9 +0.6709091501810112,1.8289532746743027,1.5707963267948966,40.9,570.9,570.6,1721.1,2251.3,2251.3 +0.670901718692408,1.8289526656985915,1.7016960206944713,68.2,564.7,623.0,1763.9,980.4,152.0 +0.6708972769322713,1.8289505853771728,1.832595714594046,113.9,612.3,740.0,1963.8,430.0,50.9 +0.6709522626428399,1.8289854634010339,1.9634954084936205,192.4,741.0,961.8,2413.1,250.6,31.5 +0.6709693854838183,1.8290048970020352,2.0943951023931953,349.9,1049.5,1429.9,2632.4,161.2,34.0 +0.6709601097655404,1.8289850755638057,2.2252947962927703,543.2,1845.6,1786.7,2324.8,106.2,47.5 +0.6709659303270178,1.829007564654576,2.356194490192345,541.5,1751.2,1751.6,2220.2,70.3,70.9 +0.6709634060212801,1.8290378417605173,2.4870941840919194,586.3,1787.2,1846.3,911.6,47.5,106.6 +0.6709675961849065,1.8290288322144885,2.6179938779914944,692.4,1976.8,2104.4,347.9,33.5,161.2 +0.6709546810030796,1.8289117927655423,2.748893571891069,898.8,2407.3,2627.5,192.2,32.3,252.3 +0.6708332269451347,1.8288568442241533,2.8797932657906435,1345.8,2681.9,2554.2,114.3,51.7,431.3 +0.6708530370667162,1.82884707089799,3.010692959690218,1764.2,2363.1,2304.7,68.7,151.6,565.0 +0.6708417889018321,1.7285908539885466,0.0,1621.3,2250.6,2251.0,140.8,571.0,571.0 +0.6709396491275403,1.72931452524092,0.1308996938995747,1705.0,1347.3,616.7,129.1,565.4,624.6 +0.6709205615460919,1.7293080378113765,0.2617993877991494,1940.2,630.0,250.5,136.8,611.8,739.3 +0.6708873433816291,1.729286382185612,0.39269908169872414,2431.1,392.2,172.9,173.6,937.2,961.0 +0.6708575304463599,1.7292551607080477,0.5235987755982988,2542.0,276.7,149.0,271.4,1047.3,1590.0 +0.6708467115866099,1.7292308466985238,0.6544984694978736,2282.8,210.0,151.0,586.1,1742.5,1683.6 +0.670834743666931,1.7291832763437587,0.7853981633974483,2221.6,170.8,170.3,540.8,1651.8,1651.5 +0.6708361807246358,1.7291719011784783,0.916297857297023,618.8,150.9,209.7,543.0,1683.3,1742.0 +0.6708488094964065,1.7291329548884353,1.0471975511965976,272.6,149.4,276.7,599.1,1859.5,1986.7 +0.670874756172005,1.7290893370356692,1.1780972450961724,173.2,172.5,391.7,912.8,2262.6,2482.0 +0.6708698156701526,1.7290931344042844,1.3089969389957472,136.6,250.0,611.4,1068.9,2682.2,2554.3 +0.6708821929854257,1.729086507647009,1.4398966328953218,129.1,541.8,565.5,1702.8,2361.1,2302.8 +0.6709536103188699,1.7290694269716205,1.5707963267948966,140.8,570.8,570.6,1621.3,2251.4,2251.1 +0.6709457006382915,1.7290680838694925,1.7016960206944713,171.6,564.8,623.1,1660.4,1368.9,540.9 +0.6709410700326255,1.7290652423782464,1.832595714594046,229.5,612.4,740.0,1848.6,628.8,249.8 +0.670996062611662,1.7290995598774288,1.9634954084936205,334.1,937.0,962.1,2271.9,391.4,172.5 +0.6710132570747831,1.7291186603090407,2.0943951023931953,549.5,1049.8,1588.2,2632.5,276.6,149.4 +0.6710040317307421,1.7290986410559286,2.2252947962927703,543.3,1742.1,1683.4,2324.9,209.6,150.9 +0.671009757473991,1.729121041028216,2.356194490192345,541.4,1651.0,1651.8,2220.0,170.2,170.8 +0.6710069298564534,1.7291512429184346,2.4870941840919194,586.2,1683.6,1742.9,1211.3,150.9,210.0 +0.67101073130848,1.729141997968656,2.6179938779914944,692.5,1861.2,1989.1,546.7,149.0,276.7 +0.6709973321494203,1.7291580173476477,2.748893571891069,898.8,2266.3,2486.6,333.4,173.6,393.7 +0.6708195387949145,1.7289154629257277,2.8797932657906435,1345.6,2681.5,2554.4,229.9,251.0,611.7 +0.6708460962982812,1.72890192253875,3.010692959690218,1661.0,2363.7,2304.6,172.3,537.7,565.1 +0.6708324715571657,1.6286411814882165,0.0,1521.4,2251.0,2251.3,240.8,571.0,570.8 +0.6709360839137146,1.6293185975784685,0.1308996938995747,1602.1,1731.2,1000.5,232.7,565.3,624.7 +0.6709177066825365,1.629312313095797,0.2617993877991494,1824.8,829.3,449.9,252.4,611.8,739.4 +0.6708842753073335,1.6292905070111183,0.39269908169872414,2289.1,533.2,314.0,315.2,740.3,961.0 +0.6708541037297923,1.629258877239657,0.5235987755982988,2541.8,392.2,264.6,470.6,1047.2,1499.7 +0.6708430169028442,1.6292340312450273,0.6544984694978736,2283.1,313.5,254.5,586.2,1639.0,1580.0 +0.6708309307302986,1.629185886678757,0.7853981633974483,2220.8,270.8,270.3,540.9,1551.6,1551.3 +0.6708289343822674,1.629215723732073,0.916297857297023,1006.0,254.4,313.2,543.1,1579.7,1638.7 +0.6708501845763606,1.6291486479853057,1.0471975511965976,472.2,264.9,392.2,599.1,1744.3,1871.5 +0.6711264603209339,1.6291678489180819,1.1780972450961724,314.8,313.9,533.3,737.4,2122.5,2341.9 +0.6709448505711025,1.629334396870671,1.3089969389957472,252.3,450.0,611.5,1069.8,2760.3,2553.3 +0.6707847986493713,1.6288596633446215,1.4398966328953218,232.6,623.6,565.4,1599.1,2361.4,2302.9 +0.6710485401836007,1.6288013910481116,1.5707963267948966,240.9,570.8,570.5,1521.1,2251.4,2250.9 +0.6709774828643877,1.6292332535744398,1.7016960206944713,275.2,564.7,623.2,1557.1,1756.7,929.8 +0.6707366416414551,1.6291570829575717,1.832595714594046,345.3,612.6,820.0,1733.2,827.8,449.0 +0.671107260666683,1.6287954710641837,1.9634954084936205,476.0,826.7,962.2,2130.2,532.8,313.8 +0.6712763092752205,1.6289816300320747,2.0943951023931953,598.8,1049.8,1474.0,2773.1,392.3,265.1 +0.6708138190310475,1.6291402083593876,2.2252947962927703,543.2,1638.5,1579.4,2324.7,313.2,254.5 +0.6708055350819342,1.629101421632918,2.356194490192345,541.6,1551.4,1551.6,2220.8,270.3,270.9 +0.6711593693270026,1.629119912924415,2.4870941840919194,586.3,1580.2,1639.1,1598.1,254.5,313.7 +0.6711677711750902,1.6290938906471748,2.6179938779914944,842.6,1745.4,1873.2,746.3,264.7,392.4 +0.6711509984760754,1.6291149496339072,2.748893571891069,899.0,2124.6,2344.8,475.0,315.1,535.1 +0.6708859537943307,1.6288571282693474,2.8797932657906435,1485.7,2760.2,2553.2,345.4,450.9,611.7 +0.6709021995045688,1.628849170542915,3.010692959690218,1557.1,2363.2,2304.1,275.8,623.9,565.1 +0.6708858584086825,1.5285908521962348,0.0,1421.4,2251.0,2251.2,340.8,571.0,571.0 +0.6709586536579926,1.5293048891933578,0.1308996938995747,1498.0,2115.7,1300.3,336.2,565.4,624.7 +0.6709355476506825,1.5292971928439014,0.2617993877991494,1709.3,1028.7,649.3,368.0,611.9,739.4 +0.670902429053326,1.529275661443882,0.39269908169872414,2147.4,674.5,455.3,456.8,740.1,961.1 +0.6708735372171875,1.5292455331782884,0.5235987755982988,2541.8,507.8,380.3,669.7,1047.2,1426.2 +0.6708634791238568,1.5292227835331123,0.6544984694978736,2282.8,417.1,358.1,586.2,1535.7,1476.6 +0.6708518221993176,1.5291769241922533,0.7853981633974483,2221.0,370.8,370.3,540.8,1451.8,1451.1 +0.6708531440081579,1.5291671975665193,0.916297857297023,1393.1,357.9,416.8,543.0,1476.3,1535.2 +0.670865269001637,1.5291297162595598,1.0471975511965976,671.9,380.5,507.8,599.1,1628.8,1755.7 +0.6708904107997463,1.5290872672545897,1.1780972450961724,456.7,454.8,674.1,736.9,1980.3,2199.5 +0.6708845030916383,1.5290919319755825,1.3089969389957472,367.8,648.6,611.4,1068.9,2681.9,2554.6 +0.6708958166139463,1.5290858839299597,1.4398966328953218,336.0,623.7,565.4,1496.1,2361.7,2302.8 +0.6709661355347533,1.5290690433406355,1.5707963267948966,340.8,570.9,570.7,1421.2,2251.2,2251.0 +0.6709572022716075,1.5290676885126835,1.7016960206944713,378.5,564.6,623.2,1453.5,2147.8,1319.8 +0.67095164425143,1.5290646353621264,1.832595714594046,460.8,612.5,740.1,1616.8,1027.1,648.3 +0.6710058463033753,1.5290985222744071,1.9634954084936205,617.6,741.0,962.0,1988.2,673.8,454.7 +0.6710224329707476,1.529117046970954,2.0943951023931953,598.7,1049.8,1430.0,2632.9,507.7,380.4 +0.6710127744279561,1.52909639442911,2.2252947962927703,543.4,1535.2,1476.3,2324.8,416.7,357.9 +0.6710182587456963,1.5291181101326132,2.356194490192345,541.5,1451.3,1451.7,2220.9,370.3,370.8 +0.6710153978904607,1.5291476175350667,2.4870941840919194,586.2,1476.4,1535.9,1982.5,358.0,417.2 +0.671019315739671,1.5291377537743984,2.6179938779914944,692.5,1630.2,1757.7,944.9,380.2,507.9 +0.6710062146976304,1.5291532312373946,2.748893571891069,898.8,1983.8,2203.6,616.4,456.4,676.4 +0.6708248094052351,1.5289120783165118,2.8797932657906435,1474.9,2681.6,2554.2,461.1,649.7,611.7 +0.6708505499990415,1.5288989787972131,3.010692959690218,1453.7,2363.3,2304.4,379.3,624.0,565.0 +0.6708365800404037,1.4286382095425576,0.0,1321.3,2250.5,2251.3,440.8,571.0,570.8 +0.6709378903048852,1.4293176464994475,0.1308996938995747,1394.4,2305.7,1683.6,439.8,565.2,624.7 +0.6709191442926914,1.4293112518097675,0.2617993877991494,1593.7,1228.0,848.7,483.6,611.9,739.4 +0.67088572401706,1.4292894590020992,0.39269908169872414,2006.1,815.6,596.3,598.6,740.1,961.1 +0.6708556386390304,1.4292579322147343,0.5235987755982988,2657.6,623.5,495.8,691.9,1047.2,1426.8 +0.6708446226732375,1.4292332328227366,0.6544984694978736,2282.7,520.6,461.6,586.1,1431.8,1373.0 +0.6708325651042731,1.4291852481601057,0.7853981633974483,2221.2,470.8,470.4,540.8,1351.6,1351.2 +0.6708340190896229,1.4291734777993106,0.916297857297023,1779.8,461.4,520.3,543.0,1372.9,1431.6 +0.6708467575658796,1.4291341775711484,1.0471975511965976,871.6,496.1,623.4,764.9,1512.9,1640.2 +0.6708728857789182,1.4290902678141149,1.1780972450961724,598.3,596.0,739.8,767.9,1839.0,2058.4 +0.6708681725736455,1.4290938474759272,1.3089969389957472,483.4,738.9,611.4,1068.8,2603.2,2554.8 +0.6708808054833563,1.4290870775416078,1.4398966328953218,439.5,623.7,565.4,1392.5,2360.7,2303.1 +0.6709524891129376,1.4290699278263546,1.5707963267948966,440.8,570.9,570.7,1321.2,2251.4,2251.1 +0.6709448308173533,1.429068583777959,1.7016960206944713,482.0,564.6,623.2,1350.2,2303.8,1709.1 +0.6709404268851274,1.4290658003404488,1.832595714594046,576.4,612.3,740.1,1501.7,1226.4,847.3 +0.6709956119030639,1.429100226251919,1.9634954084936205,737.6,740.9,962.2,1846.8,814.6,595.8 +0.6710129525357751,1.4291194692516598,2.0943951023931953,598.7,1049.9,1430.1,2630.1,623.1,496.0 +0.6710038235430889,1.4290996118094395,2.2252947962927703,543.3,1431.6,1372.7,2324.4,520.2,461.3 +0.6710095959895305,1.4291221825230682,2.356194490192345,541.6,1351.3,1351.6,2220.8,470.2,470.8 +0.6710067672761614,1.429152549762046,2.4870941840919194,586.3,1373.3,1432.2,2282.9,461.5,520.8 +0.6710105265937014,1.4291434512582486,2.6179938779914944,692.4,1514.4,1642.0,1143.9,495.8,623.6 +0.6709970516458211,1.4291595913521502,2.748893571891069,898.9,1842.2,2062.4,757.9,597.9,738.5 +0.6708188866677631,1.4289163056482996,2.8797932657906435,1345.3,2602.5,2558.4,576.7,739.3,611.8 +0.6708454811231991,1.4289027432820218,3.010692959690218,1350.6,2363.5,2304.4,482.9,624.1,565.0 +0.6708318496695684,1.3286419885660825,0.0,1221.2,2251.1,2251.1,540.7,571.0,570.8 +0.6709358578146783,1.3293187661003592,0.1308996938995747,1290.8,2305.1,2067.4,543.4,565.4,624.7 +0.6709175353455954,1.3293124981729694,0.2617993877991494,1478.2,1427.2,1048.1,599.1,611.9,739.4 +0.6708840960050451,1.3292906865518765,0.39269908169872414,1864.2,956.7,737.5,740.3,740.2,960.9 +0.6708539050608733,1.3292590350588545,0.5235987755982988,2541.9,739.1,611.4,691.9,1047.2,1398.3 +0.6708428031319048,1.329234159504702,0.6544984694978736,2282.6,624.2,565.1,586.1,1328.3,1269.5 +0.6708307101891176,1.3291859826120769,0.7853981633974483,2221.1,570.8,570.2,540.8,1251.8,1251.3 +0.6708321767643318,1.329174027201607,0.916297857297023,2166.9,565.0,623.7,543.1,1269.4,1328.1 +0.6708449714122869,1.3291345624602597,1.0471975511965976,1070.8,611.6,738.9,599.0,1397.3,1525.0 +0.6708711895791203,1.3290905211618531,1.1780972450961724,739.9,737.1,739.8,736.8,1697.8,1917.0 +0.6708665847624155,1.3290940031393133,1.3089969389957472,599.0,739.1,611.4,1232.8,2404.0,2554.5 +0.6708793370643221,1.3290871680547829,1.4398966328953218,542.8,623.8,565.3,1289.1,2361.1,2302.6 +0.6709511440488676,1.3290699910076795,1.5707963267948966,540.8,570.9,570.7,1221.2,2251.3,2250.8 +0.6709436008418376,1.3290686481201985,1.7016960206944713,585.4,564.8,623.1,1246.5,2304.0,2098.8 +0.6709393011735267,1.3290658886188886,1.832595714594046,692.0,612.4,740.2,1386.0,1425.5,1046.6 +0.6709945750300207,1.329100362998886,1.9634954084936205,737.8,741.1,962.2,1705.0,955.9,736.7 +0.6710119839138309,1.3291196707712298,2.0943951023931953,598.7,1049.9,1397.2,2430.3,738.6,611.4 +0.6710029033354867,1.3290998847413016,2.2252947962927703,543.3,1328.1,1269.2,2324.6,623.6,564.9 +0.6710087025354629,1.3291225324836922,2.356194490192345,541.5,1251.1,1251.8,2220.5,570.2,570.8 +0.6710058772437005,1.3291529776585667,2.4870941840919194,586.3,1269.5,1328.7,2283.6,565.2,624.2 +0.6710096230249133,1.3291439485614105,2.6179938779914944,692.6,1399.1,1526.2,1343.2,611.5,739.3 +0.6709961144298354,1.3291601491910834,2.748893571891069,898.9,1700.5,1920.7,899.0,739.4,738.6 +0.6708183133656771,1.3289166900791378,2.8797932657906435,1385.0,2403.2,2553.9,692.4,739.3,611.7 +0.6708449949286793,1.3289030806269855,3.010692959690218,1246.9,2363.5,2304.5,586.4,624.1,565.2 +0.6708313994320415,1.228642328386073,0.0,1121.3,2251.3,2251.1,640.7,571.0,570.8 +0.6709356630212396,1.2293188712301584,0.1308996938995747,1187.3,2305.1,2365.2,647.0,565.3,624.6 +0.6709173793418602,1.2293126149186633,0.2617993877991494,1362.5,1626.7,1247.4,714.8,611.7,739.5 +0.6708839374622695,1.229290801070618,0.39269908169872414,1723.0,1098.0,878.7,881.8,740.2,961.1 +0.6708537360753907,1.2292591372892867,0.5235987755982988,2502.1,854.7,727.0,691.9,1164.8,1282.8 +0.6708426257298985,1.22923424454331,0.6544984694978736,2282.5,727.6,668.7,586.2,1224.9,1166.0 +0.6708305293426085,1.2291860489489297,0.7853981633974483,2221.1,670.7,670.2,540.9,1152.0,1151.3 +0.6708319971363894,1.229174075532838,0.916297857297023,2324.8,668.4,727.4,542.9,1165.7,1224.5 +0.6708447972488814,1.229134594793916,1.0471975511965976,1270.6,727.2,854.3,599.1,1281.6,1409.5 +0.670871024177843,1.229090540728943,1.1780972450961724,881.8,878.3,739.8,736.8,1556.8,1775.9 +0.6708664299160881,1.2290940132225603,1.3089969389957472,714.7,738.9,611.5,1112.7,2204.6,2554.1 +0.6708791938333157,1.2290871718126466,1.4398966328953218,646.4,623.6,565.3,1185.7,2360.8,2302.8 +0.6709510128022326,1.229069992151862,1.5707963267948966,640.8,570.9,570.7,1121.2,2251.6,2250.7 +0.6709434807774162,1.229068649412071,1.7016960206944713,689.0,587.4,623.2,1143.4,2303.5,2362.2 +0.6709391912336551,1.2290658922490298,1.832595714594046,807.6,612.4,740.0,1270.3,1624.9,1246.0 +0.6709944736927617,1.2291003713503108,1.9634954084936205,737.6,741.0,962.1,1563.2,1096.9,878.0 +0.6710118891762126,1.2291196854280677,2.0943951023931953,598.7,1137.9,1281.4,2230.4,854.3,726.9 +0.6710028132885094,1.229099906331036,2.2252947962927703,543.3,1224.4,1165.7,2324.7,727.2,668.3 +0.6710086150821748,1.229122561537003,2.356194490192345,541.5,1151.1,1151.8,2221.0,670.2,670.7 +0.6710057901194729,1.2291530142677356,2.4870941840919194,586.3,1165.6,1225.0,2283.0,668.7,727.7 +0.6710095346051829,1.2291439918990368,2.6179938779914944,692.4,1283.3,1411.0,1542.3,727.1,854.8 +0.6709960227556839,1.2291601984099207,2.748893571891069,898.8,1559.0,1779.4,1040.5,880.8,738.6 +0.6708182581841835,1.2289167253123834,2.8797932657906435,1269.4,2203.9,2554.3,807.9,739.2,611.7 +0.6708449485637727,1.2289031111043678,3.010692959690218,1143.3,2363.5,2304.8,689.9,624.0,565.0 +0.6708313568621486,1.1286423593285777,0.0,1021.2,2251.3,2251.0,740.9,570.9,570.9 +0.6709356456431231,1.1293188817991076,0.1308996938995747,1083.7,2305.1,2364.9,750.6,565.3,624.7 +0.6709173642815027,1.1293126261889546,0.2617993877991494,1246.8,1826.4,1446.6,830.5,611.8,739.3 +0.6708839212787804,1.1292908116027092,0.39269908169872414,1581.0,1238.9,1019.9,896.8,740.2,960.9 +0.670853718302825,1.1292591460390513,0.5235987755982988,2302.0,970.3,842.7,692.0,1153.9,1167.3 +0.6708426067807571,1.1292342509937157,0.6544984694978736,2282.7,831.4,772.3,586.1,1121.3,1062.1 +0.670830509899825,1.1291860529422526,0.7853981633974483,2221.1,770.8,770.3,540.8,1051.7,1051.4 +0.6708319778223271,1.129174077162598,0.916297857297023,2325.1,771.9,830.8,543.1,1062.2,1121.2 +0.6708447786270463,1.129134594324635,1.0471975511965976,1469.9,842.8,970.0,599.2,1166.2,1293.6 +0.6708710066904787,1.1290905385819254,1.1780972450961724,1023.6,960.5,739.9,736.9,1415.5,1634.9 +0.6708664138169723,1.1290940098274644,1.3089969389957472,830.3,739.1,611.5,1068.8,2005.5,2384.8 +0.6708791792643068,1.1290871675960572,1.4398966328953218,749.9,623.7,565.4,1082.1,2361.2,2302.5 +0.6709509997994876,1.129069987609508,1.5707963267948966,740.8,570.9,570.7,1021.1,2251.3,2251.2 +0.6709434692433108,1.129068644918178,1.7016960206944713,792.3,564.7,623.2,1039.7,2303.9,2362.2 +0.6709391810178705,1.1290658880978488,1.832595714594046,923.3,612.4,740.1,1154.7,1823.8,1445.1 +0.6709944645712763,1.1291003678401905,1.9634954084936205,737.5,741.0,962.1,1421.1,1237.9,1019.1 +0.6710118808805933,1.1291196827594012,2.0943951023931953,598.7,1152.4,1166.1,2030.9,969.5,842.6 +0.6710028055668544,1.1290999045834933,2.2252947962927703,543.2,1120.8,1062.2,2324.4,830.5,772.0 +0.6710086076620152,1.1291225607551887,2.356194490192345,541.4,1051.3,1051.7,2220.3,770.3,770.9 +0.6710057827187702,1.1291530144453947,2.4870941840919194,586.2,1062.3,1121.5,2283.1,772.1,831.4 +0.6710095270206001,1.1291439929310154,2.6179938779914944,692.5,1167.5,1295.2,1741.5,842.8,970.5 +0.6709960147586306,1.1291602001815377,2.748893571891069,898.9,1417.9,1637.9,1181.9,958.4,738.7 +0.6708182530488767,1.1289167276434569,2.8797932657906435,1153.7,2004.3,2384.1,923.5,739.2,611.7 +0.6708449444738864,1.1289031128761156,3.010692959690218,1039.8,2363.9,2304.9,793.5,624.0,565.0 +0.770910161042096,1.829109128500156,0.0,1721.1,2150.9,2150.8,41.0,670.9,670.9 +0.7709645544421906,1.8289407216482978,0.1308996938995747,1808.4,964.8,148.9,25.5,668.9,728.2 +0.7711167998708331,1.8289889107503716,0.2617993877991494,2056.0,431.0,51.3,21.3,727.2,854.8 +0.7710454921822608,1.8289440508106587,0.39269908169872414,2571.9,251.1,31.8,32.0,1078.3,1102.5 +0.7710353998501991,1.8289349594076878,0.5235987755982988,2426.7,161.2,33.5,72.2,1246.0,1705.4 +0.7708223467260499,1.8291053611862562,0.6544984694978736,2179.1,106.6,47.5,231.5,1845.9,1787.0 +0.7708149611864508,1.8290768764098615,0.7853981633974483,2121.2,70.9,70.4,640.8,1751.5,1751.2 +0.7708173392255175,1.8290694791585935,0.916297857297023,232.2,47.4,106.3,646.5,1786.8,1845.3 +0.7708273603734551,1.8290402964291252,1.0471975511965976,73.2,33.9,161.3,714.6,1974.7,2102.4 +0.7708506596565322,1.8290018470439886,1.1780972450961724,31.7,31.5,250.6,1054.3,2403.5,2622.9 +0.7708430318047258,1.8290089728505483,1.3089969389957472,21.1,50.9,430.3,1268.0,2566.3,2438.7 +0.7708525076282208,1.8290046351821192,1.4398966328953218,25.7,152.2,668.8,1806.3,2258.0,2199.5 +0.7709207922980029,1.8289889007505666,1.5707963267948966,40.9,670.9,670.7,1721.4,2151.2,2151.2 +0.7709097778095756,1.8289880378196788,1.7016960206944713,68.2,668.1,726.6,1763.6,980.1,151.9 +0.7709022010052217,1.8289848523103829,1.832595714594046,114.0,728.0,855.6,1963.8,429.9,50.8 +0.770954608870566,1.829018000198648,1.9634954084936205,192.4,1077.8,1103.8,2413.7,250.5,31.5 +0.7709698391709399,1.8290353236738288,2.0943951023931953,349.9,1249.4,1704.0,2517.5,161.2,33.9 +0.7709593785697622,1.8290131906639306,2.2252947962927703,646.8,1845.5,1787.0,2220.9,106.2,47.4 +0.7709646557795817,1.82903332198244,2.356194490192345,641.5,1751.3,1752.1,2120.6,70.3,70.9 +0.7709621556824857,1.8290613686382966,2.4870941840919194,689.8,1786.7,1846.4,826.5,47.5,106.6 +0.770966881737248,1.8290503625451335,2.6179938779914944,808.1,1976.8,2104.6,347.7,33.5,161.2 +0.7709548732421259,1.8290651119753039,2.748893571891069,1040.2,2408.1,2627.9,192.2,32.2,252.4 +0.7708210624668846,1.8288783108130913,2.8797932657906435,1691.8,2566.1,2438.5,114.3,51.7,431.3 +0.7708485272616187,1.8288644049754479,3.010692959690218,1764.6,2259.8,2201.0,68.7,151.6,668.6 +0.7708382979977876,1.728606658113069,0.0,1620.9,2151.5,2151.2,140.8,670.9,670.9 +0.7709365972739309,1.7293148186195715,0.1308996938995747,1705.1,1347.7,532.3,129.0,668.8,728.2 +0.7709176194410176,1.7293083579091673,0.2617993877991494,1940.6,629.9,250.5,136.8,727.5,880.4 +0.7708844043614771,1.729286691625729,0.39269908169872414,2431.2,392.1,172.9,173.6,882.0,1102.7 +0.7708545814012141,1.729255435738689,0.5235987755982988,2425.9,276.6,149.0,271.4,1246.5,1714.0 +0.7708437515317186,1.7292310719206445,0.6544984694978736,2179.4,210.0,151.0,617.0,1742.4,1683.3 +0.7708317971205859,1.7291834595740478,0.7853981633974483,2121.1,170.8,170.3,640.9,1651.7,1651.1 +0.7708332502623764,1.7291720425534627,0.916297857297023,618.7,150.9,209.7,646.6,1683.3,1741.9 +0.770845904144538,1.7291330640914997,1.0471975511965976,272.6,149.4,276.7,714.6,1859.5,1986.6 +0.7708718840591573,1.7290894356962467,1.1780972450961724,173.3,172.5,391.7,878.1,2262.5,2481.4 +0.7708669699963681,1.7290932236198644,1.3089969389957472,136.6,250.0,629.4,1268.1,2566.6,2438.5 +0.7708793693505193,1.7290865833153974,1.4398966328953218,129.1,541.8,668.7,1703.2,2257.8,2199.1 +0.7709508079531011,1.7290695109435517,1.5707963267948966,140.8,670.9,670.7,1621.3,2151.7,2151.1 +0.7709429150988845,1.729068169657455,1.7016960206944713,171.6,668.1,726.6,1660.7,1368.7,540.9 +0.7709383034439526,1.729065317171465,1.832595714594046,229.5,728.0,1019.7,1848.4,628.8,249.8 +0.7709933135974286,1.7290996360186734,1.9634954084936205,334.1,967.8,1103.9,2271.7,391.5,172.5 +0.7710105240856654,1.7292181056953033,2.0943951023931953,549.4,1249.4,1717.7,2517.0,276.6,149.3 +0.7708405649039897,1.7291472276628208,2.2252947962927703,646.8,1741.9,1683.5,2221.7,209.8,150.9 +0.7708382091871272,1.7291354901504472,2.356194490192345,641.5,1651.2,1651.6,2120.5,170.3,170.8 +0.7711895401338795,1.7290961014706472,2.4870941840919194,689.8,1683.8,1742.8,1212.1,151.0,210.1 +0.7711931630480134,1.7290855174642632,2.6179938779914944,808.2,1861.2,1988.8,546.9,149.1,276.7 +0.7711726918838143,1.729112311028867,2.748893571891069,1040.4,2266.4,2486.0,333.6,173.7,393.7 +0.7708944486541103,1.7288498484804657,2.8797932657906435,1590.1,2565.4,2437.7,229.8,251.4,631.1 +0.7709093508716429,1.7288426138976558,3.010692959690218,1661.0,2259.4,2200.7,172.2,539.2,668.6 +0.770892676893768,1.6285846576382266,0.0,1521.1,2151.0,2151.2,240.8,670.9,671.0 +0.7709615781160918,1.6293032219940513,0.1308996938995747,1601.6,1731.9,916.3,232.6,668.9,728.2 +0.7709378606617657,1.629295343187446,0.2617993877991494,1824.8,829.3,449.9,252.4,727.4,854.9 +0.7709047682477441,1.6292738385444547,0.39269908169872414,2289.4,533.3,314.1,315.2,881.8,1102.8 +0.7708760274381417,1.6292438892059464,0.5235987755982988,2426.3,392.3,264.6,470.5,1246.6,1625.7 +0.7708660923761359,1.6292213923260492,0.6544984694978736,2179.6,313.6,254.5,689.9,1638.9,1580.1 +0.7708544860612414,1.629175808819157,0.7853981633974483,2121.0,270.8,270.3,640.9,1551.7,1551.3 +0.7708557897255633,1.6291663475761318,0.916297857297023,1006.2,254.4,313.2,646.5,1579.7,1638.8 +0.7708678341500006,1.6291291022543377,1.0471975511965976,472.2,264.9,392.3,714.7,1744.0,1871.6 +0.7708928470205219,1.6290868420605178,1.1780972450961724,315.0,313.7,532.7,877.9,2121.1,2340.6 +0.7708867840555833,1.6290916469888541,1.3089969389957472,252.2,449.3,727.0,1268.2,2566.5,2438.6 +0.7708979264761964,1.6290856925684931,1.4398966328953218,232.5,727.3,668.8,1599.3,2257.6,2199.4 +0.7709680683918156,1.629068891549853,1.5707963267948966,240.8,671.0,670.7,1521.1,2151.3,2151.6 +0.7709589700562235,1.6290675354198458,1.7016960206944713,275.1,668.2,726.5,1557.1,1758.6,930.5 +0.7709532623985972,1.6290644482227792,1.832595714594046,345.1,728.1,855.6,1732.8,828.3,449.2 +0.7710073366810654,1.629098265751448,1.9634954084936205,475.8,882.8,1104.0,2129.9,532.7,313.6 +0.7710238251327017,1.6291166976158595,2.0943951023931953,714.3,1249.4,1629.7,2517.0,392.2,264.9 +0.7710140969595013,1.6290959426743914,2.2252947962927703,646.8,1638.2,1579.8,2221.2,313.1,254.4 +0.771019542788784,1.6291175477288373,2.356194490192345,641.5,1551.3,1551.7,2120.4,270.2,270.8 +0.7710166770376009,1.629146943135398,2.4870941840919194,689.8,1580.3,1639.3,1596.8,254.5,313.6 +0.7710206144475279,1.6291369797327473,2.6179938779914944,833.6,1745.7,1873.4,745.9,264.6,392.3 +0.7710075619271637,1.6291523703562418,2.748893571891069,1040.4,2124.8,2345.3,474.9,315.0,535.1 +0.7708256433728595,1.6289115018841607,2.8797932657906435,1545.0,2565.8,2438.5,345.5,450.5,727.2 +0.7708512604174154,1.6288984692327135,3.010692959690218,1557.5,2260.1,2200.9,275.8,727.5,668.7 +0.7708372422234732,1.5286377000949052,0.0,1421.4,2150.9,2151.1,340.8,671.1,670.8 +0.7709381867787821,1.529317491196813,0.1308996938995747,1498.1,2200.0,1299.8,336.2,668.7,728.3 +0.7709193723568041,1.5293110761931894,0.2617993877991494,1708.9,1028.7,649.3,368.0,727.5,855.0 +0.7708859476606749,1.529289281908142,0.39269908169872414,2148.0,674.5,455.2,456.8,881.8,1102.7 +0.7708558718152879,1.5292577673178427,0.5235987755982988,2426.4,507.9,380.2,670.0,1246.2,1604.5 +0.7708448644508572,1.5292330866839081,0.6544984694978736,2179.0,417.1,358.1,689.7,1535.4,1476.6 +0.7708328102253206,1.529185122782453,0.7853981633974483,2121.4,370.8,370.3,640.8,1451.7,1450.9 +0.7708342624937166,1.5291733723722882,0.916297857297023,1392.9,357.8,416.8,646.6,1476.4,1535.2 +0.7708469946216853,1.529134089864951,1.0471975511965976,671.7,380.5,507.9,714.6,1628.2,1755.8 +0.770848028144436,1.5291303525427298,1.1780972450961724,456.6,454.9,674.0,909.2,1980.2,2199.2 +0.7708669944916481,1.5291118880136902,1.3089969389957472,367.8,648.8,727.1,1438.5,2566.6,2439.4 +0.7708859862804988,1.5291017555108717,1.4398966328953218,335.9,727.2,668.8,1495.9,2257.9,2199.4 +0.7709569541395754,1.529084786108019,1.5707963267948966,340.7,671.0,670.7,1421.3,2151.2,2151.3 +0.7709462930527418,1.5290833517776403,1.7016960206944713,378.5,668.2,726.6,1453.7,2200.3,1319.6 +0.7709384849006475,1.5290795440462621,1.832595714594046,460.7,728.1,855.7,1617.2,1071.1,648.2 +0.7709906217776187,1.529112065783262,1.9634954084936205,617.6,882.8,1103.8,1988.2,673.6,454.7 +0.7710056547374192,1.5291288363013786,2.0943951023931953,714.3,1249.6,1628.4,2585.9,507.7,380.4 +0.7709950500610376,1.529106224295107,2.2252947962927703,646.8,1535.0,1476.0,2221.8,416.6,357.9 +0.7710001595192261,1.5291259419040621,2.356194490192345,641.6,1451.1,1452.0,2120.3,370.2,370.8 +0.7709974263262424,1.5291535865209824,2.4870941840919194,689.9,1476.5,1535.6,1982.2,358.0,417.1 +0.7710019129250559,1.5291420963945495,2.6179938779914944,808.2,1630.4,1757.9,988.8,380.3,508.0 +0.7709605526143992,1.5292036226640884,2.748893571891069,1040.4,1983.4,2203.3,616.1,456.5,676.6 +0.7708286653099972,1.5289539555069838,2.8797932657906435,1544.7,2565.8,2438.6,461.1,649.8,727.3 +0.7708614636300828,1.5289370240743254,3.010692959690218,1453.8,2259.7,2201.4,379.4,727.5,668.6 +0.7708444710746333,1.42866938581061,0.0,1321.2,2150.9,2151.4,440.8,671.0,670.8 +0.770916332499821,1.4293015975963574,0.1308996938995747,1394.4,2201.5,1684.2,439.8,668.8,728.4 +0.770910123578487,1.4292991089972087,0.2617993877991494,1593.7,1228.3,848.8,483.5,727.4,854.8 +0.7708805852727637,1.4292797839860993,0.39269908169872414,2005.9,815.7,596.4,598.6,881.7,1102.7 +0.7708517190145404,1.4292495896857655,0.5235987755982988,2426.2,623.6,495.9,807.4,1396.2,1514.1 +0.7708411381938266,1.4292256807856862,0.6544984694978736,2178.7,520.6,461.5,689.8,1432.0,1372.9 +0.7708292141735283,1.4291782423291954,0.7853981633974483,2121.4,470.8,470.4,640.8,1351.9,1351.3 +0.7708306916293167,1.429166930129957,0.916297857297023,1780.1,461.4,520.3,646.5,1372.5,1431.7 +0.7708433561611676,1.4291280291378108,1.0471975511965976,871.5,496.0,623.3,714.6,1512.9,1640.2 +0.770869321007934,1.4290844336157031,1.1780972450961724,598.3,596.0,815.0,878.0,1838.8,2058.0 +0.770864400708496,1.4290882783609669,1.3089969389957472,483.4,848.1,727.0,1348.2,2566.2,2439.0 +0.77087678384809,1.4290817250303491,1.4398966328953218,439.3,727.2,668.8,1392.5,2258.1,2199.6 +0.7709481814508821,1.4290646657226156,1.5707963267948966,440.8,671.0,670.8,1321.2,2151.3,2151.3 +0.7708960192621389,1.4290585589488483,1.7016960206944713,482.0,668.2,726.5,1350.0,2200.2,1709.6 +0.7709207740971793,1.4290648152953163,1.832595714594046,576.4,801.2,855.7,1501.3,1226.9,847.5 +0.7710076386362393,1.4291152911171092,1.9634954084936205,759.2,882.9,1103.7,1846.9,814.8,595.8 +0.7710121414336798,1.4291206471975082,2.0943951023931953,714.2,1394.3,1512.8,2517.3,623.2,496.0 +0.7710002073055909,1.4290955250004886,2.2252947962927703,646.9,1431.4,1372.7,2221.1,520.2,461.4 +0.7710055972561752,1.4291163710373915,2.356194490192345,641.4,1351.1,1351.9,2120.1,470.3,470.8 +0.7710028292957848,1.429146301564363,2.4870941840919194,712.5,1372.9,1432.4,2179.7,461.5,520.7 +0.7710066154910677,1.429137218114221,2.6179938779914944,808.0,1514.3,1642.1,1144.3,495.9,623.6 +0.7709931348644649,1.4291534815694247,2.748893571891069,1040.2,1841.9,2062.2,757.7,597.9,818.0 +0.7708171203682764,1.4289151213726647,2.8797932657906435,1500.6,2566.0,2438.6,576.6,849.0,727.3 +0.7708435691151234,1.4289016398474454,3.010692959690218,1350.4,2259.8,2200.6,482.9,727.6,668.5 +0.7708301809822085,1.3286412260609402,0.0,1221.3,2151.1,2150.9,540.9,671.0,670.9 +0.7709351801895005,1.3293190864260764,0.1308996938995747,1291.0,2202.1,2067.5,543.4,669.0,728.1 +0.7709170101523961,1.329312864912954,0.2617993877991494,1478.1,1427.6,1048.0,599.2,727.4,855.0 +0.7708835648754262,1.3292910478962277,0.39269908169872414,1864.5,956.8,737.7,740.4,881.8,1102.5 +0.770853336572977,1.3292593531976031,0.5235987755982988,2458.0,764.5,611.3,807.4,1385.2,1398.4 +0.7708422039912033,1.3292344160142027,0.6544984694978736,2178.7,624.1,565.1,689.7,1328.3,1269.3 +0.77083009806093,1.329186171476834,0.7853981633974483,2121.0,570.9,570.3,640.8,1251.8,1251.1 +0.7708315687533127,1.32917415077356,0.916297857297023,2221.8,564.9,623.8,646.5,1269.5,1328.2 +0.7708443830097526,1.3291346279353156,1.0471975511965976,1070.8,611.6,738.9,714.6,1397.3,1524.7 +0.7708706327991166,1.3290905400441044,1.1780972450961724,740.0,737.0,881.5,878.0,1697.8,1917.1 +0.7708660664067705,1.3290939874637204,1.3089969389957472,598.9,854.5,727.0,1268.3,2403.8,2539.9 +0.7708788610675018,1.3290871295909334,1.4398966328953218,542.9,727.2,668.8,1289.2,2258.2,2199.3 +0.7709507116124734,1.3290699430495319,1.5707963267948966,540.8,670.8,670.7,1221.1,2151.4,2151.4 +0.7709432091468909,1.329068600932439,1.7016960206944713,585.4,668.2,726.5,1246.9,2200.5,2098.3 +0.7709389462220474,1.329065850459382,1.832595714594046,691.9,728.0,855.7,1386.0,1425.6,1046.8 +0.7709942510975734,1.3291003422385463,1.9634954084936205,878.6,882.9,1103.9,1705.2,955.9,736.8 +0.7710116837187589,1.3291196730141972,2.0943951023931953,714.3,1383.7,1397.2,2429.9,738.6,611.4 +0.7710026198123349,1.3290999124237408,2.2252947962927703,646.8,1327.7,1269.0,2221.3,623.7,564.8 +0.7710084280726747,1.3291225873039467,2.356194490192345,641.5,1251.3,1251.9,2120.6,570.3,570.8 +0.771005603866198,1.3291530596841703,2.4870941840919194,689.8,1269.3,1328.6,2179.4,565.1,624.3 +0.7710093447492044,1.3291440549396818,2.6179938779914944,808.1,1398.7,1526.9,1343.3,611.6,739.2 +0.7709958245847379,1.3291602767164634,2.748893571891069,1040.2,1700.8,1920.8,899.0,739.4,879.8 +0.770787864383515,1.3288882374378792,2.8797932657906435,1384.9,2402.8,2539.2,692.3,854.7,727.4 +0.7708185861483332,1.32887256192446,3.010692959690218,1247.1,2259.5,2200.8,586.3,727.5,668.6 +0.7708114268557492,1.2286176585757693,0.0,1121.3,2151.0,2151.1,640.9,671.1,670.8 +0.7709247097831696,1.2296358945661088,0.1308996938995747,1187.3,2201.6,2261.5,646.9,691.5,728.3 +0.7710284128731347,1.2288512389668338,0.2617993877991494,1362.3,1627.3,1247.9,714.8,727.3,855.0 +0.7710478586760492,1.2288637475327664,0.39269908169872414,1722.1,1129.3,879.0,881.9,881.7,1102.6 +0.7710619917887044,1.2288810967806343,0.5235987755982988,2426.5,855.0,727.2,807.6,1246.3,1282.9 +0.770821202993918,1.2290827238008561,0.6544984694978736,2179.4,727.7,668.9,689.7,1224.9,1165.8 +0.7708149222768238,1.229058933330015,0.7853981633974483,2121.5,670.8,670.3,640.8,1151.6,1151.1 +0.7708162188374784,1.2290593051780605,0.916297857297023,2221.7,668.5,727.5,646.6,1165.5,1224.4 +0.7708271098143351,1.2290275404428146,1.0471975511965976,1270.6,727.3,854.5,714.7,1281.9,1409.3 +0.7708505136343976,1.228989107689281,1.1780972450961724,881.7,878.5,881.4,877.9,1556.7,1775.7 +0.7708424262777576,1.228996776863914,1.3089969389957472,714.8,854.4,726.8,1268.3,2204.2,2439.4 +0.7708511322571795,1.2289929140716778,1.4398966328953218,646.5,727.1,668.8,1185.3,2258.1,2199.4 +0.7709185171080686,1.228977523727326,1.5707963267948966,640.8,670.9,670.6,1121.2,2151.5,2151.1 +0.7709065960256299,1.2289767338202835,1.7016960206944713,689.0,668.1,726.6,1143.2,2200.4,2258.5 +0.7708981850505028,1.2289733401203615,1.832595714594046,807.8,728.1,855.8,1270.3,1625.2,1246.0 +0.7709498629616971,1.2290061192107529,1.9634954084936205,878.6,882.7,1104.0,1563.3,1097.2,878.2 +0.7709645246590273,1.229022947443085,2.0943951023931953,714.1,1249.4,1281.9,2229.8,854.3,727.1 +0.7709537213489179,1.2290001893162015,2.2252947962927703,646.7,1224.5,1165.5,2221.2,727.2,668.6 +0.7709588580687547,1.2290196640386966,2.356194490192345,641.4,1151.3,1151.5,2120.4,670.3,670.9 +0.7709563811203863,1.2290471118204083,2.4870941840919194,689.9,1165.7,1224.9,2179.6,668.7,727.8 +0.770961336440251,1.2290355668886468,2.6179938779914944,808.2,1283.2,1410.8,1542.6,727.3,855.0 +0.7709496242145505,1.229049922869322,2.748893571891069,1040.4,1559.3,1779.2,1040.5,880.9,879.7 +0.7708242541083837,1.2288698653258057,2.8797932657906435,1269.3,2203.9,2438.0,807.7,854.8,727.1 +0.7708522866774663,1.2288556854203998,3.010692959690218,1143.3,2259.9,2201.0,689.9,727.4,668.7 +0.7708426400591872,1.12859823006613,0.0,1021.1,2151.2,2151.1,740.8,671.0,670.9 +0.7709378366439602,1.1293132218351962,0.1308996938995747,1083.7,2201.4,2261.3,750.6,668.8,728.2 +0.7709184192299705,1.129306629540507,0.2617993877991494,1246.8,1826.2,1446.7,830.4,727.3,855.1 +0.7708852597019574,1.1292850026042203,0.39269908169872414,1581.1,1239.2,1020.0,1023.6,881.8,1211.8 +0.7708555853807612,1.1292539117746154,0.5235987755982988,2302.3,970.1,842.7,807.5,1246.4,1167.1 +0.7708448710888546,1.129229772385443,0.6544984694978736,2178.9,831.2,772.1,689.7,1121.4,1062.4 +0.7708329720767867,1.1291824081297794,0.7853981633974483,2121.3,770.9,770.2,641.0,1051.6,1051.1 +0.7708344154165749,1.1291712286819793,0.916297857297023,2221.6,772.0,830.7,646.6,1062.4,1121.1 +0.7708470033677872,1.1291324636812057,1.0471975511965976,1470.1,842.7,969.9,714.6,1166.4,1293.7 +0.7708728742770179,1.1290890129680218,1.1780972450961724,1023.5,1019.6,881.4,878.1,1415.7,1634.8 +0.7708678225991014,1.1290929324533314,1.3089969389957472,830.2,854.6,727.1,1247.1,2005.1,2384.5 +0.7708800668959603,1.1290863770561537,1.4398966328953218,749.9,727.2,668.7,1082.3,2257.9,2199.5 +0.7709513442522695,1.1290693470133215,1.5707963267948966,740.7,671.0,670.8,1021.3,2151.8,2150.9 +0.7709432993826787,1.1290680056296836,1.7016960206944713,792.4,668.3,726.7,1039.9,2200.0,2258.9 +0.770938551442094,1.129065115578377,1.832595714594046,923.3,728.1,855.8,1154.4,1823.8,1445.1 +0.7709934459544864,1.1290993680314312,1.9634954084936205,878.7,882.9,1211.8,1421.8,1269.1,1019.0 +0.7710105687464651,1.1291183912114773,2.0943951023931953,714.2,1293.4,1166.3,2030.9,969.7,842.4 +0.7710013108908281,1.129098275006235,2.2252947962927703,646.7,1120.8,1062.3,2221.4,830.7,771.9 +0.7710070328752089,1.1291205801258242,2.356194490192345,641.5,1051.1,1051.7,2120.2,770.2,770.9 +0.7710042174518761,1.1291507047417921,2.4870941840919194,689.8,1062.4,1121.6,2179.5,772.2,831.3 +0.7710080614333757,1.129141390315893,2.6179938779914944,808.1,1167.4,1295.3,1741.4,842.8,970.5 +0.7709947002308263,1.129157365086718,2.748893571891069,1085.5,1418.2,1638.0,1181.7,1022.1,879.9 +0.7708189260548666,1.1289152372619804,2.8797932657906435,1153.7,2004.7,2383.9,923.4,854.9,727.3 +0.7708457589692821,1.1289015522829626,3.010692959690218,1039.7,2260.3,2200.8,793.5,727.7,668.6 +0.8709110404225283,1.8291077741550847,0.0,1720.9,2050.9,2051.0,41.0,771.0,770.9 +0.8709648436121006,1.8289405732530861,0.1308996938995747,1808.7,964.9,148.9,25.6,772.5,831.7 +0.8711170500541127,1.8289887512599776,0.2617993877991494,2055.7,431.0,51.3,21.3,843.1,970.4 +0.8710457060659367,1.828943869303531,0.39269908169872414,2571.8,251.1,31.8,32.0,1023.3,1244.0 +0.8710356236063499,1.8289347896272554,0.5235987755982988,2311.5,161.2,33.5,72.2,1445.1,1824.5 +0.8708195567913095,1.8291028560239957,0.6544984694978736,2076.1,106.5,47.5,231.6,1846.0,1786.8 +0.8708119875364693,1.829073503445074,0.7853981633974483,2021.2,70.9,70.4,740.9,1751.5,1751.3 +0.8708133692267677,1.8290714176424994,0.916297857297023,232.2,47.4,106.3,750.0,1786.7,1846.0 +0.8708246432021267,1.8290383347298438,1.0471975511965976,73.2,33.9,161.3,830.1,1975.0,2102.8 +0.8708485259394394,1.8289990285806794,1.1780972450961724,31.7,31.5,250.7,1019.0,2403.6,2622.5 +0.8708409964478382,1.829006103129511,1.3089969389957472,21.1,50.9,430.2,1467.3,2450.9,2323.1 +0.8708503200449929,1.8290018614407446,1.4398966328953218,25.7,152.2,772.3,1806.0,2154.2,2095.9 +0.8709183505679182,1.828986231213269,1.5707963267948966,40.9,770.8,770.7,1721.1,2051.3,2051.0 +0.870907057435178,1.8289853869987702,1.7016960206944713,68.2,771.4,830.0,1763.9,979.9,151.9 +0.8708992217560333,1.8289821220894096,1.832595714594046,114.0,843.7,971.4,1964.1,429.9,50.8 +0.8709514039427877,1.82901514513141,1.9634954084936205,192.5,1108.8,1245.6,2413.7,250.6,31.5 +0.870966461142884,1.829032307916321,2.0943951023931953,349.9,1449.1,1829.1,2401.5,161.2,33.9 +0.8709559053330336,1.8290099701924512,2.2252947962927703,750.2,1845.1,1786.7,2117.5,106.2,47.4 +0.8709611517835849,1.829029892038502,2.356194490192345,741.3,1750.7,1751.8,2020.7,70.3,70.9 +0.8709586665106408,1.8290577559280623,2.4870941840919194,793.2,1787.0,1845.8,826.5,47.5,106.6 +0.8709634749845856,1.829046585083661,2.6179938779914944,923.7,1977.2,2104.0,347.6,33.5,161.2 +0.8709515573101371,1.829061220522015,2.748893571891069,1181.8,2407.6,2627.9,192.2,32.3,252.3 +0.8708212666845759,1.8288762493813264,2.8797932657906435,1745.0,2450.2,2322.4,114.3,51.7,431.3 +0.8708490836288306,1.8288621640624279,3.010692959690218,1764.6,2156.5,2097.3,68.7,151.6,772.0 +0.8708390943357653,1.728899182521047,0.0,1621.6,2050.9,2051.0,140.8,770.9,770.8 +0.8709534414690934,1.7292943746199692,0.1308996938995747,1705.3,1347.4,532.3,129.0,772.5,831.9 +0.8709232327018858,1.7292844044373885,0.2617993877991494,1940.4,629.9,250.5,136.8,842.9,970.5 +0.8708897493405501,1.7292625895719587,0.39269908169872414,2431.0,423.2,172.9,173.6,1023.5,1244.3 +0.8708620442168487,1.7292336347304391,0.5235987755982988,2310.4,276.6,149.0,271.3,1445.7,1860.8 +0.8708530866612317,1.7292127650085165,0.6544984694978736,2075.5,210.0,151.0,617.1,1742.6,1683.5 +0.8708420577169503,1.7291691070025355,0.7853981633974483,2021.0,170.8,170.3,740.9,1651.7,1651.3 +0.8708434196545317,1.7291615520280252,0.916297857297023,618.8,150.9,209.7,749.9,1683.3,1742.3 +0.8708550537071029,1.7291260746777128,1.0471975511965976,272.6,149.4,276.7,830.1,1859.5,1987.0 +0.8708792738862882,1.7290853413999594,1.1780972450961724,173.3,172.5,391.7,1019.1,2262.3,2481.6 +0.8708721308334703,1.729091302241332,1.3089969389957472,136.6,250.0,629.5,1467.5,2450.9,2323.2 +0.870882002637166,1.7290860992688142,1.4398966328953218,129.1,541.8,772.1,1702.9,2154.1,2096.2 +0.8709507935157215,1.7290696865066109,1.5707963267948966,140.8,770.9,770.6,1621.3,2051.5,2051.4 +0.8709404093135527,1.7290683185233147,1.7016960206944713,171.5,771.7,830.1,1660.8,1368.7,540.9 +0.8709335636115717,1.7290648560327186,1.832595714594046,229.5,843.6,1063.6,1848.6,628.9,249.9 +0.8709867038166278,1.7290980459349474,1.9634954084936205,334.0,1024.7,1245.4,2271.7,391.5,172.5 +0.8710025307657813,1.7291156906244374,2.0943951023931953,549.4,1449.2,1859.0,2401.9,276.6,149.4 +0.8709924473161651,1.7290940538517594,2.2252947962927703,750.3,1742.4,1683.0,2117.9,209.6,150.8 +0.8709978098868056,1.7291147804351998,2.356194490192345,741.4,1651.1,1652.0,2020.5,170.2,170.8 +0.8709950809007405,1.7291433934576532,2.4870941840919194,793.2,1683.7,1743.0,1211.4,150.9,210.0 +0.8709993552837827,1.7291327731128048,2.6179938779914944,1041.6,1861.5,1989.4,546.6,149.0,276.7 +0.8709867278559554,1.7291476783952546,2.748893571891069,1181.9,2266.3,2486.7,333.5,173.6,393.7 +0.87081789207003,1.7289131649377225,2.8797932657906435,1744.5,2450.2,2322.9,229.9,251.0,630.4 +0.8708448695499751,1.7288994108655993,3.010692959690218,1661.1,2156.2,2097.7,172.3,537.9,772.0 +0.8708316860934433,1.6286388798541176,0.0,1521.3,2050.8,2051.0,240.8,770.8,771.0 +0.8709355667746199,1.6293185689149774,0.1308996938995747,1601.8,1731.0,916.0,232.6,772.6,831.8 +0.8709172277840547,1.629312296498331,0.2617993877991494,1824.5,829.3,449.9,252.4,843.0,970.6 +0.870883793605263,1.6292904877340253,0.39269908169872414,2289.5,533.2,314.1,315.3,1023.7,1244.4 +0.8708536124171345,1.6292588449930427,0.5235987755982988,2310.7,392.2,264.6,470.6,1601.8,1745.2 +0.8708425173531863,1.629233980281332,0.6544984694978736,2075.5,313.5,254.5,793.3,1638.7,1579.9 +0.870830429995709,1.6291858167892403,0.7853981633974483,2021.2,270.8,270.3,741.0,1551.9,1551.1 +0.8708318977213654,1.6291738737225965,0.916297857297023,1005.7,254.3,313.2,750.0,1579.9,1638.6 +0.8708446906514389,1.6291344208245837,1.0471975511965976,472.2,264.9,392.3,830.2,1744.1,1871.5 +0.8708709050842347,1.6290903916190649,1.1780972450961724,314.9,313.7,532.9,1050.1,2121.2,2340.3 +0.8708662937246853,1.6290938823851382,1.3089969389957472,252.2,449.3,828.7,1553.8,2451.0,2323.0 +0.8708790375288301,1.62908705227455,1.4398966328953218,232.5,830.6,772.5,1599.3,2154.2,2095.8 +0.8709508350967954,1.6290698800671246,1.5707963267948966,240.8,770.9,770.7,1521.0,2051.8,2050.8 +0.8709432826646024,1.629068538043484,1.7016960206944713,275.0,771.6,830.1,1557.1,1758.4,930.3 +0.8709389750296496,1.6290657748844133,1.832595714594046,345.1,843.8,971.4,1732.9,828.1,449.0 +0.8709942418820616,1.6291002447421372,1.9634954084936205,475.8,1024.6,1245.5,2130.2,532.6,313.6 +0.8710116456867392,1.6291195473098055,2.0943951023931953,749.1,1600.2,1743.7,2401.1,392.1,264.9 +0.8710025635634673,1.629099754137478,2.2252947962927703,750.3,1638.5,1579.9,2117.6,313.1,254.4 +0.8710083634517207,1.6291223949339808,2.356194490192345,741.5,1551.3,1551.8,2020.1,270.2,270.8 +0.8710055396900585,1.6291528350587583,2.4870941840919194,793.3,1580.1,1639.3,1596.4,254.5,313.6 +0.8710092897379849,1.629143801539189,2.6179938779914944,923.8,1745.9,1873.3,745.9,264.6,392.3 +0.8709957841238045,1.6291600001837927,2.748893571891069,1181.4,2125.1,2345.0,506.0,315.0,535.2 +0.870818242687529,1.6289166383440696,2.8797932657906435,1731.8,2450.3,2322.5,345.5,450.4,829.7 +0.870844959893729,1.6289030102234603,3.010692959690218,1557.4,2156.9,2097.4,275.8,831.0,772.1 +0.8708313863364429,1.5286422655541598,0.0,1421.1,2051.4,2051.0,340.8,771.1,770.9 +0.8709356633621408,1.5293188609950215,0.1308996938995747,1498.0,2097.9,1300.0,336.2,772.4,831.9 +0.8709173632522786,1.529312600026516,0.2617993877991494,1709.1,1028.6,649.3,368.0,1001.2,970.5 +0.8708839097909535,1.5292907794152226,0.39269908169872414,2147.1,674.4,455.2,456.9,1023.6,1244.3 +0.8708537002431179,1.5292591073348585,0.5235987755982988,2310.9,507.8,380.2,669.9,1489.8,1629.6 +0.8708425846033278,1.5292342053552366,0.6544984694978736,2075.9,417.0,358.0,793.3,1535.5,1476.3 +0.8708304859148259,1.529186000303251,0.7853981633974483,2021.1,370.8,370.3,740.9,1451.9,1451.3 +0.8708319538931668,1.5291740176959587,0.916297857297023,1392.8,357.9,416.7,750.0,1476.2,1535.2 +0.8708447564663189,1.529134528837037,1.0471975511965976,671.8,380.5,507.8,920.6,1628.3,1755.9 +0.8708709876855891,1.5290904683347315,1.1780972450961724,456.7,454.9,674.0,1019.4,1980.3,2199.3 +0.8708663989136994,1.5290939359605475,1.3089969389957472,367.8,648.7,842.8,1568.7,2559.2,2323.1 +0.8708791688740694,1.5290870914544974,1.4398966328953218,336.0,830.6,772.3,1496.1,2154.3,2096.0 +0.8709509938029728,1.5290699108156807,1.5707963267948966,340.8,771.0,770.7,1421.0,2051.5,2051.2 +0.8709434675274786,1.529068568596849,1.7016960206944713,378.5,771.6,830.0,1453.7,2096.5,1319.8 +0.8709391830521807,1.5290658131106774,1.832595714594046,460.8,1000.4,971.3,1617.2,1027.1,648.1 +0.8709944693702905,1.5291002948850243,1.9634954084936205,617.5,1024.5,1245.4,1988.6,673.7,454.6 +0.8710118876829613,1.529119612359093,2.0943951023931953,829.8,1493.0,1628.3,2405.5,507.6,380.4 +0.8710028137429789,1.5290998369725164,2.2252947962927703,750.3,1534.9,1476.4,2117.7,416.6,357.8 +0.8710086164495489,1.529122495798899,2.356194490192345,741.5,1451.4,1451.9,2020.7,370.3,370.8 +0.8710057914478173,1.5291529520024865,2.4870941840919194,793.3,1476.7,1535.8,2066.9,358.0,417.2 +0.8710095352323448,1.5291439328207468,2.6179938779914944,949.4,1630.2,1757.5,945.1,380.2,508.0 +0.8709960219931515,1.529160142088589,2.748893571891069,1181.6,1983.5,2203.7,616.2,456.5,676.6 +0.8708182682250687,1.528916702887388,2.8797932657906435,1616.1,2558.2,2322.8,461.1,649.7,842.8 +0.8708449618143873,1.52890308703243,3.010692959690218,1453.9,2156.5,2097.2,379.3,831.1,772.0 +0.8708313754930138,1.4286423409084636,0.0,1321.3,2051.1,2051.1,440.7,771.0,770.9 +0.8709356705227714,1.4293188728197697,0.1308996938995747,1394.7,2098.5,1683.6,439.8,772.3,831.8 +0.8709173707378058,1.4293126119640105,0.2617993877991494,1593.4,1228.0,892.6,483.5,843.0,970.5 +0.8708839156182331,1.4292907903640772,0.39269908169872414,2006.3,815.6,596.3,598.5,1023.6,1244.4 +0.8708537042945294,1.4292591164715376,0.5235987755982988,2310.9,623.3,495.9,869.2,1446.1,1514.2 +0.8708425874190733,1.429234212297581,0.6544984694978736,2075.8,520.5,461.6,793.3,1432.0,1372.9 +0.8708304880763742,1.429186004846823,0.7853981633974483,2021.1,470.8,470.3,740.8,1351.7,1351.2 +0.8708319560666163,1.4291740199510776,0.916297857297023,1780.0,461.4,520.3,750.0,1372.9,1431.4 +0.8708447592019938,1.4291345290215358,1.0471975511965976,915.2,496.0,623.4,830.3,1513.0,1640.4 +0.8708709914084787,1.4290904667450324,1.1780972450961724,598.4,596.0,815.3,1019.1,1838.9,2058.2 +0.8708664039571398,1.4290939330579027,1.3089969389957472,483.4,848.1,842.5,1467.5,2450.6,2323.4 +0.870879175431795,1.429087087737957,1.4398966328953218,439.4,830.7,772.1,1392.6,2154.7,2096.2 +0.8709510019253065,1.429069906665168,1.5707963267948966,440.7,770.9,770.6,1321.3,2051.4,2051.2 +0.8709434771449248,1.4290685644758647,1.7016960206944713,482.0,771.7,830.0,1350.1,2096.6,1709.2 +0.8709391939857284,1.429065809445042,1.832595714594046,576.4,843.5,971.4,1501.6,1226.4,847.4 +0.8709944813839783,1.4291002919146631,1.9634954084936205,759.3,1024.5,1245.5,1846.5,814.6,595.7 +0.8710119004910531,1.4291196102530974,2.0943951023931953,829.8,1449.2,1512.4,2401.7,648.6,495.8 +0.8710028270040242,1.4290998358762295,2.2252947962927703,750.3,1431.5,1372.7,2117.8,520.1,461.3 +0.871008629866469,1.4291224957100384,2.356194490192345,741.4,1351.3,1351.9,2020.1,470.2,470.8 +0.871005804792964,1.4291529528140576,2.4870941840919194,793.3,1373.0,1432.2,2075.7,461.5,520.6 +0.8710095482434826,1.4291439344361079,2.6179938779914944,923.8,1514.6,1642.4,1144.0,495.9,623.6 +0.8709960345881648,1.4291601443121829,2.748893571891069,1181.6,1842.1,2062.2,757.6,597.9,818.1 +0.870818270195853,1.4289167041065856,2.8797932657906435,1500.8,2450.1,2323.0,576.8,849.2,843.0 +0.8708861196443882,1.4288851283867183,3.010692959690218,1350.5,2156.6,2097.3,482.8,831.1,772.2 +0.8708453330412349,1.3286523666203913,0.0,1221.3,2051.3,2050.8,540.8,770.8,770.9 +0.8709403976739816,1.3293112072673696,0.1308996938995747,1291.0,2098.4,2151.9,543.4,772.5,831.8 +0.8709205693222845,1.32930448615109,0.2617993877991494,1478.1,1427.4,1048.0,599.2,843.0,970.6 +0.8708491977600598,1.329256393866664,0.39269908169872414,1865.0,956.8,737.6,740.1,1023.6,1244.3 +0.8708416747599007,1.32924913642085,0.5235987755982988,2451.3,739.0,611.5,923.0,1446.0,1398.5 +0.8708346666599386,1.3292320414312064,0.6544984694978736,2075.4,624.1,565.2,793.4,1328.3,1269.3 +0.8708101468615717,1.3291269914551083,0.7853981633974483,2021.2,570.8,570.3,740.7,1252.0,1251.2 +0.8708101376524486,1.329154354600023,0.916297857297023,2118.1,564.9,623.8,749.9,1269.3,1328.3 +0.8708208204650326,1.3291216326001922,1.0471975511965976,1070.9,611.7,738.9,855.8,1397.3,1524.8 +0.8708485523471733,1.3290751493789097,1.1780972450961724,740.0,737.1,956.4,1019.2,1698.1,1917.0 +0.8708480350292946,1.329074793802092,1.3089969389957472,599.0,970.2,842.7,1452.8,2403.8,2323.0 +0.870866254238932,1.3290650352752507,1.4398966328953218,542.9,830.6,772.4,1289.1,2154.7,2095.5 +0.8709440402849518,1.3290465004390783,1.5707963267948966,540.8,770.9,770.6,1221.2,2051.5,2051.1 +0.8709421743122937,1.3290453585788748,1.7016960206944713,585.4,771.6,830.2,1246.8,2096.9,2155.4 +0.8709429405516936,1.3290441433252826,1.832595714594046,691.9,869.2,971.4,1386.0,1425.6,1046.5 +0.8710024302734428,1.3290812781974704,1.9634954084936205,901.0,1024.6,1245.3,1705.1,955.8,736.8 +0.8710229492334092,1.3291039524621553,2.0943951023931953,829.8,1449.1,1397.3,2401.2,738.6,611.4 +0.8710158376971646,1.3290878730696563,2.2252947962927703,750.2,1328.2,1269.2,2118.0,623.5,564.9 +0.8710123015042585,1.3290660890261083,2.356194490192345,741.5,1251.0,1251.8,2020.3,570.4,570.9 +0.8709993387977706,1.329332868368564,2.4870941840919194,793.3,1269.6,1328.8,2075.9,565.2,624.3 +0.8707010530572167,1.3290861878386524,2.6179938779914944,923.6,1398.2,1526.2,1344.8,611.3,739.0 +0.8710801775958577,1.329192311203739,2.748893571891069,1182.1,1700.8,1921.4,899.0,739.5,959.4 +0.8708869413417711,1.3289288346625234,2.8797932657906435,1384.6,2404.2,2322.5,692.1,970.2,842.7 +0.8709101704391592,1.3289170186571275,3.010692959690218,1246.6,2156.0,2097.1,586.4,831.1,772.0 +0.8708881056850967,1.228648839333366,0.0,1121.4,2050.9,2050.9,640.8,771.0,771.0 +0.8709602250001104,1.2293067924534606,0.1308996938995747,1187.3,2098.2,2157.8,647.0,772.6,831.8 +0.8709366941391606,1.2292989560091372,0.2617993877991494,1362.5,1627.2,1247.4,714.7,843.0,970.6 +0.8709033314542354,1.2292772710868332,0.39269908169872414,1722.5,1098.1,878.6,882.0,1023.5,1353.4 +0.8708742823191902,1.2292469785748075,0.5235987755982988,2310.3,854.7,726.8,923.1,1410.5,1282.8 +0.8708641306665978,1.2292240611949912,0.6544984694978736,2075.9,727.7,668.6,793.3,1224.9,1165.7 +0.8708524251814965,1.229178028870617,0.7853981633974483,2021.2,670.9,670.3,741.0,1151.6,1151.0 +0.8708537453923635,1.2291681405117598,0.916297857297023,2118.0,668.4,727.2,750.1,1165.8,1224.7 +0.8708659064872296,1.2291305124339909,1.0471975511965976,1270.8,727.2,854.6,830.3,1281.7,1409.3 +0.8708911136403684,1.229087935420257,1.1780972450961724,881.8,878.3,1023.2,1019.1,1556.7,1775.7 +0.8708852953279778,1.2290925036839397,1.3089969389957472,714.6,970.3,842.7,1363.0,2204.5,2323.0 +0.8708967136950259,1.2290863936168122,1.4398966328953218,646.4,830.7,772.4,1185.7,2154.4,2095.8 +0.8709671434953511,1.2290695163796477,1.5707963267948966,640.8,771.0,770.7,1121.4,2051.0,2050.9 +0.8709583175156396,1.2290681585818817,1.7016960206944713,688.9,771.6,830.2,1143.3,2097.1,2155.3 +0.8709528553912659,1.229065134814675,1.832595714594046,807.7,843.7,971.4,1270.3,1625.2,1246.2 +0.8710071379062306,1.2290990700745856,1.9634954084936205,1020.0,1024.5,1353.0,1563.0,1097.1,878.0 +0.8710237842020504,1.2291176566599997,2.0943951023931953,829.8,1408.9,1281.8,2230.2,854.3,727.0 +0.8710141590414899,1.2290970778838464,2.2252947962927703,750.4,1224.5,1165.7,2118.0,727.0,668.5 +0.8710196536728497,1.2291188682237015,2.356194490192345,741.5,1151.2,1151.7,2020.5,670.2,670.8 +0.8710167852137615,1.2291484420383685,2.4870941840919194,793.2,1165.9,1225.3,2076.1,668.7,727.7 +0.8710206750119608,1.2291386363706007,2.6179938779914944,923.7,1283.3,1411.0,1542.8,727.1,854.8 +0.8710075397572709,1.229154155926158,2.748893571891069,1227.1,1558.8,1779.1,1040.4,880.7,1021.4 +0.8708250278424745,1.2289124276117525,2.8797932657906435,1269.4,2203.8,2323.0,808.0,970.4,842.8 +0.8708506666709515,1.2288993806881452,3.010692959690218,1143.5,2156.2,2097.6,689.9,831.1,772.1 +0.870836629329204,1.1286385933219685,0.0,1021.3,2051.1,2051.0,740.8,771.0,771.0 +0.8709379836482523,1.1293176773198796,0.1308996938995747,1084.0,2098.1,2157.7,750.6,772.4,831.9 +0.8709192120879292,1.1293112753454888,0.2617993877991494,1246.9,1826.6,1447.0,830.4,843.0,970.4 +0.8708857705752006,1.1292894702201433,0.39269908169872414,1581.0,1239.1,1019.9,1023.6,1023.5,1244.4 +0.8708556689392423,1.1292579273102565,0.5235987755982988,2302.6,970.4,842.5,923.1,1294.8,1167.6 +0.8708446423637243,1.1292332098534792,0.6544984694978736,2075.9,831.3,772.1,793.3,1121.4,1062.2 +0.870832579438585,1.1291852060884007,0.7853981633974483,2021.1,770.8,770.2,741.0,1051.8,1051.2 +0.8708340333636903,1.1291734173621728,0.916297857297023,2118.8,771.8,830.8,750.1,1062.2,1121.2 +0.8708467762883617,1.129134100648264,1.0471975511965976,1470.1,842.5,970.0,830.1,1166.3,1293.7 +0.8708729124992924,1.1290901770653083,1.1780972450961724,1023.4,1019.4,1023.2,1019.0,1415.4,1634.8 +0.8708682100438873,1.1290937463867006,1.3089969389957472,830.2,970.3,842.6,1247.3,2004.8,2323.4 +0.870880855145834,1.1290869700767816,1.4398966328953218,749.7,830.6,772.1,1082.0,2154.5,2096.0 +0.8709525510712702,1.129069817470246,1.5707963267948966,740.8,770.9,770.6,1021.4,2051.4,2051.2 +0.8709449046661181,1.1290684740953845,1.7016960206944713,792.4,771.7,830.1,1039.6,2096.9,2155.3 +0.8709405111393286,1.129065694474963,1.832595714594046,923.1,843.6,971.3,1154.6,1824.2,1444.8 +0.8709957042981361,1.1291001260322373,1.9634954084936205,1019.8,1024.6,1245.8,1421.5,1238.0,1019.0 +0.871013050847017,1.1291193760164933,2.0943951023931953,829.8,1293.4,1166.1,2030.5,969.8,842.5 +0.8710039253476263,1.129099526588163,2.2252947962927703,750.4,1121.0,1062.0,2117.6,830.7,772.0 +0.8710096990003684,1.1291221050698006,2.356194490192345,741.5,1051.2,1051.8,2020.5,770.3,770.9 +0.8710068697492831,1.129152479272525,2.4870941840919194,793.3,1062.1,1121.3,2076.0,772.2,831.3 +0.8710106267168723,1.1291433870919612,2.6179938779914944,923.8,1167.7,1295.2,1741.3,842.9,970.5 +0.8709971487207885,1.1291595321299335,2.748893571891069,1244.2,1417.5,1637.8,1181.8,1022.4,1021.5 +0.8708189245657643,1.1289162793727874,2.8797932657906435,1153.9,2004.4,2322.8,923.5,970.5,842.7 +0.8708455142365509,1.128902719583856,3.010692959690218,1039.9,2156.6,2097.6,793.3,831.0,772.0 +0.9709107229057806,1.8291087123073555,0.0,1721.1,1951.2,1950.9,41.0,870.9,871.0 +0.9709647424546118,1.828940678904965,0.1308996938995747,1808.7,964.7,148.9,25.6,876.1,935.5 +0.9711169615710263,1.8289888604133986,0.2617993877991494,2055.3,430.9,51.3,21.3,958.4,1086.0 +0.9710456251618634,1.8289439829514025,0.39269908169872414,2572.2,251.1,31.8,32.0,1164.8,1386.1 +0.9710355353090079,1.8289348948674777,0.5235987755982988,2195.5,161.2,33.5,72.2,1644.5,1976.6 +0.9710478025468393,1.8289547037122331,0.6544984694978736,1972.3,106.6,47.5,231.4,1846.2,1787.1 +0.9710477231131988,1.8289598298916252,0.7853981633974483,1921.0,70.9,70.4,840.8,1751.8,1750.9 +0.9710474551309469,1.8290005397562767,0.916297857297023,317.8,47.5,106.3,853.5,1786.7,1845.4 +0.9710458785733916,1.8290089131372387,1.0471975511965976,73.3,34.0,161.3,945.6,1974.9,2102.4 +0.9710477406620082,1.8290044831491794,1.1780972450961724,31.8,31.6,250.7,1160.0,2403.1,2622.0 +0.9710124350571796,1.8290376166770872,1.3089969389957472,21.2,51.1,430.3,1810.6,2335.8,2207.7 +0.9709905081549738,1.8290503354138368,1.4398966328953218,25.8,152.4,875.9,1806.0,2051.0,1992.5 +0.9710260802589454,1.8290423446331319,1.5707963267948966,41.0,871.0,870.7,1720.9,1951.1,1951.1 +0.970984402582781,1.829040856028273,1.7016960206944713,68.3,875.1,933.5,1764.0,980.9,152.4 +0.9709494199783425,1.829029951339717,1.832595714594046,114.0,959.1,1253.4,1963.5,430.2,51.0 +0.9709788318386217,1.8290493084082518,1.9634954084936205,192.5,1166.1,1387.1,2412.9,250.8,31.6 +0.9709768606045279,1.8290488922419847,2.0943951023931953,349.9,1856.2,1975.1,2286.4,161.3,34.0 +0.97095521890864,1.8290070342024232,2.2252947962927703,831.3,1845.1,1786.6,2013.9,106.3,47.5 +0.970955216485663,1.8290065792851606,2.356194490192345,841.6,1751.1,1751.3,1920.3,70.4,71.0 +0.9709530674929875,1.8290147804166548,2.4870941840919194,896.9,1786.9,1846.2,827.3,47.5,106.6 +0.9709627940101706,1.8289862771558918,2.6179938779914944,1039.4,1976.7,2104.5,347.9,33.5,161.2 +0.9709597451304162,1.8289864711704524,2.748893571891069,1322.8,2407.2,2627.1,192.3,32.3,252.3 +0.9708551998561575,1.828847641859111,2.8797932657906435,1936.8,2333.9,2206.5,114.3,51.8,431.6 +0.9708799551037655,1.8288352620021375,3.010692959690218,1764.4,2052.5,1993.8,68.7,152.0,875.8 +0.970868787859998,1.728576827462796,0.0,1620.8,1950.8,1951.1,140.8,870.9,870.8 +0.9709488503938575,1.7293073934662808,0.1308996938995747,1705.2,1347.5,532.4,129.0,875.9,935.3 +0.9709269973267547,1.7293000705036494,0.2617993877991494,1940.2,673.8,250.5,136.8,958.7,1086.1 +0.9708938826323188,1.729278507936866,0.39269908169872414,2431.1,392.0,172.9,173.5,1165.6,1385.9 +0.9708647524110569,1.7292480611664698,0.5235987755982988,2195.0,276.6,149.0,271.4,1717.3,1861.1 +0.970854488999556,1.7292248470296223,0.6544984694978736,1972.2,210.0,151.0,617.1,1742.8,1683.7 +0.9708427769933398,1.7291784975225317,0.7853981633974483,1921.0,170.8,170.3,840.8,1651.8,1650.9 +0.9708441535097958,1.7291682955560015,0.916297857297023,704.1,150.9,209.7,853.5,1683.2,1742.0 +0.9708564443737581,1.7291304000080767,1.0471975511965976,316.5,149.3,276.7,945.7,1859.6,1986.8 +0.970881840014662,1.7290876455141402,1.1780972450961724,173.3,172.5,391.7,1191.6,2262.8,2481.6 +0.9708762153149949,1.729092081494733,1.3089969389957472,136.6,250.1,629.4,1800.1,2335.1,2207.3 +0.9708878282358749,1.7290858698666152,1.4398966328953218,129.1,541.7,875.7,1702.8,2050.8,1992.3 +0.9709584531937226,1.7290689852575147,1.5707963267948966,140.8,871.2,870.7,1621.3,1951.2,1951.3 +0.9709497997594292,1.7290676380823076,1.7016960206944713,171.5,875.2,933.6,1660.6,1368.9,626.5 +0.9709445006823434,1.7290646207885214,1.832595714594046,229.5,959.3,1087.1,1848.5,628.9,249.8 +0.9709989251177954,1.7290986170183962,1.9634954084936205,334.0,1166.3,1387.1,2272.4,391.5,172.5 +0.9710156865239539,1.7291172982027996,2.0943951023931953,549.4,1740.8,1859.5,2285.9,276.6,149.3 +0.9710061728463995,1.7290968041481372,2.2252947962927703,853.7,1741.9,1683.1,2014.3,209.6,150.8 +0.9710117535159861,1.7291187016078973,2.356194490192345,841.7,1651.2,1651.7,1920.7,170.2,170.8 +0.9710089195966594,1.7291484142599427,2.4870941840919194,896.9,1683.6,1742.9,1211.2,150.9,210.1 +0.9710128356012673,1.729138732582428,2.6179938779914944,1039.5,1861.3,1989.2,546.6,149.0,276.6 +0.9709996517799379,1.7291543875041118,2.748893571891069,1323.1,2266.7,2486.3,333.5,173.6,393.6 +0.9708219876523088,1.7289131686819512,2.8797932657906435,1847.5,2334.5,2207.0,229.9,251.0,630.3 +0.9708483725052343,1.7288997260809007,3.010692959690218,1661.2,2053.1,1993.8,172.3,537.9,875.5 +0.9708346996855283,1.628638986362707,0.0,1521.0,1951.2,1951.0,240.8,871.1,871.0 +0.9709369908935568,1.6293179966697637,0.1308996938995747,1601.6,1731.5,916.0,232.6,876.2,935.3 +0.9709183761904085,1.6293116415689908,0.2617993877991494,1824.9,829.4,449.8,252.4,958.7,1086.1 +0.9708849350264028,1.629289833354145,0.39269908169872414,2289.6,533.2,314.0,315.2,1165.4,1386.1 +0.970854802608118,1.6292582514009177,0.5235987755982988,2194.9,392.3,264.6,470.7,1645.1,1745.4 +0.9708437497856206,1.6292334769798127,0.6544984694978736,1972.0,313.5,254.6,896.8,1638.9,1580.1 +0.9708316781158147,1.6291854120207445,0.7853981633974483,1920.9,270.9,270.3,840.8,1551.6,1551.0 +0.9708331377043212,1.6291735640840797,0.916297857297023,1005.9,254.4,313.2,853.6,1579.8,1638.8 +0.9708459001875162,1.6291341953356109,1.0471975511965976,472.1,264.9,392.2,945.8,1744.1,1871.6 +0.9708720668405834,1.6290902319774656,1.1780972450961724,315.0,313.7,532.8,1160.5,2120.9,2340.7 +0.9708673994543111,1.6290937716486515,1.3089969389957472,252.2,449.4,828.7,1666.7,2335.3,2207.9 +0.9708800822805486,1.6290869748335763,1.4398966328953218,232.5,931.7,875.7,1599.8,2051.1,1992.5 +0.9709518168862371,1.629069815390218,1.5707963267948966,240.7,871.1,870.7,1521.2,1951.3,1951.1 +0.9709442061786919,1.6290684727731926,1.7016960206944713,275.0,875.1,933.7,1557.0,1758.0,930.2 +0.9709398453539616,1.629065699059928,1.832595714594046,345.0,959.5,1086.7,1732.6,828.0,449.0 +0.970995066459182,1.6291001450504186,1.9634954084936205,475.8,1166.3,1387.3,2130.7,532.5,313.6 +0.9710124347605512,1.6291194150310973,2.0943951023931953,749.2,1648.6,1743.9,2285.8,392.1,264.8 +0.9710033261743919,1.6290995866798634,2.2252947962927703,853.8,1638.4,1579.9,2014.4,313.1,254.4 +0.9710091103284718,1.6291221886283092,2.356194490192345,841.5,1551.1,1551.9,1920.1,270.2,270.8 +0.9710062834826921,1.629152588064658,2.4870941840919194,896.9,1580.1,1639.4,1596.4,254.5,313.6 +0.9710100384706942,1.6291435183407146,2.6179938779914944,1039.5,1745.3,1873.4,745.9,264.6,392.3 +0.9709965500362978,1.6291596842756273,2.748893571891069,1323.4,2125.4,2345.1,474.8,315.0,535.1 +0.9708186450205054,1.6289164090901176,2.8797932657906435,1731.7,2334.4,2207.3,345.5,450.4,829.7 +0.9708452923233225,1.6289028184778314,3.010692959690218,1557.6,2052.8,1993.7,275.8,924.2,875.7 +0.9708316901572263,1.5286420742272075,0.0,1421.0,1951.4,1950.8,340.8,871.0,870.9 +0.9709358113276975,1.5293187970490638,0.1308996938995747,1498.3,1995.0,1300.1,336.2,875.9,935.6 +0.9709174742370212,1.5293125251279494,0.2617993877991494,1709.3,1028.8,649.2,368.0,958.8,1086.1 +0.9708840139819735,1.5292907009971413,0.39269908169872414,2147.8,674.3,455.2,456.9,1165.4,1386.0 +0.9708538051743107,1.5292590307867326,0.5235987755982988,2194.9,508.0,380.3,670.1,1645.1,1630.0 +0.9708426911203383,1.529234133235771,0.6544984694978736,1972.4,417.1,358.1,896.9,1535.6,1476.6 +0.9708305928549565,1.5291859333474185,0.7853981633974483,1921.0,370.9,370.3,840.9,1451.9,1451.0 +0.9708320601144688,1.5291739557136474,0.916297857297023,1392.9,357.8,416.8,853.5,1476.5,1534.9 +0.9711514351554409,1.5291582230833634,1.0471975511965976,671.4,380.6,508.1,946.0,1628.9,1756.4 +0.97115022542236,1.529158027633739,1.1780972450961724,487.7,455.1,674.4,1161.1,1980.7,2200.0 +0.9711073673728007,1.5291969786191508,1.3089969389957472,367.8,649.2,958.0,1709.2,2334.7,2207.1 +0.9710759150341515,1.5292133844024116,1.4398966328953218,336.1,933.9,875.7,1495.7,2050.5,1992.1 +0.971101585310727,1.5292069782811335,1.5707963267948966,340.9,870.9,870.9,1421.1,1951.1,1951.0 +0.9710507820639679,1.529204389975627,1.7016960206944713,378.7,875.2,933.8,1453.8,1993.3,1318.0 +0.9710080166653944,1.5291900437324306,1.832595714594046,461.0,1043.2,1087.4,1617.7,1026.6,648.0 +0.9710310792870064,1.5292048323514478,1.9634954084936205,618.0,1167.1,1387.9,1989.3,673.4,454.6 +0.9710243899180543,1.5291991871134352,2.0943951023931953,945.2,1650.5,1627.7,2285.2,507.5,380.4 +0.9709998684376575,1.5291514544555316,2.2252947962927703,853.8,1534.9,1476.2,2013.6,416.5,357.8 +0.970998438806105,1.529145092518007,2.356194490192345,841.6,1451.2,1451.7,1920.2,370.1,370.9 +0.9709959438334871,1.5291478311618447,2.4870941840919194,897.2,1476.7,1536.1,1972.4,358.1,417.3 +0.9710067615914846,1.5291141523535137,2.6179938779914944,1039.9,1630.4,1758.6,944.2,380.3,508.2 +0.9710053786868547,1.5291099566196933,2.748893571891069,1324.1,1984.0,2204.4,615.8,456.6,676.9 +0.9710297099526753,1.5290875197120415,2.8797932657906435,1615.3,2333.3,2205.8,486.0,650.8,958.1 +0.9710380455826472,1.52908256662089,3.010692959690218,1453.7,2051.8,1993.2,379.0,934.3,875.7 +0.9710006167093583,1.4287991691821549,0.0,1321.5,1950.8,1951.2,440.6,871.0,871.1 +0.9710128164396987,1.4293346785624448,0.1308996938995747,1394.3,1994.5,1685.4,439.8,876.3,935.3 +0.97097385902781,1.4293220556787083,0.2617993877991494,1593.2,1228.6,848.8,483.6,958.6,1085.9 +0.9709350014469136,1.4292969790024637,0.39269908169872414,2005.5,815.7,596.5,598.5,1165.2,1385.8 +0.9709036365126352,1.4292643723508682,0.5235987755982988,2195.2,623.6,495.8,868.8,1642.1,1514.1 +0.9708923953789949,1.4292396958891112,0.6544984694978736,1972.0,520.7,461.6,897.0,1432.4,1373.2 +0.9708800824816464,1.4291920290904574,0.7853981633974483,1921.2,470.9,470.3,840.8,1351.8,1351.2 +0.9708777916686528,1.4292226681943707,0.916297857297023,1781.4,461.4,520.2,853.6,1372.8,1431.2 +0.9708986639222695,1.429155892125522,1.0471975511965976,871.8,495.9,623.2,945.9,1512.8,1640.3 +0.9709280070736184,1.4291062532615966,1.1780972450961724,598.4,595.9,815.0,1160.2,1838.7,2057.6 +0.9709228446122841,1.4291099554493436,1.3089969389957472,483.3,847.8,958.3,1594.4,2335.2,2207.9 +0.9709332330666053,1.4291042893621733,1.4398966328953218,439.5,934.2,875.8,1392.6,2051.0,1992.5 +0.9710019760455717,1.4290876081417694,1.5707963267948966,440.8,871.2,870.8,1321.4,1951.2,1950.9 +0.9709914188238832,1.4290861067464622,1.7016960206944713,482.0,875.1,933.6,1350.2,1993.5,1710.4 +0.9709843479962615,1.429082657774543,1.832595714594046,576.4,959.4,1086.8,1501.5,1227.0,847.7 +0.9710372671065645,1.4291157756924062,1.9634954084936205,759.1,1166.2,1387.0,1846.4,815.1,595.9 +0.971052871266541,1.4291333067116891,2.0943951023931953,945.5,1640.3,1512.9,2385.6,623.2,496.0 +0.9710424620448018,1.4291116333173837,2.2252947962927703,854.0,1431.8,1372.7,2014.1,520.2,461.3 +0.9710474750490092,1.4291322407380953,2.356194490192345,841.6,1351.5,1351.9,1920.4,470.3,470.8 +0.9710402886262,1.4292116762920726,2.4870941840919194,897.0,1372.8,1432.0,1972.0,461.5,520.6 +0.9710546609343024,1.4291668891953178,2.6179938779914944,1039.5,1514.4,1642.0,1144.7,495.8,623.5 +0.9710464271418506,1.4291743744548742,2.748893571891069,1323.1,1841.5,2062.0,757.7,597.8,817.9 +0.9708355727174548,1.4289152871701734,2.8797932657906435,1500.4,2335.1,2206.9,576.7,849.0,958.5 +0.9708590129478617,1.428903389152068,3.010692959690218,1350.3,2052.8,1994.1,482.8,934.5,875.6 +0.970843313090147,1.3286419899512891,0.0,1221.0,1951.2,1950.9,540.8,871.1,870.9 +0.970941535221755,1.3293167233270786,0.1308996938995747,1290.9,1994.6,2054.2,543.4,876.0,935.3 +0.9709221997800744,1.3293101522799247,0.2617993877991494,1477.9,1427.5,1047.9,599.2,958.5,1086.0 +0.9708887310398493,1.3292883420093797,0.39269908169872414,1864.6,956.7,737.6,740.3,1165.3,1494.3 +0.9708587139167355,1.32925691155677,0.5235987755982988,2194.5,739.1,611.5,1038.8,1525.9,1398.7 +0.9708477636702219,1.329232365375489,0.6544984694978736,1972.3,624.3,565.1,896.8,1328.5,1269.2 +0.9708357236035002,1.3291845458323555,0.7853981633974483,1921.0,570.8,570.3,840.9,1251.6,1251.4 +0.9708371580875358,1.3291729357840922,0.916297857297023,2014.8,565.0,623.8,853.5,1269.2,1328.0 +0.9708498397572942,1.329133775550893,1.0471975511965976,1071.0,611.4,739.0,945.6,1397.6,1524.9 +0.9708758819001343,1.3290899695635294,1.1780972450961724,740.1,737.1,956.4,1160.3,1698.0,1916.9 +0.9708710731826221,1.3290936265365594,1.3089969389957472,599.0,1047.3,958.3,1478.2,2335.5,2207.4 +0.9708836049816771,1.3290869118736448,1.4398966328953218,542.9,934.1,875.8,1289.0,2050.6,1992.4 +0.9709551847095164,1.3290697781487957,1.5707963267948966,540.7,870.9,870.6,1221.2,1951.2,1951.2 +0.9709474317917025,1.3290684325516846,1.7016960206944713,585.4,875.1,933.5,1246.8,1993.6,2052.0 +0.970942940096654,1.329065637638306,1.832595714594046,692.0,959.1,1087.2,1386.1,1425.7,1046.7 +0.9709980486515277,1.3291000271214908,1.9634954084936205,901.0,1166.3,1494.0,1705.1,956.0,737.0 +0.971015328820484,1.3291192177506497,2.0943951023931953,945.2,1524.5,1397.1,2285.9,738.7,611.4 +0.9710061499315167,1.3290993068821462,2.2252947962927703,853.7,1328.0,1269.1,2013.7,623.6,564.8 +0.9710118889597719,1.3291218155171984,2.356194490192345,841.5,1251.3,1251.8,1920.1,570.3,570.8 +0.9710090504763748,1.3291521125370251,2.4870941840919194,896.9,1269.7,1328.7,1972.3,565.2,624.2 +0.9710128104892553,1.3291429517071802,2.6179938779914944,1039.2,1398.8,1526.4,1343.4,611.5,739.2 +0.9709993638332945,1.3291590312523764,2.748893571891069,1368.4,1700.8,1921.0,898.9,739.3,959.4 +0.9708199271848816,1.328915842945877,2.8797932657906435,1385.1,2334.6,2207.6,692.2,1048.4,958.6 +0.9708463068322792,1.328902395155426,3.010692959690218,1246.9,2053.1,1994.3,586.4,934.6,875.8 +0.9708325839571541,1.228641641451608,0.0,1121.3,1951.2,1951.5,640.8,870.9,870.8 +0.9709362447960003,1.2293186267329812,0.1308996938995747,1187.6,1994.7,2054.2,646.9,875.9,935.4 +0.9709178256491875,1.2293123302682598,0.2617993877991494,1362.4,1627.0,1247.5,714.7,958.4,1086.2 +0.9708843629878339,1.229290506131987,0.39269908169872414,1722.8,1097.9,878.8,882.1,1165.3,1386.0 +0.9708541683305476,1.2292588536865914,0.5235987755982988,2258.7,854.9,727.0,1038.8,1410.5,1283.0 +0.9708430666046978,1.2292339826291978,0.6544984694978736,1972.1,727.7,668.7,897.0,1225.2,1165.8 +0.9708309728352505,1.229185811615514,0.7853981633974483,1921.1,670.8,670.3,840.9,1151.6,1151.3 +0.9708324376517932,1.2293082796617019,0.916297857297023,2014.9,668.6,727.3,853.5,1165.6,1224.8 +0.9711515447888256,1.2291580925153287,1.0471975511965976,1269.7,727.3,854.8,946.1,1282.2,1409.6 +0.9711503311067745,1.2291579027373203,1.1780972450961724,881.4,878.6,1098.0,1160.8,1557.3,1776.4 +0.9711074665287408,1.2291968605389898,1.3089969389957472,714.4,1085.3,958.1,1362.4,2206.1,2342.7 +0.971076005962374,1.2292132721322209,1.4398966328953218,646.4,934.0,875.6,1185.3,2050.7,1992.3 +0.9711016669897048,1.2292068684947688,1.5707963267948966,640.9,870.8,870.8,1121.1,1951.1,1950.6 +0.971050854857146,1.2292042807972061,1.7016960206944713,689.1,875.3,933.7,1143.3,1993.1,2052.4 +0.9710080809990959,1.2291899337709986,1.832595714594046,807.9,959.5,1087.4,1270.6,1623.8,1245.2 +0.9710311362224109,1.229204718949099,1.9634954084936205,1043.3,1167.0,1387.9,1563.7,1096.5,877.8 +0.9710244411667094,1.2291990685177998,2.0943951023931953,945.1,1408.5,1281.5,2231.7,853.9,727.0 +0.9709999153947153,1.2291513303723263,2.2252947962927703,853.9,1224.2,1165.6,2013.8,727.0,668.3 +0.9709984833840489,1.2291449622438952,2.356194490192345,841.8,1151.2,1151.8,1920.3,670.3,671.0 +0.9709959884495856,1.229147694276525,2.4870941840919194,920.0,1166.2,1225.4,1972.4,668.8,727.9 +0.9710068073685,1.2291140099328168,2.6179938779914944,1039.9,1283.3,1411.6,1541.4,727.3,855.2 +0.9710054279606551,1.2291098092650083,2.748893571891069,1324.2,1559.8,1779.8,1040.0,881.1,1101.2 +0.9710297630529614,1.2290873690998732,2.8797932657906435,1268.7,2207.6,2344.6,807.1,1085.3,958.1 +0.9710381031344084,1.2290824142514198,3.010692959690218,1143.0,2052.3,1993.4,689.4,934.2,875.6 +0.9710006788119194,1.1287990214051955,0.0,1021.2,1950.9,1951.4,740.6,871.1,871.1 +0.9710128898085372,1.129334641172278,0.1308996938995747,1083.8,1994.5,2053.9,750.5,875.9,935.4 +0.9709739357035575,1.1293220196207767,0.2617993877991494,1246.6,1827.3,1447.5,830.3,958.6,1085.9 +0.9709350801264176,1.1292969446950791,0.39269908169872414,1580.8,1239.4,1020.0,1023.5,1164.9,1384.8 +0.9709037161965927,1.129264339911089,0.5235987755982988,2195.0,970.5,842.7,1039.0,1295.1,1167.4 +0.9708924756415606,1.129239665458928,0.6544984694978736,1972.2,831.2,772.3,896.9,1121.5,1062.4 +0.9708801624657933,1.129192000326225,0.7853981633974483,1920.7,770.9,770.2,840.9,1051.8,1051.2 +0.9708813398287996,1.1291806468744032,0.916297857297023,2014.0,772.1,830.8,853.4,1062.5,1120.9 +0.9708936971273165,1.1291416642965684,1.0471975511965976,1470.8,842.7,969.8,945.7,1166.4,1293.7 +0.9709193702162077,1.1290978238333287,1.1780972450961724,1023.6,1019.3,1165.1,1160.1,1415.1,1634.5 +0.970914297591962,1.1291014234853036,1.3089969389957472,830.2,1086.0,958.4,1247.5,2004.6,2207.7 +0.9709266564634771,1.1290946956495305,1.4398966328953218,749.9,934.3,875.8,1082.2,2050.9,1992.9 +0.9709981163871092,1.1290773850502895,1.5707963267948966,740.8,870.9,870.7,1021.3,1951.3,1951.2 +0.9709903110674133,1.1290759700084432,1.7016960206944713,792.5,875.1,933.5,1039.7,1993.1,2051.7 +0.9709857512559185,1.1290732782843924,1.832595714594046,923.1,959.2,1086.7,1154.5,1824.9,1445.9 +0.971040779779549,1.129107714620107,1.9634954084936205,1161.1,1166.1,1384.1,1421.4,1238.5,1019.3 +0.9710579483438561,1.1291269222305944,2.0943951023931953,945.5,1293.8,1166.4,2030.4,969.8,842.6 +0.971048531859741,1.1291071039635505,2.2252947962927703,853.8,1121.0,1062.3,2014.3,830.6,771.8 +0.9710566961571716,1.129137138416169,2.356194490192345,841.6,1051.3,1051.9,1920.4,770.4,770.9 +0.9710539117947645,1.1291619079117918,2.4870941840919194,896.9,1062.4,1121.5,1972.1,772.2,831.3 +0.9710577096763675,1.1291515791336764,2.6179938779914944,1039.3,1167.4,1295.0,1742.4,842.5,970.4 +0.9710440246229101,1.1291676664976489,2.748893571891069,1323.1,1417.4,1637.4,1182.1,1022.0,1162.9 +0.9708356343683231,1.128913763255704,2.8797932657906435,1153.6,2004.5,2207.3,923.6,1086.0,958.3 +0.9708585923782103,1.1289021247702964,3.010692959690218,1039.7,2052.6,1994.1,793.4,934.5,875.7 +1.0709226782044978,1.8291046413202632,0.0,1720.8,1851.2,1851.0,41.0,971.1,970.7 +1.070969135561879,1.828940140281333,0.1308996938995747,1808.8,964.6,233.4,25.5,979.7,1038.9 +1.0711206774650126,1.8289881230546456,0.2617993877991494,2055.4,430.9,51.3,21.3,1074.1,1201.5 +1.0710485053203112,1.8289427263667826,0.39269908169872414,2544.8,251.1,31.8,32.0,1306.7,1527.5 +1.071038393520928,1.8289336260717495,0.5235987755982988,2079.6,161.2,33.5,72.2,1963.1,1976.8 +1.071050774671147,1.8289536681385519,0.6544984694978736,1868.7,106.6,47.5,231.4,1846.2,1787.1 +1.0710507609187936,1.8289591240056529,0.7853981633974483,1821.2,70.9,70.4,940.9,1751.9,1751.0 +1.0710504713948523,1.829000170863801,0.916297857297023,232.6,47.5,106.3,956.9,1786.6,1845.8 +1.071048790942256,1.8290088509109608,1.0471975511965976,73.3,34.0,161.3,1061.0,1974.4,2101.9 +1.0710504857650875,1.8290046725465685,1.1780972450961724,31.8,31.6,250.7,1301.2,2403.1,2555.2 +1.071014974307795,1.829037990197183,1.3089969389957472,21.2,51.0,430.2,1865.4,2220.0,2092.1 +1.0709928195875549,1.8290508261787848,1.4398966328953218,25.8,152.4,979.3,1806.3,1947.3,1888.8 +1.0710281577903256,1.8290428880488587,1.5707963267948966,41.0,970.9,970.7,1721.1,1851.1,1851.0 +1.0709862623279947,1.8290413941301171,1.7016960206944713,68.3,978.6,1036.8,1763.9,980.9,238.1 +1.0709510852125743,1.8290304353118687,1.832595714594046,114.0,1074.8,1253.3,1963.9,430.2,51.0 +1.0709803322027733,1.829049697557229,1.9634954084936205,192.5,1307.7,1528.9,2413.2,250.7,31.6 +1.070978234782179,1.8290491594848737,2.0943951023931953,349.9,1961.1,1974.7,2170.6,161.3,34.0 +1.070956507674918,1.8290071641138321,2.2252947962927703,831.3,1845.5,1786.6,1910.3,106.3,47.5 +1.0709564599573342,1.8290065636449409,2.356194490192345,941.5,1750.9,1751.3,1820.2,70.4,71.0 +1.0709543047639953,1.829014621965498,2.4870941840919194,1000.5,1786.9,1846.0,827.2,47.5,106.6 +1.0709640597291552,1.8289859894118181,2.6179938779914944,1240.8,1976.9,2104.2,347.9,33.5,161.2 +1.0709610691638707,1.8289860732329895,2.748893571891069,1464.4,2407.3,2549.8,192.3,32.3,252.3 +1.0708568571597787,1.8288475226019123,2.8797932657906435,1962.2,2218.3,2091.4,114.3,51.8,431.7 +1.0708815079732874,1.8288351989305889,3.010692959690218,1764.3,1949.0,1889.9,68.7,151.9,974.8 +1.0708701671160914,1.7285765660398418,0.0,1621.2,1850.9,1850.8,140.8,970.9,970.7 +1.0709494759945255,1.7293071512555453,0.1308996938995747,1705.2,1347.5,616.8,129.0,979.8,1038.9 +1.0709274838535117,1.7292997864399897,0.2617993877991494,1940.5,629.9,294.4,136.8,1074.1,1201.5 +1.0708943596861804,1.7292782200125627,0.39269908169872414,2431.2,392.0,172.9,173.6,1307.0,1527.6 +1.0708652483993506,1.7292477970600388,0.5235987755982988,2079.5,276.6,149.0,271.3,1844.5,1861.1 +1.0708550023845413,1.7292246202234054,0.6544984694978736,1868.8,210.0,151.0,617.1,1742.6,1683.5 +1.0708432970589699,1.7291783120507371,0.7853981633974483,1820.9,170.8,170.3,940.8,1651.8,1651.3 +1.070844670188036,1.7291681500620493,0.916297857297023,618.7,150.9,209.7,957.3,1683.5,1741.9 +1.0708569482882542,1.729130289976931,1.0471975511965976,272.6,149.4,276.7,1061.5,1859.6,1987.0 +1.0708823239169496,1.7290875634296106,1.1780972450961724,173.2,172.5,391.8,1301.8,2262.4,2481.2 +1.0708766756773425,1.7290920201336142,1.3089969389957472,136.6,250.1,629.4,1866.0,2220.0,2092.0 +1.0708882628945504,1.729085822569827,1.4398966328953218,129.1,541.8,979.1,1702.9,1947.4,1888.6 +1.0709588612279268,1.7290689436120694,1.5707963267948966,140.8,970.8,970.6,1621.3,1851.3,1851.3 +1.0709501831461992,1.729067596362854,1.7016960206944713,171.5,978.4,1036.9,1660.6,1368.8,540.9 +1.0709448615559578,1.7290645746075106,1.832595714594046,229.5,1074.9,1202.5,1848.3,672.7,249.9 +1.0709992664963954,1.7290985607966498,1.9634954084936205,334.0,1308.2,1529.0,2272.1,391.4,172.5 +1.071016012710254,1.7291172282811378,2.0943951023931953,549.4,1848.3,1859.5,2170.1,276.6,149.4 +1.0710064877810168,1.729096719295947,2.2252947962927703,957.4,1742.0,1683.5,1910.6,209.6,150.9 +1.0710120617600627,1.7291186002015586,2.356194490192345,941.4,1651.3,1651.7,1820.1,170.3,170.8 +1.0710092264611255,1.729148295564961,2.4870941840919194,1000.4,1683.6,1742.8,1211.3,150.9,210.0 +1.0710131446323012,1.7291385984525676,2.6179938779914944,1155.1,1861.1,1988.7,590.5,149.0,276.7 +1.0709999680645097,1.729154239494627,2.748893571891069,1464.7,2266.3,2486.5,333.4,173.6,393.7 +1.0708221596887033,1.7289130640046775,2.8797932657906435,1847.4,2219.3,2091.5,229.9,251.0,630.4 +1.0708485170842494,1.728899636086561,3.010692959690218,1660.9,1949.3,1890.3,172.3,537.9,979.0 +1.0708348340002358,1.6286388978530923,0.0,1521.0,1851.2,1850.9,240.8,970.8,971.0 +1.0709370648212722,1.629317979303523,0.1308996938995747,1601.6,1731.4,915.9,232.6,979.5,1038.9 +1.0709184255319208,1.6293116168340065,0.2617993877991494,1824.9,829.2,449.9,252.4,1074.2,1202.0 +1.070884976588079,1.6292898040945272,0.39269908169872414,2289.5,533.1,314.1,315.2,1307.0,1527.7 +1.070854841469513,1.629258219727942,0.5235987755982988,2079.4,392.3,264.6,470.6,1873.2,1745.2 +1.0708437875140548,1.6292334438754212,0.6544984694978736,1868.5,313.5,254.5,1000.3,1638.9,1580.0 +1.0708317152599958,1.6291853777979872,0.7853981633974483,1821.4,270.8,270.2,940.8,1551.8,1551.3 +1.0708331746436466,1.6291735288336562,0.916297857297023,1005.8,254.4,313.2,957.0,1579.9,1638.9 +1.070845937208231,1.6291341591977986,1.0471975511965976,472.1,264.9,392.3,1086.8,1743.8,1871.4 +1.0708721041917473,1.6290901950830463,1.1780972450961724,315.0,313.7,532.9,1301.5,2121.5,2340.5 +1.0708674374296137,1.6290937341818583,1.3089969389957472,252.2,449.2,828.8,1825.3,2219.7,2091.8 +1.070880120966206,1.6290869371216965,1.4398966328953218,232.5,931.6,979.0,1599.4,1947.4,1888.9 +1.0709518561625624,1.6290697776796912,1.5707963267948966,240.8,970.7,970.7,1521.3,1851.5,1851.0 +1.0709442460907912,1.6290684353511617,1.7016960206944713,275.0,978.6,1037.1,1557.3,1758.0,930.2 +1.0709398857165726,1.629065662161453,1.832595714594046,345.1,1241.2,1202.6,1732.8,828.1,449.0 +1.0709951069306485,1.6291001086375536,1.9634954084936205,475.8,1308.0,1529.1,2130.4,532.6,313.6 +1.0710124751743018,1.6291193791020198,2.0943951023931953,749.2,1845.6,1743.9,2170.2,392.1,264.9 +1.0710033663789105,1.6290995512730615,2.2252947962927703,957.3,1638.6,1580.0,1910.6,313.1,254.3 +1.071009150210779,1.6291221535007372,2.356194490192345,941.5,1551.5,1551.8,1820.6,270.3,270.8 +1.0710063230803293,1.629152552990351,2.4870941840919194,1000.4,1580.2,1639.4,1596.6,254.5,313.6 +1.0710100777643166,1.6291434833017917,2.6179938779914944,1155.2,1745.6,1873.9,745.9,264.6,392.4 +1.0709965892552613,1.6291596491340097,2.748893571891069,1464.7,2125.3,2344.6,474.7,315.0,535.1 +1.070818666636436,1.6289163904715387,2.8797932657906435,1731.8,2219.0,2091.7,345.6,450.4,829.8 +1.0708453118358638,1.628902800916883,3.010692959690218,1557.3,1948.8,1890.5,275.8,924.2,979.0 +1.0708317106658714,1.5286420593647456,0.0,1421.1,1851.4,1851.1,340.8,971.0,971.0 +1.0709358343367907,1.5293188042768242,0.1308996938995747,1498.1,1891.4,1299.8,336.2,979.7,1038.8 +1.0709174825982375,1.5293125279598216,0.2617993877991494,1709.3,1028.7,693.1,368.0,1074.0,1201.6 +1.0708840142775728,1.5292906989529262,0.39269908169872414,2148.1,674.4,455.2,456.9,1306.9,1527.8 +1.0708538004673356,1.5292590235652317,0.5235987755982988,2079.4,507.7,380.2,669.8,1757.2,1629.8 +1.0708426833818274,1.5292341206402282,0.6544984694978736,1868.4,417.1,358.1,1000.4,1535.5,1476.6 +1.0708305837819714,1.5291859153429486,0.7853981633974483,1821.4,370.7,370.3,940.8,1451.7,1451.2 +1.0708320511435194,1.5291739325465121,0.916297857297023,1393.1,357.9,416.7,957.0,1476.7,1535.3 +1.070844853253697,1.5291344435470784,1.0471975511965976,671.9,380.5,507.8,1061.4,1628.9,1755.8 +1.070871084183621,1.5290903827998394,1.1780972450961724,456.6,454.8,674.0,1301.4,1980.5,2199.5 +1.0708664955768337,1.529093850206316,1.3089969389957472,367.9,648.7,1028.2,1709.5,2219.5,2091.9 +1.070879265790917,1.5290870058447812,1.4398966328953218,336.0,1037.6,979.2,1496.1,1947.3,1889.2 +1.0709510906837483,1.5290698254525752,1.5707963267948966,340.8,971.0,970.6,1421.2,1851.2,1851.1 +1.0709435645784533,1.5290684837928343,1.7016960206944713,378.5,978.7,1037.3,1453.9,1889.8,1319.6 +1.0709392800061035,1.5290657291530843,1.832595714594046,460.7,1074.8,1202.6,1617.3,1027.3,648.3 +1.0709945656749795,1.529100211431751,1.9634954084936205,617.5,1308.1,1529.0,1988.4,673.7,454.7 +1.0710119832248706,1.5291195292396218,2.0943951023931953,948.7,1755.6,1628.3,2170.1,507.7,380.5 +1.0710029084132344,1.5290997542366347,2.2252947962927703,957.2,1535.1,1476.3,1910.5,416.6,357.9 +1.0710087102310095,1.5291224128968843,2.356194490192345,941.6,1451.2,1451.7,1820.3,370.2,370.8 +1.0710058846674504,1.5291528684649616,2.4870941840919194,1000.5,1476.6,1535.8,1868.8,358.0,417.2 +1.0710096280014483,1.5291438487375089,2.6179938779914944,1155.2,1630.2,1757.6,944.7,380.2,507.9 +1.0709961149908178,1.529160057270323,2.748893571891069,1464.7,1983.2,2203.5,616.2,456.5,676.4 +1.0708183217125005,1.5289166578698268,2.8797932657906435,1616.4,2219.5,2091.5,461.1,649.7,1028.9 +1.070845009990863,1.5289030447998155,3.010692959690218,1454.0,1949.1,1890.8,379.3,1038.2,979.3 +1.070831425401985,1.4286423043226462,0.0,1321.4,1851.1,1851.0,440.9,971.0,970.9 +1.0709357163617754,1.42931887491411,0.1308996938995747,1394.6,1891.1,1684.0,439.8,979.5,1038.9 +1.0709173890075379,1.4293126059058663,0.2617993877991494,1593.6,1228.0,848.6,483.6,1074.0,1201.8 +1.0708839184297687,1.4292907751101738,0.39269908169872414,2006.2,815.6,596.4,598.7,1307.1,1635.2 +1.0708536973701337,1.4292590913107155,0.5235987755982988,2079.6,623.4,495.8,869.2,1642.1,1514.4 +1.0708425745216599,1.4292341767554457,0.6544984694978736,1868.6,520.4,461.6,1000.3,1432.0,1372.9 +1.0708304724969897,1.4291859587974023,0.7853981633974483,1821.0,470.8,470.2,940.7,1351.6,1351.3 +1.070831940620557,1.4291739638206966,0.916297857297023,1779.9,461.4,520.3,957.1,1372.8,1431.9 +1.0708447463694508,1.429134463982345,1.0471975511965976,871.3,496.0,623.3,1061.3,1513.3,1640.3 +1.0708709831708323,1.4290903945304771,1.1780972450961724,598.3,596.0,815.0,1301.5,1838.7,2058.6 +1.0708664016945604,1.4290938554730528,1.3089969389957472,483.4,848.0,1073.9,1594.3,2360.1,2092.1 +1.0708791797829325,1.4290870068274717,1.4398966328953218,439.4,1037.4,979.3,1392.5,1947.4,1889.1 +1.0709510128022206,1.4290698246200164,1.5707963267948966,440.8,970.8,970.8,1321.3,1851.7,1851.1 +1.0709434942947156,1.4290684830630132,1.7016960206944713,481.9,978.5,1037.1,1350.3,1890.1,1709.0 +1.070939216585321,1.4290657300739578,1.832595714594046,576.3,1074.8,1202.6,1501.8,1226.4,847.5 +1.0709945080702126,1.4291002155880435,1.9634954084936205,759.2,1308.0,1635.0,1846.8,814.8,595.8 +1.0710119300674297,1.4291195376889014,2.0943951023931953,1060.7,1639.9,1512.7,2170.5,623.0,495.9 +1.0710028583671412,1.4290997674330863,2.2252947962927703,957.3,1431.4,1372.6,1910.9,520.1,461.4 +1.071008661863734,1.4291224311698492,2.356194490192345,941.4,1351.4,1351.6,1820.5,470.3,470.8 +1.0710058364731017,1.429152891824585,2.4870941840919194,1000.5,1372.9,1432.5,1868.7,461.6,520.7 +1.0710095788552028,1.4291438766275921,2.6179938779914944,1155.1,1514.7,1642.3,1144.1,495.9,623.5 +1.0709960636407805,1.4291600890783112,2.748893571891069,1509.7,1841.8,2062.0,757.7,598.0,818.2 +1.0708182883082324,1.428916680389156,2.8797932657906435,1500.9,2359.4,2091.8,576.8,849.0,1074.1 +1.0708449816076706,1.428903064602971,3.010692959690218,1350.5,1949.1,1890.4,482.8,1038.2,979.2 +1.0708313991860094,1.3286423244791883,0.0,1221.3,1851.2,1851.0,540.9,971.1,970.9 +1.0709357063717644,1.3293188818807762,0.1308996938995747,1290.9,1891.7,1950.6,543.4,979.6,1039.1 +1.070917379887655,1.3293126131408854,0.2617993877991494,1478.1,1427.4,1048.0,599.2,1073.9,1201.6 +1.070883908227314,1.3292907816575688,0.39269908169872414,1864.1,956.9,737.6,740.2,1306.7,1527.7 +1.070853685912996,1.329259096477303,0.5235987755982988,2079.3,739.0,611.5,1068.5,1525.9,1398.4 +1.070842562163742,1.3292341801955518,0.6544984694978736,1868.4,624.1,565.1,1000.4,1328.5,1269.6 +1.0708304597545724,1.329185960404021,0.7853981633974483,1821.1,570.8,570.3,940.8,1251.7,1251.2 +1.0708319279622989,1.3291739636646571,0.916297857297023,1911.2,565.0,623.8,979.8,1269.5,1328.0 +1.0708447342175142,1.3291344622602812,1.0471975511965976,1071.1,611.6,739.0,1061.4,1397.2,1524.8 +1.0708459009936178,1.3291305277917036,1.1780972450961724,740.0,737.2,956.2,1301.5,1697.7,1917.0 +1.0708649986582248,1.3291119455630724,1.3089969389957472,599.0,1047.7,1073.9,1478.4,2219.6,2092.1 +1.0708841460345078,1.3291017285972297,1.4398966328953218,542.9,1037.4,979.1,1289.0,1947.2,1889.0 +1.0709552781067149,1.3290847233467864,1.5707963267948966,540.7,970.9,970.7,1221.2,1851.5,1851.0 +1.0709447717852238,1.3290832914822897,1.7016960206944713,585.5,978.5,1037.1,1246.9,1889.7,1948.5 +1.0709371038832614,1.3290795172056735,1.832595714594046,691.9,1075.0,1202.6,1386.0,1425.6,1046.6 +1.0709893594901423,1.3291121050343295,1.9634954084936205,900.8,1308.2,1529.0,1705.2,956.0,736.8 +1.0710044832976153,1.329128963411163,2.0943951023931953,1060.8,1524.4,1397.2,2170.2,738.8,611.4 +1.07099394266007,1.3291064482244874,2.2252947962927703,957.3,1328.2,1269.1,1910.4,623.5,564.8 +1.070999086955456,1.329126269408288,2.356194490192345,941.4,1251.0,1251.6,1820.5,570.2,570.8 +1.0709963576064936,1.329154018197704,2.4870941840919194,1000.5,1269.5,1328.5,1869.1,565.2,624.2 +1.0710008254425443,1.32914262088596,2.6179938779914944,1155.1,1399.1,1526.5,1343.4,611.5,739.3 +1.0709594139534553,1.3292042376161617,2.748893571891069,1527.0,1700.9,1920.7,899.1,739.3,959.5 +1.0708279818268338,1.328954401935591,2.8797932657906435,1385.0,2219.2,2091.7,692.2,1048.5,1074.0 +1.0708608917150366,1.3289374101048996,3.010692959690218,1247.0,1949.3,1890.2,586.4,1038.0,978.9 +1.070843949555975,1.228669781975495,0.0,1121.0,1851.2,1851.2,640.7,970.9,971.0 +1.0709161377959084,1.2293017226338083,0.1308996938995747,1187.3,1891.0,1950.6,646.9,979.4,1038.9 +1.070909947597996,1.2292992399430742,0.2617993877991494,1362.6,1626.9,1247.6,714.6,1073.9,1201.8 +1.070880385886662,1.2292799002762278,0.39269908169872414,1722.7,1098.0,878.7,882.0,1307.1,1525.3 +1.070851492480802,1.2292496763649519,0.5235987755982988,2220.2,854.7,727.2,1154.3,1410.5,1283.0 +1.0708408920814396,1.2292257303317566,0.6544984694978736,1868.7,727.7,668.7,1000.3,1224.9,1165.7 +1.0708289596439988,1.2291782524246684,0.7853981633974483,1821.3,670.8,670.3,940.8,1151.7,1151.1 +1.070830438798183,1.2291669021643037,0.916297857297023,1910.9,668.5,727.2,957.0,1165.8,1224.6 +1.0708431141765606,1.229127967394823,1.0471975511965976,1270.6,727.1,854.4,1061.1,1281.8,1409.4 +1.0708690970790429,1.2290843448368216,1.1780972450961724,881.8,878.2,1097.3,1301.7,1556.6,1776.1 +1.070864199208179,1.229088169394164,1.3089969389957472,714.7,1201.4,1074.0,1362.9,2204.0,2092.1 +1.0708766070948663,1.2290816029464993,1.4398966328953218,646.2,1037.6,979.1,1185.6,1947.4,1889.0 +1.070948029779244,1.2290645386142782,1.5707963267948966,640.8,971.1,970.6,1121.1,1851.2,1851.2 +1.0708958952163097,1.2290584333260814,1.7016960206944713,688.9,978.6,1037.1,1143.2,1889.9,1948.2 +1.07092066867586,1.2290646948659467,1.832595714594046,807.7,1074.9,1202.6,1270.2,1625.0,1245.9 +1.0709819688429734,1.2291030120169428,1.9634954084936205,1042.7,1308.1,1525.1,1563.1,1097.1,878.2 +1.0709992127418726,1.2291221532615633,2.0943951023931953,1060.7,1409.0,1281.7,2170.4,854.2,727.0 +1.0709889895479496,1.2291002702974465,2.2252947962927703,957.4,1224.5,1165.6,1910.5,727.1,668.4 +1.0709941225058262,1.2291200377216709,2.356194490192345,941.6,1151.3,1151.6,1820.4,670.3,670.8 +1.0709914401783565,1.2291474907222413,2.4870941840919194,1000.5,1166.0,1224.9,1868.4,668.7,727.7 +1.070996022594355,1.2291357923433612,2.6179938779914944,1155.0,1283.3,1411.1,1542.4,727.1,854.9 +1.0709839726849588,1.2291497668294487,2.748893571891069,1464.6,1559.2,1779.3,1040.5,880.8,1100.8 +1.0708162266976,1.2289162885956373,2.8797932657906435,1269.5,2203.9,2091.9,807.9,1201.6,1074.1 +1.0708431416385507,1.2289025589939913,3.010692959690218,1143.3,1949.6,1890.2,689.9,1038.1,979.2 +1.0708298142981458,1.1286418733526846,0.0,1021.0,1851.0,1851.0,740.9,970.9,970.8 +1.0709349990847699,1.1293192462436887,0.1308996938995747,1083.7,1891.3,1950.4,750.5,979.5,1038.9 +1.0709168074699211,1.1293130180303619,0.2617993877991494,1246.8,1826.3,1446.7,830.2,1074.2,1201.6 +1.0708833273207787,1.1292911788860507,0.39269908169872414,1581.0,1239.0,1019.8,1023.5,1431.2,1415.3 +1.070853069136757,1.129495455695058,0.5235987755982988,2079.2,995.6,842.7,1154.2,1295.0,1167.3 +1.0711878504408847,1.1289942754963564,0.6544984694978736,1868.4,831.1,772.2,1000.1,1121.3,1062.3 +1.071188266982766,1.12900237473825,0.7853981633974483,1820.9,770.9,770.5,940.7,1051.6,1051.2 +1.0711869844354818,1.1290501401380952,0.916297857297023,1911.1,772.2,831.0,957.2,1062.1,1121.2 +1.0711823111740202,1.1290658785539733,1.0471975511965976,1469.6,842.9,970.3,1061.4,1166.4,1293.7 +1.071179471413266,1.1290678238517105,1.1780972450961724,1023.4,1020.0,1239.4,1407.9,1415.8,1634.7 +1.0711383844064635,1.1291053527951402,1.3089969389957472,830.2,1201.1,1073.7,1246.9,2005.5,2142.4 +1.0711102330637101,1.129120435208442,1.4398966328953218,750.1,1037.5,979.2,1081.9,1947.1,1888.5 +1.0711396877809694,1.1291135318728482,1.5707963267948966,741.0,971.2,970.9,1021.1,1851.3,1851.0 +1.0710924365220158,1.1291115628102681,1.7016960206944713,792.7,978.7,1037.2,1039.8,1890.2,1948.2 +1.0710526505488174,1.1290988001241917,1.832595714594046,923.5,1075.1,1203.2,1154.7,1823.6,1444.9 +1.07107799520913,1.1291156942824239,1.9634954084936205,1184.9,1430.0,1414.8,1421.9,1237.9,1019.1 +1.0710727980397823,1.1291123864591586,2.0943951023931953,1060.8,1292.8,1166.0,2031.7,969.7,842.6 +1.0710489734787938,1.1290670840735477,2.2252947962927703,957.3,1120.8,1062.0,1910.6,830.7,772.0 +1.0710476393473083,1.129063005183899,2.356194490192345,941.7,1051.3,1051.5,1820.1,770.2,771.0 +1.0710448423436474,1.129067714281057,2.4870941840919194,1000.7,1062.3,1121.4,1868.7,772.3,831.4 +1.0710549664788216,1.12903574870235,2.6179938779914944,1155.5,1167.7,1295.4,1740.9,843.0,970.9 +1.0710527913529129,1.1290329370948204,2.748893571891069,1417.0,1418.1,1638.0,1181.6,1022.7,1242.8 +1.0710761188018214,1.1290116599202495,2.8797932657906435,1153.2,2007.0,2144.0,922.9,1201.2,1073.8 +1.0710833590728606,1.1290076401043758,3.010692959690218,1039.7,1948.8,1889.8,793.2,1038.0,979.1 +1.1711187295509122,1.8291439077840985,0.0,1721.2,1750.5,1750.7,40.9,1071.0,1071.2 +1.171039060743734,1.8289412772321305,0.1308996938995747,1808.5,964.8,148.9,25.5,1083.3,1142.5 +1.1710389732932625,1.8289414042081946,0.2617993877991494,2055.6,430.9,51.3,21.3,1189.7,1317.2 +1.1710375495093697,1.8289406873010015,0.39269908169872414,2404.2,251.1,31.8,32.0,1448.1,1668.7 +1.1710415224586102,1.8289470826323186,0.5235987755982988,1963.9,161.2,33.5,72.2,2042.9,1976.3 +1.1710542883149557,1.8289682285559152,0.6544984694978736,1765.6,106.6,47.5,231.4,1846.3,1786.8 +1.1710529735761155,1.828968941162789,0.7853981633974483,1720.9,70.9,70.4,1040.9,1751.9,1751.1 +1.1710526943833577,1.8290035564142981,0.916297857297023,232.6,47.5,106.3,1060.6,1786.6,1845.7 +1.1710527705012563,1.82900582607415,1.0471975511965976,117.3,34.0,161.3,1176.7,1975.0,2102.0 +1.17105770498672,1.8289961483134292,1.1780972450961724,31.8,31.6,250.7,1442.3,2402.7,2449.8 +1.1710264175881107,1.8290253149374398,1.3089969389957472,21.2,51.0,430.3,2056.4,2104.0,1976.3 +1.1710091057186693,1.8290354461766662,1.4398966328953218,25.8,152.4,981.0,1806.5,1843.9,1785.2 +1.1710495216305856,1.8290262855990904,1.5707963267948966,40.9,1071.1,1070.6,1721.3,1751.3,1751.3 +1.1710123895139146,1.8290249392005304,1.7016960206944713,68.3,1082.2,1140.5,1763.9,980.9,152.4 +1.1709814341222424,1.829015297303,1.832595714594046,114.0,1190.5,1318.1,1963.4,430.2,51.0 +1.1710141584102425,1.8290368358472193,1.9634954084936205,192.5,1449.8,1670.4,2413.2,250.8,31.6 +1.1710145700344554,1.8290391700591002,2.0943951023931953,349.9,2048.1,1974.8,2054.5,161.3,34.0 +1.1709943520048192,1.8290003158873414,2.2252947962927703,831.3,1845.2,1786.6,1806.8,106.3,47.5 +1.1709948703134614,1.829002908596,2.356194490192345,1041.6,1751.1,1751.8,1720.3,70.4,70.9 +1.1709924322110392,1.8290139496038063,2.4870941840919194,1104.1,1787.2,1846.0,827.2,47.5,106.6 +1.1710012306147983,1.8289878723329416,2.6179938779914944,1295.9,1977.0,2104.5,347.9,33.5,161.2 +1.1709967741783072,1.8289900103280696,2.748893571891069,1605.9,2407.1,2454.7,192.3,32.3,252.3 +1.1708711700391476,1.8288400633090058,2.8797932657906435,1962.5,2102.6,1975.0,114.3,51.9,431.8 +1.1708939639459865,1.8288287333221513,3.010692959690218,1764.4,1845.9,1786.5,68.7,152.0,975.3 +1.1708816793115264,1.7285700433381832,0.0,1621.5,1751.1,1751.0,140.8,1070.9,1071.0 +1.17095455326352,1.7293045722118543,0.1308996938995747,1705.2,1347.6,532.4,129.1,1083.3,1142.5 +1.1709315311733004,1.7292968991030362,0.2617993877991494,1940.8,630.0,250.5,136.8,1189.7,1317.2 +1.1708984348508438,1.7292753674059091,0.39269908169872414,2403.4,392.2,172.9,173.5,1448.6,1669.2 +1.1708695611356823,1.72924522839204,0.5235987755982988,1963.7,276.7,149.0,271.3,1988.7,1861.1 +1.1708595110469415,1.7292224568868244,0.6544984694978736,1765.2,210.0,151.0,617.0,1742.7,1683.3 +1.1708478845010415,1.7291765908592418,0.7853981633974483,1721.3,170.8,170.3,1040.6,1651.7,1651.4 +1.1708492269369701,1.729166854798471,0.916297857297023,618.9,150.9,209.7,1060.6,1683.1,1742.1 +1.1708613741272553,1.7291293729280435,1.0471975511965976,272.6,149.4,276.7,1319.7,1859.6,1987.1 +1.170886541104234,1.7290869472297143,1.1780972450961724,173.3,172.6,391.7,1442.9,2262.7,2413.2 +1.170880643113854,1.729091627401875,1.3089969389957472,136.6,250.1,629.5,1940.8,2104.0,1976.3 +1.170891955995091,1.7290855796714606,1.4398966328953218,129.0,541.7,1082.6,1702.8,1844.2,1785.7 +1.1709622708964578,1.7290687622680387,1.5707963267948966,140.8,1071.0,1070.6,1621.3,1751.2,1751.0 +1.1709533288623115,1.7290674124124428,1.7016960206944713,171.5,1082.1,1140.5,1660.7,1368.9,541.0 +1.1709477676846696,1.7290643375445143,1.832595714594046,229.5,1190.4,1318.2,1848.3,629.1,249.8 +1.1710019680075379,1.7290982133396786,1.9634954084936205,334.0,1449.8,1670.7,2272.0,391.5,203.5 +1.171018556618354,1.7291167325017038,2.0943951023931953,549.4,1986.6,1859.2,2054.8,276.6,149.3 +1.171008918466525,1.729096060809749,2.2252947962927703,1060.8,1741.7,1683.1,1807.2,209.6,150.9 +1.1710144286521738,1.7291177652046428,2.356194490192345,1041.8,1650.9,1651.7,1720.3,170.2,170.8 +1.171011584012625,1.729147280438665,2.4870941840919194,1104.0,1683.7,1742.8,1211.4,150.9,210.1 +1.1710155311075088,1.7291374229436427,2.6179938779914944,1270.7,1861.4,1988.9,546.7,149.0,276.7 +1.1710024318847412,1.729152922840767,2.748893571891069,1606.2,2266.7,2407.8,333.5,173.6,393.7 +1.1708235922876042,1.7289121456820538,2.8797932657906435,1847.6,2103.3,1975.9,229.9,251.0,630.6 +1.1708497217858904,1.7288988405992503,3.010692959690218,1661.1,1845.6,1786.9,172.3,537.9,1082.9 +1.1708359448577976,1.6286380984828424,0.0,1521.2,1751.0,1751.0,240.8,1071.0,1070.9 +1.1709375668348723,1.629317732862421,0.1308996938995747,1601.7,1787.4,915.9,232.6,1083.3,1142.4 +1.1709188175194993,1.629311337521083,0.2617993877991494,1824.9,829.2,449.9,252.4,1189.6,1317.5 +1.170885364442221,1.6292895240558107,0.39269908169872414,2289.7,533.4,314.0,315.2,1448.5,1669.3 +1.1708552476405834,1.6292579623423022,0.5235987755982988,1963.6,392.2,264.7,470.6,1872.9,1745.3 +1.1708442096904932,1.6292332204714441,0.6544984694978736,1765.0,313.6,254.5,1002.8,1639.2,1579.8 +1.1708321437556735,1.6291851918221316,0.7853981633974483,1721.2,270.8,270.3,1040.9,1551.8,1551.1 +1.1708336002860695,1.629173378929365,0.916297857297023,1005.8,254.4,313.2,1060.7,1579.8,1638.6 +1.1708463515609833,1.6291340413466697,1.0471975511965976,472.2,264.9,392.3,1176.9,1744.2,1871.5 +1.1708725007349285,1.6290901026994713,1.1780972450961724,314.9,313.7,532.8,1442.6,2121.1,2340.1 +1.1708678128571208,1.6290936607025832,1.3089969389957472,252.3,449.4,828.8,1825.2,2104.1,1976.7 +1.1708804732157483,1.629086876442974,1.4398966328953218,232.5,931.9,1082.5,1599.6,1843.6,1785.1 +1.1709521843247195,1.6290697223776758,1.5707963267948966,240.8,1070.8,1070.6,1521.2,1751.3,1750.8 +1.1709445519002197,1.6290683800955361,1.7016960206944713,275.0,1082.0,1140.4,1557.0,1786.7,930.3 +1.1709401711249714,1.6290656027590602,1.832595714594046,345.0,1241.4,1318.3,1732.8,828.0,449.0 +1.1709953746612496,1.6291000400796127,1.9634954084936205,475.8,1449.5,1671.1,2130.3,532.6,313.6 +1.1710127291727475,1.6291192980923768,2.0943951023931953,749.1,1871.2,1743.6,2054.7,392.1,264.9 +1.1710036103876988,1.6290994565917267,2.2252947962927703,1061.0,1638.7,1580.0,1807.2,313.1,254.4 +1.1710093884292843,1.629122043736825,2.356194490192345,1041.5,1551.2,1551.9,1720.4,270.2,270.8 +1.1710065602717876,1.62915242764824,2.4870941840919194,1104.1,1580.2,1639.3,1596.9,254.5,313.6 +1.171010317247385,1.6291433440967351,2.6179938779914944,1270.7,1745.6,1873.6,745.9,264.6,392.4 +1.1709968354153697,1.6291594976364456,2.748893571891069,1605.9,2125.1,2345.2,474.9,315.0,535.1 +1.170818811219442,1.6289162912311457,2.8797932657906435,1732.0,2103.6,1976.0,345.5,450.3,829.8 +1.1708454350242123,1.628902713183247,3.010692959690218,1557.4,1845.9,1787.0,275.8,924.3,1082.8 +1.1708318268094993,1.5286419738124937,0.0,1421.2,1751.0,1750.9,340.8,1071.0,1070.8 +1.1709358977852231,1.5293187826859673,0.1308996938995747,1497.9,1787.5,1300.0,336.2,1083.2,1142.6 +1.1709175242206116,1.5293124998847945,0.2617993877991494,1709.4,1028.8,649.2,368.0,1189.9,1317.3 +1.1708840486822794,1.529290666731934,0.39269908169872414,2147.7,674.3,455.2,457.0,1448.6,1776.7 +1.1708538321552242,1.529258988922303,0.5235987755982988,1963.7,507.8,380.2,670.0,1757.0,1629.7 +1.170842713820923,1.529234084351661,0.6544984694978736,1764.7,417.1,358.1,1103.9,1535.8,1476.5 +1.1708306135930227,1.52918587765805,0.7853981633974483,1721.1,370.8,370.3,1040.8,1451.6,1451.3 +1.1708320807747123,1.5291738935368697,0.916297857297023,1392.9,357.9,416.8,1060.8,1476.3,1535.2 +1.1708448830702223,1.5291344033862897,1.0471975511965976,671.6,380.4,507.9,1177.0,1628.6,1755.7 +1.170871114495181,1.5290903416898138,1.1780972450961724,456.5,454.9,674.0,1442.9,1980.0,2199.5 +1.1708665267026228,1.5290938083761574,1.3089969389957472,367.8,648.7,1028.0,1710.0,2104.2,1976.2 +1.1708792978296425,1.5290869636682605,1.4398966328953218,335.9,1141.2,1082.7,1496.0,1844.0,1785.6 +1.1709511235121908,1.5290697832589524,1.5707963267948966,340.7,1070.9,1070.7,1421.5,1751.5,1751.0 +1.1709435982309673,1.529068441895879,1.7016960206944713,378.5,1082.1,1140.6,1453.8,1786.4,1319.8 +1.1708985069803006,1.52920622391977,1.832595714594046,460.8,1190.4,1318.2,1616.9,1027.7,648.8 +1.1711008669637313,1.52933557562837,1.9634954084936205,617.7,1449.3,1776.1,1987.9,674.1,455.0 +1.1709879139437855,1.5292147480573897,2.0943951023931953,948.6,1755.4,1628.2,2054.9,507.9,380.5 +1.1709434175666558,1.5291287027144813,2.2252947962927703,1061.0,1535.2,1476.2,1807.3,416.7,357.9 +1.170940772831236,1.5291150779391822,2.356194490192345,1041.7,1451.1,1451.6,1720.3,370.3,370.8 +1.1709388717694118,1.529121448287927,2.4870941840919194,1104.0,1476.5,1535.8,1765.0,358.1,417.2 +1.1709481019990116,1.5290945670956113,2.6179938779914944,1270.5,1629.9,1757.6,945.3,380.2,508.0 +1.1709434532650533,1.5290969577579883,2.748893571891069,1651.5,1983.3,2203.1,616.4,456.5,676.3 +1.17081762272076,1.5289063223712953,2.8797932657906435,1616.2,2103.5,1975.7,461.1,649.9,1029.2 +1.1708450098866703,1.5288923876118266,3.010692959690218,1453.8,1845.7,1786.9,379.4,1141.6,1082.6 +1.1708323190396084,1.4286314814898242,0.0,1321.3,1751.2,1751.2,440.8,1070.9,1071.0 +1.1709351688777418,1.4293180430810102,0.1308996938995747,1394.7,1787.6,1683.6,439.7,1083.0,1142.5 +1.1709166433150966,1.4293117140741205,0.2617993877991494,1593.6,1227.8,848.7,483.6,1189.8,1317.1 +1.170883205120493,1.4292899014211522,0.39269908169872414,2006.0,815.6,596.4,598.6,1448.5,1669.5 +1.1708530623620252,1.4292582954044695,0.5235987755982988,1963.8,623.3,495.9,869.4,1641.8,1513.9 +1.170841998959406,1.4292334851478574,0.6544984694978736,1765.0,520.7,461.5,1104.1,1432.0,1373.0 +1.1708299330501344,1.429185387647899,0.7853981633974483,1721.3,470.9,470.2,1041.0,1351.8,1351.4 +1.1708314022890633,1.429173507313696,0.916297857297023,1807.4,461.4,520.3,1060.6,1373.1,1431.7 +1.1708441818176887,1.4291341127136787,1.0471975511965976,871.2,495.9,623.3,1176.9,1512.9,1640.2 +1.1708703719132203,1.4290901375636151,1.1780972450961724,598.3,596.1,815.2,1442.7,1839.1,2057.6 +1.1708657251132546,1.429093667821713,1.3089969389957472,483.4,848.1,1189.5,1593.8,2103.7,1976.2 +1.1708784263563847,1.4290868610735523,1.4398966328953218,439.4,1140.8,1082.6,1392.5,1843.7,1785.8 +1.1709501786730312,1.4290697061438116,1.5707963267948966,440.8,1070.8,1070.8,1321.2,1751.4,1751.3 +1.1709425826047402,1.4290683657329133,1.7016960206944713,482.0,1082.1,1140.3,1350.4,1786.4,1709.0 +1.1709382367603678,1.4290655878303293,1.832595714594046,576.4,1190.6,1318.3,1501.4,1226.4,847.5 +1.1709934708838947,1.429100037336262,1.9634954084936205,759.3,1449.6,1670.7,1846.7,814.7,595.7 +1.1710108503278474,1.429119315405059,2.0943951023931953,1148.7,1639.9,1512.8,2055.0,623.2,495.9 +1.1710017566564515,1.4290994910604042,2.2252947962927703,1060.8,1431.5,1372.8,1807.1,520.1,461.4 +1.171007554413382,1.4291221007026313,2.356194490192345,1041.6,1351.1,1352.0,1720.3,470.3,470.9 +1.171004734002983,1.4291525150208835,2.4870941840919194,1103.9,1372.9,1432.2,1765.4,461.6,520.7 +1.1710084976906512,1.4291434582532743,2.6179938779914944,1270.5,1514.8,1642.0,1143.9,495.9,623.6 +1.1709950047297677,1.4291596417653578,2.748893571891069,1668.7,1842.2,2062.4,757.5,598.0,818.0 +1.1708181073019406,1.4289164874628293,2.8797932657906435,1500.7,2103.8,1975.8,576.7,849.1,1189.6 +1.1708449122647113,1.4289028132849602,3.010692959690218,1350.5,1845.7,1786.6,482.8,1141.7,1082.9 +1.1708313879604313,1.3286420804856132,0.0,1221.4,1751.0,1750.6,540.8,1070.9,1070.9 +1.170935672110168,1.3293188565499716,0.1308996938995747,1291.0,1787.5,1847.0,543.3,1083.1,1142.7 +1.1709173314473904,1.329312583591864,0.2617993877991494,1478.2,1427.5,1047.9,599.2,1189.6,1317.2 +1.1708838545507545,1.329290748885808,0.39269908169872414,1864.4,956.8,737.6,740.3,1448.8,1666.5 +1.1708536301685817,1.3292590613262307,0.5235987755982988,1963.7,739.1,611.5,1068.5,1526.1,1398.6 +1.1708425053392382,1.3292341428966472,0.6544984694978736,1764.9,624.1,565.2,1104.0,1328.3,1269.4 +1.1708304029003793,1.3291859213851591,0.7853981633974483,1721.3,570.7,570.4,1040.8,1251.5,1251.3 +1.1708318713754222,1.329173922924542,0.916297857297023,1807.5,564.8,623.8,1060.7,1269.5,1327.9 +1.170844678339153,1.3291344201581574,1.0471975511965976,1071.1,611.6,739.0,1176.8,1397.3,1524.6 +1.1708709170906304,1.329090348795315,1.1780972450961724,739.9,737.4,956.2,1442.5,1697.5,1917.4 +1.1708683170533394,1.3290917643425766,1.3089969389957472,599.0,1047.6,1189.4,1478.5,2160.7,1976.5 +1.170879452136626,1.3290857744570015,1.4398966328953218,542.9,1141.1,1082.5,1288.9,1843.9,1785.3 +1.1709509513988254,1.3290686737096595,1.5707963267948966,540.7,1070.9,1070.7,1221.4,1751.6,1750.7 +1.170943486242244,1.3290673353778528,1.7016960206944713,585.4,1082.1,1140.5,1246.8,1786.7,1844.8 +1.170939375602164,1.3290646342306172,1.832595714594046,692.1,1190.5,1318.4,1386.0,1425.5,1046.7 +1.170994840648667,1.3290992299571531,1.9634954084936205,900.8,1449.6,1666.0,1704.9,955.9,736.9 +1.1710123992663086,1.3291187004625211,2.0943951023931953,1176.3,1524.4,1397.0,2186.5,738.7,611.4 +1.1710034159167821,1.3290990971964503,2.2252947962927703,1060.8,1328.1,1269.3,1806.9,623.6,564.8 +1.1710092590756858,1.329121934142985,2.356194490192345,1041.4,1251.1,1251.9,1720.7,570.4,570.9 +1.1710064276885586,1.3291525601335938,2.4870941840919194,1104.1,1269.4,1328.6,1765.3,565.1,624.2 +1.1710101261748103,1.329143690319949,2.6179938779914944,1270.9,1399.1,1526.5,1343.3,611.6,739.2 +1.1709965364703216,1.3291600232674348,2.748893571891069,1605.9,1700.9,1920.7,899.0,739.4,959.4 +1.1708183959623677,1.328916489651141,2.8797932657906435,1385.0,2160.1,1976.3,692.4,1048.4,1189.8 +1.170845064835623,1.3289028871779265,3.010692959690218,1246.9,1845.7,1787.1,586.4,1141.5,1082.7 +1.1708314875154266,1.2286421703821606,0.0,1121.4,1750.8,1751.3,640.9,1070.8,1071.0 +1.1709357560757339,1.2293188580958923,0.1308996938995747,1187.4,1787.5,1846.8,646.9,1083.2,1142.7 +1.1709174090440608,1.2293125833037724,0.2617993877991494,1362.4,1626.9,1247.5,714.8,1189.8,1317.1 +1.1708839300006744,1.229290747589605,0.39269908169872414,1722.8,1097.9,878.8,881.9,1572.3,1556.5 +1.17085370455369,1.2292590595233872,0.5235987755982988,1963.3,854.5,727.0,1267.9,1410.7,1282.8 +1.170842579203295,1.2292341409206484,0.6544984694978736,1764.9,727.7,668.6,1104.0,1224.9,1165.9 +1.1708304760514583,1.2291859190164582,0.7853981633974483,1721.1,670.9,670.2,1040.8,1151.6,1151.1 +1.1708319441316417,1.2291739202342316,0.916297857297023,1808.1,668.3,727.2,1060.7,1165.7,1224.5 +1.1708447508014048,1.229134417047241,1.0471975511965976,1270.6,727.2,854.5,1176.9,1282.0,1409.3 +1.1708709893154579,1.2290903449276172,1.1780972450961724,881.8,878.4,1097.5,1550.2,1556.6,1775.7 +1.1708664101302506,1.2291809686796404,1.3089969389957472,714.6,1246.5,1189.5,1362.8,2104.1,1976.2 +1.1709325050636392,1.2290620392520153,1.4398966328953218,646.5,1140.9,1082.5,1185.7,1844.0,1785.7 +1.1709648813123015,1.2290539015352921,1.5707963267948966,640.7,1070.9,1070.8,1121.1,1751.5,1751.2 +1.1709476865615176,1.229052212086264,1.7016960206944713,688.9,1081.9,1140.4,1143.2,1786.2,1845.0 +1.170943507522765,1.229049474263657,1.832595714594046,807.7,1190.5,1318.3,1270.3,1625.1,1245.8 +1.1710014150873516,1.229085591078998,1.9634954084936205,1042.8,1602.9,1556.1,1563.3,1097.2,877.9 +1.1710214063390603,1.2291076670938685,2.0943951023931953,1176.2,1409.0,1281.8,2054.6,854.1,726.9 +1.1710141040791662,1.2290912053212246,2.2252947962927703,1060.9,1224.3,1165.7,1807.1,727.0,668.4 +1.1710207212885182,1.229117381696184,2.356194490192345,1041.7,1151.6,1152.0,1720.7,670.3,670.9 +1.1710177759684188,1.2291512213861977,2.4870941840919194,1104.0,1165.9,1225.3,1765.2,668.6,727.7 +1.1710206115231936,1.2291451832311813,2.6179938779914944,1270.7,1283.4,1410.9,1542.3,727.1,854.8 +1.1710055575055571,1.2291638582250402,2.748893571891069,1558.7,1559.2,1779.0,1040.4,880.8,1101.0 +1.170819181003711,1.2289154548091612,2.8797932657906435,1269.6,2103.8,1976.1,807.9,1247.9,1189.4 +1.1708863028197112,1.2288842420374753,3.010692959690218,1143.3,1846.0,1787.0,689.8,1141.6,1082.8 +1.1708456356755363,1.1286516159671467,0.0,1021.1,1751.1,1751.3,740.8,1070.9,1070.7 +1.170940639191191,1.1293111216585197,0.1308996938995747,1084.0,1787.3,1847.0,750.4,1083.0,1142.5 +1.1709207665397394,1.1293043879797504,0.2617993877991494,1246.8,1826.0,1446.7,830.3,1189.7,1317.3 +1.1708493766399277,1.1292562858808752,0.39269908169872414,1581.1,1239.3,1020.0,1023.7,1448.5,1415.4 +1.1708418459184466,1.129249022215159,0.5235987755982988,2059.3,970.3,842.6,1269.8,1295.1,1167.2 +1.170834833253849,1.1292319216716273,0.6544984694978736,1765.0,831.3,772.2,1103.9,1121.2,1062.1 +1.1708103101560638,1.1291268653346047,0.7853981633974483,1721.4,770.8,770.4,1040.8,1051.7,1051.2 +1.1708103002481065,1.1291542229629088,0.916297857297023,1807.7,771.9,830.6,1060.6,1062.4,1121.2 +1.1708209837430115,1.1291214957091285,1.0471975511965976,1470.1,842.7,970.0,1176.8,1166.4,1293.6 +1.170848717539919,1.1290750075178508,1.1780972450961724,1023.4,1019.4,1238.8,1442.7,1415.5,1634.9 +1.1708482037745116,1.1290746482788916,1.3089969389957472,830.2,1316.9,1189.3,1247.2,2005.4,2097.6 +1.1708664272070681,1.1290648880617145,1.4398966328953218,749.8,1141.2,1082.6,1082.2,1844.1,1785.6 +1.170944217147963,1.1290463523382899,1.5707963267948966,740.8,1071.1,1070.5,1021.1,1751.2,1751.2 +1.1709423552316742,1.1290452113747846,1.7016960206944713,792.4,1082.0,1140.7,1039.7,1786.3,1844.6 +1.170943124620305,1.1290439987573189,1.832595714594046,923.2,1190.4,1318.3,1154.7,1824.3,1445.1 +1.1710026161014375,1.1290811361733073,1.9634954084936205,1184.5,1449.6,1415.1,1421.5,1238.2,1019.0 +1.1710231359625556,1.1291038130616786,2.0943951023931953,1176.5,1293.4,1166.1,2030.4,969.7,842.4 +1.1710160241706966,1.1290877369054066,2.2252947962927703,1060.8,1120.9,1062.2,1806.9,830.6,771.8 +1.1710124870064638,1.1290659559281448,2.356194490192345,1041.5,1051.0,1051.8,1720.3,770.1,770.8 +1.1709995239612243,1.1293327343666477,2.4870941840919194,1103.9,1062.3,1121.4,1765.2,772.4,831.4 +1.170698994502069,1.1290891766891527,2.6179938779914944,1270.3,1167.2,1294.9,1743.7,842.7,970.2 +1.1707314938611944,1.1290193801068575,2.748893571891069,1418.1,1417.1,1637.0,1182.7,1022.0,1241.7 +1.170803568030766,1.1289654858034086,2.8797932657906435,1153.8,2005.5,2117.0,923.3,1317.1,1189.7 +1.1708176495177123,1.1289583123410534,3.010692959690218,1039.7,1845.8,1787.0,793.2,1141.6,1082.5 +1.2708859657992082,1.8291737579656275,0.0,1721.0,1651.1,1651.0,40.9,1170.8,1170.9 +1.2709566176004543,1.8289476832017373,0.1308996938995747,1808.6,964.6,148.9,25.5,1186.7,1245.9 +1.2711095049393981,1.8289960372230647,0.2617993877991494,2055.8,431.0,51.3,21.3,1305.2,1432.4 +1.2710390562501777,1.8289516922024704,0.39269908169872414,2271.3,251.1,31.8,32.0,1589.9,1810.5 +1.2710284883069534,1.8289420539154402,0.5235987755982988,1848.5,161.2,33.5,72.2,2104.5,1976.2 +1.2710402101269815,1.828960790525845,0.6544984694978736,1661.7,106.6,47.5,231.4,1846.3,1786.9 +1.2710398587580314,1.8289646429033415,0.7853981633974483,1621.3,70.9,70.4,1140.9,1751.5,1751.4 +1.2710396497874075,1.8290041015347218,0.916297857297023,317.8,47.5,106.3,1164.2,1786.5,1845.8 +1.2710384312985439,1.829011345185777,1.0471975511965976,73.3,34.0,161.3,1292.2,1974.9,2102.3 +1.2710408835967673,1.8290059841972282,1.1780972450961724,31.8,31.6,250.7,1583.4,2403.0,2321.8 +1.271006314196558,1.8290384270779074,1.3089969389957472,21.2,51.0,430.2,2056.3,1988.5,1861.2 +1.270985211464219,1.8290506962486388,1.4398966328953218,25.8,152.4,981.3,1806.5,1740.6,1682.0 +1.2710216381479436,1.8290424947693675,1.5707963267948966,41.0,1170.8,1170.6,1721.2,1651.3,1651.3 +1.2709807634746837,1.829041012481406,1.7016960206944713,68.3,1185.3,1244.0,1763.8,981.0,152.4 +1.2709465019251531,1.829030299926036,1.832595714594046,114.0,1306.0,1459.4,1963.7,430.3,51.0 +1.2709765239799422,1.8290500066448456,1.9634954084936205,192.5,1591.4,1812.2,2413.4,250.7,62.7 +1.2709750157465594,1.8290500458841867,2.0943951023931953,349.9,2101.9,1974.9,1939.1,161.3,34.0 +1.2709536804868615,1.8290087019362955,2.2252947962927703,831.3,1845.5,1786.5,1703.6,106.3,47.5 +1.2709538293504261,1.8290087886096948,2.356194490192345,1141.9,1751.4,1751.6,1620.4,70.4,70.9 +1.2709516822156772,1.8290175152559782,2.4870941840919194,1207.4,1787.2,1846.0,827.3,47.5,106.6 +1.2709612820974148,1.8289894796514372,2.6179938779914944,1386.2,1976.8,2104.7,347.9,33.5,161.2 +1.2709579995324247,1.8289900629016884,2.748893571891069,1747.3,2407.4,2295.6,192.3,32.3,252.3 +1.2709792636007904,1.8289716509212406,2.8797932657906435,1962.9,1987.1,1859.9,114.3,51.8,431.6 +1.270983925310795,1.8289697122371342,3.010692959690218,1764.5,1742.2,1683.1,68.7,151.9,974.8 +1.2709410818555094,1.7286826287094312,0.0,1621.4,1650.7,1651.1,140.8,1171.2,1171.0 +1.2709858139697658,1.7292959305519107,0.1308996938995747,1705.3,1348.3,532.6,129.0,1186.6,1246.2 +1.2709575447487862,1.7292866711051404,0.2617993877991494,1940.1,630.2,250.5,136.8,1305.2,1433.1 +1.2709242489293024,1.7292651135915025,0.39269908169872414,2262.5,392.2,172.9,173.5,1589.9,1810.7 +1.2708962234598966,1.7292360685715698,0.5235987755982988,1848.3,276.6,174.5,271.3,1988.8,1861.2 +1.2708869275911177,1.7292149485608674,0.6544984694978736,1661.6,210.1,151.0,616.8,1742.7,1683.6 +1.2708755469299262,1.7291708677965927,0.7853981633974483,1621.4,170.8,170.3,1140.7,1651.7,1651.3 +1.2708767168906494,1.7291628626032165,0.916297857297023,619.3,150.9,209.7,1164.1,1683.5,1742.2 +1.2708882846367104,1.7292116997767621,1.0471975511965976,272.7,149.4,276.7,1292.4,1859.4,1987.0 +1.2711416831037905,1.7291515738462049,1.1780972450961724,173.3,172.7,392.0,1584.2,2263.0,2310.2 +1.2709595841302013,1.729318676053665,1.3089969389957472,162.2,250.5,629.9,1939.9,1987.8,1860.0 +1.271043917225505,1.7292741185132945,1.4398966328953218,129.2,543.0,1185.9,1702.8,1740.5,1682.0 +1.271096315628625,1.7292617914184802,1.5707963267948966,140.9,1171.2,1170.8,1620.9,1651.3,1651.0 +1.2710412723812927,1.7292592066379875,1.7016960206944713,171.7,1185.6,1244.2,1660.7,1367.5,540.6 +1.27098543528736,1.7292410541472267,1.832595714594046,229.7,1397.7,1434.0,1848.5,628.7,249.9 +1.270994915655032,1.7292473921378773,1.9634954084936205,334.4,1592.0,1813.6,2272.7,391.4,172.6 +1.270977527816106,1.7292302412108003,2.0943951023931953,550.0,1986.2,1859.0,1938.9,276.6,149.4 +1.2709460698868946,1.7291695479015854,2.2252947962927703,1164.3,1741.8,1683.3,1703.2,209.6,150.9 +1.270941546557232,1.7291496902162868,2.356194490192345,1141.6,1651.2,1651.5,1620.3,170.2,170.9 +1.2709396084110003,1.729139515681289,2.4870941840919194,1207.8,1683.5,1742.9,1209.9,150.9,210.1 +1.2709539421760019,1.7290945499592807,2.6179938779914944,1386.7,1861.4,1989.0,546.3,149.0,276.8 +1.270958542283288,1.7290810379399475,2.748893571891069,1748.3,2267.3,2314.7,364.4,173.6,393.9 +1.270990334075489,1.7290517689456237,2.8797932657906435,1846.4,1986.8,1859.5,229.6,251.3,631.6 +1.2710069775050026,1.7290424980098138,3.010692959690218,1660.7,1741.8,1682.7,172.0,539.7,1186.2 +1.2709794427868149,1.6287665782379526,0.0,1521.4,1650.9,1651.0,240.6,1171.1,1170.8 +1.271004636551199,1.6293379885750856,0.1308996938995747,1601.3,1684.0,916.7,232.6,1186.7,1246.3 +1.2709680687466256,1.6293260976822768,0.2617993877991494,1824.4,829.7,450.0,252.4,1305.0,1432.8 +1.2709293345872317,1.6293010801385077,0.39269908169872414,2262.5,533.3,314.1,315.2,1590.0,1918.7 +1.2708975945180068,1.6292680383926985,0.5235987755982988,1848.2,392.4,264.6,470.4,1873.2,1745.4 +1.2708860190657891,1.6292426887073992,0.6544984694978736,1661.7,313.6,254.5,1002.0,1639.3,1579.9 +1.2708735571677865,1.629194263926265,0.7853981633974483,1621.0,270.9,270.3,1140.8,1551.7,1551.3 +1.2708747808034686,1.629182175624748,0.916297857297023,1006.6,254.3,313.1,1163.9,1579.6,1638.7 +1.2708873589951641,1.629142537115549,1.0471975511965976,472.3,264.9,392.1,1292.3,1743.9,1871.1 +1.27091338719915,1.6290981656211032,1.1780972450961724,315.0,313.6,532.7,1583.8,2120.8,2271.3 +1.270908748283344,1.6291013737135367,1.3089969389957472,252.2,449.2,828.4,1825.3,1988.5,1861.0 +1.2709215866100494,1.6290943908995053,1.4398966328953218,232.5,930.8,1185.9,1599.4,1740.5,1682.0 +1.2709935402839585,1.6290769686286075,1.5707963267948966,240.8,1170.8,1170.4,1521.3,1651.1,1651.2 +1.2709861960167896,1.6290755612062164,1.7016960206944713,274.9,1185.3,1244.1,1557.2,1682.7,931.0 +1.2709820507620702,1.6290729756749849,1.832595714594046,345.1,1306.2,1433.5,1732.4,828.5,449.1 +1.2710374309284527,1.629107609799839,1.9634954084936205,475.7,1591.6,1917.9,2130.0,532.6,313.6 +1.2710548687715606,1.6291270764140522,2.0943951023931953,748.9,1871.5,1744.0,1939.5,392.2,264.9 +1.271045637888849,1.6291075475423797,2.2252947962927703,1164.4,1639.1,1579.8,1703.7,313.1,254.4 +1.2710511946284402,1.6291303795959713,2.356194490192345,1141.4,1551.5,1552.0,1620.7,270.3,270.8 +1.2710481511694156,1.6291608433633518,2.4870941840919194,1207.5,1580.3,1638.9,1661.3,254.5,313.6 +1.2710515787802632,1.6291517958195838,2.6179938779914944,1386.4,1745.7,1873.2,746.0,264.6,392.2 +1.2710379425073,1.6291678242087286,2.748893571891069,1824.0,2124.5,2266.3,475.0,315.0,535.0 +1.2708333450168154,1.628915410476139,2.8797932657906435,1731.9,1988.0,1860.4,345.5,450.5,829.8 +1.270856666050474,1.6289035761881603,3.010692959690218,1557.6,1742.5,1683.2,275.8,924.4,1186.3 +1.2708411374420985,1.5286423304057322,0.0,1421.3,1651.0,1651.0,340.7,1171.1,1170.7 +1.270940734855902,1.5293173520997165,0.1308996938995747,1498.0,1684.0,1300.0,336.2,1186.7,1246.1 +1.2709215689028106,1.5293108322048192,0.2617993877991494,1709.2,1028.7,649.2,368.0,1305.2,1432.8 +1.2708880621660614,1.5292889959047757,0.39269908169872414,2147.8,674.4,455.2,456.8,1590.2,1811.4 +1.2708579719974467,1.52925748324372,0.5235987755982988,1848.1,507.9,380.3,669.8,1757.1,1629.8 +1.270846966009396,1.5292328276550133,0.6544984694978736,1661.4,417.1,357.9,1207.3,1535.4,1476.5 +1.2708349013867728,1.5291848893887756,0.7853981633974483,1621.1,370.8,370.3,1140.8,1451.8,1451.3 +1.2708363417539332,1.5291731653009282,0.916297857297023,1392.9,357.9,416.7,1164.2,1476.2,1535.3 +1.2708490563584653,1.529133903365369,1.0471975511965976,671.8,380.5,507.8,1292.5,1628.5,1755.9 +1.2708751524352888,1.5290900148290985,1.1780972450961724,456.6,454.8,674.1,1583.7,1980.5,2198.9 +1.2708704103591588,1.5290936105023323,1.3089969389957472,367.7,648.7,1027.9,1709.8,1988.5,1861.0 +1.270883016197525,1.52908685576636,1.4398966328953218,336.0,1244.6,1186.2,1496.2,1740.6,1682.1 +1.2709546721923695,1.529069704506313,1.5707963267948966,340.8,1170.9,1170.9,1421.4,1651.3,1651.3 +1.2709469909340765,1.5290683602107986,1.7016960206944713,378.6,1185.6,1243.7,1453.6,1682.6,1319.7 +1.270942563597505,1.5290655822187993,1.832595714594046,460.7,1306.0,1433.8,1617.0,1027.3,648.3 +1.2709977261399281,1.5291000028640267,1.9634954084936205,617.6,1591.2,1812.3,1988.4,673.7,454.6 +1.2710150472329929,1.5291192342506847,2.0943951023931953,948.8,1755.7,1628.2,1939.2,507.7,380.4 +1.2710058960547126,1.5290993688635597,2.2252947962927703,1164.1,1535.1,1476.1,1703.3,416.6,357.9 +1.2710116491560568,1.529121925316415,2.356194490192345,1141.6,1451.0,1451.5,1620.5,370.2,370.8 +1.2710088112118554,1.5291522692111188,2.4870941840919194,1207.7,1476.6,1535.8,1661.6,358.0,417.2 +1.2710125609180176,1.529143150149613,2.6179938779914944,1386.1,1630.1,1758.0,945.0,380.3,507.9 +1.2709990936927247,1.5291592650265258,2.748893571891069,1809.7,1983.4,2203.8,616.3,456.5,676.5 +1.2708197077890828,1.528916007952284,2.8797932657906435,1616.4,1988.0,1860.8,461.1,649.8,1029.2 +1.270846116400774,1.5289025442061766,3.010692959690218,1453.9,1742.3,1683.3,379.4,1245.1,1186.4 +1.2708324095330075,1.428641798713488,0.0,1321.3,1651.2,1651.0,440.8,1171.1,1170.7 +1.2709362072030754,1.4293186957935933,0.1308996938995747,1394.6,1683.9,1743.6,439.8,1186.6,1246.1 +1.2709177711052488,1.4293123943585444,0.2617993877991494,1593.6,1228.1,848.7,483.5,1305.4,1432.9 +1.2708842858930822,1.4292905563969187,0.39269908169872414,2006.1,815.8,596.4,598.7,1590.2,1807.8 +1.2708540722688335,1.4292588837558817,0.5235987755982988,1848.2,623.4,495.9,869.2,1641.9,1514.3 +1.2708429578349072,1.429233989243319,0.6544984694978736,1661.3,520.5,461.6,1207.4,1431.7,1372.9 +1.2708308584949446,1.4291857937633796,0.7853981633974483,1621.2,470.8,470.2,1140.9,1351.6,1351.2 +1.2708323241118284,1.4291738205363356,0.916297857297023,1704.3,461.4,520.3,1164.1,1373.0,1431.5 +1.2708451223533053,1.4291343399115202,1.0471975511965976,871.3,495.9,623.3,1292.5,1512.8,1640.3 +1.2708713478157145,1.4290902852746301,1.1780972450961724,598.2,596.0,815.3,1583.9,1839.1,2058.2 +1.2708667535573472,1.429093757189823,1.3089969389957472,483.4,848.1,1227.3,1593.9,1988.2,1860.6 +1.2708795178531065,1.429086916287432,1.4398966328953218,439.5,1244.2,1186.2,1392.4,1740.2,1682.3 +1.2709513364159506,1.4290697371100367,1.5707963267948966,440.7,1170.7,1170.7,1321.0,1651.4,1651.3 +1.270943804720338,1.4290683958648192,1.7016960206944713,482.0,1185.5,1244.0,1350.1,1682.9,1741.0 +1.2709395147480451,1.4290656412483334,1.832595714594046,576.4,1306.3,1433.9,1501.4,1226.5,847.5 +1.270994795217077,1.429100121762608,1.9634954084936205,759.2,1591.2,1807.4,1846.8,814.7,595.7 +1.2710122084283415,1.4291194367085223,2.0943951023931953,1148.6,1640.0,1512.8,1939.2,623.1,495.9 +1.2710031298450395,1.4290996587956815,2.2252947962927703,1164.2,1431.6,1372.9,1703.5,520.1,461.3 +1.2710089288879407,1.429122313544057,2.356194490192345,1141.5,1351.1,1351.7,1620.8,470.2,470.8 +1.271006102254609,1.4291527643214454,2.4870941840919194,1207.6,1373.1,1432.3,1661.5,461.6,520.6 +1.2710098452731105,1.4291437403538874,2.6179938779914944,1386.2,1514.5,1642.3,1144.0,495.9,623.6 +1.2709963341830706,1.4291599446207395,2.748893571891069,1747.7,1842.2,2062.6,757.5,597.9,818.1 +1.2708184290193387,1.4289165891211535,2.8797932657906435,1500.6,1987.5,1860.4,576.7,849.0,1228.4 +1.2708451003668217,1.428902985067072,3.010692959690218,1350.4,1742.1,1683.5,482.8,1245.2,1186.3 +1.2708315120589428,1.3286422496501373,0.0,1221.1,1651.0,1651.2,540.8,1171.0,1170.9 +1.270935781852743,1.3293188753261733,0.1308996938995747,1291.1,1684.1,1743.3,543.4,1186.8,1246.1 +1.2709174214736036,1.3293125965293262,0.2617993877991494,1478.3,1427.4,1047.9,599.1,1305.3,1432.9 +1.2708839343098728,1.3292907559207598,0.39269908169872414,1864.2,956.8,737.7,740.3,1713.7,1697.5 +1.2708537034983007,1.3292590623392626,0.5235987755982988,1847.9,739.1,611.4,1068.5,1526.1,1398.2 +1.2708425748216974,1.3292341378840182,0.6544984694978736,1661.3,624.2,565.1,1207.5,1328.3,1269.2 +1.2708304701267548,1.3291859099889507,0.7853981633974483,1621.0,570.8,570.3,1140.7,1251.6,1251.0 +1.2708319382647575,1.329173905487809,0.916297857297023,1704.2,564.9,623.8,1164.1,1269.4,1328.4 +1.2708447463818908,1.3291343972061824,1.0471975511965976,1070.8,611.6,738.9,1292.6,1397.3,1524.6 +1.2708709874521122,1.3290903209056741,1.1780972450961724,739.9,737.2,956.3,1692.2,1697.8,1917.2 +1.270866411604525,1.3290937767059328,1.3089969389957472,599.0,1047.4,1305.0,1478.3,2129.6,1860.8 +1.2708791959593964,1.3290869248734154,1.4398966328953218,542.9,1244.3,1186.0,1289.1,1740.7,1682.2 +1.2709510351793079,1.3290697415475852,1.5707963267948966,540.8,1170.9,1170.7,1221.3,1651.4,1651.1 +1.2709435226567103,1.3290684005979236,1.7016960206944713,585.4,1185.8,1244.0,1246.8,1682.8,1741.3 +1.2709392501421235,1.329065649597745,1.832595714594046,691.9,1306.2,1434.0,1386.2,1425.4,1046.5 +1.2709945455071547,1.3291001380444754,1.9634954084936205,901.0,1743.8,1697.3,1704.8,955.8,736.8 +1.2710119702267548,1.3291194637644441,2.0943951023931953,1292.0,1524.8,1397.4,1939.3,738.7,611.4 +1.2710029001685434,1.3290996974848381,2.2252947962927703,1164.4,1328.1,1269.3,1703.5,623.6,564.8 +1.2710087042054061,1.3291223649602137,2.356194490192345,1141.5,1251.3,1251.8,1620.4,570.2,570.9 +1.2710058784672478,1.3291528289809211,2.4870941840919194,1207.5,1269.5,1328.5,1661.9,565.0,624.2 +1.2710096197750507,1.329143816798926,2.6179938779914944,1386.4,1398.8,1526.4,1343.3,611.6,739.3 +1.270996103078329,1.3291600316696215,2.748893571891069,1700.1,1700.9,1920.9,899.1,739.3,959.5 +1.2708183082195106,1.3289166554231646,2.8797932657906435,1384.9,2128.9,1860.4,692.2,1048.2,1305.1 +1.2708450016849453,1.3289030395048786,3.010692959690218,1246.8,1742.4,1683.4,586.3,1245.1,1186.3 +1.270831423104426,1.2286423050022344,0.0,1121.2,1651.1,1651.1,640.8,1171.1,1170.9 +1.2709357425699568,1.2293188952101402,0.1308996938995747,1187.4,1684.1,1743.2,646.9,1186.6,1246.0 +1.2709173884946814,1.2293126183060292,0.2617993877991494,1362.5,1626.7,1247.2,714.9,1305.5,1433.0 +1.2708839001477743,1.2292907768471042,0.39269908169872414,1722.7,1098.1,878.8,882.0,1590.4,1556.6 +1.2708536668839647,1.2292590804276666,0.5235987755982988,1847.9,854.5,727.0,1267.7,1410.6,1282.9 +1.270842536310254,1.2292341521538719,0.6544984694978736,1661.5,727.8,668.6,1207.7,1224.9,1165.8 +1.2708304308506406,1.2291859201543498,0.7853981633974483,1621.0,670.6,670.3,1141.0,1151.6,1151.0 +1.270828438755117,1.2292156603771032,0.916297857297023,1704.1,668.4,727.3,1164.1,1165.7,1224.4 +1.2708497099379734,1.2291485179671657,1.0471975511965976,1270.5,727.1,854.6,1292.4,1281.9,1409.0 +1.2708796024980047,1.229098673337627,1.1780972450961724,881.7,878.4,1097.5,1583.9,1556.8,1775.9 +1.27087494086173,1.2291022274328662,1.3089969389957472,714.6,1246.7,1305.3,1362.9,1988.2,1860.9 +1.270885770252504,1.2290964284725487,1.4398966328953218,646.3,1244.8,1186.1,1185.5,1740.4,1682.1 +1.270954912585323,1.2290798688759093,1.5707963267948966,640.8,1170.9,1170.6,1121.2,1651.6,1651.0 +1.270944668456673,1.2290784414964024,1.7016960206944713,688.8,1185.5,1243.9,1143.2,1683.0,1741.3 +1.270937903459407,1.2290749385042141,1.832595714594046,807.5,1306.3,1433.9,1270.4,1624.8,1245.8 +1.270991105065537,1.2291081177407328,1.9634954084936205,1042.9,1591.6,1555.8,1563.5,1097.1,878.0 +1.2710069771471653,1.2291257787445273,2.0943951023931953,1291.9,1408.8,1281.7,1987.2,854.2,727.0 +1.2708412788369052,1.2291488175875336,2.2252947962927703,1164.6,1224.6,1165.6,1703.8,727.4,668.5 +1.2708389531233901,1.229137234776824,2.356194490192345,1141.4,1151.2,1151.7,1620.3,670.4,670.8 +1.2708340505441456,1.229171768536608,2.4870941840919194,1207.3,1165.8,1224.9,1661.4,668.6,727.8 +1.2708584983849547,1.2290949895691379,2.6179938779914944,1385.9,1282.5,1410.3,1543.9,726.9,854.7 +1.2708694027675844,1.2290728537630784,2.748893571891069,1559.3,1558.6,1777.9,1041.2,880.3,1100.1 +1.270903509727514,1.229041982885481,2.8797932657906435,1269.6,1988.1,1860.2,807.8,1248.1,1305.1 +1.270920709913823,1.2290328219967097,3.010692959690218,1143.5,1742.2,1683.1,689.8,1244.9,1186.1 +1.2708921567074083,1.1287561634267924,0.0,1021.4,1651.1,1650.9,740.5,1171.0,1171.1 +1.2709669782368165,1.1293334505497197,0.1308996938995747,1083.6,1684.0,1743.0,750.5,1186.4,1246.1 +1.2709408134303903,1.1293247501428,0.2617993877991494,1246.8,1860.0,1447.1,830.2,1305.2,1432.5 +1.2709045053206887,1.1293011851901218,0.39269908169872414,1580.6,1239.3,1020.0,1023.7,1590.5,1415.4 +1.2708730454124522,1.1292682961076244,0.5235987755982988,1848.0,970.4,842.7,1385.6,1295.2,1167.3 +1.2708613277324918,1.1292424558664957,0.6544984694978736,1661.4,831.3,772.4,1207.3,1121.8,1062.3 +1.270848865778639,1.1291933513934689,0.7853981633974483,1621.2,770.7,770.2,1141.0,1051.6,1051.4 +1.2708502391127756,1.1291805601952527,0.916297857297023,1704.2,771.9,830.7,1164.1,1062.2,1121.0 +1.2708631358318434,1.1291403166993927,1.0471975511965976,1470.6,842.7,970.0,1292.3,1166.4,1293.6 +1.2708896090664545,1.1290955319955445,1.1780972450961724,1023.6,1019.2,1238.6,1581.8,1415.2,1634.6 +1.2708854325578518,1.12909844863964,1.3089969389957472,855.8,1432.7,1305.1,1247.5,1962.8,1860.9 +1.2708987308823918,1.1290912645742108,1.4398966328953218,749.7,1244.5,1186.1,1082.3,1740.6,1682.1 +1.2709711337722136,1.129073826056191,1.5707963267948966,740.8,1170.8,1170.8,1021.3,1651.4,1650.9 +1.2709641839922363,1.1290724517951585,1.7016960206944713,792.3,1185.6,1244.0,1039.9,1682.8,1741.2 +1.2709604035628175,1.1290699045821733,1.832595714594046,923.1,1306.2,1433.9,1154.8,1860.3,1445.3 +1.2710161041806416,1.129104675771558,1.9634954084936205,1184.4,1591.5,1415.3,1421.4,1238.2,1019.3 +1.2710338102108834,1.1291243426290585,2.0943951023931953,1291.9,1293.6,1166.2,1939.4,969.9,842.5 +1.2710248342227137,1.1291050070731663,2.2252947962927703,1164.4,1121.0,1062.4,1703.8,830.7,771.7 +1.2710305947439704,1.1291280824640673,2.356194490192345,1141.4,1051.2,1051.8,1620.7,770.2,770.8 +1.271027655426834,1.1291588548566036,2.4870941840919194,1207.4,1062.5,1121.6,1661.9,772.2,831.5 +1.2710311528292981,1.1291501002002637,2.6179938779914944,1386.2,1167.4,1295.3,1741.8,842.8,970.4 +1.2710174368981852,1.1291664435419588,2.748893571891069,1417.5,1417.6,1637.5,1182.0,1022.1,1242.2 +1.2708249067357644,1.1289174553851669,2.8797932657906435,1153.8,1962.7,1860.5,923.5,1432.8,1305.6 +1.270849854135445,1.1289047577711224,3.010692959690218,1040.1,1742.0,1683.7,793.5,1245.4,1186.0 +1.3709144953655017,1.8291089836117194,0.0,1721.2,1551.2,1550.9,41.0,1270.8,1270.9 +1.370915586456752,1.8285208638267731,0.1308996938995747,1808.4,967.1,149.6,25.6,1290.0,1349.3 +1.370888487545004,1.8282293143313089,0.2617993877991494,2054.7,431.8,51.7,21.5,1420.0,1547.7 +1.3706930824339454,1.8263110320468834,0.39269908169872414,2126.2,255.7,35.5,35.5,1727.7,1947.6 +1.3705312516302885,1.8265147722303223,0.5235987755982988,1733.6,164.5,36.5,77.2,2102.5,1974.2 +1.3705236687802334,1.8265111445302404,0.6544984694978736,1558.7,109.5,50.2,240.5,1844.2,1784.6 +1.3705110337555189,1.826472575138777,0.7853981633974483,1521.6,73.6,72.9,1240.6,1749.0,1748.5 +1.3705145473812266,1.8264666020708,0.916297857297023,243.6,50.2,108.8,1267.1,1783.5,1842.1 +1.3705323209523228,1.8264334625428704,1.0471975511965976,78.7,37.0,164.0,1516.9,1970.9,2098.3 +1.3705649010606986,1.8263981967017466,1.1780972450961724,35.5,35.2,253.9,1722.5,2353.3,2132.2 +1.3706660494327474,1.8260916285720412,1.3089969389957472,24.9,57.2,436.0,2053.4,1874.2,1746.6 +1.3706794976786238,1.8263287780829918,1.4398966328953218,28.3,161.9,990.3,1804.0,1637.0,1578.9 +1.3709707072512407,1.8262763179854025,1.5707963267948966,43.4,1270.8,1270.5,1718.7,1551.3,1551.2 +1.3709348356181155,1.8269422457620084,1.7016960206944713,70.6,1288.8,1347.6,1761.6,986.8,245.9 +1.3707085119103226,1.82688024917989,1.832595714594046,116.7,1422.0,1550.2,1961.8,433.9,55.2 +1.3708626357238956,1.8262339729825992,1.9634954084936205,196.2,1731.5,1952.4,2281.3,286.1,35.6 +1.3707728817611444,1.826305720519029,2.0943951023931953,355.4,2099.0,1971.7,1823.9,164.6,37.3 +1.3707485725673445,1.8262766910697628,2.2252947962927703,842.0,1842.7,1783.7,1600.5,109.2,50.4 +1.3707427457594001,1.826267502408801,2.356194490192345,1241.5,1748.6,1748.7,1520.7,73.2,73.7 +1.3707421188153202,1.8262602809549073,2.4870941840919194,1310.8,1784.0,1843.1,838.3,50.4,109.5 +1.3707617464590782,1.8262179657888722,2.6179938779914944,1501.6,1973.5,2101.1,353.5,36.7,164.4 +1.3707749974019312,1.8262102040839887,2.748893571891069,1888.2,2345.5,2125.2,227.3,36.2,256.1 +1.3708617146650648,1.8259401840370195,2.8797932657906435,1957.5,1871.4,1744.0,117.9,58.6,439.1 +1.3708647106529228,1.826102278137562,3.010692959690218,1761.0,1637.6,1579.2,71.3,163.2,989.9 +1.3709096042443898,1.7258785390308777,0.0,1618.7,1550.9,1551.0,143.3,1271.0,1271.0 +1.3709545785625536,1.727045898440875,0.1308996938995747,1703.2,1355.5,540.5,131.3,1290.1,1349.8 +1.3709390143168434,1.727051693529716,0.2617993877991494,1938.3,634.2,254.8,139.3,1420.8,1548.7 +1.3709139738245577,1.7270488791092933,0.39269908169872414,2126.7,395.1,175.9,176.6,1731.9,2055.8 +1.3708892592992417,1.7270373202826226,0.5235987755982988,1732.4,279.1,151.5,275.7,1986.2,1858.3 +1.3708800322235764,1.7270305458486308,0.6544984694978736,1557.9,212.3,153.2,625.6,1740.2,1681.3 +1.3708679436138296,1.7269978541807476,0.7853981633974483,1521.1,173.0,172.5,1240.9,1649.5,1649.1 +1.3708690242608808,1.7269992258736242,0.916297857297023,627.2,153.1,211.9,1267.7,1681.0,1740.1 +1.3708817579498975,1.7269724420906454,1.0471975511965976,320.8,151.9,279.2,1408.0,1857.2,1984.4 +1.3709078497825793,1.7269417703748202,1.1780972450961724,176.3,175.6,394.8,1725.2,2259.5,2147.5 +1.3709019056445382,1.7269598782981919,1.3089969389957472,139.1,254.4,633.8,1938.2,1872.9,1745.0 +1.3709104901295304,1.7269687613433404,1.4398966328953218,131.3,550.4,1289.7,1700.6,1637.0,1578.5 +1.3709739444569546,1.726967124242866,1.5707963267948966,142.9,1271.2,1270.8,1619.2,1551.3,1551.2 +1.3709539817888112,1.7269790634028226,1.7016960206944713,173.8,1289.1,1347.3,1658.4,1377.1,549.4 +1.3709337661638206,1.726985240555571,1.832595714594046,232.0,1421.9,1549.6,1845.9,633.2,254.1 +1.370971347403016,1.7270225011202671,1.9634954084936205,337.1,1733.5,2055.2,2269.1,394.5,175.5 +1.3709722999844847,1.7270381812803377,2.0943951023931953,553.8,1983.8,1856.9,1823.6,279.1,151.8 +1.370950692469492,1.727009261089528,2.2252947962927703,1227.6,1740.1,1681.0,1600.0,211.8,153.1 +1.3709499602141157,1.7270189239703106,2.356194490192345,1241.6,1649.1,1649.7,1520.4,172.4,173.0 +1.3709477104133305,1.7270355778028452,2.4870941840919194,1311.1,1681.6,1740.5,1219.3,153.1,212.3 +1.3709586387411623,1.7270152286647091,2.6179938779914944,1502.0,1859.0,1986.5,550.8,151.5,279.2 +1.3709572228363949,1.7270249240109448,2.748893571891069,1962.3,2263.5,2151.6,336.4,176.5,396.7 +1.3709286117137889,1.727040844483264,2.8797932657906435,1843.3,1870.6,1743.1,231.5,255.4,636.2 +1.3709535481277337,1.7270387630643513,3.010692959690218,1658.6,1637.8,1579.6,173.9,548.5,1289.3 +1.3709506778193048,1.6267918280900673,0.0,1519.6,1550.9,1551.2,242.5,1271.0,1271.2 +1.370974487885853,1.627914496696972,0.1308996938995747,1600.5,1580.6,921.1,234.0,1290.6,1372.6 +1.37095453077309,1.6279145670469242,0.2617993877991494,1823.6,832.0,452.4,253.9,1421.0,1548.4 +1.370930632392389,1.6279070598543557,0.39269908169872414,2121.2,535.1,315.8,317.1,1731.9,1952.8 +1.370908912900237,1.6278931576810802,0.5235987755982988,1732.8,393.6,266.1,473.3,1871.3,1743.6 +1.370902608129921,1.6278861854142344,0.6544984694978736,1558.0,314.9,255.8,1008.0,1637.3,1578.6 +1.370892172428193,1.6278548309502154,0.7853981633974483,1521.4,272.1,271.6,1240.7,1550.4,1549.9 +1.370893105118637,1.627858056299775,0.916297857297023,1011.0,255.7,314.6,1267.8,1578.5,1637.4 +1.370903845403532,1.6278326244618286,1.0471975511965976,474.8,266.4,393.8,1408.1,1742.3,1869.7 +1.3709266392639599,1.6278018654576683,1.1780972450961724,316.8,315.5,534.7,1725.1,2119.5,2165.9 +1.3709170572409515,1.6278180144282668,1.3089969389957472,253.7,452.0,831.2,1823.5,1873.0,1745.2 +1.3709226380908615,1.627823131350347,1.4398966328953218,233.9,936.7,1289.8,1598.1,1636.7,1578.4 +1.370984593651126,1.6278164110132975,1.5707963267948966,242.1,1270.6,1270.5,1519.8,1551.3,1551.1 +1.3709650726057347,1.627822942290758,1.7016960206944713,276.4,1288.9,1347.6,1555.7,1579.4,935.4 +1.3709471785109324,1.6278244136217705,1.832595714594046,346.6,1421.7,1549.3,1731.3,830.8,451.7 +1.3709884380893507,1.627858536501181,1.9634954084936205,477.6,1733.3,1954.2,2128.5,534.4,315.4 +1.3709934228152862,1.6278730606587093,2.0943951023931953,751.8,1869.6,1742.3,1824.0,393.6,266.4 +1.370975155518416,1.6278448922245743,2.2252947962927703,1267.8,1637.2,1578.4,1600.0,314.4,255.7 +1.3709762308308828,1.6278567147758463,2.356194490192345,1241.5,1549.7,1550.4,1520.4,271.5,272.1 +1.3709737779647952,1.627875949049363,2.4870941840919194,1311.2,1579.0,1638.0,1558.2,255.8,314.9 +1.3709825471559358,1.6278575298684146,2.6179938779914944,1501.9,1744.1,1872.0,748.3,266.1,393.8 +1.3709776046813202,1.6278676570499717,2.748893571891069,1888.9,2122.9,2170.6,476.6,316.8,536.9 +1.370936055668858,1.6278842943080603,2.8797932657906435,1729.0,1870.5,1742.8,371.4,453.7,834.5 +1.3709572456318297,1.6278790232525613,3.010692959690218,1555.6,1637.8,1579.1,276.5,934.4,1289.6 +1.3709544599901873,1.527632378900553,0.0,1420.4,1550.9,1550.7,341.6,1270.8,1271.4 +1.3709756162433424,1.528767335314556,0.1308996938995747,1497.5,1580.2,1301.6,336.6,1290.3,1349.7 +1.3709560405242753,1.5287631310471275,0.2617993877991494,1708.7,1029.6,650.2,368.5,1420.9,1548.7 +1.3709341063240628,1.5287514976778254,0.39269908169872414,2121.0,675.0,455.9,457.5,1731.7,1948.7 +1.3709151987266033,1.5287350804981068,0.5235987755982988,1732.5,508.3,380.7,670.8,1757.0,1629.1 +1.370911520267571,1.528727350834027,0.6544984694978736,1558.0,417.5,358.5,1311.2,1534.9,1476.2 +1.3709026303822651,1.5286966412098209,0.7853981633974483,1520.8,371.3,370.7,1240.7,1451.3,1451.0 +1.3709035010383845,1.5287010231891045,0.916297857297023,1394.7,358.3,417.2,1267.6,1475.8,1534.7 +1.3709125267929256,1.5286763377747918,1.0471975511965976,672.8,381.0,508.3,1407.9,1627.9,1755.4 +1.370932447425332,1.5286450584765345,1.1780972450961724,457.3,455.5,674.7,1725.1,1979.4,2129.2 +1.3709197027807718,1.5286589669513768,1.3089969389957472,368.4,649.6,1029.0,1709.2,1872.7,1745.3 +1.3709227643918345,1.528660172847676,1.4398966328953218,336.4,1323.5,1289.5,1495.2,1636.9,1578.4 +1.3709836816881114,1.5286484028690883,1.5707963267948966,341.2,1271.1,1270.7,1421.0,1551.3,1550.9 +1.3709649870838438,1.528649643077082,1.7016960206944713,379.0,1289.0,1347.3,1453.2,1579.5,1321.4 +1.3709497302138876,1.5286465605100528,1.832595714594046,461.3,1422.1,1549.5,1616.7,1028.3,649.1 +1.3709949094365954,1.5286777573130053,1.9634954084936205,618.2,1733.3,1947.5,1987.7,674.3,455.3 +1.371004097608841,1.5286913610621249,2.0943951023931953,949.9,1754.9,1627.7,1823.8,508.2,380.9 +1.3709893081813218,1.528664156845155,2.2252947962927703,1267.9,1534.7,1475.9,1600.1,417.1,358.3 +1.370992292656168,1.5286783535566344,2.356194490192345,1241.5,1450.5,1451.6,1520.6,370.7,371.3 +1.3709896879766232,1.5287004028878914,2.4870941840919194,1311.0,1476.1,1535.3,1557.8,358.4,417.6 +1.370996339045908,1.5286841383227177,2.6179938779914944,1501.9,1629.7,1757.4,945.8,380.8,508.4 +1.3709878347611637,1.5286949391416211,2.748893571891069,1889.1,1983.1,2124.7,616.8,457.1,677.2 +1.3709258071253496,1.5286843921121327,2.8797932657906435,1614.7,1870.7,1743.1,460.6,651.7,1032.6 +1.3709451540880697,1.5286753233451729,3.010692959690218,1453.4,1637.7,1579.6,379.1,1319.3,1289.5 +1.3709413757780244,1.4284272285099557,0.0,1321.1,1551.1,1551.0,440.9,1271.1,1271.3 +1.370973015440401,1.4292821838806598,0.1308996938995747,1394.5,1580.1,1639.8,439.8,1290.5,1349.6 +1.3709443972251074,1.4292728457009862,0.2617993877991494,1593.4,1228.0,848.6,483.6,1421.1,1548.4 +1.3709122188459717,1.4292519599260352,0.39269908169872414,2006.1,815.6,596.4,598.6,1854.7,1838.5 +1.370885440241,1.4292241618254788,0.5235987755982988,1732.5,623.4,495.8,869.2,1641.7,1513.8 +1.3708770015181895,1.42920453561864,0.6544984694978736,1557.9,520.7,461.5,1310.9,1432.0,1372.8 +1.370866129667099,1.4291621232603846,0.7853981633974483,1521.0,470.8,470.3,1241.0,1351.5,1351.2 +1.3708673266871134,1.429155694091751,0.916297857297023,1600.5,461.4,520.3,1267.8,1372.7,1431.5 +1.3708785478207857,1.4291211783337903,1.0471975511965976,871.4,496.0,623.4,1408.0,1513.1,1640.4 +1.3709021879996715,1.4290812073162602,1.1780972450961724,598.4,595.9,815.1,1833.8,1838.9,2057.9 +1.370894374073653,1.4290877076314519,1.3089969389957472,483.4,848.1,1227.2,1594.0,1873.0,1745.2 +1.3709035342058327,1.429082841474606,1.4398966328953218,439.4,1347.9,1289.6,1392.6,1637.1,1578.7 +1.3709716122234628,1.4290665988450084,1.5707963267948966,440.8,1271.0,1270.7,1321.1,1551.4,1550.9 +1.3709605630681971,1.4290652449872026,1.7016960206944713,481.9,1289.2,1347.3,1350.1,1579.8,1637.9 +1.3709531097448975,1.4290616613758325,1.832595714594046,576.2,1421.7,1549.6,1501.8,1226.5,847.5 +1.3710057053260678,1.4290946207761022,1.9634954084936205,759.3,1885.3,1838.4,1846.6,814.8,595.8 +1.3710210758323786,1.4291119475762508,2.0943951023931953,1148.7,1640.0,1512.6,1823.6,623.2,496.0 +1.3710106426909519,1.4290899177686716,2.2252947962927703,1267.8,1431.5,1372.7,1600.2,520.2,461.3 +1.37101576975293,1.4291101938858284,2.356194490192345,1241.8,1351.1,1351.7,1520.3,470.3,470.9 +1.3710129300656921,1.4291383342703605,2.4870941840919194,1311.1,1373.1,1432.1,1558.1,461.6,520.8 +1.3710172307410557,1.4291272533195514,2.6179938779914944,1501.7,1514.6,1642.2,1144.2,495.9,623.6 +1.3710047500592655,1.429141748099809,2.748893571891069,1841.7,1841.8,2062.1,757.6,597.9,818.0 +1.3708289647956722,1.4289057273275136,2.8797932657906435,1500.8,1872.2,1744.6,576.7,849.2,1228.7 +1.3708549259535523,1.4288925304755953,3.010692959690218,1350.4,1638.8,1579.8,482.9,1348.4,1289.8 +1.3708411980652841,1.3286318354522146,0.0,1221.1,1551.1,1551.1,540.8,1271.1,1270.9 +1.3709395342493982,1.3293162464231338,0.1308996938995747,1291.1,1580.3,1639.6,543.4,1290.3,1349.8 +1.3709202613052287,1.3293096948361427,0.2617993877991494,1478.3,1427.1,1048.1,599.2,1421.0,1548.5 +1.3708868288282496,1.329287902078251,0.39269908169872414,1864.3,956.6,737.5,740.3,1731.8,1697.8 +1.3708568411417534,1.3292564903689223,0.5235987755982988,1732.5,739.1,611.4,1068.5,1526.1,1398.4 +1.3708459078023225,1.3292319601718527,0.6544984694978736,1558.1,624.2,565.2,1311.0,1328.6,1269.3 +1.3708338881594209,1.3291841648063856,0.7853981633974483,1521.2,570.8,570.2,1241.0,1251.5,1251.0 +1.3708353313513837,1.3291725756420392,0.916297857297023,1600.8,564.9,623.8,1267.4,1269.3,1328.0 +1.3708480166837222,1.3291334377925121,1.0471975511965976,1071.0,611.5,738.8,1407.8,1397.5,1524.7 +1.3708740595717417,1.3290896619037924,1.1780972450961724,740.0,737.1,956.4,1724.8,1698.0,1916.9 +1.3708692413402714,1.3290933402025389,1.3089969389957472,599.0,1047.3,1420.6,1478.4,1872.6,1745.3 +1.370881756787047,1.329086634689508,1.4398966328953218,543.0,1348.2,1289.5,1289.2,1637.0,1578.2 +1.3709533177164002,1.329069516809926,1.5707963267948966,540.8,1270.8,1270.8,1221.2,1551.3,1551.1 +1.3709455449031178,1.32906817380242,1.7016960206944713,585.4,1288.9,1347.7,1246.7,1579.6,1637.9 +1.3709410377196687,1.3290653645930413,1.832595714594046,692.0,1421.8,1549.4,1385.8,1426.0,1046.8 +1.3709961335155745,1.3290997417391925,1.9634954084936205,901.2,1733.0,1697.1,1704.9,955.9,736.9 +1.3710134058139192,1.3291189207532217,2.0943951023931953,1348.2,1524.4,1397.1,1824.2,738.7,611.5 +1.3710042314864115,1.3290989905885775,2.2252947962927703,1267.9,1327.9,1269.3,1600.4,623.6,564.9 +1.3710099809697398,1.3291214832682303,2.356194490192345,1241.3,1251.1,1251.8,1520.3,570.2,570.9 +1.3710071512326478,1.3291517743029921,2.4870941840919194,1311.3,1269.4,1328.5,1558.2,565.1,624.2 +1.3710109288641004,1.3291426083079805,2.6179938779914944,1501.9,1398.7,1526.5,1343.3,611.5,739.3 +1.3709974883043627,1.329158692500255,2.748893571891069,1699.8,1700.5,1920.8,899.1,739.4,959.3 +1.37081935883892,1.3289157968133791,2.8797932657906435,1385.4,1872.6,1744.9,692.3,1048.3,1420.9 +1.3708459301551894,1.3289022483809814,3.010692959690218,1246.8,1638.8,1579.7,586.4,1348.8,1289.6 +1.3708323089051178,1.2286415155828436,0.0,1121.1,1551.4,1551.3,640.8,1271.0,1271.1 +1.3709361236786002,1.2293186655165498,0.1308996938995747,1187.7,1580.5,1640.0,647.0,1290.2,1349.6 +1.3709176773959104,1.2293123616222514,0.2617993877991494,1362.6,1626.9,1247.5,714.7,1421.0,1548.4 +1.370884185782707,1.229290520337941,0.39269908169872414,1723.0,1097.8,878.6,882.0,1731.7,1556.5 +1.3708539679730096,1.2292588436986194,0.5235987755982988,1732.4,854.7,727.1,1267.9,1410.3,1283.0 +1.3708428505320143,1.229233944433028,0.6544984694978736,1557.8,727.7,668.7,1310.9,1224.9,1165.9 +1.3708307501449095,1.2291857442222134,0.7853981633974483,1521.1,670.8,670.2,1240.7,1151.8,1151.1 +1.3708322157312163,1.229173766022613,0.916297857297023,1600.3,668.4,727.3,1267.7,1165.8,1224.6 +1.3708450152435474,1.229134280900039,1.0471975511965976,1270.5,727.0,854.5,1408.0,1281.8,1409.1 +1.370871243198837,1.2290902229729943,1.1780972450961724,881.6,878.5,1097.5,1723.3,1556.7,1775.5 +1.3708666519623072,1.2290936920748885,1.3089969389957472,714.7,1246.8,1420.6,1362.8,1961.6,1744.9 +1.3708794196039964,1.2290868488890858,1.4398966328953218,646.4,1347.8,1289.5,1185.8,1636.8,1578.5 +1.3709512416558747,1.229069669162156,1.5707963267948966,640.7,1270.8,1270.5,1121.3,1551.3,1551.2 +1.3709437134810023,1.2290683278939307,1.7016960206944713,688.7,1289.1,1347.4,1143.2,1579.2,1637.7 +1.3709394269763937,1.2290655734586153,1.832595714594046,807.7,1422.0,1549.4,1270.1,1624.7,1246.0 +1.370994710378231,1.2291000552001905,1.9634954084936205,1042.6,1733.4,1556.1,1563.1,1097.1,878.0 +1.3710121260594395,1.229119372189075,2.0943951023931953,1407.2,1408.9,1281.7,1942.7,854.4,727.0 +1.3710030498330077,1.2290995964576972,2.2252947962927703,1267.7,1224.4,1165.7,1600.0,727.1,668.2 +1.3710088506505176,1.2291222537680813,2.356194490192345,1241.5,1151.4,1151.8,1520.3,670.2,670.8 +1.3710060248241764,1.2291527076794977,2.4870941840919194,1311.1,1166.1,1224.9,1558.3,668.7,727.8 +1.3710097683011992,1.2291436868032886,2.6179938779914944,1502.0,1283.2,1410.9,1542.5,727.0,855.0 +1.3709962563446463,1.229159894373453,2.748893571891069,1558.5,1559.1,1779.5,1040.4,880.9,1100.8 +1.3708184048274252,1.22891657140636,2.8797932657906435,1269.2,1960.6,1744.8,807.8,1247.8,1421.1 +1.3708450864105046,1.2289029625189576,3.010692959690218,1143.2,1639.0,1579.8,690.1,1348.4,1289.7 +1.3708315059561336,1.1286422317998686,0.0,1021.3,1551.1,1550.9,740.8,1270.9,1271.0 +1.3709357936493956,1.129318865879279,0.1308996938995747,1083.7,1580.5,1639.7,750.5,1290.5,1349.7 +1.37091741891792,1.1293125834182516,0.2617993877991494,1247.0,1744.9,1446.6,830.3,1421.0,1548.5 +1.3708839224909373,1.129290738026803,0.39269908169872414,1581.2,1238.9,1019.8,1023.5,1634.8,1415.2 +1.3708536851886897,1.129259038673873,0.5235987755982988,1732.5,970.4,842.8,1467.1,1294.9,1167.3 +1.3708425520831387,1.1292341076785195,0.6544984694978736,1558.1,831.2,772.3,1311.0,1121.4,1062.4 +1.370830445075741,1.1291858728170618,0.7853981633974483,1521.2,770.8,770.4,1240.6,1051.9,1051.2 +1.3708319127664566,1.1291738612848148,0.916297857297023,1600.5,772.1,830.8,1267.7,1062.3,1121.1 +1.370844722245227,1.1291343464836663,1.0471975511965976,1470.2,842.7,970.0,1407.8,1166.3,1293.9 +1.3708458963590286,1.1291303990781048,1.1780972450961724,1023.2,1019.5,1238.7,1581.6,1415.4,1634.7 +1.3708650017280855,1.129111809056642,1.3089969389957472,830.3,1446.1,1420.8,1247.2,1873.1,1745.6 +1.3708841587768756,1.129101586544391,1.4398966328953218,749.9,1348.1,1289.6,1082.2,1636.9,1578.4 +1.370955301043151,1.1290845789561086,1.5707963267948966,740.7,1270.9,1270.8,1021.0,1551.3,1551.2 +1.3709448049527686,1.1290831475669616,1.7016960206944713,792.4,1289.1,1347.5,1039.8,1579.3,1638.0 +1.3709371462878124,1.1290793761390194,1.832595714594046,923.4,1422.1,1549.6,1154.6,1744.8,1445.1 +1.3709894091696164,1.12911196866866,1.9634954084936205,1184.3,1634.2,1414.8,1421.4,1238.2,1019.0 +1.3710045384309195,1.1291288331881288,2.0943951023931953,1407.4,1293.5,1165.9,1823.7,969.6,842.6 +1.370994001486398,1.1291063250061697,2.2252947962927703,1267.8,1121.1,1062.3,1600.2,830.7,772.0 +1.3709991475397774,1.1291261531527677,2.356194490192345,1241.7,1051.3,1051.7,1520.4,770.2,770.6 +1.370996418222642,1.1291539086129787,2.4870941840919194,1311.2,1062.4,1121.4,1558.2,772.2,831.5 +1.3710008846153108,1.1291425175644585,2.6179938779914944,1501.9,1167.8,1295.3,1732.4,842.8,970.5 +1.370959470263657,1.129204139978172,2.748893571891069,1417.0,1417.6,1637.8,1181.8,1022.4,1242.4 +1.3708253994444224,1.1289545316805076,2.8797932657906435,1154.0,1872.5,1744.7,923.7,1447.0,1420.9 +1.3708580217929343,1.1289376966537326,3.010692959690218,1039.9,1638.6,1579.8,793.4,1348.8,1289.8 diff --git a/tools/localisation_machine_learning/data/sector2.csv b/tools/localisation_machine_learning/data/sector2.csv new file mode 100644 index 00000000..603dec1a --- /dev/null +++ b/tools/localisation_machine_learning/data/sector2.csv @@ -0,0 +1,2496 @@ +0.17085815683124295,0.17093761986366207,0.0,63.1,2751.1,2751.2,1698.9,71.0,70.9 +0.17094947221024442,0.17104270734636717,0.1308996938995747,91.5,2823.1,2882.5,823.6,47.4,106.7 +0.1709496078811476,0.17104255893099518,0.2617993877991494,139.4,3131.3,3259.4,349.1,187.6,95.1 +0.17115929112583556,0.1706904708575998,0.39269908169872414,223.5,2592.6,2372.8,191.2,109.8,62.8 +0.17118833318596033,0.17072432732583742,0.5235987755982988,392.8,2078.4,1950.3,113.9,50.8,59.6 +0.1712190003752866,0.17078004965106697,0.6544984694978736,911.8,1823.2,1764.2,68.5,129.3,70.2 +0.17122590238284915,0.1708178526094699,0.7853981633974483,2721.2,1729.0,1728.4,40.9,93.5,93.0 +0.17122425551149908,0.1708878663756379,0.916297857297023,2842.6,973.3,150.1,25.4,70.4,129.2 +0.1712145989160796,0.1709218750762722,1.0471975511965976,3210.3,431.6,51.5,105.7,59.1,186.4 +0.1712032994977258,0.1709383803425879,1.1780972450961724,2381.2,252.3,31.4,31.1,62.8,282.0 +0.17115163597302172,0.17098704685478539,1.3089969389957472,1938.4,161.1,33.5,72.2,94.9,474.0 +0.17111138458605363,0.17100995522815143,1.4398966328953218,1741.3,106.5,93.6,90.7,236.9,1065.5 +0.17112789867930928,0.1710068653247805,1.5707963267948966,1699.3,71.0,70.8,62.9,2751.1,2750.8 +0.1710165549053984,0.17100641972516528,1.7016960206944713,234.2,47.5,105.9,48.2,2820.6,2997.2 +0.17099866555606144,0.1710015475557074,1.832595714594046,73.8,187.1,94.9,46.6,3131.4,3259.2 +0.17102042569758322,0.17101709140928123,1.9634954084936205,32.3,109.7,62.8,63.2,2590.8,2402.5 +0.17100698492933147,0.17100554586646766,2.0943951023931953,21.3,51.3,59.1,116.7,2077.3,1949.9 +0.17097652499786095,0.17094878266832692,2.2252947962927703,25.9,129.1,70.3,318.1,1822.4,1763.9 +0.17097203956387164,0.17093179265782088,2.356194490192345,41.7,92.9,93.5,2720.6,1728.3,1729.5 +0.1709699909273402,0.17092371938009165,2.4870941840919194,68.7,70.2,129.3,2800.8,969.4,150.2 +0.17098381573273613,0.17088071338247945,2.6179938779914944,73.3,59.6,187.2,3119.8,430.8,51.7 +0.17098817879247838,0.17086886893600073,2.748893571891069,62.3,62.3,282.4,2537.5,251.8,31.8 +0.17101931458595437,0.17084135190666427,2.8797932657906435,46.3,94.4,474.3,2030.3,161.4,33.9 +0.1710350904405713,0.17083380536485193,3.010692959690218,48.0,234.1,1057.0,1784.6,106.4,93.2 +0.1710943433586279,0.27113861822661,0.0,162.9,2750.6,2751.2,1599.0,71.1,71.1 +0.17104015363096756,0.2706767843031961,0.1308996938995747,195.0,2823.2,2883.0,822.7,47.5,106.8 +0.17106921417466772,0.27068640941810806,0.2617993877991494,254.9,3131.9,3157.4,348.9,33.9,161.4 +0.17110504422922315,0.27070971767629515,0.39269908169872414,365.4,2450.5,2262.4,191.1,92.1,203.9 +0.1711339613035949,0.2707435125746236,0.5235987755982988,592.4,1962.5,1834.9,113.9,161.8,175.2 +0.17116171185081197,0.2707935983040435,0.6544984694978736,1298.3,1719.8,1661.0,68.5,232.8,173.7 +0.17116702456502347,0.27082372861556125,0.7853981633974483,2721.2,1629.0,1628.7,40.8,193.5,193.0 +0.17116574827046618,0.2708858280007782,0.916297857297023,2842.6,972.3,149.8,25.4,173.9,232.7 +0.17115842907553327,0.27091261308492887,1.0471975511965976,3210.6,431.4,51.4,21.3,174.7,302.0 +0.17115104338301398,0.27092329651112945,1.1780972450961724,2239.3,252.2,31.3,62.2,204.0,423.2 +0.1711041674034751,0.2709676390385791,1.3089969389957472,1822.5,161.0,33.5,72.2,294.3,673.6 +0.17106922641592637,0.2709876973480032,1.4398966328953218,1637.8,106.5,48.1,194.1,627.2,1456.5 +0.17109122954384604,0.2709835093734574,1.5707963267948966,1599.0,71.0,70.8,162.9,2751.5,2751.4 +0.171036670885852,0.2709822898570282,1.7016960206944713,233.6,47.4,105.9,151.7,2821.3,2879.7 +0.17099003002762486,0.27096849318330185,1.832595714594046,73.7,34.4,162.1,162.3,3132.6,3155.0 +0.17100944394557685,0.2709824559465379,1.9634954084936205,32.2,92.0,203.9,204.9,2449.1,2230.1 +0.17099978324205292,0.27097488346863563,2.0943951023931953,21.2,160.9,174.6,316.4,1961.0,1833.9 +0.17097308675957462,0.2709246961696634,2.2252947962927703,25.9,232.6,173.9,706.0,1719.0,1660.2 +0.1709706127653999,0.27091540166223327,2.356194490192345,41.6,192.9,193.5,2720.8,1628.4,1629.2 +0.17096842778566085,0.2709150827132836,2.4870941840919194,145.9,173.7,232.8,2800.8,968.2,149.8 +0.17098040893123723,0.27087896638388,2.6179938779914944,114.4,175.2,302.9,3120.1,430.4,51.6 +0.17098125315720042,0.2708729795631757,2.748893571891069,172.6,203.8,423.9,2395.1,251.6,31.7 +0.17100797427482925,0.2708498239899779,2.8797932657906435,161.8,294.0,674.1,1914.7,161.3,33.9 +0.17101870539364672,0.27084511335896844,3.010692959690218,151.5,621.8,1445.5,1681.3,106.4,47.6 +0.1710717526497094,0.3711452153643109,0.0,262.9,2751.3,2751.3,1499.1,71.0,71.0 +0.17102852450112457,0.37067068549273907,0.1308996938995747,298.6,2822.8,2882.2,822.9,47.5,106.8 +0.17106037627323636,0.3706811697991892,0.2617993877991494,370.6,3131.4,2958.1,349.0,33.9,250.5 +0.1710973226692275,0.3707051597969335,0.39269908169872414,507.0,2309.7,2090.3,191.1,31.9,252.7 +0.17112676876064437,0.37073948469671225,0.5235987755982988,791.6,1846.9,1719.2,113.9,172.8,290.8 +0.17115482840910284,0.37079004609551336,0.6544984694978736,1683.9,1616.1,1557.0,68.5,149.7,277.3 +0.17116028601911615,0.3708206184165592,0.7853981633974483,2721.1,1528.7,1528.6,40.8,293.5,293.0 +0.17115906003488415,0.3708831533754533,0.916297857297023,2842.8,972.4,149.8,25.4,277.4,336.2 +0.17115168390581167,0.3709103461801415,1.0471975511965976,2983.5,431.5,51.4,21.3,290.2,417.5 +0.1711441381549154,0.37092136267184417,1.1780972450961724,2097.9,252.1,31.3,31.1,345.2,564.3 +0.1710970444977021,0.3709659824900857,1.3089969389957472,1706.9,161.0,33.4,116.0,493.5,872.9 +0.1710618357148742,0.37098625650376227,1.4398966328953218,1534.2,106.5,48.1,297.6,1017.3,1846.1 +0.17108353505214383,0.37098215033229653,1.5707963267948966,1499.0,71.0,70.7,262.9,2751.5,2751.4 +0.17102868548605737,0.3709809351316473,1.7016960206944713,233.7,47.4,105.9,255.2,2821.1,2879.6 +0.17098177690714964,0.3709670859227068,1.832595714594046,73.7,34.4,250.2,277.9,3132.0,2955.9 +0.17100097714876283,0.3709808993634409,1.9634954084936205,32.2,32.5,253.5,346.6,2308.3,2088.8 +0.17099117909490946,0.3709731221139172,2.0943951023931953,21.2,171.9,290.1,516.2,1846.2,1718.3 +0.1709644045149276,0.37092273696858835,2.2252947962927703,25.9,151.7,277.4,1093.4,1615.5,1557.0 +0.17096192232940696,0.3709132447036587,2.356194490192345,41.6,293.0,293.4,2720.0,1528.5,1529.3 +0.17095980508602862,0.37091273728049057,2.4870941840919194,68.6,277.2,336.4,2800.4,968.6,149.8 +0.1709718713989232,0.370876488411493,2.6179938779914944,228.5,290.8,418.6,3120.4,430.6,51.6 +0.17097285464098852,0.37087039770845265,2.748893571891069,191.8,345.2,565.2,2253.9,251.6,31.7 +0.17099969588896324,0.37084719068641414,2.8797932657906435,277.4,493.6,873.5,1799.4,161.3,33.9 +0.17101054404506916,0.37084246206061255,3.010692959690218,254.9,1009.2,1832.5,1577.8,106.4,47.6 +0.17106369832988091,0.4711426379095489,0.0,362.9,2750.6,2750.9,1399.1,71.0,71.0 +0.17102212476028372,0.47067008003930355,0.1308996938995747,402.1,2823.6,2882.5,823.1,47.5,106.8 +0.17105439938220887,0.4706806853017862,0.2617993877991494,486.1,3131.9,2759.6,349.0,33.9,161.4 +0.17109149825985548,0.470441419471034,0.39269908169872414,648.5,2168.6,1948.9,191.1,31.9,252.5 +0.17085427148909146,0.4710733244726941,0.5235987755982988,991.4,1731.0,1603.2,113.8,50.7,406.5 +0.17085485987811286,0.4710713892045473,0.6544984694978736,2072.1,1512.5,1453.8,68.4,149.8,381.0 +0.1708472830281023,0.4710420753545024,0.7853981633974483,2721.1,1428.9,1428.5,40.8,393.6,393.0 +0.1708484521365904,0.47104647266542066,0.916297857297023,2842.4,971.3,149.5,25.4,381.0,439.8 +0.17085734476449108,0.47102128740866167,1.0471975511965976,2783.1,431.1,51.3,21.3,406.0,533.3 +0.170876898720173,0.47098920429783653,1.1780972450961724,1955.6,252.0,31.2,31.1,486.6,705.9 +0.1708636750464779,0.4710017514841909,1.3089969389957472,1590.5,160.9,33.4,240.7,693.5,1073.1 +0.1708664938702624,0.4710010172065988,1.4398966328953218,1430.7,106.3,48.0,236.7,1409.0,2239.0 +0.17092774838437397,0.4709871839212554,1.5707963267948966,1398.8,70.8,70.7,363.0,2751.0,2751.4 +0.1709100551989278,0.47098629529655045,1.7016960206944713,233.0,47.3,105.8,358.9,2821.1,2880.0 +0.17089651450553112,0.4709813318382061,1.832595714594046,73.4,34.2,162.0,393.7,3132.6,2755.1 +0.17094388258159596,0.47101150140826276,1.9634954084936205,32.0,32.3,253.4,488.8,2166.2,1947.2 +0.17095531208287673,0.4710250270932941,2.0943951023931953,21.1,51.0,405.8,716.6,1730.1,1602.5 +0.1709424917420888,0.47099849687052364,2.2252947962927703,25.7,151.3,381.0,1483.0,1511.5,1452.9 +0.1709467288812746,0.471014070568627,2.356194490192345,41.5,393.1,393.6,2720.3,1428.3,1429.2 +0.17094433348480542,0.47103785071702453,2.4870941840919194,68.5,381.0,440.1,2801.2,967.0,149.1 +0.1709503343923226,0.47102303338983487,2.6179938779914944,114.3,406.7,534.4,3051.5,430.0,51.3 +0.17094025165513588,0.4710347498516354,2.748893571891069,314.1,487.0,707.1,2111.6,251.3,31.5 +0.17082878416418204,0.4708628416921523,2.8797932657906435,348.9,693.0,1072.5,1684.1,161.3,33.8 +0.17085777669935268,0.470848177770802,3.010692959690218,358.5,1395.4,2217.8,1474.5,106.3,47.5 +0.17093654749310697,0.571166683366112,0.0,463.0,2750.6,2750.9,1299.0,70.9,70.9 +0.170940296547169,0.570712473140152,0.1308996938995747,505.6,2823.2,2882.2,824.4,47.4,106.7 +0.17097756250453064,0.5707244104389428,0.2617993877991494,601.4,2941.9,2561.7,349.2,33.8,161.2 +0.17101189190273036,0.5707463644731725,0.39269908169872414,789.9,2027.8,1808.9,191.2,31.8,296.6 +0.17103758987955164,0.5707761013344392,0.5235987755982988,1189.0,1616.0,1488.3,113.9,50.5,429.4 +0.17106328759248024,0.5708210806295273,0.6544984694978736,2451.1,1409.4,1350.3,68.5,323.5,484.4 +0.17106774422073887,0.5708455843258013,0.7853981633974483,2721.3,1329.0,1328.4,40.8,493.6,493.0 +0.17106726699445757,0.5709026412170419,0.916297857297023,2842.1,974.1,150.0,25.4,484.4,543.1 +0.17106186162334946,0.5709251023725574,1.0471975511965976,2586.9,431.9,51.4,21.3,521.2,648.5 +0.1710570497559849,0.57093211624848,1.1780972450961724,1815.7,252.3,31.2,31.0,627.2,846.3 +0.17101330681016522,0.5709739978399195,1.3089969389957472,1476.3,161.1,33.3,71.9,891.4,1270.6 +0.1709817150300965,0.570992776751579,1.4398966328953218,1327.7,106.4,48.0,235.7,1793.8,2621.1 +0.17100699226157093,0.5709876671723633,1.5707963267948966,1299.0,70.9,70.6,462.9,2752.2,2750.5 +0.17095551039922477,0.5709864267940628,1.7016960206944713,234.0,47.4,105.7,462.1,2820.8,2879.0 +0.17089457855320436,0.5709710412937206,1.832595714594046,73.7,34.3,161.8,509.0,2938.5,2559.6 +0.17092602735529278,0.5709921294918539,1.9634954084936205,32.2,32.4,296.5,629.9,2027.0,1807.7 +0.17091984589937306,0.5709874393169625,2.0943951023931953,21.1,51.0,431.1,914.8,1615.5,1487.8 +0.17089418808308018,0.5709384839864502,2.2252947962927703,25.8,323.3,484.4,1865.1,1408.5,1349.9 +0.17089225113129805,0.5709297161475755,2.356194490192345,41.5,493.0,493.5,2720.5,1328.5,1328.7 +0.17089067565153773,0.5709296092849938,2.4870941840919194,68.5,484.4,543.3,2800.4,970.0,149.9 +0.17090287587367636,0.570893929070299,2.6179938779914944,114.3,522.0,649.5,2855.9,430.8,51.5 +0.17090413319133577,0.570888254312403,2.748893571891069,191.5,627.8,847.8,1971.9,251.8,31.6 +0.17093080382085324,0.5708655037907502,2.8797932657906435,348.8,891.9,1271.5,1568.5,161.3,33.8 +0.17094136789712214,0.5708610852390144,3.010692959690218,462.1,1780.8,2602.3,1371.0,106.4,47.5 +0.17099399001009402,0.6711607588160209,0.0,562.9,2751.2,2750.8,1199.1,71.0,70.9 +0.17096410599951398,0.6706741072636033,0.1308996938995747,609.2,2822.6,2882.7,824.3,47.4,106.7 +0.1709984740241243,0.6706852433948054,0.2617993877991494,717.1,2741.8,2362.1,349.3,33.8,161.3 +0.1710357709074256,0.670709189076196,0.39269908169872414,931.3,1886.7,1667.5,191.2,31.8,252.3 +0.17106503865337178,0.6707429277826156,0.5235987755982988,1387.9,1500.3,1372.8,113.9,50.6,429.5 +0.17109324117325647,0.67079284371262,0.6544984694978736,2777.9,1305.9,1246.8,68.5,427.1,587.9 +0.17109883506230422,0.6708226389387788,0.7853981633974483,2720.9,1229.2,1228.6,40.8,593.6,593.1 +0.17109811268047226,0.6708847096483954,0.916297857297023,2842.2,973.9,149.9,25.4,587.9,646.7 +0.1710912869568882,0.670911648067618,1.0471975511965976,2387.2,431.9,51.4,21.3,636.7,763.8 +0.1710841596134275,0.6709223667674578,1.1780972450961724,1673.6,252.3,31.2,31.0,768.3,987.2 +0.17103751733473055,0.6709669870784625,1.3089969389957472,1360.5,161.1,33.4,71.9,1090.9,1469.7 +0.1710026748198378,0.6709875358187405,1.4398966328953218,1224.1,106.5,48.0,388.2,2183.3,2820.5 +0.1710245808107373,0.6709833016556161,1.5707963267948966,1199.0,70.9,70.6,563.0,2751.3,2751.2 +0.17096992104712244,0.6709820641981981,1.7016960206944713,234.0,47.4,105.7,565.3,2820.9,2879.1 +0.17092313912133847,0.6709684027762346,1.832595714594046,73.7,34.3,161.9,624.6,2739.6,2359.8 +0.17094255891091276,0.6709821146653945,1.9634954084936205,32.2,32.4,253.2,771.6,1885.6,1666.5 +0.17093311861268717,0.6709741300648693,2.0943951023931953,21.2,51.1,431.1,1114.4,1499.8,1372.0 +0.17090662261859588,0.6709238294620148,2.2252947962927703,25.8,426.8,588.0,2252.0,1305.2,1246.3 +0.17090445695524809,0.6709144924838177,2.356194490192345,41.5,593.0,593.5,2720.2,1228.7,1229.3 +0.17090280119511495,0.6709141046176315,2.4870941840919194,68.5,587.9,647.0,2800.6,969.9,149.9 +0.170915017688422,0.6708782271300437,2.6179938779914944,114.3,637.5,765.2,2656.4,430.8,51.5 +0.17091631939920607,0.6708724230262795,2.748893571891069,191.5,769.1,989.0,1830.6,251.7,31.6 +0.1709431005556399,0.6708495899855089,2.8797932657906435,483.2,1091.4,1470.8,1453.0,161.3,33.8 +0.17095379278392261,0.6708451533367954,3.010692959690218,565.5,2167.7,2822.5,1267.8,106.4,47.5 +0.1710065627911223,0.7711449639948946,0.0,662.9,2750.4,2751.2,1099.3,71.0,70.9 +0.17097349334194442,0.770670022653207,0.1308996938995747,712.8,2823.3,2882.1,824.0,47.4,106.7 +0.17102392928688545,0.7706851999631019,0.2617993877991494,832.7,2542.2,2162.3,349.2,33.8,161.3 +0.17105204078082295,0.7707034065891192,0.39269908169872414,1073.4,1745.3,1525.8,191.2,31.8,252.4 +0.1710801078214442,0.7707359041951929,0.5235987755982988,1587.7,1384.7,1257.0,113.9,50.6,507.6 +0.1711087416024622,0.7707867476071577,0.6544984694978736,2800.7,1202.2,1143.2,68.5,530.6,691.5 +0.17111471587362034,0.7708183620099622,0.7853981633974483,2721.5,1129.2,1128.5,40.8,693.5,693.0 +0.17111386668608858,0.7708823865740007,0.916297857297023,2842.6,973.7,149.9,25.4,691.4,750.2 +0.17110642913941534,0.7709111360871848,1.0471975511965976,2186.6,431.8,51.4,21.3,752.3,879.6 +0.17109832245935166,0.7709233821285111,1.1780972450961724,1531.5,252.2,31.2,31.0,909.3,1128.5 +0.1710504491901688,0.7709691091799371,1.3089969389957472,1244.7,161.1,33.4,72.0,1289.9,1669.3 +0.1710142371364203,0.7709903361917345,1.4398966328953218,1120.7,106.5,48.0,491.6,2573.5,2926.0 +0.1710347434439813,0.7709864444000292,1.5707963267948966,1099.1,70.9,70.6,662.9,2751.5,2750.3 +0.170978773828495,0.7709851780530386,1.7016960206944713,233.9,47.4,105.7,669.0,2820.8,2879.1 +0.17093083133823897,0.7709711556402405,1.832595714594046,73.7,34.3,161.9,740.3,2539.5,2160.2 +0.1709492664802234,0.7709842945008598,1.9634954084936205,32.2,32.4,253.2,913.4,1744.4,1525.1 +0.17093906885461174,0.7709755895113954,2.0943951023931953,21.2,51.1,506.8,1314.3,1384.1,1256.7 +0.17091208328483998,0.7709244467359673,2.2252947962927703,25.8,530.3,691.5,2639.4,1201.8,1142.8 +0.17090967038486554,0.7709142279970482,2.356194490192345,41.5,692.9,693.5,2720.3,1128.7,1129.1 +0.1709079786150995,0.770913001852364,2.4870941840919194,68.5,691.5,750.3,2800.1,969.7,149.9 +0.17092039430463812,0.7708763517633102,2.6179938779914944,114.3,753.3,880.6,2456.5,430.8,51.5 +0.1709220275199289,0.7708699128501464,2.748893571891069,191.6,910.9,1130.7,1688.9,251.7,31.7 +0.17094929130209555,0.7708465900512249,2.8797932657906435,494.2,1291.2,1670.7,1337.4,161.3,33.8 +0.17096053464636904,0.7708418361557807,3.010692959690218,669.0,2555.0,2905.5,1164.3,106.4,47.5 +0.17101399555936245,0.8711421810075657,0.0,762.9,2751.0,2751.4,999.1,71.0,70.9 +0.1709801000150172,0.8706701506775822,0.1308996938995747,816.3,2822.5,2882.8,823.8,47.4,106.7 +0.17101406317715104,0.8706812003788778,0.2617993877991494,948.3,2343.0,1962.6,349.2,33.9,161.3 +0.17105159587280666,0.8707053659050388,0.39269908169872414,1215.0,1604.0,1384.6,191.2,31.8,252.4 +0.17108118387323515,0.8707395529087192,0.5235987755982988,1786.7,1269.1,1141.4,113.9,50.6,597.9 +0.17110953463821021,0.8707899768795575,0.6544984694978736,2800.6,1098.6,1039.5,68.5,149.3,795.1 +0.171115178324453,0.8708203284934997,0.7853981633974483,2721.0,1029.0,1028.5,40.8,793.4,792.8 +0.1711143219558175,0.8708828600041136,0.916297857297023,2842.6,973.6,149.9,25.4,794.9,853.7 +0.17110726927476677,0.8709101720887547,1.0471975511965976,1987.0,431.7,51.4,21.3,867.8,995.1 +0.17109988349448702,0.8709212214347914,1.1780972450961724,1390.0,252.3,31.3,31.0,1050.4,1269.4 +0.17105293354806314,0.8709660349635076,1.3089969389957472,1128.9,161.1,33.4,72.0,1489.4,1868.1 +0.17101777800702414,0.8709866446126076,1.4398966328953218,1017.0,106.5,48.0,572.5,2879.1,2820.9 +0.17103939934823256,0.8709825039009071,1.5707963267948966,999.1,70.9,70.7,763.0,2751.3,2751.4 +0.17096131568526376,0.8709836071773962,1.7016960206944713,234.0,47.4,105.7,772.6,2820.6,2879.9 +0.17092893872277903,0.8709743017516081,1.832595714594046,73.7,59.8,161.9,855.8,2340.0,1960.9 +0.1709505766159811,0.870989483762987,1.9634954084936205,32.2,32.4,253.3,1054.9,1603.3,1384.0 +0.1709402374253904,0.8709806972322482,2.0943951023931953,21.2,51.1,596.9,1513.9,1268.6,1141.1 +0.17091260338168632,0.8709283927551386,2.2252947962927703,25.8,633.8,795.0,2843.1,1098.4,1039.4 +0.1709097921144575,0.8709165878413301,2.356194490192345,41.6,792.9,793.7,2719.9,1028.7,1029.0 +0.17090810777792442,0.870913728661711,2.4870941840919194,68.5,795.1,854.0,2799.6,969.6,150.0 +0.17092095173167715,0.8708755781292918,2.6179938779914944,114.3,868.9,996.5,2257.7,430.7,51.5 +0.1709233112751342,0.870867890327756,2.748893571891069,191.6,1052.0,1272.2,1547.7,251.8,31.7 +0.17095154665774245,0.8708436222981435,2.8797932657906435,348.9,1490.5,1870.1,1221.5,161.3,33.8 +0.1709638872761619,0.8708382567015036,3.010692959690218,772.5,2857.7,2822.0,1060.5,106.4,47.5 +0.27096757824663725,0.17074778603630092,0.0,63.0,2651.4,2650.8,1699.0,171.0,171.0 +0.27099230008439323,0.1710478450546744,0.1308996938995747,91.5,2719.9,2778.7,1207.6,151.0,148.9 +0.2709922897563243,0.17104780938996966,0.2617993877991494,139.4,3015.7,3143.0,548.6,231.4,95.1 +0.27121318523899113,0.17075281719453073,0.39269908169872414,223.5,2592.3,2373.0,332.4,173.5,62.8 +0.27121599965135,0.17075828056013242,0.5235987755982988,392.8,2078.2,1950.8,229.6,187.4,59.6 +0.271241378389102,0.1708040880024193,0.6544984694978736,911.4,1823.3,1764.3,172.1,129.4,70.2 +0.2712476404667339,0.1708394187858835,0.7853981633974483,2621.4,1728.9,1728.4,140.9,93.6,93.0 +0.27124590820729405,0.17090963181684926,0.916297857297023,2738.9,1361.0,537.6,129.0,70.4,129.2 +0.2712358448398395,0.17094457483736125,1.0471975511965976,3093.8,631.5,251.2,136.9,59.1,186.4 +0.27122377584159746,0.1709619743017512,1.1780972450961724,2381.8,394.1,173.1,172.3,62.9,282.0 +0.27117116682119197,0.17101130870075565,1.3089969389957472,1938.4,276.8,149.1,139.5,94.9,474.1 +0.27112989504389845,0.17103461878100878,1.4398966328953218,1741.1,210.0,151.6,90.7,236.9,1065.4 +0.2711453964173816,0.17103156995806268,1.5707963267948966,1699.3,171.0,170.8,62.9,2651.8,2651.8 +0.27108486883515087,0.17102997996755986,1.7016960206944713,624.0,150.9,151.4,48.3,2717.5,2775.5 +0.27103292641870563,0.1710146755507267,1.832595714594046,273.1,231.1,94.9,46.7,3016.0,3143.3 +0.27108709515534984,0.17104653352819765,1.9634954084936205,173.5,174.2,62.8,63.2,2591.0,2371.9 +0.2710541217395336,0.17101365468158702,2.0943951023931953,136.8,186.4,59.1,116.7,2077.3,1949.9 +0.2710223562612211,0.1709544453853009,2.2252947962927703,129.4,129.2,70.4,318.1,1822.8,1764.0 +0.2710190138634685,0.17094266688075743,2.356194490192345,141.6,93.0,93.5,2620.2,1728.5,1728.9 +0.27101662213261,0.17094204565390814,2.4870941840919194,172.2,70.2,129.3,2696.8,1355.4,536.0 +0.27102807093287856,0.1709063309532899,2.6179938779914944,117.2,59.6,187.2,3003.8,629.9,251.0 +0.2710284218188722,0.1709006506527857,2.748893571891069,62.4,62.4,282.3,2537.3,393.2,173.2 +0.2710544376515309,0.17087769545160447,2.8797932657906435,46.3,94.5,474.2,2030.8,276.9,149.5 +0.2709767944084801,0.17078253793775255,3.010692959690218,48.0,234.9,1059.4,1784.6,209.8,151.1 +0.2710379121587441,0.27108559182662084,0.0,162.9,2650.6,2650.8,1599.2,171.0,171.1 +0.2710275102767989,0.27108560480636323,0.1308996938995747,194.9,2719.4,2779.2,1205.3,151.0,210.4 +0.270991162963948,0.2710752806795571,0.2617993877991494,254.9,3016.7,3144.2,548.1,149.5,250.1 +0.27095355127338877,0.2710525592245179,0.39269908169872414,365.3,2450.3,2231.0,332.3,250.7,203.7 +0.2709227274898176,0.2710221121809253,0.5235987755982988,592.6,1961.7,1834.4,229.4,250.3,175.1 +0.27091134921421645,0.27099907021243075,0.6544984694978736,1299.5,1719.6,1660.6,172.1,232.7,173.7 +0.2708989927929438,0.270952829258692,0.7853981633974483,2621.0,1629.1,1628.3,140.9,193.4,193.0 +0.2708999704568858,0.27094246595105553,0.916297857297023,2739.5,1358.4,536.6,129.0,173.9,232.8 +0.27089794048097965,0.2709508165145118,1.0471975511965976,3095.5,630.9,251.1,137.0,174.7,302.2 +0.2709416437282022,0.2708800710798609,1.1780972450961724,2238.9,393.8,173.1,172.4,204.2,423.4 +0.2709106535257941,0.2709079083623813,1.3089969389957472,1822.0,276.6,149.1,255.0,294.5,674.2 +0.27091988120998195,0.27090517607753273,1.4398966328953218,1637.8,209.9,151.6,194.2,628.2,1458.1 +0.27119656943746523,0.2708444146343352,1.5707963267948966,1599.3,170.9,170.7,163.0,2651.8,2651.1 +0.2710611300991792,0.27084000597966273,1.7016960206944713,622.4,150.9,209.3,151.8,2717.8,2776.1 +0.27102128934848796,0.27082777412101633,1.832595714594046,272.7,150.0,250.3,162.4,3017.3,3144.7 +0.27106917638255407,0.2708593051782342,1.9634954084936205,173.2,250.7,204.0,205.1,2448.3,2229.4 +0.27108634322495617,0.27088037699856793,2.0943951023931953,136.7,251.1,174.7,316.8,1960.7,1833.8 +0.271078051218004,0.2708641751924712,2.2252947962927703,129.3,232.6,174.0,707.0,1718.7,1660.0 +0.2710840782827424,0.2708909319651127,2.356194490192345,141.6,192.9,193.6,2620.4,1628.3,1628.9 +0.27108065498268663,0.2709253857395808,2.4870941840919194,217.7,173.7,232.9,2697.3,1352.2,534.3 +0.27106801849490875,0.2709696474058849,2.6179938779914944,230.1,175.2,303.0,3004.6,629.2,250.5 +0.27107206709941106,0.2709589375388255,2.748893571891069,203.7,203.8,424.0,2394.9,392.8,173.0 +0.2709052116860873,0.27079307436496247,2.8797932657906435,161.9,294.3,674.5,1914.3,276.7,149.4 +0.27092629371989707,0.2707827441324213,3.010692959690218,151.5,622.7,1447.5,1681.1,209.8,151.1 +0.2710027760307061,0.37110208879057827,0.0,262.9,2651.0,2651.5,1498.9,170.9,171.1 +0.2709938870285197,0.3711022373443118,0.1308996938995747,298.5,2720.4,2779.0,1204.9,151.0,210.4 +0.27095421530383,0.3710908813014584,0.2617993877991494,370.5,3016.7,2957.6,548.0,149.5,277.1 +0.27091260385452415,0.37106556713434724,0.39269908169872414,507.1,2308.6,2089.6,332.1,232.9,344.9 +0.2708785376508575,0.37103145195516296,0.5235987755982988,792.0,1846.7,1719.2,229.4,250.3,290.7 +0.27086510418508863,0.37100423455586706,0.6544984694978736,1685.8,1616.2,1557.1,172.1,336.2,277.2 +0.2708519515887738,0.3709536850334667,0.7853981633974483,2621.1,1529.0,1528.5,140.8,293.5,293.0 +0.2708532577482178,0.3709392896692705,0.916297857297023,2739.4,1357.9,536.4,129.0,277.4,336.3 +0.27086688502146244,0.37074819500208256,1.0471975511965976,2982.2,630.8,251.0,137.0,290.2,417.7 +0.2711776007509465,0.3710287994041104,1.1780972450961724,2098.4,394.1,173.2,203.3,345.2,564.3 +0.2709959571243477,0.37119616693829993,1.3089969389957472,1707.0,276.9,149.2,271.5,493.4,872.5 +0.2710734024972219,0.37115596792237016,1.4398966328953218,1534.4,210.0,151.6,297.8,1016.1,1844.0 +0.27112831157053097,0.3711432930647218,1.5707963267948966,1498.6,171.0,170.8,263.1,2651.1,2651.1 +0.2710785451721227,0.37114144045319963,1.7016960206944713,624.1,150.9,209.3,255.2,2717.6,2775.4 +0.27102803142422915,0.3711259621872989,1.832595714594046,273.1,150.1,277.6,278.0,3016.4,2957.2 +0.271042023582457,0.37113587454328556,1.9634954084936205,173.5,233.5,345.3,346.7,2309.1,2089.5 +0.2710278995696049,0.37112281528287916,2.0943951023931953,136.8,250.9,290.3,516.1,1845.9,1718.6 +0.2709981307255737,0.37106676391413984,2.2252947962927703,129.4,336.4,277.5,1092.7,1615.5,1557.0 +0.27099411020456554,0.3710514170032335,2.356194490192345,141.7,293.1,293.6,2620.7,1528.5,1528.8 +0.27099192832132646,0.3710451551121887,2.4870941840919194,172.2,277.4,336.4,2696.9,1356.1,536.1 +0.27100491695842427,0.37100377574418064,2.6179938779914944,230.1,290.9,418.6,3003.7,630.3,251.1 +0.27100805581531445,0.3709930618348469,2.748893571891069,314.3,345.3,565.2,2254.3,393.3,173.2 +0.2710376699779519,0.37096611801134927,2.8797932657906435,277.6,493.6,873.2,1799.5,276.9,149.5 +0.27105194151738987,0.37095856747496647,3.010692959690218,255.1,1008.4,1830.5,1578.0,210.0,151.1 +0.2711097922350668,0.4712622159603548,0.0,363.1,2650.2,2651.2,1399.2,171.1,171.1 +0.2710471651759053,0.4707089534933877,0.1308996938995747,402.2,2719.7,2778.8,1206.5,151.1,210.4 +0.27107097788749335,0.47071688452658256,0.2617993877991494,486.3,3016.1,2758.9,548.3,149.5,443.6 +0.2711029033190606,0.4707376796610414,0.39269908169872414,648.6,2168.0,1949.4,332.4,173.6,394.4 +0.27112902727239574,0.4707684176322642,0.5235987755982988,991.3,1730.9,1603.3,229.5,393.0,406.4 +0.27115502193169383,0.47081519108717074,0.6544984694978736,2070.2,1512.6,1453.7,172.0,440.0,380.9 +0.2711595418147747,0.4708419256293961,0.7853981633974483,2621.1,1429.1,1428.5,140.8,393.5,393.0 +0.2711583363766995,0.47090081718097365,0.916297857297023,2739.3,1359.1,536.8,128.9,380.9,439.8 +0.27115183969100876,0.4709247214041259,1.0471975511965976,2784.0,631.1,251.1,136.9,405.8,533.2 +0.2711458711581184,0.4709330158669003,1.1780972450961724,1955.9,393.9,173.0,172.3,486.3,705.6 +0.27110079786416513,0.47097555485239306,1.3089969389957472,1591.0,276.6,149.0,271.5,692.9,1072.5 +0.2710679109691281,0.47099440575350005,1.4398966328953218,1431.0,209.9,151.6,401.1,1407.4,2236.5 +0.2710920778233259,0.4709896320061644,1.5707963267948966,1399.0,170.9,170.8,363.0,2650.8,2650.8 +0.27103957029907744,0.4709883928402636,1.7016960206944713,623.0,150.8,209.3,358.6,2717.6,2775.9 +0.2709947816714656,0.4709750679468534,1.832595714594046,272.8,150.0,444.2,393.5,3016.4,2756.4 +0.27101575872957745,0.47098993615936613,1.9634954084936205,173.4,174.2,395.3,488.5,2167.1,1948.0 +0.27100726424820204,0.47098355750742993,2.0943951023931953,136.7,392.0,405.7,715.9,1730.2,1602.8 +0.2709813125650756,0.4709347096632759,2.2252947962927703,129.4,439.7,380.9,1481.6,1512.0,1453.2 +0.2709791637948346,0.47092681465261865,2.356194490192345,141.6,392.9,393.5,2620.2,1428.4,1429.2 +0.2709769037774639,0.47081938537293744,2.4870941840919194,172.2,380.8,440.0,2697.2,1353.8,535.0 +0.2709921133119345,0.4708760770172915,2.6179938779914944,230.1,406.5,534.2,3004.7,629.5,250.7 +0.2709861616577885,0.47088091466390747,2.748893571891069,333.2,486.6,706.8,2113.0,393.0,173.1 +0.2710103675083457,0.47085998061467604,2.8797932657906435,393.0,693.2,1073.2,1683.2,276.8,149.4 +0.27102071461679633,0.4708553716134376,3.010692959690218,358.5,1396.9,2220.4,1474.6,209.9,151.1 +0.27107443950792903,0.5711563976521672,0.0,462.9,2650.9,2650.9,1299.1,171.0,171.0 +0.27103100602019664,0.5706751647827102,0.1308996938995747,505.6,2720.0,2779.1,1206.7,151.1,210.4 +0.2710623344941203,0.5706854818121014,0.2617993877991494,601.8,2939.1,2559.5,548.4,149.5,277.0 +0.2710987710881346,0.5707091513375826,0.39269908169872414,790.3,2027.0,1807.4,332.3,173.6,394.3 +0.27112781851145806,0.5707430518976642,0.5235987755982988,1190.3,1615.2,1487.8,229.5,404.0,522.0 +0.2711556079505959,0.5707931326608489,0.6544984694978736,2456.1,1409.2,1350.0,172.0,520.6,484.4 +0.27116094054256784,0.5708232088640113,0.7853981633974483,2621.2,1328.9,1328.4,140.8,493.5,493.0 +0.27115971000794903,0.5708852636972856,0.916297857297023,2739.3,1349.5,536.8,128.9,484.4,543.3 +0.2711524442644924,0.5709120196707242,1.0471975511965976,2584.2,630.9,251.0,136.9,521.3,648.6 +0.27114510550257254,0.5709226777808722,1.1780972450961724,1814.2,393.9,173.0,172.3,627.5,846.6 +0.2710982767644531,0.5709670198846468,1.3089969389957472,1475.6,276.6,149.0,356.2,892.4,1271.6 +0.27106337394133423,0.5709870989978387,1.4398966328953218,1327.4,209.9,151.5,504.5,1797.1,2626.1 +0.2710854009485308,0.5709829082970639,1.5707963267948966,1299.1,171.0,170.8,462.9,2650.8,2651.2 +0.27103086169216223,0.5709816918882333,1.7016960206944713,623.1,150.9,209.3,462.1,2717.9,2775.9 +0.27098423467350063,0.5709679092614486,1.832595714594046,272.9,150.0,277.6,509.1,2936.2,2557.0 +0.27100366860476977,0.5709818658687447,1.9634954084936205,173.3,174.3,395.2,630.2,2025.6,1807.0 +0.2709940385129937,0.5709742797160853,2.0943951023931953,136.8,402.9,521.1,915.6,1614.6,1487.5 +0.27096737028882684,0.5709240977753931,2.2252947962927703,129.4,520.4,484.3,1868.6,1408.4,1350.0 +0.2709649289211724,0.5709148157678303,2.356194490192345,141.6,492.9,493.6,2620.7,1328.5,1329.2 +0.2709627858659884,0.5709145111718161,2.4870941840919194,172.2,484.3,543.3,2697.2,1350.3,535.1 +0.2709747875870485,0.570878429046564,2.6179938779914944,230.1,522.0,649.8,2853.1,629.7,250.8 +0.27097565872003526,0.5708724743997471,2.748893571891069,455.4,628.2,848.4,1971.1,393.0,173.1 +0.2710023776942438,0.5708493574130029,2.8797932657906435,508.5,892.7,1272.6,1567.9,276.8,149.4 +0.2710130949935346,0.5708446786657955,3.010692959690218,462.0,1784.0,2607.2,1370.9,209.9,151.1 +0.2710661043192735,0.6711447446866989,0.0,562.9,2650.5,2650.8,1199.0,171.0,171.0 +0.27102409078314416,0.6706704889354584,0.1308996938995747,609.2,2719.4,2778.8,1206.9,151.1,210.4 +0.27105623628125675,0.6706810564741128,0.2617993877991494,717.3,2740.1,2360.2,548.3,149.5,277.0 +0.2710932727761339,0.6707050860555759,0.39269908169872414,932.0,1885.8,1666.5,332.3,173.5,437.6 +0.271122747262168,0.6707394156300273,0.5235987755982988,1389.6,1500.0,1372.5,229.5,250.0,612.3 +0.27115083970426873,0.6707899780599174,0.6544984694978736,2696.8,1305.5,1246.5,172.0,535.3,587.9 +0.27115631685006003,0.6708205428442473,0.7853981633974483,2620.9,1229.1,1228.4,140.8,593.5,593.1 +0.2708256695155592,0.6709531148914836,0.916297857297023,2740.0,1246.2,535.5,128.9,588.1,647.0 +0.27083454278897867,0.6709274000629024,1.0471975511965976,2382.1,630.1,250.7,136.9,637.1,764.6 +0.2708576010568526,0.6708903904674406,1.1780972450961724,1671.4,393.4,172.9,172.4,769.0,988.8 +0.27084990137874343,0.6708981977393755,1.3089969389957472,1359.2,276.4,149.0,446.1,1092.7,1472.7 +0.2708593544642835,0.6708942145964787,1.4398966328953218,1223.7,209.7,151.5,608.0,2192.2,2716.0 +0.2709275836276006,0.6708794640635283,1.5707963267948966,1199.0,170.8,170.7,563.0,2651.1,2651.5 +0.2709162529253375,0.6708793583942507,1.7016960206944713,621.1,150.8,209.3,565.7,2717.9,2776.3 +0.2709082309991131,0.6708764238533171,1.832595714594046,272.3,149.9,277.7,625.1,2734.2,2355.7 +0.27095997454706094,0.670909941486749,1.9634954084936205,173.0,174.1,437.4,772.5,1883.4,1664.6 +0.2709744270623457,0.6709275111526496,2.0943951023931953,136.6,251.0,611.2,1116.8,1498.6,1371.3 +0.2709635105746915,0.670905027405382,2.2252947962927703,129.2,540.1,587.9,2261.6,1304.6,1246.0 +0.2709685513294956,0.6709246526124906,2.356194490192345,141.5,593.0,593.7,2620.7,1228.3,1229.2 +0.2709658696552883,0.6709523466794551,2.4870941840919194,172.1,588.1,647.3,2697.4,1246.8,533.3 +0.27097102266897527,0.6709408595988886,2.6179938779914944,230.1,637.9,765.9,2651.2,628.6,250.2 +0.27095922866850597,0.6709555338204096,2.748893571891069,333.4,770.0,990.5,1828.7,392.5,172.8 +0.27085931060954954,0.6708120182798514,2.8797932657906435,548.9,1092.7,1472.3,1452.1,276.7,149.4 +0.27088745048036733,0.6707979430146704,3.010692959690218,565.6,2172.4,2718.3,1267.1,209.8,151.1 +0.2709679226223854,0.7711190695318471,0.0,663.0,2650.9,2650.9,1099.2,170.9,171.0 +0.2709610181349534,0.7711191410689155,0.1308996938995747,712.8,2719.7,2779.6,1121.6,151.0,210.4 +0.27092245547663363,0.7711079527434885,0.2617993877991494,832.9,2540.4,2160.7,548.3,149.4,277.1 +0.2708816425652645,0.771082908426838,0.39269908169872414,1073.4,1775.9,1556.5,332.1,173.6,394.4 +0.2708481608993416,0.7710491321402966,0.5235987755982988,1588.5,1384.5,1256.7,229.4,250.1,629.4 +0.2708352893644602,0.7710224117577644,0.6544984694978736,2757.5,1202.0,1142.9,172.0,535.8,691.5 +0.27082242579768634,0.7709723716485375,0.7853981633974483,2620.6,1128.9,1128.4,140.8,693.6,693.0 +0.27082394711679797,0.7709586166549249,0.916297857297023,2739.3,1143.0,536.8,129.0,691.5,750.4 +0.27083757203685177,0.7709176538713771,1.0471975511965976,2184.8,631.0,251.0,136.9,752.5,879.9 +0.2708652002516503,0.7708727189827753,1.1780972450961724,1530.8,393.8,173.0,172.3,910.0,1129.1 +0.27086506331209526,0.7708744636600862,1.3089969389957472,1244.3,276.6,149.0,271.5,1291.5,1671.0 +0.2708773086547368,0.7708691515441557,1.4398966328953218,1120.3,209.9,151.5,711.6,2577.9,2716.2 +0.2709497818910085,0.7708532050293564,1.5707963267948966,1099.0,170.9,170.7,663.0,2651.1,2651.1 +0.27094283409638686,0.7708532491653599,1.7016960206944713,622.6,150.8,209.3,669.3,2717.5,2776.0 +0.27093872887862214,0.7708518793071202,1.832595714594046,272.7,149.9,277.6,740.6,2537.4,2158.3 +0.270993757676217,0.7708875816901659,1.9634954084936205,173.2,174.1,395.1,913.8,1743.8,1524.6 +0.2710106511705861,0.77090776047371,2.0943951023931953,136.6,250.8,631.2,1315.5,1383.6,1256.5 +0.2710010583201959,0.770888394343614,2.2252947962927703,129.2,539.0,691.4,2644.8,1201.3,1142.8 +0.2710065444447476,0.7709111308424474,2.356194490192345,141.5,693.0,693.6,2620.7,1128.4,1129.0 +0.27100423187906675,0.7709511761584398,2.4870941840919194,172.1,691.4,750.7,2697.4,1143.2,534.6 +0.271010196847637,0.7709360881352507,2.6179938779914944,230.0,753.4,881.3,2454.9,629.4,250.5 +0.27099794091752616,0.770951572928213,2.748893571891069,333.1,911.2,1131.2,1688.2,392.8,172.9 +0.27086395052363643,0.7708127777656311,2.8797932657906435,548.8,1292.1,1672.1,1336.7,276.8,149.4 +0.2708865693214248,0.7708016057007288,3.010692959690218,669.1,2559.2,2844.4,1163.8,209.9,151.1 +0.27096536701194246,0.8711232117906855,0.0,763.0,2651.1,2651.1,999.0,170.9,171.0 +0.2709581648974426,0.8711232317480766,0.1308996938995747,816.3,2720.2,2779.5,1017.9,151.0,210.3 +0.2709197310372415,0.8711120474969025,0.2617993877991494,948.3,2341.2,1961.7,548.3,149.4,277.0 +0.27087914683644737,0.871087107825852,0.39269908169872414,1215.2,1603.9,1384.6,332.2,173.5,394.3 +0.27084585575775405,0.871053501129891,0.5235987755982988,1788.0,1268.9,1141.2,229.5,250.0,727.6 +0.2708331577527525,0.871027017259042,0.6544984694978736,2696.9,1098.6,1039.5,172.0,620.5,795.0 +0.27082035219274975,0.8709772075799265,0.7853981633974483,2621.2,1029.1,1028.5,140.9,793.7,793.0 +0.27082189658006095,0.8709637108683581,0.916297857297023,2739.0,1039.3,537.0,129.0,795.0,853.8 +0.27083546796474983,0.8709229878914804,1.0471975511965976,1985.9,631.2,251.1,136.9,868.0,995.1 +0.27086296170209356,0.870878205543397,1.1780972450961724,1389.1,393.9,173.0,172.3,1051.3,1270.3 +0.27085984203145325,0.8708816167507432,1.3089969389957472,1128.6,276.6,149.0,271.4,1490.6,1869.7 +0.2708739964058639,0.8708753659057678,1.4398966328953218,1016.9,209.9,151.5,626.5,2775.1,2716.9 +0.2709468539797384,0.870859266501359,1.5707963267948966,999.2,170.9,170.7,763.1,2651.2,2651.1 +0.2709398436850266,0.8708592682515586,1.7016960206944713,623.0,150.8,209.3,772.7,2717.9,2776.2 +0.2709355405939678,0.8708578475694737,1.832595714594046,272.7,149.9,277.6,856.1,2338.5,1959.5 +0.27099038530738356,0.8708933838104052,1.9634954084936205,173.2,174.1,395.1,1055.7,1602.5,1383.4 +0.2710071608974541,0.8709133385670829,2.0943951023931953,136.6,250.8,719.1,1514.9,1268.0,1140.8 +0.2709974822113027,0.8708937853979193,2.2252947962927703,129.2,623.9,794.9,2738.4,1098.0,1039.0 +0.27100293824405264,0.8709163340661024,2.356194490192345,141.5,792.9,793.5,2620.7,1028.3,1029.1 +0.2710001607420459,0.8709465487221004,2.4870941840919194,172.1,795.0,854.2,2697.2,1039.6,534.7 +0.27100432462152946,0.8709374095685369,2.6179938779914944,229.9,869.1,996.8,2255.9,629.3,250.6 +0.27099151216959616,0.8709537989367837,2.748893571891069,333.1,1052.5,1272.8,1546.7,392.9,173.0 +0.2708603687790678,0.8708163383755341,2.8797932657906435,592.7,1491.7,1871.2,1221.3,276.8,149.4 +0.2708831635555941,0.8708050657245117,3.010692959690218,772.5,2776.7,2718.3,1060.4,209.9,151.1 +0.3708903480115708,0.17078183672449043,0.0,63.1,2551.2,2551.0,1699.0,270.9,271.0 +0.3709621379651206,0.17107119863620857,0.1308996938995747,91.5,2616.1,2675.0,1591.5,254.6,233.4 +0.37096221121868284,0.1710710696102249,0.2617993877991494,139.5,2900.3,3027.8,748.0,265.0,95.1 +0.37116961010062677,0.1706965401977798,0.39269908169872414,223.6,2592.2,2372.4,473.6,282.1,62.8 +0.3711963456338694,0.17072790892540302,0.5235987755982988,392.9,2078.2,1950.5,345.2,187.3,59.6 +0.3712266445637576,0.17078299650832607,0.6544984694978736,911.9,1823.3,1764.3,275.6,129.3,70.2 +0.3712335483894961,0.17082091998092408,0.7853981633974483,2521.2,1728.9,1728.5,240.9,93.5,93.0 +0.3712318466243414,0.17089127708173635,0.916297857297023,2636.1,1747.8,924.7,359.1,70.4,129.2 +0.37122202810284205,0.17092565469735588,1.0471975511965976,2978.8,831.0,450.9,252.4,59.1,186.4 +0.3712104855799749,0.1709424816587799,1.1780972450961724,2381.3,535.8,314.8,223.9,62.9,281.9 +0.37115852364897917,0.17099136612751287,1.3089969389957472,1938.6,392.3,264.7,139.5,94.9,474.0 +0.3711179528651653,0.17101438572830063,1.4398966328953218,1741.2,313.5,255.0,90.7,237.0,1065.6 +0.3711728249667402,0.17100022220251154,1.5707963267948966,1699.1,271.0,270.8,62.9,2550.8,2550.7 +0.3710857742305219,0.17099776554384527,1.7016960206944713,1013.4,254.3,237.0,48.2,2613.9,2672.5 +0.3710289473713663,0.1709809788342247,1.832595714594046,472.3,265.7,94.9,46.7,2900.1,3028.3 +0.37104533475164225,0.17099310815145574,1.9634954084936205,314.6,281.9,62.8,63.2,2590.8,2371.6 +0.3710347694887603,0.17098464674455527,2.0943951023931953,252.3,186.4,59.1,116.7,2076.4,1949.6 +0.3710076515215464,0.17093413965590631,2.2252947962927703,232.9,129.2,70.4,318.2,1822.8,1764.0 +0.371004885490765,0.17092465457414807,2.356194490192345,241.7,93.0,93.5,2520.1,1728.7,1728.9 +0.37100253105557346,0.17092407759997852,2.4870941840919194,230.9,70.2,129.3,2593.3,1740.3,921.2 +0.3710142922715815,0.17088773550070635,2.6179938779914944,117.1,59.6,187.2,2888.5,829.3,450.2 +0.3710151420173323,0.17088142082388136,2.748893571891069,62.3,62.3,282.3,2536.8,534.6,314.6 +0.3710418635956523,0.17085798416209474,2.8797932657906435,46.3,94.4,474.3,2030.6,392.4,265.0 +0.37105271492779013,0.1708530344778585,3.010692959690218,48.0,234.2,1057.2,1785.0,313.5,254.6 +0.37110603820592397,0.27115335335300017,0.0,162.9,2550.8,2551.0,1599.3,271.0,271.1 +0.37104644460209846,0.2706734562205728,0.1308996938995747,195.0,2616.1,2675.4,1590.2,254.6,314.0 +0.3710747076271304,0.27068284585997304,0.2617993877991494,255.0,2900.7,3028.0,747.7,430.5,294.3 +0.37111069611726294,0.2707062776868294,0.39269908169872414,365.3,2449.9,2231.3,473.4,315.3,203.9 +0.3711399391447886,0.27074045814617875,0.5235987755982988,592.3,1962.6,1834.4,345.1,302.9,175.2 +0.37116791882541456,0.27079104307279755,0.6544984694978736,1298.4,1719.5,1660.5,275.6,232.8,173.8 +0.3711733327523811,0.2708217211776516,0.7853981633974483,2521.2,1628.9,1628.6,240.8,193.5,193.0 +0.37117200610954154,0.2708843286580094,0.916297857297023,2670.8,1660.5,923.5,232.5,173.9,232.7 +0.3711645198784396,0.2709115597347438,1.0471975511965976,2980.1,830.6,450.6,349.1,174.6,302.0 +0.3711568866994686,0.2709226154838149,1.1780972450961724,2239.0,535.5,314.7,313.4,204.0,423.2 +0.3711097056860378,0.27096722141893115,1.3089969389957472,1822.3,392.2,264.6,255.0,294.3,673.7 +0.37107443058687806,0.2709874354987889,1.4398966328953218,1638.0,313.3,255.0,194.2,627.2,1456.4 +0.3710960966007611,0.27098333591530155,1.5707963267948966,1598.8,271.0,270.8,162.9,2551.1,2551.2 +0.37104122142663176,0.2709821157383556,1.7016960206944713,1012.1,254.4,312.8,151.7,2614.5,2672.3 +0.37099429886123986,0.27096823493534705,1.832595714594046,472.0,430.0,294.1,162.3,2901.2,3028.4 +0.37101346774548244,0.27098206995623864,1.9634954084936205,314.5,316.0,203.9,205.0,2448.7,2229.9 +0.37102659931063664,0.27100456502232384,2.0943951023931953,252.2,301.8,174.6,316.5,1961.1,1833.9 +0.37098737298879325,0.27093076536963356,2.2252947962927703,232.9,232.6,173.8,706.0,1719.1,1660.4 +0.37098338088125876,0.27091487029173766,2.356194490192345,241.6,192.9,193.5,2520.3,1628.5,1629.0 +0.3709811924862277,0.27091405920983735,2.4870941840919194,275.7,173.7,232.9,2593.0,1660.9,920.4 +0.3709927600427267,0.2708792475378816,2.6179938779914944,316.1,175.2,302.9,2888.5,828.8,449.9 +0.37099257939049735,0.27087485266757816,2.748893571891069,203.6,203.8,424.0,2395.1,534.4,314.6 +0.3710178931884426,0.27085299767034354,2.8797932657906435,161.8,294.0,674.1,1914.8,392.3,265.0 +0.37102700184181053,0.2708491477905217,3.010692959690218,151.4,621.8,1445.5,1681.3,313.3,254.6 +0.37107807192426645,0.37114774414051954,0.0,262.9,2551.3,2551.0,1499.0,271.0,271.1 +0.3710325875942798,0.3706689236472478,0.1308996938995747,298.6,2616.2,2675.7,1535.9,254.6,447.9 +0.3710641614859279,0.3706793306195302,0.2617993877991494,370.6,2900.6,2958.7,747.7,265.1,392.6 +0.37110121645535965,0.37070340585215433,0.39269908169872414,507.0,2309.3,2090.0,473.4,392.0,345.1 +0.371130829424033,0.3707379348804971,0.5235987755982988,791.6,1846.9,1719.0,345.1,418.4,290.8 +0.3711589951779986,0.37078874716189514,0.6544984694978736,1684.0,1616.4,1557.0,275.5,336.4,277.3 +0.3711644978423238,0.37081959318888513,0.7853981633974483,2521.4,1529.5,1528.7,240.8,293.5,293.0 +0.37116323776265897,0.3708823753675876,0.916297857297023,2635.9,1556.9,924.0,232.4,277.4,336.2 +0.37115577218703943,0.3709097817114777,1.0471975511965976,2978.8,830.8,450.6,252.4,290.2,417.6 +0.37114810251376723,0.37092097875319374,1.1780972450961724,2097.9,535.5,314.7,313.4,345.2,564.4 +0.37110085716010116,0.3709657217388027,1.3089969389957472,1706.6,392.2,264.7,370.6,493.6,872.9 +0.37106548473582596,0.3709860625543473,1.4398966328953218,1534.3,313.4,255.0,297.5,1017.1,1846.5 +0.37108702233689,0.3709820010568099,1.5707963267948966,1499.1,271.0,270.8,262.9,2551.2,2551.0 +0.3710320208710703,0.37098078642483223,1.7016960206944713,1012.5,254.3,454.8,255.2,2613.8,2672.2 +0.3709849779976173,0.37096689374917413,1.832595714594046,472.1,265.6,393.2,277.9,2901.0,2955.8 +0.37100405891195976,0.370980649774868,1.9634954084936205,314.4,391.9,345.0,346.7,2308.5,2089.2 +0.37099416110019234,0.370972801518334,2.0943951023931953,252.3,417.4,290.1,516.2,1845.8,1718.5 +0.37096731904895797,0.37092232041425865,2.2252947962927703,232.9,336.2,277.4,1093.5,1615.5,1557.0 +0.37096479542154215,0.3709127238746319,2.356194490192345,241.6,292.9,293.5,2520.4,1528.5,1529.3 +0.370962656174946,0.37091211723651507,2.4870941840919194,275.7,277.3,336.4,2593.5,1557.3,920.5 +0.3709747387947141,0.37087576738116756,2.6179938779914944,345.8,290.7,418.5,2888.8,828.7,449.9 +0.3709757486649186,0.37086959425857,2.748893571891069,345.1,345.2,565.4,2254.0,534.5,314.5 +0.37100264750886086,0.37084631887745,2.8797932657906435,277.4,493.6,873.7,1799.0,392.4,265.0 +0.3710135647218577,0.37084154526006063,3.010692959690218,255.0,1009.0,1832.6,1577.9,313.4,254.6 +0.3710668110328006,0.47114179322428873,0.0,362.9,2551.1,2551.0,1399.0,271.0,271.0 +0.3710247288811195,0.4706699815358599,0.1308996938995747,402.2,2616.2,2675.3,1432.2,254.6,313.9 +0.3710569271015543,0.4706805678546164,0.2617993877991494,486.3,2900.1,2759.3,747.8,265.1,443.4 +0.3710940195245283,0.4707046363558871,0.39269908169872414,648.6,2168.3,1948.9,473.5,374.4,486.2 +0.3711235387492028,0.4707390192112113,0.5235987755982988,990.7,1731.1,1603.6,345.0,449.3,406.5 +0.37115165631892566,0.4707896394366302,0.6544984694978736,2069.8,1512.9,1453.8,275.5,439.9,380.8 +0.371157143999451,0.47082026483212824,0.7853981633974483,2521.5,1429.1,1428.6,240.8,393.5,393.0 +0.37115594354232856,0.4708828641302911,0.916297857297023,2635.9,1453.3,924.1,232.5,380.9,439.8 +0.3711485744006698,0.470910123514771,1.0471975511965976,2784.2,830.9,450.6,252.4,405.8,533.1 +0.37114101192054777,0.47092119070618743,1.1780972450961724,1956.3,535.6,314.7,344.4,486.3,705.4 +0.37109389245712865,0.47096586084733216,1.3089969389957472,1591.2,392.3,264.6,460.8,692.8,1072.2 +0.3710586461134776,0.47098618317046426,1.4398966328953218,1430.7,313.4,255.0,401.0,1406.9,2235.7 +0.3710802961401667,0.4709820864176528,1.5707963267948966,1399.2,271.0,270.7,363.0,2551.6,2551.1 +0.37102539963043857,0.47098087046896864,1.7016960206944713,1012.7,254.3,312.8,358.6,2655.4,2672.5 +0.3709784463412067,0.4709670179272816,1.832595714594046,472.1,265.6,444.1,393.6,2900.3,2756.4 +0.37099761487783456,0.47098080039261503,1.9634954084936205,314.5,374.3,486.1,488.4,2166.9,1948.1 +0.37098780364503037,0.470972978599155,2.0943951023931953,252.3,450.8,405.7,716.0,1755.4,1602.9 +0.37096102347199206,0.47092256061407833,2.2252947962927703,232.9,439.7,380.9,1480.8,1512.1,1453.4 +0.3709585494256367,0.4709130376157453,2.356194490192345,241.6,393.0,393.5,2520.7,1428.5,1428.9 +0.37095645916431125,0.47091249927815215,2.4870941840919194,275.7,380.7,439.9,2593.6,1454.1,920.5 +0.37096854463144147,0.4708762380831506,2.6179938779914944,427.7,406.4,534.0,2888.6,828.8,450.0 +0.3709695634387215,0.4708701366738026,2.748893571891069,455.4,486.7,706.8,2112.7,534.4,314.5 +0.37099642398123167,0.4708469313561938,2.8797932657906435,393.0,693.0,1073.1,1683.7,392.4,265.0 +0.37100728834501917,0.47084220770435636,3.010692959690218,358.5,1396.4,2219.7,1474.7,313.4,254.6 +0.37106044973825086,0.5711423828328002,0.0,462.8,2551.0,2550.9,1299.2,271.0,271.0 +0.3710193741563741,0.5706700121439365,0.1308996938995747,505.7,2615.9,2674.8,1328.3,254.6,314.0 +0.37105178951520823,0.5706806556715052,0.2617993877991494,601.7,2900.1,2560.1,747.8,265.0,392.6 +0.3710889361321533,0.5707047366084219,0.39269908169872414,790.2,2027.4,1808.2,473.5,315.2,535.9 +0.37111846389648423,0.5707390961733341,0.5235987755982988,1190.0,1616.1,1488.1,345.1,449.2,522.0 +0.3711466094113318,0.5707896927700808,0.6544984694978736,2455.0,1409.1,1350.0,275.6,543.5,484.4 +0.37115211580671253,0.5708202851805373,0.7853981633974483,2521.0,1329.2,1328.5,240.8,493.4,492.9 +0.3711509565887725,0.57088287614104,0.916297857297023,2635.9,1349.6,924.2,232.5,484.5,543.3 +0.3711436254012368,0.5709101416395919,1.0471975511965976,2584.6,830.9,450.7,252.4,521.2,648.6 +0.3711360841762973,0.5709212065509133,1.1780972450961724,1814.8,535.6,314.7,313.3,627.3,846.5 +0.3710889851124214,0.5709658937187787,1.3089969389957472,1475.5,392.2,264.7,470.8,892.1,1271.5 +0.3710537497466442,0.5709862502953689,1.4398966328953218,1327.5,313.3,254.9,504.6,1796.6,2590.5 +0.371075396464702,0.5709821481992763,1.5707963267948966,1299.0,270.9,270.7,462.9,2550.8,2551.0 +0.37102049638223683,0.570980930437665,1.7016960206944713,1012.9,254.3,312.7,462.1,2614.2,2672.0 +0.3709735361597975,0.5709670890748413,1.832595714594046,472.2,265.6,393.3,509.1,2900.9,2557.9 +0.3709927082666493,0.5709808544857367,1.9634954084936205,314.4,315.9,536.9,630.1,2025.9,1806.9 +0.3709829158643275,0.5709730041169085,2.0943951023931953,252.2,450.7,521.2,915.5,1614.5,1487.6 +0.3709561517989563,0.5709225806127758,2.2252947962927703,232.8,543.1,484.4,1868.1,1408.5,1349.9 +0.37095370092664953,0.5709130574053469,2.356194490192345,241.6,492.9,493.5,2520.3,1328.6,1329.0 +0.3709516497052244,0.5709125163574129,2.4870941840919194,275.7,484.3,543.4,2593.6,1350.1,920.7 +0.3709637512076984,0.5708762751251475,2.6179938779914944,345.7,522.0,649.9,2888.5,829.0,450.0 +0.3709648027123925,0.5708701885930751,2.748893571891069,474.7,628.1,848.2,1971.3,534.5,314.5 +0.3709916657742145,0.5708470080485808,2.8797932657906435,508.5,892.6,1272.5,1568.2,392.4,265.0 +0.37100252544840034,0.5708423049373301,3.010692959690218,462.0,1783.5,2606.6,1371.1,313.4,254.6 +0.3710556645090491,0.6711424568895925,0.0,562.8,2551.3,2551.5,1199.1,271.0,271.0 +0.3710153006117561,0.6706699863641545,0.1308996938995747,609.1,2616.0,2675.8,1225.1,254.6,314.0 +0.3710478769316351,0.670680672189131,0.2617993877991494,717.3,2739.9,2360.6,747.9,265.1,392.5 +0.3710850684877336,0.6707047649468074,0.39269908169872414,931.8,1885.8,1667.0,473.5,315.2,535.9 +0.3711146073300622,0.6707391117382528,0.5235987755982988,1389.1,1500.3,1372.5,345.1,519.6,637.7 +0.3711427775266418,0.6707896966140816,0.6544984694978736,2593.8,1305.6,1246.6,275.6,647.0,587.9 +0.3711482997510619,0.6708202706198523,0.7853981633974483,2521.1,1229.1,1228.4,240.8,593.5,593.0 +0.37114717184562357,0.6708828617364935,0.916297857297023,2635.6,1246.2,924.2,232.4,588.0,646.7 +0.37113986791357173,0.6709101377798157,1.0471975511965976,2385.0,830.9,450.7,252.4,636.7,764.1 +0.3711323399609808,0.6709212057801266,1.1780972450961724,1672.9,535.5,314.7,313.3,768.5,987.7 +0.3710852527552551,0.6709659095906746,1.3089969389957472,1360.1,392.3,264.7,576.4,1091.4,1470.6 +0.37105002156092426,0.6709862947656504,1.4398966328953218,1224.0,313.4,255.0,607.9,2186.2,2613.1 +0.37107166132971425,0.6709821897108759,1.5707963267948966,1199.0,270.9,270.7,563.0,2551.0,2551.8 +0.3710167543493921,0.6709809705649661,1.7016960206944713,1012.8,254.3,312.8,565.5,2613.8,2672.7 +0.3709697850692421,0.6709671367902501,1.832595714594046,472.2,265.6,393.3,624.8,2737.9,2358.4 +0.3709889567309436,0.670980887331891,1.9634954084936205,314.4,315.9,536.9,771.8,1884.6,1666.0 +0.37097917634004374,0.6709730127095712,2.0943951023931953,252.3,494.6,636.8,1115.0,1499.3,1372.0 +0.37095242302695,0.670922582298682,2.2252947962927703,232.8,646.6,587.8,2255.6,1304.8,1246.4 +0.3709499891392149,0.6709130561056096,2.356194490192345,241.6,593.0,593.4,2520.2,1228.4,1229.0 +0.37094796784147777,0.6709125102472573,2.4870941840919194,275.7,587.9,646.9,2593.7,1246.9,920.8 +0.3709600823222721,0.6708762818850464,2.6179938779914944,345.7,637.7,765.4,2654.9,829.1,450.0 +0.3709611601215201,0.6708702047507844,2.748893571891069,596.9,769.4,989.4,1830.2,534.5,314.5 +0.3709880267217666,0.6708470417294581,2.8797932657906435,624.0,1092.0,1472.3,1452.5,392.4,265.0 +0.37099888460757896,0.6708423534718608,3.010692959690218,565.6,2170.2,2614.3,1267.5,313.4,254.6 +0.37105200870623606,0.7711424892979639,0.0,662.9,2550.7,2550.8,1099.2,271.0,271.0 +0.371012187017648,0.7706699626737024,0.1308996938995747,712.9,2615.9,2676.0,1121.5,254.6,314.0 +0.3710448868640249,0.7706806809768443,0.2617993877991494,832.9,2540.6,2161.5,748.0,265.0,392.5 +0.37108211332242147,0.7707047831166602,0.39269908169872414,1073.6,1745.2,1525.5,473.5,315.1,578.8 +0.37111166108092464,0.7707391206288516,0.5235987755982988,1588.1,1384.4,1256.7,345.1,609.7,753.3 +0.3711398504355057,0.7707896970951489,0.6544984694978736,2719.8,1202.2,1143.0,275.5,750.5,691.4 +0.37114538489268806,0.770820257607415,0.7853981633974483,2521.5,1129.0,1128.5,240.8,693.6,693.0 +0.37114428090560725,0.7708828493872464,0.916297857297023,2636.1,1142.7,924.3,232.4,691.4,750.3 +0.37113699766129876,0.7709101339785822,1.0471975511965976,2185.7,831.0,450.7,252.4,752.3,879.7 +0.3711294796080963,0.7709212047447693,1.1780972450961724,1531.4,535.6,314.7,313.4,909.7,1128.7 +0.3710824011556747,0.7709659215784204,1.3089969389957472,1244.4,392.3,264.6,561.9,1290.6,1669.5 +0.3710471727972511,0.7709863288100902,1.4398966328953218,1120.6,313.4,255.0,711.3,2575.3,2613.6 +0.37106880688506416,0.7709822215887081,1.5707963267948966,1099.1,270.9,270.7,662.9,2551.1,2551.1 +0.3710138942845837,0.7709810013844809,1.7016960206944713,1013.0,254.3,312.7,669.1,2614.4,2672.1 +0.3709669177687928,0.7709671733249817,1.832595714594046,472.1,265.6,393.2,740.4,2538.5,2159.5 +0.3709860888257826,0.7709809123460267,1.9634954084936205,314.5,315.9,578.7,913.6,1744.1,1524.9 +0.37097631741617565,0.7709730189847304,2.0943951023931953,252.3,608.6,752.3,1314.9,1384.0,1256.5 +0.37094957219258723,0.7709225830684168,2.2252947962927703,232.8,750.2,691.5,2612.0,1201.5,1142.9 +0.3709471512277746,0.7709130543553073,2.356194490192345,241.6,692.9,693.5,2520.4,1128.4,1129.2 +0.37094515280806184,0.7709125045911389,2.4870941840919194,275.7,691.4,750.5,2593.0,1143.1,920.8 +0.370957277269915,0.7708762858645739,2.6179938779914944,345.6,753.3,880.9,2455.6,828.9,450.0 +0.3709583752739729,0.7708702157479097,2.748893571891069,474.6,910.9,1131.1,1688.9,534.5,314.6 +0.37098524471374944,0.7708470659999016,2.8797932657906435,739.7,1291.6,1671.3,1337.1,392.4,265.0 +0.37099610138322436,0.7708423890223342,3.010692959690218,669.1,2558.0,2614.7,1163.9,313.5,254.6 +0.3710492142136098,0.8711425126228203,0.0,762.9,2550.6,2550.9,999.0,271.0,271.0 +0.37100980669321676,0.8706699443570858,0.1308996938995747,816.4,2615.7,2675.2,1017.8,254.6,314.0 +0.3710426013035434,0.870680687580818,0.2617993877991494,948.6,2341.5,1961.5,747.9,265.0,392.5 +0.37107985462614534,0.8707047970006325,0.39269908169872414,1215.1,1603.6,1384.5,473.5,315.1,535.8 +0.37110940931498865,0.8707391275357392,0.5235987755982988,1787.7,1268.7,1141.4,345.0,449.2,868.9 +0.3711376133811954,0.8707896976936442,0.6544984694978736,2593.8,1098.9,1039.7,275.6,854.0,794.9 +0.3711431572206296,0.8708202480146308,0.7853981633974483,2521.6,1029.1,1028.5,240.8,793.5,793.1 +0.37114207151376266,0.87088284041642,0.916297857297023,2635.4,1039.2,924.4,255.2,795.0,853.8 +0.37113480405127686,0.870910131644747,1.0471975511965976,1986.5,830.8,450.7,252.4,867.8,995.1 +0.3711272935123712,0.8709212046114758,1.1780972450961724,1389.8,535.7,314.8,313.3,1050.5,1270.0 +0.37108022168362875,0.8709659314624931,1.3089969389957472,1128.9,392.2,264.6,470.7,1490.1,1869.0 +0.3710449954162029,0.8709863555916624,1.4398966328953218,1017.1,313.4,255.0,814.9,2671.6,2613.8 +0.3710666250820556,0.8709822467320201,1.5707963267948966,999.4,271.0,270.7,762.7,2551.7,2550.7 +0.3710117081120257,0.8709810257164572,1.7016960206944713,1013.0,254.3,312.8,772.6,2613.8,2672.5 +0.37096472600071173,0.8709672020034016,1.832595714594046,472.2,265.6,393.2,855.9,2339.1,1960.1 +0.3709838965407667,0.8709809321830202,1.9634954084936205,314.5,315.9,536.8,1055.1,1603.0,1383.7 +0.37097413195429435,0.8709730244555678,2.0943951023931953,252.3,450.5,867.7,1514.2,1268.4,1141.0 +0.3709473928873542,0.8709225842829003,2.2252947962927703,232.8,853.6,795.0,2635.7,1098.1,1039.0 +0.3709449817881191,0.8709130535926548,2.356194490192345,241.6,793.0,793.4,2520.8,1028.5,1029.1 +0.3709430008551846,0.8709125007942728,2.4870941840919194,275.7,795.0,854.2,2593.0,1039.7,920.8 +0.37095513295727717,0.8708762893885442,2.6179938779914944,345.7,869.0,996.4,2256.0,829.1,450.0 +0.3709562464252162,0.8708702245986988,2.748893571891069,474.6,1052.4,1272.5,1547.3,534.6,314.5 +0.37098311806250445,0.8708470849669618,2.8797932657906435,748.4,1491.0,1870.8,1221.6,392.3,265.0 +0.37099397383396193,0.8708424165915072,3.010692959690218,772.6,2673.7,2614.9,1060.4,313.4,254.6 +0.4709978394287316,0.17074780700128067,0.0,63.0,2451.0,2451.4,1699.1,371.1,371.0 +0.4710107743136577,0.17145616089920934,0.1308996938995747,91.5,2512.5,2572.0,1742.7,496.5,233.7 +0.470959004498093,0.1714393607365261,0.2617993877991494,139.5,2784.8,2912.6,947.5,380.6,95.3 +0.4709060129727335,0.17140516053451837,0.39269908169872414,223.8,2592.4,2372.6,614.9,282.3,63.0 +0.47086323097186095,0.1713600191226703,0.5235987755982988,393.3,2077.9,1950.5,460.9,187.5,59.8 +0.4708445689287058,0.17132119645989397,0.6544984694978736,912.6,1823.3,1764.2,379.2,129.5,70.4 +0.4708289051141425,0.17125881620993577,0.7853981633974483,2421.0,1729.0,1728.3,341.0,93.8,93.2 +0.47083051468067777,0.17123353850340517,0.916297857297023,2531.9,1763.7,1312.2,381.6,70.7,129.5 +0.4708465788708595,0.17118207934707064,1.0471975511965976,2863.8,1030.8,650.5,350.0,59.5,186.8 +0.47087851854356744,0.17112791823572215,1.1780972450961724,2381.2,677.4,456.6,224.3,63.3,282.4 +0.4708813652097422,0.17112379047280668,1.3089969389957472,1937.7,508.1,380.3,139.9,95.6,474.8 +0.47090268789226736,0.17111196156336272,1.4398966328953218,1740.9,416.9,358.5,91.1,238.5,1067.0 +0.470983528229072,0.17109219616507132,1.5707963267948966,1698.8,370.9,370.7,63.3,2451.3,2450.9 +0.47098458388923814,0.1710907652157725,1.7016960206944713,1402.8,506.1,238.5,48.6,2510.2,2568.9 +0.47098799984197776,0.1710901713765698,1.832595714594046,671.6,381.2,95.6,47.1,2784.7,2913.2 +0.47104976349093547,0.17112851002886065,1.9634954084936205,455.6,282.4,63.3,63.7,2590.4,2371.1 +0.47107198730333466,0.17115282403535703,2.0943951023931953,367.8,186.8,59.5,117.4,2076.6,1949.8 +0.47106583009127,0.17113875731319306,2.2252947962927703,336.3,129.5,70.7,319.4,1822.4,1763.7 +0.4710727749699996,0.17116730074340647,2.356194490192345,341.6,93.3,93.8,2420.4,1728.1,1729.0 +0.4710695244188695,0.1712032344365384,2.4870941840919194,317.0,70.5,129.6,2490.2,1764.1,1306.3 +0.47107140625127014,0.17119896934191003,2.6179938779914944,117.7,59.9,187.6,2773.1,1028.2,649.2 +0.47105515845594115,0.17121888608051616,2.748893571891069,62.7,62.7,282.7,2537.3,676.1,456.0 +0.47082349133254636,0.1709362926297595,2.8797932657906435,46.5,94.6,473.9,2056.7,508.1,380.6 +0.47084643088316985,0.17092460093928752,3.010692959690218,48.1,234.1,1055.0,1785.4,417.0,358.0 +0.47091764633282196,0.2712360599767314,0.0,163.0,2451.2,2450.7,1598.9,371.0,370.8 +0.47090192429535627,0.2708292277096642,0.1308996938995747,194.9,2512.0,2571.0,1638.9,358.1,417.2 +0.47092708999552524,0.2708371422630773,0.2617993877991494,254.8,2783.3,2911.2,948.4,431.2,294.8 +0.470948223679745,0.27085042262775416,0.39269908169872414,364.9,2452.7,2233.5,615.2,423.6,204.1 +0.4709632819976326,0.2708682448487434,0.5235987755982988,591.3,1963.3,1835.6,460.9,303.1,175.3 +0.4709596061140753,0.27085612172415807,0.6544984694978736,1294.3,1720.4,1661.1,379.3,233.0,173.8 +0.47096873348346313,0.27089966044021074,0.7853981633974483,2421.2,1628.8,1628.4,340.7,193.7,193.0 +0.47096866261886877,0.2709514461639446,0.916297857297023,2531.6,1659.9,1314.6,335.8,174.0,232.6 +0.47096710567678296,0.2709618367575066,1.0471975511965976,2862.8,1031.7,650.9,367.7,174.7,301.8 +0.4709698187979689,0.27095669368098285,1.1780972450961724,2241.3,677.8,456.6,366.0,203.9,422.8 +0.47093612233145976,0.2709890967200528,1.3089969389957472,1848.8,508.1,380.3,255.3,293.9,672.6 +0.4709160348079949,0.2710017066010153,1.4398966328953218,1638.0,416.9,358.4,194.4,625.3,1452.3 +0.4709533024209396,0.2709934758556771,1.5707963267948966,1598.8,370.9,370.6,163.0,2451.6,2451.0 +0.4709131446818403,0.27099227626038735,1.7016960206944713,1406.0,357.7,415.9,151.7,2510.2,2613.4 +0.4708793599629798,0.2709822327902722,1.832595714594046,672.0,380.9,294.7,162.3,2783.7,2912.1 +0.47090982243238755,0.271002238693552,1.9634954084936205,455.8,423.5,204.2,204.8,2451.1,2231.8 +0.4709088057338687,0.27100238652956565,2.0943951023931953,367.9,302.2,174.7,316.1,1988.0,1834.4 +0.4708606197977085,0.27090800497109724,2.2252947962927703,336.4,232.9,173.9,704.0,1719.1,1660.3 +0.47087024986638076,0.27094863149935366,2.356194490192345,341.4,193.1,193.5,2420.4,1628.6,1628.9 +0.47086829998063034,0.27096701160016723,2.4870941840919194,379.0,173.8,232.8,2489.7,1660.6,1309.0 +0.47087824368845327,0.2709390026498588,2.6179938779914944,316.8,175.2,302.7,2772.2,1029.3,649.8 +0.47087732309784897,0.27093705317778727,2.748893571891069,204.0,203.7,423.5,2396.9,676.3,456.0 +0.47090165982668447,0.2709164198736935,2.8797932657906435,162.0,293.7,673.1,1915.7,508.2,380.5 +0.4709098836933281,0.27091311500302595,3.010692959690218,151.5,620.1,1440.9,1681.8,417.0,358.0 +0.4709598057770217,0.3712107122378485,0.0,262.9,2451.1,2451.0,1499.1,371.0,370.9 +0.47089646747216946,0.3707061935086273,0.1308996938995747,298.5,2512.3,2571.5,1535.4,358.1,462.9 +0.4709459606932886,0.37072186379346683,0.2617993877991494,370.3,2783.8,2911.3,948.1,380.5,494.3 +0.470983229171652,0.3707455804717439,0.39269908169872414,506.5,2311.1,2090.9,615.0,456.5,345.3 +0.47100929021248084,0.3707755606489309,0.5235987755982988,790.6,1847.1,1719.9,460.8,418.7,291.0 +0.47103492621474147,0.3708200981846699,0.6544984694978736,1680.0,1616.7,1557.4,379.0,336.5,277.3 +0.47103935317882184,0.37084386891531174,0.7853981633974483,2421.3,1528.7,1528.6,340.8,293.6,292.9 +0.47103908628488594,0.37090023575945064,0.916297857297023,2532.0,1556.7,1313.7,335.8,277.5,336.0 +0.4710340472298578,0.3709221187917566,1.0471975511965976,2863.0,1031.3,650.9,534.1,290.1,417.3 +0.4710296723256485,0.37092865494072047,1.1780972450961724,2099.1,677.5,456.6,454.1,344.9,564.0 +0.4709864258480292,0.3709702594111757,1.3089969389957472,1707.2,508.0,380.2,370.8,493.0,871.8 +0.47095532759953807,0.3709711466565595,1.4398966328953218,1534.6,416.9,358.4,297.7,1014.6,1841.8 +0.4709890292498794,0.37098206563629166,1.5707963267948966,1499.0,370.9,370.6,262.9,2451.6,2451.0 +0.47088325902962136,0.3709816478048584,1.7016960206944713,1405.2,357.8,461.5,255.1,2510.4,2568.6 +0.4708701608097715,0.3709781609468652,1.832595714594046,671.9,381.1,493.7,277.8,2784.4,2912.2 +0.4708983012496469,0.37099712291236187,1.9634954084936205,455.7,457.3,345.3,346.5,2309.3,2090.1 +0.47089047712630794,0.3709904810018836,2.0943951023931953,367.8,417.6,290.2,515.5,1846.5,1718.9 +0.4708639855971195,0.3709397553321838,2.2252947962927703,336.3,336.3,277.4,1091.1,1615.7,1556.9 +0.47086178837244724,0.3709293000033298,2.356194490192345,341.5,293.0,293.4,2420.4,1528.7,1528.6 +0.47086044951294403,0.3709276358170521,2.4870941840919194,379.0,277.3,336.3,2489.8,1557.1,1308.3 +0.4708731731080693,0.3708906894241837,2.6179938779914944,461.0,290.8,418.2,2772.7,1028.9,649.6 +0.47087527057835443,0.3708839926318752,2.748893571891069,345.3,345.0,564.9,2255.3,676.1,456.0 +0.47090285311757196,0.3708605489301886,2.8797932657906435,277.5,493.0,872.6,1800.1,508.1,380.5 +0.4709143850706951,0.37085571882302903,3.010692959690218,255.0,1006.7,1828.2,1578.0,416.9,358.1 +0.47096808704958404,0.47115618194950093,0.0,362.9,2451.2,2451.0,1399.1,370.9,370.9 +0.47094432738991227,0.4706740915293266,0.1308996938995747,402.0,2512.2,2571.5,1431.9,358.1,417.4 +0.4709800287065134,0.4706856043530976,0.2617993877991494,486.0,2784.2,2761.8,948.1,380.5,507.9 +0.47101763839397237,0.4707096706129692,0.39269908169872414,648.3,2169.6,1950.4,614.9,533.8,486.5 +0.47104693875647624,0.47074332988180356,0.5235987755982988,989.8,1732.0,1603.9,460.8,534.3,406.5 +0.47107521967323324,0.4707931271887029,0.6544984694978736,2065.4,1513.0,1453.7,379.1,440.0,380.8 +0.471080869212048,0.47082275786222416,0.7853981633974483,2421.2,1429.1,1428.5,340.8,393.6,392.9 +0.4710802928560173,0.4708847473774267,0.916297857297023,2531.8,1453.2,1313.4,335.8,380.9,439.6 +0.4710736147370522,0.4709116595230125,1.0471975511965976,2786.7,1031.5,650.7,367.7,405.6,532.9 +0.47106658768123566,0.47092233313908105,1.1780972450961724,1957.4,677.6,456.5,454.2,486.1,704.9 +0.4710200478641045,0.4709669846999147,1.3089969389957472,1591.8,508.0,380.2,486.5,692.2,1071.1 +0.47098527808916474,0.47098763335511107,1.4398966328953218,1431.1,416.9,358.4,401.2,1403.8,2231.4 +0.4710072082220481,0.4709833745120593,1.5707963267948966,1399.2,371.0,370.7,363.0,2451.4,2451.3 +0.4709525688794435,0.4709821324031882,1.7016960206944713,1404.8,357.8,416.0,358.7,2636.2,2569.0 +0.4709057924213419,0.47096851672720663,1.832595714594046,671.9,381.1,508.7,393.4,2784.8,2758.9 +0.47092524903187805,0.4709821839899484,1.9634954084936205,455.6,533.4,486.3,488.1,2168.2,1949.5 +0.47091589218844565,0.4709741195093917,2.0943951023931953,367.9,533.2,405.8,715.2,1730.9,1603.4 +0.4708894652495516,0.4709238196044512,2.2252947962927703,336.3,439.8,380.9,1478.0,1512.3,1453.4 +0.4708873872951969,0.4709145029718331,2.356194490192345,341.5,393.0,393.5,2420.4,1428.6,1429.0 +0.47088586743371313,0.47091412740649585,2.4870941840919194,379.1,380.8,439.8,2489.5,1453.6,1308.3 +0.4708981365037294,0.47087833801294643,2.6179938779914944,461.1,406.3,533.9,2772.4,1028.9,649.5 +0.4708995421846188,0.4707207632582866,2.748893571891069,486.7,486.5,706.3,2114.2,676.2,456.0 +0.4708727981328779,0.4708139739819992,2.8797932657906435,393.1,693.1,1072.8,1683.5,507.9,380.5 +0.4708870371003543,0.4708072367180365,3.010692959690218,358.5,1396.0,2218.8,1474.5,416.9,358.1 +0.4709631405292979,0.5711300456808188,0.0,463.0,2451.0,2451.2,1299.2,370.9,371.0 +0.47095516656711084,0.5711299856506198,0.1308996938995747,505.6,2512.1,2572.2,1328.8,358.2,417.3 +0.4709165751364065,0.5711187081876541,0.2617993877991494,601.6,2784.6,2560.0,947.4,380.6,605.3 +0.47087602676033047,0.5710937431516971,0.39269908169872414,790.1,2027.0,1808.3,614.6,515.6,627.4 +0.4708427861423123,0.5710601506357333,0.5235987755982988,1189.8,1615.9,1488.0,460.7,624.2,522.0 +0.4708301915822292,0.5710337494906732,0.6544984694978736,2454.3,1409.5,1350.1,379.1,543.5,484.4 +0.4708173996726452,0.570984001674445,0.7853981633974483,2421.0,1328.9,1328.3,340.8,493.6,493.0 +0.470818979043596,0.570970619030599,0.916297857297023,2531.8,1349.5,1311.8,336.0,484.5,543.2 +0.4708325386051598,0.5709300087721834,1.0471975511965976,2584.7,1030.6,650.4,368.0,521.2,648.7 +0.47085995463720653,0.5708852537839189,1.1780972450961724,1814.8,677.4,456.5,485.5,627.5,846.6 +0.47085676951702315,0.5708887086900023,1.3089969389957472,1475.4,507.9,380.2,602.1,892.4,1271.6 +0.470870855951887,0.5708825276697682,1.4398966328953218,1327.2,416.8,358.5,504.7,1796.4,2509.7 +0.4709436321862767,0.5708663510579046,1.5707963267948966,1298.9,370.9,370.8,463.0,2451.3,2450.8 +0.47093657016428225,0.5708662935795183,1.7016960206944713,1369.9,357.7,416.2,462.2,2510.6,2568.9 +0.4709322217907329,0.5708648755357402,1.832595714594046,671.2,381.1,605.2,509.2,2785.1,2558.2 +0.47098705932804735,0.570900339584018,1.9634954084936205,455.4,515.6,627.4,630.2,2026.0,1807.1 +0.47100386809270933,0.570920198194766,2.0943951023931953,367.7,648.6,521.3,915.6,1614.8,1487.5 +0.4709941943449482,0.5709006304586564,2.2252947962927703,336.3,543.3,484.5,1868.1,1408.5,1349.6 +0.47099966082485506,0.5709231714790752,2.356194490192345,341.5,493.0,493.6,2420.4,1328.6,1329.3 +0.47099693788806096,0.5709533471614194,2.4870941840919194,379.2,484.4,543.6,2489.9,1350.2,1306.1 +0.47100108211904745,0.5709442188430078,2.6179938779914944,486.6,522.1,649.8,2772.8,1028.1,649.1 +0.4709883266669304,0.5709605769178046,2.748893571891069,596.9,628.1,848.3,1971.5,675.8,455.8 +0.47099751132155193,0.5709540028096656,2.8797932657906435,508.5,892.6,1272.4,1568.1,507.9,380.4 +0.47098852073732594,0.5709598286029001,3.010692959690218,462.0,1783.1,2511.5,1371.0,416.9,358.0 +0.4710175962708651,0.6712416592986408,0.0,563.0,2450.6,2451.3,1199.2,371.0,370.9 +0.4709803003063699,0.6706668426776794,0.1308996938995747,609.3,2512.5,2571.4,1224.9,358.1,417.4 +0.4710135841247162,0.670677671508509,0.2617993877991494,717.0,2784.3,2361.4,947.6,380.6,508.0 +0.4710513578740833,0.6707019844265527,0.39269908169872414,931.5,1886.6,1667.0,614.8,456.7,677.3 +0.4710813306378826,0.6707365783938863,0.5235987755982988,1388.5,1500.4,1372.6,460.8,648.2,637.8 +0.47110998235561835,0.670787542840549,0.6544984694978736,2490.2,1305.9,1246.7,379.1,647.1,588.0 +0.47111576857864573,0.6708184804858177,0.7853981633974483,2421.8,1229.3,1228.3,340.8,593.7,592.9 +0.4711149090275536,0.6708815852758523,0.916297857297023,2532.2,1246.3,1304.9,335.9,587.9,646.6 +0.4711077139138896,0.6709094183442308,1.0471975511965976,2386.3,1030.9,650.5,367.9,636.8,764.0 +0.4711000708201602,0.6708885576457866,1.1780972450961724,1673.3,677.4,456.4,454.2,768.4,987.4 +0.4708451350376315,0.6708579787019096,1.3089969389957472,1359.6,507.7,380.2,670.5,1092.3,1471.7 +0.4708596091048001,0.6708511873572909,1.4398966328953218,1223.7,416.7,358.4,608.1,2189.2,2543.2 +0.470938802869709,0.6708336871641121,1.5707963267948966,1198.9,370.9,370.8,563.1,2451.2,2451.2 +0.4709393549558635,0.6708339231469549,1.7016960206944713,1266.7,357.7,416.3,565.7,2510.8,2569.3 +0.4709423439127596,0.6708345649145682,1.832595714594046,670.8,381.1,508.8,625.0,2779.4,2357.0 +0.4710033995289338,0.670873986728395,1.9634954084936205,455.3,457.6,678.8,772.1,1884.3,1665.1 +0.47102477077188126,0.6708989731707655,2.0943951023931953,367.6,650.4,636.8,1116.0,1498.8,1371.8 +0.471018066212785,0.6708848795523965,2.2252947962927703,336.3,646.8,588.0,2258.4,1304.9,1246.1 +0.47102485782246195,0.6709130905173055,2.356194490192345,341.5,593.0,593.6,2420.6,1228.1,1229.0 +0.4710218105949732,0.6709487754570886,2.4870941840919194,379.2,588.0,647.2,2490.0,1246.9,1304.3 +0.47102455195260523,0.6709443623213331,2.6179938779914944,461.3,637.9,765.8,2653.3,1027.2,648.6 +0.4710091554525794,0.6709647103672971,2.748893571891069,616.2,769.8,990.0,1829.3,675.5,455.7 +0.47086730741203237,0.6708103598335813,2.8797932657906435,624.2,1092.4,1472.5,1477.8,507.7,380.4 +0.47089081735361654,0.6707987209142237,3.010692959690218,565.5,2172.1,2511.4,1267.4,416.9,358.1 +0.4709696904129492,0.7711198901965635,0.0,662.9,2451.0,2451.6,1099.0,371.0,371.0 +0.4709623990433355,0.771119935242119,0.1308996938995747,712.9,2512.8,2571.6,1121.5,358.2,417.5 +0.4709238504429446,0.7711087453753187,0.2617993877991494,832.7,2540.4,2161.1,947.1,380.7,508.2 +0.4708831506214055,0.771083769932196,0.39269908169872414,1073.6,1744.5,1525.5,614.6,457.0,677.8 +0.47084976836868275,0.7710501074360903,0.5235987755982988,1588.9,1384.3,1256.5,460.8,736.5,753.2 +0.4708369783111892,0.7710235354484183,0.6544984694978736,2489.9,1202.1,1143.0,379.2,750.5,691.4 +0.4708241321767964,0.7709736379984238,0.7853981633974483,2420.9,1129.0,1128.4,340.8,693.5,692.9 +0.47082564676144634,0.770960030796978,0.916297857297023,2532.0,1142.8,1201.8,336.0,691.4,750.3 +0.4708392258734041,0.7709191987937136,1.0471975511965976,2184.7,1030.2,650.3,368.0,752.4,880.0 +0.4708667711112742,0.7708743469692898,1.1780972450961724,1530.7,677.2,456.4,454.7,909.9,1128.9 +0.47086371316443426,0.7708776957806909,1.3089969389957472,1244.4,507.8,380.3,670.3,1291.4,1670.4 +0.470877940713734,0.7708713894292467,1.4398966328953218,1120.5,416.8,358.4,711.6,2544.9,2509.9 +0.47095088108693706,0.770855309236196,1.5707963267948966,1098.9,370.9,370.6,663.1,2451.4,2450.8 +0.4709439385522877,0.7708553419459145,1.7016960206944713,1163.1,357.8,416.2,669.2,2511.0,2569.1 +0.4709396919211735,0.7708539441308473,1.832595714594046,671.1,381.1,508.8,740.4,2537.4,2158.3 +0.47099456593461747,0.7708895421682571,1.9634954084936205,455.4,457.5,678.7,913.9,1743.7,1524.5 +0.4710113405202635,0.7709095718599792,2.0943951023931953,367.7,738.3,752.3,1315.6,1383.5,1256.0 +0.47100165769640684,0.7708900609653511,2.2252947962927703,336.2,750.2,691.4,2531.4,1201.4,1142.7 +0.47100709703267024,0.7709126432813864,2.356194490192345,341.5,692.9,693.6,2420.3,1128.4,1129.1 +0.4710042800085438,0.7709428948416306,2.4870941840919194,379.2,691.5,750.6,2490.1,1143.0,1202.3 +0.47100843073479515,0.7709337650613413,2.6179938779914944,461.2,753.4,881.1,2455.0,1027.6,648.8 +0.4709955783197187,0.7709501729144281,2.748893571891069,738.3,911.1,1131.2,1688.0,675.6,455.7 +0.4710047687160371,0.7709436159213856,2.8797932657906435,739.6,1292.2,1672.2,1336.9,507.8,380.4 +0.47099577171339924,0.7709494736714795,3.010692959690218,669.1,2559.4,2511.1,1163.9,416.8,358.1 +0.47102484319836374,0.8712313149866413,0.0,762.9,2451.2,2451.0,999.0,370.9,371.0 +0.4709892442677241,0.8706640092217812,0.1308996938995747,816.5,2512.3,2571.7,1017.7,358.2,417.5 +0.4710231401154431,0.8706750524238758,0.2617993877991494,948.3,2342.0,1962.3,947.6,380.6,508.1 +0.47106125619410805,0.8706996281394166,0.39269908169872414,1214.9,1603.8,1384.8,614.8,456.7,720.2 +0.4710914424386596,0.8707345194686211,0.5235987755982988,1787.0,1268.8,1141.3,460.8,725.7,869.0 +0.47112016136718626,0.8707857623665121,0.6544984694978736,2489.9,1098.6,1039.5,379.0,854.2,795.1 +0.47112596448310085,0.8708169894420392,0.7853981633974483,2421.2,1029.1,1028.8,340.8,793.3,792.8 +0.47112501938684515,0.8708803167079708,0.916297857297023,2532.4,1039.3,1098.2,335.9,794.9,853.6 +0.47111769791183017,0.8709083215462916,1.0471975511965976,1986.9,1030.8,650.5,367.9,867.8,995.1 +0.4711099247935237,0.8709199554229701,1.1780972450961724,1389.6,677.5,456.4,454.4,1050.7,1269.6 +0.4710624955425695,0.8709651762077801,1.3089969389957472,1129.0,507.9,380.3,807.8,1489.6,1868.5 +0.47102681677252517,0.8709860172489692,1.4398966328953218,1017.0,416.9,358.4,815.1,2568.0,2509.6 +0.47104791442065963,0.8709820207828791,1.5707963267948966,999.0,371.0,370.7,762.9,2451.5,2450.9 +0.4709924939102929,0.8709807914113756,1.7016960206944713,1059.4,357.8,416.2,772.4,2510.4,2569.0 +0.4709450444556431,0.8709668946852542,1.832595714594046,671.7,381.1,508.8,855.9,2339.9,1960.5 +0.47096385846324085,0.8709803401126603,1.9634954084936205,455.6,457.5,719.8,1055.0,1603.0,1384.0 +0.47095389110074304,0.8709720359496729,2.0943951023931953,367.8,724.3,867.9,1514.1,1268.1,1141.1 +0.47092703731528474,0.8709212564383111,2.2252947962927703,336.3,853.8,795.0,2555.7,1098.1,1039.4 +0.47092463693893455,0.8709113931657493,2.356194490192345,341.6,792.9,793.5,2420.8,1028.5,1029.0 +0.47092282220889625,0.870910511316187,2.4870941840919194,379.1,795.0,854.0,2490.2,1039.6,1098.6 +0.4709351058862784,0.8708741007603946,2.6179938779914944,461.2,868.8,996.4,2257.3,1028.5,649.2 +0.470936499743842,0.8708678673764001,2.748893571891069,615.8,1052.1,1272.0,1547.6,675.9,456.0 +0.4709635700397322,0.8708446625134711,2.8797932657906435,855.3,1490.6,1870.5,1221.4,508.0,380.5 +0.47097461578753885,0.8708399773937956,3.010692959690218,772.5,2570.5,2511.1,1060.6,417.0,358.1 +0.5709784603585101,0.17074567345937974,0.0,63.0,2351.0,2351.0,1698.8,470.9,471.0 +0.571001667921719,0.17145558904580138,0.1308996938995747,91.5,2408.9,2468.4,1742.6,507.2,233.7 +0.5709520102485877,0.17143943192205446,0.2617993877991494,139.5,2669.0,2796.6,1146.8,474.8,95.3 +0.5708994852461204,0.17140550238877061,0.39269908169872414,223.8,2592.2,2372.6,756.0,282.3,63.0 +0.5708567396333584,0.17136035647922387,0.5235987755982988,393.3,2077.8,1950.4,576.4,187.5,59.8 +0.5708380346885137,0.1713213916348375,0.6544984694978736,912.7,1823.1,1763.9,482.7,129.5,70.5 +0.5708223743020134,0.17125883518588392,0.7853981633974483,2321.5,1728.7,1728.2,440.9,93.8,93.2 +0.570824023237267,0.17123337802977212,0.916297857297023,2428.0,1763.4,1699.2,439.5,70.7,129.4 +0.5708401691656022,0.17118176594614054,1.0471975511965976,2748.2,1230.6,850.4,393.8,59.5,186.8 +0.5708722231424795,0.17112750421868284,1.1780972450961724,2380.7,819.2,598.3,224.3,63.4,282.4 +0.5708751859257072,0.1711233040688085,1.3089969389957472,1937.8,623.5,496.0,139.9,95.6,474.8 +0.5708966231354445,0.1711114218858656,1.4398966328953218,1741.0,520.3,462.0,91.1,238.5,1067.1 +0.5709775759679953,0.17109165475528365,1.5707963267948966,1698.8,471.0,470.8,63.3,2351.0,2350.9 +0.5709787300535317,0.1710902316031091,1.7016960206944713,1783.6,506.8,238.4,48.6,2407.4,2465.6 +0.5709822384468274,0.17108964248262448,1.832595714594046,870.8,474.8,95.6,47.1,2669.3,2797.0 +0.571044083483175,0.17112801422409185,1.9634954084936205,596.7,282.5,63.3,63.7,2590.4,2371.2 +0.5710663752542009,0.1711523792084464,2.0943951023931953,483.3,186.8,59.5,117.4,2076.5,1949.2 +0.5710602851454936,0.17113835902780594,2.2252947962927703,439.8,129.5,70.7,319.5,1822.4,1763.5 +0.5710672841977411,0.17116696287701005,2.356194490192345,441.5,93.3,93.8,2320.8,1728.0,1728.9 +0.5710640598396672,0.17120297639858673,2.4870941840919194,317.0,70.5,129.6,2386.3,1764.2,1691.6 +0.5710659616737296,0.17119878541085365,2.6179938779914944,117.7,59.9,187.6,2657.5,1227.3,848.1 +0.5710496910080923,0.17121878388274614,2.748893571891069,62.7,62.7,282.7,2537.1,817.2,597.2 +0.5708190197851167,0.17093657628890302,2.8797932657906435,46.5,94.6,473.9,2031.3,623.7,496.1 +0.5708422460610186,0.17092473784634366,3.010692959690218,48.1,234.1,1054.8,1785.5,520.4,461.5 +0.5709137931899618,0.2712364840063817,0.0,163.0,2351.5,2351.3,1598.9,471.0,470.8 +0.5709006798566961,0.27123562975450866,0.1308996938995747,194.9,2408.8,2468.4,1638.9,461.6,520.8 +0.5708576026550252,0.27122235839092257,0.2617993877991494,254.7,2668.2,2795.3,1148.3,496.0,294.8 +0.5708136190464768,0.2711945294882858,0.39269908169872414,364.9,2452.1,2233.4,756.5,423.6,204.1 +0.5707779107042293,0.27115750223671675,0.5235987755982988,591.4,1963.4,1835.5,576.5,303.2,175.3 +0.5707642382202026,0.27112773488144737,0.6544984694978736,1294.3,1720.5,1660.8,482.8,233.0,173.8 +0.5707509570603377,0.271074505183317,0.7853981633974483,2321.3,1629.1,1628.4,440.7,193.7,193.0 +0.5707530695555709,0.27105822629463017,0.916297857297023,2428.7,1660.1,1702.8,439.4,174.0,232.7 +0.5707676514357937,0.27101515163321177,1.0471975511965976,2747.3,1231.6,850.9,483.2,174.8,301.9 +0.5707962794856581,0.2709680443155531,1.1780972450961724,2240.8,819.7,598.5,366.2,204.1,423.0 +0.5707946897643247,0.2709698329677448,1.3089969389957472,1823.1,623.8,496.0,255.5,294.2,672.9 +0.5708105657451588,0.27096268761600295,1.4398966328953218,1638.0,520.4,461.9,194.4,625.8,1452.7 +0.5708851699833172,0.27094533959083167,1.5707963267948966,1598.7,471.0,470.6,163.1,2351.2,2351.2 +0.570880024007049,0.27094472463884256,1.7016960206944713,1679.9,461.2,519.3,151.9,2406.5,2590.9 +0.5708775079317213,0.2709435538685325,1.832595714594046,871.4,496.5,294.9,162.4,2668.6,2795.7 +0.5709341831934552,0.2709793466241903,1.9634954084936205,597.1,423.6,204.3,205.0,2451.0,2231.5 +0.5709527137988617,0.2709997872025911,2.0943951023931953,483.4,302.3,174.8,316.3,1962.1,1834.8 +0.5709442124943682,0.2709815002601834,2.2252947962927703,439.7,233.0,174.0,704.3,1719.4,1660.5 +0.5709504200496127,0.27100555643308755,2.356194490192345,441.4,193.2,193.6,2320.4,1628.1,1629.0 +0.5709481653076127,0.27103713194676327,2.4870941840919194,482.5,173.9,232.8,2386.7,1660.5,1695.1 +0.5709519199359836,0.2710295340622184,2.6179938779914944,317.0,175.3,302.8,2656.8,1228.6,849.0 +0.5709387501014566,0.2710469623847134,2.748893571891069,204.1,203.8,423.5,2397.3,817.9,597.6 +0.5709468626910238,0.27104119877793886,2.8797932657906435,162.0,293.9,673.2,1915.5,623.6,496.1 +0.5709367081136589,0.27104735888409626,3.010692959690218,151.6,620.2,1441.2,1681.8,520.5,461.5 +0.5709644086227187,0.3713280465621578,0.0,263.0,2350.9,2351.1,1499.0,471.0,470.8 +0.5709255766726107,0.37068862340543207,0.1308996938995747,298.4,2408.5,2467.6,1535.4,461.6,520.9 +0.5709563324410106,0.37069851489327776,0.2617993877991494,370.3,2668.4,2795.2,1148.0,587.1,494.4 +0.5710330995390984,0.3707432844034426,0.39269908169872414,506.4,2311.4,2092.1,756.5,564.9,345.3 +0.5710399412396308,0.3707524694747415,0.5235987755982988,790.3,1847.5,1719.8,576.5,418.8,290.9 +0.5710647986743125,0.3707954294269722,0.6544984694978736,1678.4,1616.4,1557.6,482.7,336.5,277.3 +0.571070648924486,0.3708252812159718,0.7853981633974483,2321.7,1529.1,1528.5,440.8,293.6,292.9 +0.5710702021613454,0.37088998142474927,0.916297857297023,2428.3,1556.9,1615.4,439.3,277.4,336.0 +0.571062735676623,0.37092013126727164,1.0471975511965976,2747.0,1231.4,850.9,534.0,290.1,417.2 +0.5710540194314191,0.37093362277725705,1.1780972450961724,2099.2,819.6,598.3,507.8,344.9,563.6 +0.5710052712313531,0.37098049598686766,1.3089969389957472,1732.7,623.8,496.0,370.9,492.8,871.6 +0.5709679426029218,0.3710026936178348,1.4398966328953218,1534.8,520.4,461.9,297.7,1013.9,1840.6 +0.5709871453562182,0.3709989867033585,1.5707963267948966,1498.9,471.0,470.7,263.0,2351.5,2350.8 +0.5709299684821532,0.37099761748740034,1.7016960206944713,1576.6,461.0,519.3,255.1,2406.3,2464.9 +0.5708809290357522,0.370983363793443,1.832595714594046,871.5,586.4,494.0,277.7,2668.8,2796.0 +0.5709385342222004,0.37101692966282074,1.9634954084936205,596.9,564.6,345.2,346.4,2309.9,2090.7 +0.5709073679271743,0.37098496040162887,2.0943951023931953,483.4,417.7,290.2,515.4,1846.6,1744.8 +0.570877275523253,0.3709275529672209,2.2252947962927703,439.9,336.3,277.4,1090.2,1615.8,1556.9 +0.5708752647328339,0.3709179686158872,2.356194490192345,441.5,293.0,293.4,2320.6,1528.7,1529.3 +0.5708738743041658,0.37091962312943383,2.4870941840919194,533.0,277.3,336.2,2386.2,1557.1,1616.0 +0.570885445829797,0.3708864301261656,2.6179938779914944,516.1,290.7,418.2,2656.1,1228.5,849.1 +0.570885590567253,0.37088301971894366,2.748893571891069,345.5,345.0,564.8,2255.7,817.9,597.5 +0.5709105141290011,0.370862117424275,2.8797932657906435,277.5,492.9,872.2,1800.1,623.7,496.1 +0.5709190539774354,0.3708589499792898,3.010692959690218,255.0,1006.1,1827.0,1578.5,520.5,461.6 +0.570969083563015,0.4711566242642886,0.0,362.8,2351.1,2351.3,1399.2,470.9,470.9 +0.5709379051192305,0.47066965295712926,0.1308996938995747,402.0,2408.5,2467.8,1431.8,461.7,520.8 +0.5709725937487928,0.47068084293606116,0.2617993877991494,485.9,2668.5,2795.9,1148.0,496.0,623.4 +0.57101045494928,0.4707050363569778,0.39269908169872414,648.1,2169.7,1950.3,756.4,598.1,486.6 +0.5710402193175148,0.47073914641612835,0.5235987755982988,989.7,1732.0,1604.0,576.5,534.4,406.7 +0.5710689123138742,0.4707895843693719,0.6544984694978736,2064.5,1512.9,1453.8,482.7,440.1,380.8 +0.5710747653635704,0.4708199076991535,0.7853981633974483,2321.4,1429.0,1428.5,440.8,393.6,392.9 +0.5710742421347176,0.47088261160215006,0.916297857297023,2428.1,1453.2,1511.6,439.4,380.9,439.6 +0.5710506104765765,0.47096487270280574,1.0471975511965976,2747.7,1231.2,850.6,483.3,405.7,532.7 +0.5710641429193555,0.4709428662202704,1.1780972450961724,1957.1,819.5,598.4,595.2,486.0,704.9 +0.5709870019483247,0.4710147980072561,1.3089969389957472,1591.6,623.7,496.0,486.5,692.0,1070.8 +0.5709484120995145,0.4710388895651383,1.4398966328953218,1431.1,520.4,461.9,401.2,1403.6,2230.5 +0.5709984961976071,0.47102821438308173,1.5707963267948966,1399.1,470.9,470.6,362.9,2351.3,2350.7 +0.570944066363113,0.47102703029606174,1.7016960206944713,1473.0,461.1,519.5,358.6,2406.7,2465.2 +0.5708892547054368,0.47101105770838814,1.832595714594046,871.4,496.6,624.2,393.3,2668.6,2796.3 +0.5708996467179308,0.47101905365691055,1.9634954084936205,596.9,599.0,486.5,488.0,2169.0,1948.8 +0.570883010717843,0.4710031248728763,2.0943951023931953,483.3,533.1,405.7,715.0,1730.9,1603.1 +0.5708518331904132,0.47094392838403687,2.2252947962927703,439.9,439.9,380.9,1477.2,1512.1,1453.7 +0.570847628582231,0.47092533490393684,2.356194490192345,441.5,392.9,393.4,2320.5,1428.6,1429.0 +0.5708464848494726,0.47091607417986125,2.4870941840919194,482.5,380.7,439.7,2386.1,1453.8,1512.5 +0.5708472629957819,0.47091772105128715,2.6179938779914944,576.6,406.3,533.9,2656.8,1228.7,848.9 +0.5708700910815483,0.4708782722402529,2.748893571891069,486.9,486.4,706.2,2114.2,817.8,597.5 +0.570907245714777,0.4708459045714226,2.8797932657906435,393.0,692.3,1071.7,1684.3,623.7,496.1 +0.5709229934350738,0.4708388748638064,3.010692959690218,358.4,1393.0,2214.6,1474.8,520.5,461.6 +0.5709788245711132,0.5711397329290375,0.0,462.8,2351.5,2350.7,1299.1,471.0,470.8 +0.5709510006608456,0.5706709119177682,0.1308996938995747,505.6,2408.3,2467.9,1328.4,461.7,520.8 +0.5709862817343075,0.5706823133545884,0.2617993877991494,601.5,2669.1,2562.0,1147.6,496.1,623.5 +0.5710240842780311,0.5707065303961314,0.39269908169872414,789.8,2028.2,1808.8,756.2,674.9,627.7 +0.5710536651494447,0.5707405334817182,0.5235987755982988,1189.0,1616.1,1488.4,576.4,650.0,522.2 +0.5710821236510388,0.5707907501866103,0.6544984694978736,2386.7,1409.5,1350.4,482.7,543.6,484.4 +0.5710878482170859,0.5708208368140988,0.7853981633974483,2321.0,1329.2,1328.2,440.7,493.6,493.0 +0.5710872157949352,0.5708832383417484,0.916297857297023,2428.3,1349.6,1408.8,439.3,484.3,543.2 +0.5710803896682085,0.5709105064841398,1.0471975511965976,2586.9,1231.0,850.4,483.3,521.1,648.3 +0.5710731570185456,0.5709214808864627,1.1780972450961724,1815.7,819.4,598.3,595.3,627.2,846.1 +0.5710263654464607,0.5709663385886272,1.3089969389957472,1476.2,623.6,496.0,602.1,891.4,1270.3 +0.5709913238475138,0.5709871003958957,1.4398966328953218,1327.7,520.3,461.8,504.7,1793.3,2406.8 +0.5710129848755648,0.5709829169703882,1.5707963267948966,1299.0,471.0,470.6,462.9,2351.7,2351.5 +0.5709580921989443,0.5709816771017531,1.7016960206944713,1369.7,461.2,519.5,462.1,2407.0,2465.1 +0.5709110911331122,0.5709679907327974,1.832595714594046,871.3,496.7,624.2,509.0,2669.1,2560.0 +0.5709303481156117,0.5709815630757094,1.9634954084936205,597.0,674.7,627.7,629.8,2027.2,1807.6 +0.5709208243973022,0.5709733801577968,2.0943951023931953,483.4,648.6,521.3,914.8,1615.3,1487.8 +0.5708942841894195,0.5709229202828434,2.2252947962927703,439.9,543.3,484.4,1864.8,1408.7,1349.8 +0.5708921367707637,0.5709134296142995,2.356194490192345,441.6,493.0,493.5,2320.7,1328.4,1329.3 +0.5708905807398367,0.5709128880923282,2.4870941840919194,482.7,484.3,543.2,2385.8,1349.8,1409.4 +0.5709028773801517,0.5708769302989545,2.6179938779914944,671.4,521.9,649.5,2656.8,1228.2,848.9 +0.5709043287220598,0.570871057560788,2.748893571891069,628.2,627.9,847.7,1972.3,817.6,597.4 +0.570931204231781,0.570848209922638,2.8797932657906435,508.6,892.0,1271.2,1568.7,623.7,496.1 +0.5709419823145487,0.5708437791498566,3.010692959690218,462.1,1780.5,2407.9,1371.2,520.6,461.5 +0.5709948106321077,0.6711436163424349,0.0,562.8,2351.5,2351.1,1199.2,471.0,470.9 +0.570963505076709,0.6706696726251806,0.1308996938995747,609.2,2408.7,2467.9,1224.8,461.7,520.9 +0.570998129274647,0.6706808953141865,0.2617993877991494,717.1,2668.8,2362.6,1147.5,496.1,623.5 +0.5710358907378351,0.6707051371116586,0.39269908169872414,931.5,1886.7,1667.3,756.1,657.2,768.9 +0.5710655685886881,0.6707393195229032,0.5235987755982988,1388.2,1500.5,1372.9,576.5,765.4,637.7 +0.5710940511742579,0.6707897528682052,0.6544984694978736,2386.4,1305.8,1246.9,482.7,647.1,588.0 +0.5710997740100382,0.6708200902110424,0.7853981633974483,2320.9,1229.0,1228.5,440.8,593.5,592.9 +0.5710990442981719,0.6708826806763692,0.916297857297023,2428.7,1246.1,1305.1,439.5,587.8,646.7 +0.5710920876582556,0.6709100884474899,1.0471975511965976,2386.6,1230.9,850.4,483.3,636.6,763.7 +0.5710847297529067,0.670921193938046,1.1780972450961724,1673.6,819.3,598.3,626.4,768.3,987.2 +0.5710377949135875,0.6709661080806608,1.3089969389957472,1360.7,623.7,495.8,717.6,1090.7,1469.5 +0.5710026184778837,0.6709868561012489,1.4398966328953218,1224.1,520.3,461.8,608.1,2183.0,2532.8 +0.5710241715353545,0.6709827133349437,1.5707963267948966,1199.2,471.0,470.6,563.0,2351.1,2351.0 +0.5709691782986571,0.6709814768990112,1.7016960206944713,1266.2,461.2,519.5,565.5,2406.6,2465.7 +0.5709220950525911,0.6709677401356919,1.832595714594046,871.0,496.7,624.3,624.6,2668.6,2360.3 +0.5709412618808257,0.6709813024098803,1.9634954084936205,596.8,656.9,768.7,771.5,1885.8,1666.5 +0.5709316346829604,0.6709731203080724,2.0943951023931953,483.3,764.1,637.0,1114.4,1499.7,1372.2 +0.5709050183580547,0.6709226028833037,2.2252947962927703,439.9,646.8,587.9,2252.6,1305.0,1246.5 +0.5709028004970667,0.6709130394495606,2.356194490192345,441.5,593.0,593.5,2320.5,1228.4,1229.0 +0.5709011595301916,0.6709124330780099,2.4870941840919194,482.7,587.9,646.9,2385.8,1246.6,1305.8 +0.5709134388764614,0.670876368878869,2.6179938779914944,576.8,637.5,765.3,2656.8,1228.2,848.7 +0.570914850695073,0.6708704116907507,2.748893571891069,738.6,769.2,989.2,1830.8,817.5,597.4 +0.570941762003451,0.6708474718508504,2.8797932657906435,624.2,1091.6,1471.4,1453.0,623.6,496.1 +0.5709525968128042,0.6708429727682037,3.010692959690218,565.6,2167.5,2517.6,1267.7,520.5,461.6 +0.5710055299104649,0.771142903014169,0.0,662.9,2351.3,2350.6,1099.1,471.0,470.8 +0.5709725969283587,0.7706696484117819,0.1308996938995747,712.9,2409.0,2468.2,1121.3,461.7,520.9 +0.5710068691522727,0.7706807794708324,0.2617993877991494,832.6,2542.1,2161.6,1147.2,496.1,623.5 +0.5710445402641984,0.77070500128786,0.39269908169872414,1073.0,1745.5,1525.9,756.1,598.3,818.9 +0.571074201852702,0.7707392213373678,0.5235987755982988,1587.6,1384.7,1257.0,576.5,881.4,753.4 +0.5711026350005707,0.7707896913550405,0.6544984694978736,2386.7,1202.3,1143.2,482.6,750.6,691.5 +0.5711083251072453,0.7708200807914758,0.7853981633974483,2321.5,1129.1,1128.5,440.8,693.5,692.8 +0.5711075252487041,0.7708826814122802,0.916297857297023,2428.3,1142.7,1201.4,439.4,691.4,750.2 +0.5711005049961637,0.7709100750840403,1.0471975511965976,2186.5,1230.7,850.3,483.3,752.2,879.6 +0.5710931127210253,0.7709211814542116,1.1780972450961724,1531.6,819.2,598.2,595.4,909.4,1128.6 +0.5710461454100935,0.77096606426085,1.3089969389957472,1244.7,623.6,495.9,833.2,1289.7,1669.2 +0.5710109528609731,0.7709867522568197,1.4398966328953218,1120.5,520.3,462.0,711.5,2465.3,2406.7 +0.5710325143432372,0.770982617830229,1.5707963267948966,1099.1,470.9,470.6,663.0,2351.1,2351.1 +0.5709775298517614,0.770981384406497,1.7016960206944713,1162.8,461.2,519.6,668.9,2407.0,2465.2 +0.5709304608677033,0.7709676290663174,1.832595714594046,871.0,496.7,624.3,740.3,2539.6,2160.6 +0.5709496237134983,0.7709812215265275,1.9634954084936205,596.8,599.1,820.0,913.2,1744.6,1525.3 +0.5709399660038574,0.7709730896980009,2.0943951023931953,483.4,879.7,752.5,1314.1,1383.8,1256.6 +0.5709133232868296,0.7709225834151017,2.2252947962927703,439.8,750.3,691.5,2428.2,1201.6,1142.9 +0.5709110664363135,0.7709130221864273,2.356194490192345,441.6,693.0,693.5,2320.4,1128.5,1129.0 +0.5709093588445321,0.7709124222685146,2.4870941840919194,482.6,691.3,750.5,2386.4,1143.1,1202.3 +0.5709216103596808,0.7708763255967956,2.6179938779914944,576.7,753.1,880.7,2456.9,1228.0,848.7 +0.5709229655071625,0.7708703443462324,2.748893571891069,757.0,910.6,1130.6,1688.7,817.6,597.4 +0.5709498714152387,0.7708473631397315,2.8797932657906435,739.7,1291.1,1670.8,1362.5,623.6,496.2 +0.570960713010642,0.770842829509452,3.010692959690218,669.1,2466.5,2408.0,1164.2,520.5,461.6 +0.571013682766943,0.8711427977211685,0.0,763.0,2351.2,2350.8,999.1,470.9,470.9 +0.5709795366801871,0.8706696953878963,0.1308996938995747,816.4,2408.8,2467.8,1017.9,461.8,521.0 +0.5710135384862689,0.8706807557534113,0.2617993877991494,948.4,2342.5,1962.5,1128.6,496.1,623.6 +0.571051134540344,0.8707049583672732,0.39269908169872414,1214.8,1604.5,1384.8,756.1,598.3,818.9 +0.5710807780044336,0.870739200896878,0.5235987755982988,1786.9,1269.1,1141.3,576.5,847.3,869.1 +0.5711091694800232,0.8707896915279498,0.6544984694978736,2386.6,1098.7,1039.6,482.7,854.1,795.1 +0.5711148328004805,0.870820112965063,0.7853981633974483,2321.4,1029.2,1028.5,440.8,793.4,792.9 +0.5711139795523769,0.8708827139066186,0.916297857297023,2428.5,1039.3,1098.1,439.5,795.0,853.7 +0.5711069126549112,0.8709100901200049,1.0471975511965976,1987.2,1140.9,850.1,483.4,867.7,994.9 +0.571099497462565,0.870921191644012,1.1780972450961724,1389.7,819.3,598.2,595.4,1050.6,1269.8 +0.5710525095633672,0.8709660463542441,1.3089969389957472,1128.9,623.5,495.9,868.8,1489.3,1868.3 +0.5710173094879663,0.8709866857129414,1.4398966328953218,1017.2,520.3,461.8,815.0,2488.1,2406.6 +0.5710388824282023,0.8709825563423992,1.5707963267948966,998.9,470.9,470.7,762.9,2351.5,2351.3 +0.5709839093646476,0.8709813251980689,1.7016960206944713,1059.3,461.2,519.6,772.4,2406.7,2465.5 +0.5709368555612242,0.8709675567495385,1.832595714594046,870.9,496.7,624.4,855.7,2339.9,1960.6 +0.5709560189786103,0.870981174358157,1.9634954084936205,596.8,599.1,820.0,1054.9,1603.3,1384.2 +0.5709463406607284,0.8709730836892071,2.0943951023931953,483.3,849.5,867.9,1513.9,1268.2,1140.9 +0.5709196795332573,0.8709225889915793,2.2252947962927703,439.8,853.9,795.0,2554.7,1098.4,1039.2 +0.5709173936926355,0.8709130326674592,2.356194490192345,441.5,793.0,793.5,2320.8,1028.7,1029.1 +0.5709156350704339,0.870912440783695,2.4870941840919194,482.7,794.9,854.0,2386.7,1039.7,1098.6 +0.5709278644618704,0.8708763219994626,2.6179938779914944,576.7,868.8,996.4,2257.4,1141.3,848.8 +0.5709291748094687,0.8708703245720566,2.748893571891069,879.9,1052.1,1271.9,1547.5,817.5,597.4 +0.5709560747422011,0.8708473133263863,2.8797932657906435,855.3,1490.6,1870.3,1221.4,623.6,496.1 +0.570966919482447,0.8708427542242454,3.010692959690218,772.6,2466.7,2408.2,1060.6,520.4,461.6 +0.6709707873668148,0.17074776384330548,0.0,63.0,2250.8,2250.9,1699.2,571.0,570.9 +0.6709979698961717,0.17145597964966441,0.1308996938995747,91.6,2305.2,2341.4,1743.0,565.4,233.6 +0.6709490218697263,0.17144003594531476,0.2617993877991494,139.5,2553.6,2680.7,1346.3,474.9,95.3 +0.6708966047087308,0.1714061628905399,0.39269908169872414,223.8,2591.8,2372.3,897.2,282.3,63.0 +0.6708538243927383,0.1713609591137495,0.5235987755982988,393.3,2078.0,1950.3,692.0,187.5,59.8 +0.6708350728244493,0.17132187913370678,0.6544984694978736,912.6,1823.1,1763.9,586.3,129.5,70.4 +0.6708194023298641,0.1712591945551225,0.7853981633974483,2220.5,1729.0,1728.5,541.0,93.8,93.2 +0.6708210694371309,0.17123361141297555,0.916297857297023,2324.7,1763.4,1822.4,543.1,70.7,129.5 +0.6708372629972753,0.1711818900135853,1.0471975511965976,2632.6,1430.0,1049.7,393.8,59.5,186.8 +0.670869387635832,0.17112754938706098,1.1780972450961724,2380.8,960.9,739.9,224.4,63.3,282.5 +0.6708724273271532,0.17112329087891043,1.3089969389957472,1937.7,739.1,611.7,139.9,95.6,474.9 +0.6708939444565025,0.1711113669490223,1.4398966328953218,1740.8,623.7,565.4,91.1,238.5,1067.1 +0.6709749781815344,0.17109159022501474,1.5707963267948966,1698.7,571.1,570.6,63.3,2251.3,2251.4 +0.6709762055020054,0.17109016973506597,1.7016960206944713,1783.6,564.6,238.4,48.6,2303.4,2361.7 +0.6709797818777351,0.1710895888049122,1.832595714594046,1070.1,474.8,95.6,47.1,2553.8,2681.2 +0.671041685885715,0.17112798804400065,1.9634954084936205,737.8,282.4,63.3,63.7,2590.3,2371.2 +0.6710640248445349,0.1711523929881873,2.0943951023931953,598.9,186.8,59.5,117.4,2076.7,1949.2 +0.6710579754978108,0.1711384128289566,2.2252947962927703,543.3,129.5,70.7,319.5,1822.1,1763.5 +0.6710650033438126,0.17116706383664648,2.356194490192345,541.4,93.3,93.8,2220.7,1728.3,1728.7 +0.671061789193975,0.1712031324000085,2.4870941840919194,316.9,70.5,129.6,2282.7,1763.9,1823.2 +0.6710636938963184,0.17119899102083247,2.6179938779914944,117.6,59.9,187.6,2541.3,1426.3,1047.6 +0.6710474028551073,0.17121903923744153,2.748893571891069,62.7,62.7,282.7,2536.4,958.5,738.6 +0.6710523899302073,0.1712145784789918,2.8797932657906435,46.6,95.0,474.8,2030.3,738.9,611.6 +0.6710391175898099,0.17122097567519234,3.010692959690218,48.2,235.2,1058.2,1784.9,623.8,565.1 +0.6710639347547702,0.27149942504227065,0.0,163.2,2251.0,2251.2,1598.7,571.0,571.0 +0.6710102610980251,0.2707322127004115,0.1308996938995747,195.0,2305.4,2364.5,1639.0,565.3,617.3 +0.6710329491393144,0.27073965843381287,0.2617993877991494,254.9,2553.1,2680.8,1346.5,611.8,294.5 +0.671062752770731,0.270758916142706,0.39269908169872414,365.2,2450.8,2232.1,897.1,423.3,204.0 +0.6710869987160331,0.2707873509257679,0.5235987755982988,592.1,1962.8,1835.2,692.1,303.0,175.2 +0.6711119472119327,0.27068608122418003,0.6544984694978736,1297.3,1720.0,1661.0,586.1,232.9,173.8 +0.6711194567575319,0.27086623946375754,0.7853981633974483,2221.3,1629.0,1628.4,540.8,193.6,193.0 +0.67111881064989,0.27091544520131716,0.916297857297023,2325.1,1660.3,1719.3,542.9,173.9,232.7 +0.6711136185623773,0.27093591358981395,1.0471975511965976,2631.9,1430.1,1049.9,593.1,174.7,302.0 +0.6711086401012372,0.270942783176793,1.1780972450961724,2239.5,960.9,739.9,365.7,204.0,423.1 +0.6710643729242055,0.2709847538948911,1.3089969389957472,1822.7,739.1,611.5,255.1,294.2,673.3 +0.6710321621782097,0.2710034580531615,1.4398966328953218,1638.0,623.8,565.4,194.2,626.7,1455.3 +0.6710568890600811,0.2709984458710404,1.5707963267948966,1599.1,571.0,570.8,162.9,2251.6,2251.0 +0.6710049054329307,0.2709971449375983,1.7016960206944713,1680.5,564.7,541.1,151.7,2303.1,2361.9 +0.6709605735160531,0.2709839839750394,1.832595714594046,1069.9,612.4,294.2,162.3,2553.6,2681.2 +0.6709820160308821,0.27099894036837413,1.9634954084936205,737.9,423.1,204.0,204.9,2449.5,2230.3 +0.6709739951883716,0.27099265916156545,2.0943951023931953,599.0,302.0,174.7,316.4,1961.5,1834.3 +0.6709483832777293,0.2709441264645229,2.2252947962927703,543.4,232.7,173.9,705.4,1718.9,1660.1 +0.6709465034068646,0.2709366124767265,2.356194490192345,541.6,193.0,193.5,2220.1,1628.6,1628.7 +0.670944504302299,0.27093798505268096,2.4870941840919194,586.3,173.7,232.8,2282.5,1660.9,1720.0 +0.67095608509768,0.27090348946393883,2.6179938779914944,316.4,175.2,302.8,2541.3,1426.7,1048.0 +0.67095629919388,0.27089879557230545,2.748893571891069,203.8,203.8,423.7,2395.9,958.7,738.9 +0.6709819840746899,0.270876633969094,2.8797932657906435,161.9,294.0,673.7,1915.2,739.0,611.6 +0.6709915399682957,0.2708725198050701,3.010692959690218,151.5,621.3,1444.2,1681.6,623.9,565.2 +0.6710431318837219,0.37117145600200474,0.0,262.8,2251.4,2250.7,1499.3,571.1,571.0 +0.6710031329348032,0.3706759214310187,0.1308996938995747,298.6,2305.5,2364.9,1535.6,565.3,624.6 +0.6710351802153933,0.3706864045997349,0.2617993877991494,370.5,2553.6,2680.4,1346.4,611.8,493.9 +0.6710717820076381,0.37071006046262567,0.39269908169872414,506.8,2309.4,2090.7,897.1,564.4,345.3 +0.6711008438068673,0.3707438015024891,0.5235987755982988,791.2,1846.9,1719.4,692.1,418.5,290.9 +0.6711287770944263,0.3707937440473139,0.6544984694978736,1682.7,1616.5,1557.4,586.2,336.4,277.2 +0.6711342083138586,0.3708236405438228,0.7853981633974483,2221.2,1528.8,1528.8,540.7,293.5,293.0 +0.6711331978277715,0.37088565131388096,0.916297857297023,2324.9,1556.6,1615.4,543.0,277.4,336.2 +0.6711261335278206,0.37091244114074695,1.0471975511965976,2632.5,1429.9,1049.7,599.0,290.2,417.5 +0.671118905835343,0.3709230866418458,1.1780972450961724,2098.3,960.8,739.9,507.3,345.1,564.2 +0.6710721841078654,0.37096751920388393,1.3089969389957472,1706.7,739.3,611.5,370.7,493.4,872.6 +0.6710373383057773,0.37098778099383756,1.4398966328953218,1534.2,623.7,565.3,297.6,1016.2,1844.7 +0.6710988681734135,0.37097221721376683,1.5707963267948966,1499.2,570.9,570.7,262.9,2251.4,2250.9 +0.6710165742829449,0.37096996348885236,1.7016960206944713,1576.8,564.8,623.0,255.2,2303.4,2361.8 +0.6709643885835652,0.3709545311687177,1.832595714594046,1070.1,612.4,493.3,277.9,2553.4,2680.8 +0.6709848282091789,0.3709689962132525,1.9634954084936205,737.9,564.2,345.1,346.6,2308.5,2089.5 +0.6709774253984013,0.3709635280974448,2.0943951023931953,598.9,417.4,290.1,516.1,1845.7,1718.7 +0.6709525014413436,0.3708263380424188,2.2252947962927703,543.4,336.2,277.4,1092.8,1615.7,1556.8 +0.6709490743749899,0.37090583556851,2.356194490192345,541.5,293.0,293.5,2220.9,1528.6,1529.1 +0.6709469523063922,0.37091230565614985,2.4870941840919194,586.3,277.2,336.4,2282.3,1557.2,1616.3 +0.6709579536418664,0.3708798617662048,2.6179938779914944,515.6,290.8,418.5,2541.7,1426.9,1047.8 +0.6709576052148793,0.37087621476367527,2.748893571891069,345.2,345.2,565.1,2254.3,959.0,738.8 +0.6709827634272552,0.3708546998250364,2.8797932657906435,277.4,493.5,873.3,1799.4,739.1,611.7 +0.6709917716746067,0.3708510296137877,3.010692959690218,255.0,1008.3,1830.8,1578.0,623.9,565.1 +0.6710426588103247,0.4711494644143983,0.0,362.8,2251.5,2250.6,1399.1,570.9,571.0 +0.6710029316995928,0.47066903846716124,0.1308996938995747,402.2,2305.3,2364.6,1432.4,565.2,624.6 +0.6710357815070599,0.47067978519088727,0.2617993877991494,486.1,2553.8,2680.7,1346.2,611.7,693.1 +0.6710731599144769,0.4707039441082199,0.39269908169872414,648.5,2168.6,1949.5,897.0,705.7,486.4 +0.6711028281088212,0.47073835288910915,0.5235987755982988,990.4,1731.6,1603.6,692.0,534.2,406.5 +0.6711311508068792,0.4707890396412968,0.6544984694978736,2067.7,1513.0,1453.7,586.2,439.9,380.8 +0.6711367579451173,0.47081970743392865,0.7853981633974483,2220.9,1429.2,1428.5,540.8,393.6,393.0 +0.6711357253897193,0.4708824465522361,0.916297857297023,2325.3,1453.3,1512.1,543.0,380.9,439.7 +0.6711284684958287,0.4709098891638568,1.0471975511965976,2632.3,1430.1,1049.6,704.7,405.8,533.0 +0.6711209150045154,0.4709210760218847,1.1780972450961724,1956.2,960.6,740.0,649.1,486.2,705.4 +0.6710737806215241,0.4709659146093512,1.3089969389957472,1591.5,739.0,611.5,486.4,692.5,1071.9 +0.6710384668362082,0.47098644520961264,1.4398966328953218,1430.9,623.8,565.4,401.2,1405.9,2234.6 +0.671059984179038,0.47098235499594576,1.5707963267948966,1398.9,570.9,570.7,362.9,2251.1,2251.3 +0.671004961095448,0.4709811305116318,1.7016960206944713,1473.4,564.7,623.1,358.6,2303.8,2361.8 +0.6709578783091585,0.47096729880077004,1.832595714594046,1070.0,612.4,692.8,393.5,2553.6,2681.0 +0.6709769774024168,0.47098095987905797,1.9634954084936205,737.9,705.4,486.2,488.3,2166.9,1948.3 +0.6709899511596116,0.47100291845056264,2.0943951023931953,598.8,533.0,405.7,715.7,1730.2,1603.1 +0.6709508941644708,0.47092921090498163,2.2252947962927703,543.4,439.7,380.9,1479.9,1511.9,1453.3 +0.6709470626762162,0.47091327941445904,2.356194490192345,541.6,392.9,393.5,2220.4,1428.5,1429.1 +0.6709451610638145,0.47091236558592464,2.4870941840919194,586.2,380.8,439.8,2282.5,1453.8,1512.6 +0.6709568852409615,0.4708776064450131,2.6179938779914944,671.0,406.4,534.2,2541.3,1427.3,1047.6 +0.6709569944661467,0.47087324762552196,2.748893571891069,486.7,486.5,706.6,2113.3,958.8,738.8 +0.6709824007732276,0.4708515205875028,2.8797932657906435,392.9,692.8,1072.7,1683.9,739.0,611.7 +0.6709915528330682,0.47084779271812116,3.010692959690218,358.5,1395.5,2218.1,1474.5,624.0,565.0 +0.6710425455270338,0.5711462864251957,0.0,462.9,2251.2,2251.1,1299.1,571.1,571.0 +0.6710028830033294,0.570668271779593,0.1308996938995747,505.7,2305.2,2364.6,1328.6,565.3,624.6 +0.6710358337032091,0.5706790514848963,0.2617993877991494,601.6,2553.8,2559.9,1346.4,611.7,739.2 +0.6710733008185531,0.5707032677905206,0.39269908169872414,790.0,2027.4,1808.3,897.2,739.9,627.6 +0.6711030363371255,0.5707377506532711,0.5235987755982988,1189.6,1615.4,1488.3,692.0,649.7,522.0 +0.6708355620251141,0.5710393369964062,0.6544984694978736,2282.8,1408.8,1350.1,586.0,543.4,484.4 +0.6708289377112878,0.5710134027819744,0.7853981633974483,2221.2,1328.7,1328.5,540.8,493.5,493.1 +0.6708301184811877,0.5710170412946904,0.916297857297023,2325.5,1349.9,1408.7,543.0,484.5,543.4 +0.6708396923401458,0.5709898601844721,1.0471975511965976,2626.4,1428.2,1048.6,599.2,521.6,649.0 +0.6708606491173709,0.5709559061117806,1.1780972450961724,1813.5,960.0,739.4,737.1,627.9,847.4 +0.670849199130205,0.5709670087478631,1.3089969389957472,1474.8,738.7,611.3,601.8,893.0,1272.9 +0.6708539906583213,0.5709653390030056,1.4398966328953218,1327.0,623.7,565.3,504.6,1800.3,2302.5 +0.6709172618430049,0.5709513168710065,1.5707963267948966,1298.9,570.9,570.6,463.1,2251.0,2250.9 +0.6709013738684967,0.5709506901142445,1.7016960206944713,1370.3,564.7,623.2,462.4,2304.4,2362.8 +0.6708893957777358,0.5709462807301651,1.832595714594046,1068.7,612.4,740.4,509.4,2554.9,2555.3 +0.6709379982106444,0.5709773949977301,1.9634954084936205,737.4,741.3,627.3,630.6,2024.9,1805.8 +0.6709502840030125,0.5709920657574108,2.0943951023931953,598.6,648.3,521.2,916.5,1639.6,1486.8 +0.6709380460867433,0.5709666429333435,2.2252947962927703,543.2,543.2,484.5,1871.7,1408.1,1349.6 +0.670942573205523,0.5709833398081072,2.356194490192345,541.5,493.0,493.7,2220.4,1328.4,1329.1 +0.6709401453623053,0.5710082480923493,2.4870941840919194,586.3,484.4,543.6,2260.6,1350.4,1409.4 +0.6709459893212076,0.5709943953680732,2.6179938779914944,692.7,522.4,650.2,2542.3,1425.2,1046.3 +0.6709354455868467,0.5710070160407434,2.748893571891069,627.8,628.5,848.7,1969.9,958.0,738.2 +0.6709476599286721,0.5709975260008668,2.8797932657906435,508.5,893.5,1273.9,1567.5,738.6,611.3 +0.6709419710606214,0.5710013624641737,3.010692959690218,462.0,1786.8,2304.6,1370.8,623.7,565.0 +0.6709751140428286,0.6712862129483368,0.0,563.0,2250.8,2251.4,1198.7,570.8,571.0 +0.6709665124070229,0.6706837695620391,0.1308996938995747,609.3,2305.0,2364.6,1224.6,565.3,624.5 +0.6710037319811374,0.6706957713554316,0.2617993877991494,717.1,2553.5,2362.0,1346.6,611.7,805.3 +0.6710407176130506,0.6707195384584472,0.39269908169872414,931.7,1886.7,1667.2,897.4,816.0,769.0 +0.6710690789382441,0.6707523316897361,0.5235987755982988,1388.7,1500.2,1372.8,692.1,765.5,637.6 +0.6710964932711485,0.6708008932487746,0.6544984694978736,2367.4,1305.8,1246.5,586.2,647.1,587.9 +0.6711017100115341,0.6708292070302155,0.7853981633974483,2221.0,1229.1,1228.4,540.7,593.6,593.0 +0.6711009560808728,0.6708897930845039,0.916297857297023,2325.1,1245.9,1304.8,542.9,587.9,646.7 +0.6710944626823481,0.6709153661942857,1.0471975511965976,2385.9,1371.8,1049.7,598.8,636.7,764.1 +0.6710879851603009,0.6709249825552066,1.1780972450961724,1673.4,960.8,739.9,736.6,768.4,987.4 +0.671042165794398,0.6709687362730044,1.3089969389957472,1360.3,739.0,611.4,717.5,1090.9,1469.7 +0.6710082740630715,0.6709886581641831,1.4398966328953218,1224.1,623.8,565.3,608.1,2184.0,2303.4 +0.6710312049113275,0.6709841836586803,1.5707963267948966,1199.1,571.0,570.6,562.9,2251.5,2251.2 +0.6709775102269108,0.670982953007154,1.7016960206944713,1266.3,564.7,623.1,565.5,2303.8,2361.5 +0.670931607025852,0.670969484008803,1.832595714594046,1070.4,612.3,804.6,624.7,2553.8,2359.8 +0.6709517489619368,0.6709836508967106,1.9634954084936205,737.8,815.6,768.7,771.6,1885.3,1666.6 +0.6709428173382257,0.6709762794573313,2.0943951023931953,598.9,764.2,636.8,1114.8,1499.8,1371.8 +0.6709166518278565,0.6709266034719505,2.2252947962927703,543.4,646.7,587.8,2253.4,1305.2,1246.5 +0.6709146131376724,0.6709179131641403,2.356194490192345,541.5,592.9,593.5,2220.6,1228.5,1229.1 +0.6709128626052203,0.670918162234762,2.4870941840919194,586.2,587.9,646.9,2283.1,1246.6,1305.8 +0.6709248891554528,0.6708827940713982,2.6179938779914944,858.9,637.7,765.4,2541.5,1372.2,1048.1 +0.6709258260587891,0.6708774194859384,2.748893571891069,769.6,769.4,989.0,1830.4,958.9,738.8 +0.6709522351358973,0.670854865792825,2.8797932657906435,624.2,1091.6,1471.2,1452.8,739.2,611.7 +0.670962524602492,0.6708505873452058,3.010692959690218,565.6,2168.8,2304.3,1267.7,623.9,565.2 +0.6710148477940632,0.7711500631460613,0.0,662.8,2250.8,2251.0,1099.1,571.0,570.9 +0.6709811598813938,0.770670872050454,0.1308996938995747,712.7,2305.3,2364.6,1121.3,565.2,624.7 +0.6710151153638411,0.7706819183898934,0.2617993877991494,832.7,2553.0,2162.1,1243.9,611.7,739.2 +0.6710525946339537,0.7707060524533567,0.39269908169872414,1073.3,1745.5,1526.2,897.2,798.3,910.0 +0.6710821314330521,0.7707401885336549,0.5235987755982988,1587.7,1384.7,1257.1,691.9,881.2,753.3 +0.6711104403155906,0.7707905485884274,0.6544984694978736,2283.0,1202.4,1143.1,586.2,750.5,691.4 +0.6711160638370481,0.770820834217514,0.7853981633974483,2221.2,1129.1,1128.7,540.8,693.5,692.9 +0.6711152003209173,0.7708832972569697,0.916297857297023,2325.1,1142.8,1201.3,543.0,691.4,750.1 +0.6711081574725304,0.7709105447404092,1.0471975511965976,2186.4,1256.4,1049.9,598.9,752.3,879.4 +0.6711007984034932,0.7709215426944727,1.1780972450961724,1531.6,960.9,740.0,767.7,909.4,1128.4 +0.6710538834493905,0.7709663128685438,1.3089969389957472,1244.5,739.1,611.4,833.3,1290.2,1669.0 +0.671018770197189,0.7709868876805002,1.4398966328953218,1120.7,623.8,565.4,711.5,2361.2,2303.0 +0.6710404394279247,0.770982735349339,1.5707963267948966,1099.0,570.9,570.8,662.9,2251.3,2250.9 +0.6709855575389565,0.7709815044121617,1.7016960206944713,1163.0,564.7,623.1,669.0,2303.2,2362.3 +0.6709385873765007,0.7709677524581386,1.832595714594046,1070.2,612.3,739.9,740.3,2553.2,2160.1 +0.6709578181359191,0.7709814154346362,1.9634954084936205,738.0,797.9,909.6,913.3,1744.2,1525.0 +0.6709481846338041,0.7709733868148987,2.0943951023931953,598.9,879.6,752.3,1314.4,1384.2,1256.5 +0.6709215513616443,0.7709229522291208,2.2252947962927703,543.4,750.3,691.5,2324.9,1201.5,1142.9 +0.6709192728312499,0.7709134570341694,2.356194490192345,541.5,692.9,693.5,2220.5,1128.6,1129.1 +0.67091749835376,0.7709129250904303,2.4870941840919194,586.3,691.5,750.3,2282.5,1143.1,1202.3 +0.670929706020832,0.7708768506347567,2.6179938779914944,692.5,753.1,880.8,2456.7,1257.0,1047.7 +0.6709309764919109,0.7708708901169197,2.748893571891069,879.8,910.7,1130.7,1689.1,959.0,738.7 +0.6709578404628115,0.7708479000856054,2.8797932657906435,739.6,1291.3,1671.1,1337.3,739.1,611.7 +0.6709686480728968,0.7708433514303863,3.010692959690218,669.1,2363.2,2304.2,1164.0,624.0,565.2 +0.6710216056383358,0.8711433191103313,0.0,762.9,2250.9,2251.0,999.1,571.0,570.9 +0.670986279923958,0.8706698528665244,0.1308996938995747,816.5,2305.2,2364.3,1017.7,565.3,624.6 +0.6709365884725776,0.8711464418620409,0.2617993877991494,948.6,2340.9,1961.1,1128.8,611.7,739.2 +0.6709209604015242,0.8711362694340947,0.39269908169872414,1215.4,1603.3,1384.3,896.9,740.2,960.9 +0.6709056439638702,0.8711209989186515,0.5235987755982988,1788.3,1268.5,1140.8,691.9,996.6,869.0 +0.6709042770229022,0.8711147714972498,0.6544984694978736,2282.8,1098.3,1039.5,586.1,854.3,795.2 +0.6708965994951576,0.8710860335952788,0.7853981633974483,2221.4,1028.9,1028.3,540.8,793.6,793.1 +0.6708974963676224,0.8710924783974143,0.916297857297023,2325.6,1039.1,1097.8,543.0,795.1,854.0 +0.6709054112105999,0.8710695128099375,1.0471975511965976,1985.7,1141.0,1049.5,599.1,868.1,995.3 +0.6709233807276243,0.871039147766663,1.1780972450961724,1389.0,960.5,739.8,736.8,1051.2,1270.5 +0.6709083381897978,0.8710528894886171,1.3089969389957472,1128.6,739.0,611.4,948.7,1490.8,1870.0 +0.6709092579262316,0.8710528511853193,1.4398966328953218,1016.9,623.6,565.3,815.2,2487.6,2303.0 +0.6709686602136401,0.8710389983859186,1.5707963267948966,999.1,571.0,570.7,763.2,2251.1,2251.3 +0.670949376414833,0.8710377462279453,1.7016960206944713,1059.6,564.7,623.2,772.8,2304.0,2362.3 +0.6709344881014313,0.871032256269507,1.832595714594046,1069.4,612.4,740.1,856.5,2338.2,1959.0 +0.6709807973286166,0.8710615971132345,1.9634954084936205,737.6,741.0,962.1,1055.7,1602.5,1383.3 +0.6709914631487347,0.8710741566153073,2.0943951023931953,598.7,995.3,867.9,1515.2,1267.7,1140.5 +0.6709780365618052,0.8710467379595455,2.2252947962927703,543.3,853.7,795.1,2324.5,1097.7,1039.1 +0.6709818577257911,0.8710613828180735,2.356194490192345,541.5,793.0,793.8,2220.5,1028.2,1029.1 +0.6709793028850519,0.8710841524654385,2.4870941840919194,586.3,795.2,854.3,2282.8,1039.2,1098.5 +0.670985217417694,0.8710684082598443,2.6179938779914944,692.6,869.3,996.7,2255.7,1141.2,1047.2 +0.6709753851652238,0.8710791570834062,2.748893571891069,899.0,1052.7,1272.7,1546.5,958.4,738.6 +0.6709884569566065,0.8710681112832641,2.8797932657906435,855.2,1491.7,1871.9,1221.2,738.9,611.5 +0.6709839705977533,0.8710706926475418,3.010692959690218,772.7,2474.6,2304.5,1060.1,623.7,565.0 +0.1709092685104756,0.17096520315023578,0.0,63.2,2750.9,2750.9,1699.1,71.0,71.0 +0.17089403529843938,0.17147378025398985,0.1308996938995747,91.6,2823.2,2882.7,823.1,47.4,106.7 +0.17088346034299,0.17146960154974877,0.2617993877991494,139.5,3130.6,3258.8,349.0,187.7,95.3 +0.17083684705663324,0.17143920738366925,0.39269908169872414,223.8,2592.0,2373.0,191.2,110.0,63.0 +0.17079180869301336,0.17139127923636743,0.5235987755982988,393.2,2077.8,1950.3,113.9,50.8,59.8 +0.17077027892494348,0.1713464945841343,0.6544984694978736,912.8,1823.2,1763.8,68.5,129.5,70.5 +0.1707532883198432,0.17127698041928863,0.7853981633974483,2721.5,1728.9,1727.9,40.9,93.8,93.2 +0.1707554242213235,0.1712447106950128,0.916297857297023,2842.6,973.2,150.1,25.5,70.7,129.5 +0.17077368437427257,0.17118700135006448,1.0471975511965976,3210.6,431.7,51.5,106.4,59.5,186.8 +0.1708090867148418,0.17112778303816034,1.1780972450961724,2380.8,252.3,31.4,31.1,63.4,282.5 +0.1708161335440786,0.17111996097236815,1.3089969389957472,1937.3,161.1,33.4,72.1,95.6,474.8 +0.17084206841207317,0.17110576281174716,1.4398966328953218,1740.8,106.5,93.6,91.1,238.6,1067.2 +0.17092762964215824,0.1710849577829361,1.5707963267948966,1698.6,70.9,70.7,63.3,2751.6,2750.9 +0.17089092972691944,0.1710846225336431,1.7016960206944713,233.7,47.4,105.8,48.6,2821.0,2995.2 +0.17092536981601678,0.17109342161400654,1.832595714594046,73.6,187.8,95.6,47.1,3132.6,3259.6 +0.17099543081908053,0.17113676103327546,1.9634954084936205,32.1,110.2,63.3,63.7,2590.6,2371.2 +0.1710194227283933,0.17116263067749138,2.0943951023931953,21.1,51.0,59.5,117.4,2102.1,1949.2 +0.17101355578216024,0.17114846420930774,2.2252947962927703,25.7,129.5,70.7,319.5,1821.7,1763.5 +0.17102067251823855,0.1711763287575323,2.356194490192345,41.5,93.3,93.8,2720.4,1728.3,1728.4 +0.17101774807006256,0.17121152078013724,2.4870941840919194,68.5,70.5,129.6,2800.5,968.4,149.5 +0.17102012875112743,0.17120663033957206,2.6179938779914944,73.8,59.9,187.6,3119.7,430.4,51.4 +0.17100442263749796,0.1712261138288509,2.748893571891069,62.7,62.8,282.8,2536.9,251.5,31.6 +0.171010025717319,0.17122127558145683,2.8797932657906435,46.6,95.0,474.9,2030.2,161.1,33.7 +0.17099735384824766,0.17122744606389384,3.010692959690218,48.2,235.2,1058.1,1784.8,106.3,93.0 +0.17098106774252683,0.17123209408627327,0.0,63.3,2751.3,2750.9,1698.5,71.0,70.9 +0.1709190085791207,0.17123079374565897,0.1308996938995747,91.6,2823.1,2882.7,823.3,47.4,106.8 +0.17093462810328441,0.171234484485705,0.2617993877991494,139.6,3131.7,3259.0,349.0,187.9,95.4 +0.1709304716066916,0.17123059537945462,0.39269908169872414,223.9,2591.3,2372.5,191.1,110.1,63.1 +0.17092249760665326,0.17122238750266905,0.5235987755982988,393.4,2078.0,1950.4,113.9,50.7,59.9 +0.17092571228016795,0.1712237405745305,0.6544984694978736,912.8,1823.1,1764.0,68.5,129.6,70.5 +0.17092006147274905,0.17120282408314624,0.7853981633974483,2721.0,1728.9,1728.3,40.8,93.8,93.3 +0.17092077881858342,0.17121674142223853,0.916297857297023,2842.2,972.9,149.9,25.4,70.7,129.5 +0.17092650592067582,0.17120041002440067,1.0471975511965976,3209.9,431.5,51.4,106.3,59.5,186.8 +0.17094070696467015,0.17117525335973816,1.1780972450961724,2381.1,252.2,31.3,31.1,63.3,282.4 +0.17092101986649744,0.1711926099834873,1.3089969389957472,1937.7,161.1,33.4,72.0,95.5,474.8 +0.17091686695149474,0.17119459867183662,1.4398966328953218,1740.7,106.4,93.6,91.1,238.3,1067.1 +0.17097121617594205,0.17118104967056125,1.5707963267948966,1698.7,70.9,70.7,63.3,2750.9,2751.0 +0.17090198467026915,0.17117990725414667,1.7016960206944713,233.6,47.4,105.8,48.6,2820.7,2995.5 +0.1709126709234959,0.17118160071284705,1.832595714594046,73.6,187.8,95.6,47.0,3131.6,3259.9 +0.1709615444869056,0.17121175887709605,1.9634954084936205,32.1,110.2,63.3,63.7,2589.8,2371.0 +0.17096949868132671,0.17122050593064597,2.0943951023931953,21.1,51.1,59.5,117.3,2076.4,1949.0 +0.17095336897845426,0.17118724858339274,2.2252947962927703,25.8,129.5,70.7,319.4,1822.2,1763.8 +0.17095586708318994,0.17119532778295143,2.356194490192345,41.5,93.2,93.8,2720.3,1728.0,1728.7 +0.17095359593868328,0.17121163317696286,2.4870941840919194,68.5,70.5,129.6,2800.7,968.5,149.6 +0.17096102606783192,0.17119015087457368,2.6179938779914944,73.8,59.9,187.6,3120.2,430.5,51.4 +0.17095390246180428,0.17119592817004348,2.748893571891069,62.7,62.8,282.8,2536.4,251.6,31.6 +0.17097036265128257,0.17118095579777304,2.8797932657906435,46.6,95.0,474.8,2030.5,161.2,33.8 +0.17096982717367643,0.17118066322177383,3.010692959690218,48.2,235.3,1058.3,1784.7,106.3,93.1 +0.7711077925466276,0.3712211487664774,0.0,263.3,2151.1,2151.4,1498.5,670.8,670.9 +0.7710473919188671,0.3709689725647414,0.1308996938995747,298.6,2201.4,2261.3,1535.7,669.0,728.3 +0.7710472667179987,0.3709690939151913,0.2617993877991494,370.6,2438.0,2565.4,1545.7,727.4,494.0 +0.7710383103295009,0.3709635793639332,0.39269908169872414,506.9,2309.6,2090.1,1038.4,564.6,345.3 +0.7710392062090761,0.3709666148571289,0.5235987755982988,791.4,1846.9,1719.1,807.5,418.6,290.9 +0.77105057501103,0.3709851126395918,0.6544984694978736,1683.3,1616.5,1557.3,689.9,336.5,277.4 +0.7710487122192451,0.3709834776541092,0.7853981633974483,2121.4,1528.7,1528.5,640.8,293.6,293.0 +0.7710484777473008,0.37101599806488283,0.916297857297023,2221.6,1556.7,1615.6,646.4,277.5,336.2 +0.7710490732599822,0.3710164226986663,1.0471975511965976,2517.0,1629.5,1249.5,714.5,290.3,417.6 +0.7710548966773118,0.3710052167434166,1.1780972450961724,2098.5,1102.6,881.8,507.5,345.3,564.4 +0.7710247435238091,0.37103322708071174,1.3089969389957472,1732.3,854.8,727.2,370.9,493.8,872.8 +0.7710087280791635,0.3710425797268402,1.4398966328953218,1534.3,727.2,668.9,297.8,1017.0,1845.4 +0.771050513994863,0.37103302491015167,1.5707963267948966,1498.8,671.0,670.8,263.1,2151.4,2150.8 +0.7710146886546742,0.3710316468420316,1.7016960206944713,1576.7,668.1,726.6,255.3,2200.3,2258.3 +0.7709849188011401,0.37102229374285445,1.832595714594046,1269.3,728.0,493.6,278.1,2438.0,2566.2 +0.7710186491654623,0.37104439773011855,1.9634954084936205,879.0,564.4,345.3,346.8,2308.3,2089.0 +0.7710198162548135,0.3710474859761965,2.0943951023931953,714.4,417.6,290.3,516.4,1845.8,1718.4 +0.7710000801643225,0.37100948947670376,2.2252947962927703,646.9,336.3,277.5,1093.0,1615.5,1556.5 +0.7710008080773307,0.3710129810427487,2.356194490192345,641.5,293.0,293.6,2120.5,1528.3,1529.1 +0.7709983213944464,0.3710248799584299,2.4870941840919194,689.9,277.4,336.5,2179.3,1557.1,1616.3 +0.7710068556584355,0.37099954579099736,2.6179938779914944,515.9,290.9,418.6,2426.0,1625.8,1246.9 +0.7710019680546566,0.37100227688863363,2.748893571891069,345.4,345.3,565.4,2254.0,1100.3,880.1 +0.7710213253981524,0.37098538024282934,2.8797932657906435,277.5,493.6,873.6,1799.1,854.6,727.1 +0.7710239527866745,0.37098435143058617,3.010692959690218,255.0,1008.7,1831.8,1577.8,727.5,668.7 +0.7710674969456309,0.4712771323266325,0.0,363.0,2151.5,2151.1,1399.0,671.0,671.0 +0.7710175777190351,0.47069485056482696,0.1308996938995747,402.2,2201.7,2261.0,1432.1,668.9,832.1 +0.7710454063931423,0.47070400015473,0.2617993877991494,486.0,2438.2,2565.4,1545.5,785.8,693.2 +0.7710794892501488,0.47072607366747965,0.39269908169872414,648.5,2168.4,1949.6,1038.3,705.6,486.4 +0.7711069241851509,0.47075808843385936,0.5235987755982988,990.7,1756.7,1603.6,807.6,534.1,406.5 +0.7711122523714428,0.4707644875835477,0.6544984694978736,2068.8,1512.4,1453.7,689.8,439.9,380.8 +0.7711244879570811,0.47082390089414594,0.7853981633974483,2121.2,1429.0,1428.6,640.9,393.5,393.0 +0.7711231685387023,0.4708914624622469,0.916297857297023,2221.6,1453.1,1512.2,646.4,380.9,439.7 +0.7711166404237942,0.47091611047323245,1.0471975511965976,2517.3,1603.3,1249.2,714.7,405.8,533.0 +0.7711116745443269,0.47088864950353826,1.1780972450961724,1956.5,1102.6,881.6,648.9,486.2,705.3 +0.7708650438789505,0.4708494108148915,1.3089969389957472,1590.9,854.4,727.0,486.1,693.4,1073.2 +0.7708791382546208,0.4708427616206532,1.4398966328953218,1430.6,727.3,668.8,401.0,1409.3,2176.7 +0.770957387761328,0.47082560325668044,1.5707963267948966,1399.0,670.9,670.7,363.0,2151.3,2150.8 +0.7709568571746359,0.4708259015838252,1.7016960206944713,1473.4,668.2,843.4,358.8,2200.3,2259.1 +0.7709588176038374,0.4708262571076749,1.832595714594046,1268.1,784.3,692.1,393.7,2439.4,2566.8 +0.7710189380426672,0.4708652522518333,1.9634954084936205,878.5,705.0,486.0,488.9,2165.8,1946.9 +0.7710395307228842,0.47088968087802163,2.0943951023931953,714.1,532.8,405.8,716.5,1729.5,1602.4 +0.771006846757127,0.4708247512917323,2.2252947962927703,646.8,439.6,381.0,1483.6,1511.7,1452.9 +0.7710218527691558,0.470889730196965,2.356194490192345,641.5,392.9,393.6,2120.8,1428.4,1429.4 +0.7710183334104717,0.47093336785253803,2.4870941840919194,689.9,380.8,440.1,2179.4,1453.9,1513.0 +0.7710214133197284,0.4709275995057449,2.6179938779914944,714.1,406.6,534.4,2426.9,1604.3,1245.8 +0.7710080801094376,0.4709444524943218,2.748893571891069,486.3,486.9,707.0,2111.7,1099.3,879.5 +0.7710175817633309,0.47093753694030305,2.8797932657906435,392.8,693.6,1073.8,1683.0,854.3,727.0 +0.7710091903893327,0.47094301928451787,3.010692959690218,358.5,1398.4,2177.7,1474.5,727.2,668.6 +0.7710391733880472,0.5712256128014241,0.0,463.0,2150.9,2151.2,1299.0,670.9,671.1 +0.7709703207207006,0.5706856290751312,0.1308996938995747,505.8,2201.7,2261.4,1328.6,669.0,728.3 +0.7710206146918591,0.5707017363676719,0.2617993877991494,601.7,2437.9,2565.4,1475.4,727.5,848.7 +0.7710597206636702,0.5707269603546403,0.39269908169872414,790.2,2026.7,1807.7,1038.2,846.9,627.3 +0.7710874544065719,0.5707592415530098,0.5235987755982988,1190.0,1615.9,1487.9,807.6,649.6,522.0 +0.7711137870602547,0.570806210251767,0.6544984694978736,2179.5,1409.2,1350.2,689.8,543.4,484.4 +0.771118440701887,0.570832592755786,0.7853981633974483,2121.1,1329.1,1328.6,640.8,493.4,493.1 +0.771117523285382,0.5708910843292567,0.916297857297023,2221.9,1349.9,1408.7,646.4,484.5,543.2 +0.7711114127143124,0.5709146738332775,1.0471975511965976,2517.3,1487.9,1249.0,714.7,521.3,648.5 +0.7711058431246655,0.5709227371191321,1.1780972450961724,1814.6,1102.4,881.4,790.6,627.5,846.6 +0.7710611716184061,0.5709652155912681,1.3089969389957472,1475.5,854.8,727.2,601.9,892.0,1271.7 +0.771028629894593,0.5709841464990875,1.4398966328953218,1327.6,727.2,668.8,504.5,1796.6,2199.7 +0.7710530528382993,0.5709793984924885,1.5707963267948966,1299.1,670.9,670.8,463.0,2151.0,2151.2 +0.7709501251426856,0.5709792191423868,1.7016960206944713,1370.0,668.2,726.6,462.2,2266.4,2259.0 +0.7709380712637691,0.5709759373230276,1.832595714594046,1269.0,728.0,847.8,509.1,2438.3,2565.6 +0.7709652189447034,0.5709946204927607,1.9634954084936205,879.0,846.4,627.1,630.1,2026.0,1807.4 +0.7709559939292691,0.5709872388902286,2.0943951023931953,714.4,648.5,521.2,915.4,1614.5,1487.4 +0.7709284584750519,0.5709351187253793,2.2252947962927703,646.9,543.1,484.5,1868.6,1431.4,1349.8 +0.7709255493546234,0.5709230684637634,2.356194490192345,641.7,492.9,493.6,2120.4,1328.5,1329.1 +0.7709237044590995,0.5709198992575271,2.4870941840919194,689.9,484.3,543.5,2179.3,1350.3,1409.6 +0.7709366322314479,0.5707556122454573,2.6179938779914944,808.2,522.1,649.8,2426.3,1488.4,1246.6 +0.7711732651979953,0.5710385253440537,2.748893571891069,628.4,627.7,847.6,1972.3,1100.8,880.7 +0.7711704712895568,0.5710418947954392,2.8797932657906435,508.6,891.8,1271.1,1568.6,855.1,727.5 +0.7711492309004062,0.5710534842264514,3.010692959690218,462.1,1779.4,2201.3,1371.3,727.6,668.7 +0.7709820656234009,0.6710979592945427,0.0,563.2,2151.3,2151.1,1198.9,671.1,671.1 +0.7709906358778925,0.6710976144240732,0.1308996938995747,609.3,2201.7,2261.2,1224.8,668.9,728.1 +0.7709826480754004,0.6710949583867662,0.2617993877991494,717.4,2437.7,2360.9,1359.9,727.4,855.0 +0.7709717485087454,0.6710878996192484,0.39269908169872414,932.0,1886.2,1666.7,1038.4,881.8,768.9 +0.7709618125375458,0.6710787738099728,0.5235987755982988,1389.3,1499.9,1372.3,807.5,765.6,637.8 +0.7709642630046402,0.6710801100655064,0.6544984694978736,2305.4,1305.3,1246.5,689.9,647.1,588.1 +0.7709581801084413,0.6710593796718174,0.7853981633974483,2121.2,1228.8,1228.4,641.0,593.7,593.1 +0.7709586504538047,0.6710734566083243,0.916297857297023,2221.6,1246.1,1305.0,646.6,588.1,646.9 +0.7709643357217422,0.671057279649588,1.0471975511965976,2385.5,1371.9,1249.1,714.6,636.9,764.4 +0.7709786747655782,0.6710323855115969,1.1780972450961724,1672.8,1102.3,881.6,878.0,768.7,988.0 +0.7709592012319563,0.6710501909205993,1.3089969389957472,1359.7,854.7,727.1,717.7,1091.6,1470.9 +0.7709552057123167,0.6710528442400767,1.4398966328953218,1223.7,727.2,668.9,608.3,2186.8,2199.6 +0.7710095169104519,0.6710401462440096,1.5707963267948966,1198.9,670.9,670.7,563.2,2151.1,2151.1 +0.7709854775517185,0.6710388310109028,1.7016960206944713,1266.4,668.1,726.6,565.8,2200.4,2258.6 +0.7709662997599411,0.6710322864583063,1.832595714594046,1269.2,728.2,855.6,625.0,2438.1,2358.6 +0.7710089746618622,0.6710595755616062,1.9634954084936205,878.8,882.8,768.6,772.1,1884.8,1665.8 +0.7710168768910608,0.671069427261966,2.0943951023931953,714.4,764.1,637.0,1115.6,1499.1,1371.8 +0.7710015440441734,0.6710390213551336,2.2252947962927703,647.0,646.9,588.2,2198.4,1305.0,1245.9 +0.7710043623812552,0.6710504810761142,2.356194490192345,641.6,593.1,593.8,2120.3,1228.4,1229.0 +0.7710017421063624,0.6710700785591805,2.4870941840919194,689.8,588.1,647.1,2178.8,1246.3,1305.7 +0.771008292294447,0.6710515246044451,2.6179938779914944,859.0,637.7,765.6,2426.1,1372.4,1246.6 +0.7709998578911195,0.6710598586155401,2.748893571891069,769.6,769.7,989.8,1829.8,1100.0,880.0 +0.7710147087165656,0.6710470321377848,2.8797932657906435,624.4,1092.3,1472.3,1452.3,854.5,727.1 +0.7710122912320077,0.6710484883923646,3.010692959690218,565.6,2170.8,2201.3,1267.4,727.5,668.6 +0.7710498058654142,0.7713366495729506,0.0,663.1,2150.8,2151.0,1099.1,670.9,671.1 +0.7710051573831442,0.7707034819262508,0.1308996938995747,712.9,2201.7,2260.5,1121.5,668.8,728.2 +0.7710330300609829,0.770712601243188,0.2617993877991494,832.8,2438.2,2161.6,1244.2,727.3,1004.5 +0.7710663884623817,0.7707341536222876,0.39269908169872414,1073.5,1745.1,1525.7,1038.2,944.0,909.9 +0.7710930919154185,0.770765290453741,0.5235987755982988,1588.2,1384.8,1256.9,807.6,881.3,753.4 +0.771119552921839,0.7708124044424267,0.6544984694978736,2179.0,1202.1,1143.1,689.8,750.6,691.5 +0.7711243232133315,0.7708393928302917,0.7853981633974483,2121.5,1129.0,1128.5,640.8,693.6,692.9 +0.7711234001527026,0.7708986703545868,0.916297857297023,2221.3,1142.9,1201.4,646.5,691.3,750.3 +0.7711170599748617,0.7709230141787333,1.0471975511965976,2186.1,1256.3,1249.3,714.5,752.4,879.6 +0.7711110509726983,0.7709316265875255,1.1780972450961724,1531.3,1102.6,881.6,877.8,909.6,1128.8 +0.7710658748397283,0.7709745357482687,1.3089969389957472,1244.5,854.6,727.0,833.1,1290.4,1669.5 +0.7710327822445718,0.7709937913868323,1.4398966328953218,1120.7,727.2,668.9,711.5,2258.2,2199.8 +0.7710566277539649,0.7709890659924363,1.5707963267948966,1099.2,670.8,670.7,663.0,2151.1,2151.0 +0.7710038114387334,0.7709878176294902,1.7016960206944713,1162.9,668.2,726.5,669.0,2199.8,2258.6 +0.7709587194044597,0.7709744999472528,1.832595714594046,1269.3,728.0,1003.6,740.3,2438.5,2159.3 +0.7709795067474977,0.770989121032009,1.9634954084936205,878.9,945.2,909.6,913.5,1744.0,1525.0 +0.7709709848234211,0.7709823766824135,2.0943951023931953,714.5,879.6,752.4,1314.5,1383.9,1256.5 +0.7709450494416585,0.7709333010185007,2.2252947962927703,646.9,750.3,691.4,2221.0,1201.8,1142.7 +0.7709430257170952,0.7709252092152625,2.356194490192345,641.6,693.0,693.6,2120.2,1128.5,1129.1 +0.7709410543098626,0.7709260284872834,2.4870941840919194,689.8,691.4,750.5,2178.9,1143.2,1202.1 +0.7709528134381102,0.7708910528225474,2.6179938779914944,808.1,753.3,880.8,2426.3,1256.5,1246.9 +0.7709533155038991,0.770885983550402,2.748893571891069,910.8,910.9,1130.9,1688.6,1100.4,880.1 +0.7709793573333499,0.770863571946119,2.8797932657906435,739.7,1291.5,1671.2,1337.0,854.5,727.2 +0.7709892933545825,0.7708593348794959,3.010692959690218,669.0,2259.5,2200.9,1164.2,727.5,668.8 +0.7710413029118193,0.8711585952298249,0.0,763.0,2150.8,2151.0,999.2,671.1,671.0 +0.7710021681572121,0.8706729252688201,0.1308996938995747,816.4,2201.7,2260.8,1017.9,668.9,728.3 +0.7710347416581104,0.8706835769583445,0.2617993877991494,948.3,2342.0,1961.9,1128.4,727.2,854.8 +0.7710717196996879,0.870707473184958,0.39269908169872414,1215.0,1604.0,1384.7,1038.4,939.5,1051.2 +0.7711010464932314,0.8707415019170504,0.5235987755982988,1787.3,1268.7,1141.1,807.5,996.7,869.0 +0.7711291469412302,0.8707917552380953,0.6544984694978736,2179.6,1098.8,1039.5,689.8,854.2,794.9 +0.7711346540334162,0.8708219696822064,0.7853981633974483,2121.2,1029.0,1028.4,640.8,793.5,792.9 +0.7711336391176838,0.8708842818340972,0.916297857297023,2221.6,1039.2,1098.1,646.5,795.0,853.7 +0.7711264993985119,0.870911343050295,1.0471975511965976,1986.4,1141.1,1249.6,714.5,867.8,995.2 +0.7711191394621797,0.8709222133060548,1.1780972450961724,1389.6,1102.6,881.6,908.8,1050.8,1269.6 +0.7710722491482401,0.8709668163709199,1.3089969389957472,1128.9,854.6,727.1,948.8,1489.7,1868.6 +0.7710372105654071,0.8709871933222226,1.4398966328953218,1017.1,727.3,668.9,815.0,2257.9,2199.3 +0.7710590146722174,0.8709830260547995,1.5707963267948966,999.0,671.0,670.7,762.8,2151.1,2150.8 +0.7710042629301752,0.8709817995955413,1.7016960206944713,1059.7,668.1,726.6,772.5,2200.1,2258.9 +0.7709574244530824,0.8709680322165443,1.832595714594046,1221.8,728.1,855.8,855.9,2339.6,1960.4 +0.7709767312098764,0.8709818102873623,1.9634954084936205,879.0,939.0,1050.7,1055.1,1603.1,1383.8 +0.7709670938481037,0.8709739566577528,2.0943951023931953,714.5,995.4,867.8,1514.4,1268.2,1140.8 +0.7709404422866557,0.870923619655843,2.2252947962927703,646.9,853.9,795.0,2221.3,1097.9,1039.4 +0.7709356591566155,0.8709079034556915,2.356194490192345,641.5,793.0,793.4,2120.5,1028.5,1029.1 +0.7709336191695183,0.8709120510898072,2.4870941840919194,689.8,795.0,854.0,2179.2,1039.5,1098.5 +0.7709454862160919,0.8708767730091598,2.6179938779914944,808.1,868.9,996.6,2256.5,1141.2,1246.9 +0.7709467544637177,0.8708705521753284,2.748893571891069,1021.2,1052.2,1272.4,1547.2,1100.3,880.2 +0.7709740170341968,0.8708470763680274,2.8797932657906435,855.2,1490.9,1870.5,1221.7,854.6,727.2 +0.7709854012092205,0.870842142150358,3.010692959690218,772.5,2259.8,2200.9,1060.5,727.5,668.7 +0.17094299331062845,0.17079401417442486,0.0,63.0,2750.8,2750.7,1698.8,71.0,71.0 +0.17092331870826427,0.1714322778391859,0.1308996938995747,91.5,2822.7,2882.2,824.0,47.5,106.7 +0.1709159688307552,0.1714292415661416,0.2617993877991494,139.5,3131.4,3259.0,349.2,187.8,95.3 +0.1708736047011646,0.17140173288949034,0.39269908169872414,223.7,2592.6,2372.4,191.3,110.1,63.0 +0.17083202666570407,0.17135785857675323,0.5235987755982988,393.1,2078.0,1950.9,114.0,50.8,59.8 +0.1708127676475407,0.17131771327016532,0.6544984694978736,911.9,1823.5,1764.2,68.6,129.6,70.4 +0.17079661540327096,0.1712529105477194,0.7853981633974483,2721.1,1729.0,1728.2,40.9,93.8,93.2 +0.1707984642750512,0.1712251120207493,0.916297857297023,2842.2,974.1,150.4,25.5,70.7,129.5 +0.1708153988983482,0.17117135634478275,1.0471975511965976,3209.8,432.0,51.6,106.4,59.5,186.7 +0.1708486533578171,0.1711152539425831,1.1780972450961724,2381.7,252.4,31.4,31.2,63.3,282.3 +0.17085313944250546,0.17110978364700302,1.3089969389957472,1938.0,161.1,33.5,72.1,95.6,474.6 +0.17087625005716703,0.1710972160731996,1.4398966328953218,1741.1,106.5,93.6,91.1,238.2,1066.1 +0.17095886697855872,0.17107705906653403,1.5707963267948966,1698.6,71.0,70.7,63.3,2751.5,2750.6 +0.17091882053602644,0.17107671567060478,1.7016960206944713,234.0,47.4,105.8,48.6,2821.2,2997.2 +0.1709511370874667,0.1710851255513579,1.832595714594046,73.7,187.9,95.6,47.1,3130.8,3259.2 +0.1710191285320595,0.17112736392380135,1.9634954084936205,32.2,110.3,63.3,63.6,2591.0,2371.6 +0.17104147407516065,0.171151653191828,2.0943951023931953,21.1,51.1,59.5,117.3,2076.6,1949.2 +0.171034398966939,0.17113575960544458,2.2252947962927703,25.8,129.5,70.7,319.1,1822.3,1763.6 +0.1710408467395284,0.17116173663309886,2.356194490192345,41.5,93.3,93.8,2720.4,1728.0,1728.7 +0.17103787482310778,0.17119498381232234,2.4870941840919194,68.5,70.5,129.5,2801.2,969.4,149.8 +0.17104058910453068,0.17118839653024698,2.6179938779914944,73.9,59.9,187.5,3119.0,430.7,51.5 +0.17102578043302552,0.17120638352281725,2.748893571891069,62.7,62.7,282.6,2537.1,251.6,31.6 +0.17103246681430445,0.17120047070457467,2.8797932657906435,46.6,94.9,474.6,2030.6,161.3,33.8 +0.17102107264245758,0.17120598160588774,3.010692959690218,48.2,235.0,1057.2,1784.9,106.4,93.1 +0.17100604945890474,0.1712103973693,0.0,63.2,2751.2,2751.5,1698.9,71.0,71.0 +0.17094509195392515,0.1712092350674166,0.1308996938995747,91.6,2823.1,2882.6,824.0,47.5,106.7 +0.17096185951503967,0.17121342178498544,0.2617993877991494,139.6,3130.6,3258.8,349.3,188.0,95.4 +0.1709585096622749,0.17121024830264808,0.39269908169872414,223.8,2592.6,2373.1,191.3,110.2,63.1 +0.170950988571967,0.17140905730090283,0.5235987755982988,393.2,2078.1,1950.2,113.9,50.7,59.9 +0.17095504798791117,0.17120338096588683,0.6544984694978736,912.0,1823.3,1764.4,68.5,129.6,70.5 +0.17094955992983882,0.171184001680595,0.7853981633974483,2721.1,1728.9,1728.0,40.9,93.8,93.2 +0.1709501042162217,0.1711990254715643,0.916297857297023,2842.6,973.8,150.1,25.4,70.7,129.4 +0.17095547187338578,0.17118351362873718,1.0471975511965976,3209.4,431.8,51.5,106.4,59.5,186.7 +0.17096916889242733,0.17115887356338622,1.1780972450961724,2381.7,252.3,31.3,31.1,63.3,282.3 +0.17094898928130114,0.171176654248957,1.3089969389957472,1938.0,161.1,33.4,72.1,95.5,474.6 +0.17094433603131462,0.1711790312366095,1.4398966328953218,1741.1,106.5,93.6,91.1,238.1,1066.0 +0.17099814971282393,0.17116558813765437,1.5707963267948966,1698.8,71.0,70.7,63.3,2751.4,2751.0 +0.17092808246653146,0.17116450873330935,1.7016960206944713,234.0,47.4,105.8,48.6,2820.8,2998.0 +0.17093847158840497,0.17116635842938344,1.832595714594046,73.7,187.8,95.5,47.0,3131.3,3259.9 +0.17098690438181524,0.17119643535567564,1.9634954084936205,32.2,110.2,63.3,63.6,2590.8,2371.5 +0.17099444323438936,0.17120492721912406,2.0943951023931953,21.2,51.1,59.4,117.3,2077.1,1949.3 +0.17097789713487657,0.1711714111803484,2.2252947962927703,25.8,129.5,70.7,319.0,1822.5,1763.2 +0.17098008411442495,0.17117912540632596,2.356194490192345,41.5,93.3,93.8,2720.3,1728.5,1728.8 +0.17097771263016032,0.1711949444135794,2.4870941840919194,68.5,70.5,129.5,2800.7,969.5,149.8 +0.17098509182951718,0.1711730429915166,2.6179938779914944,73.9,59.9,187.5,3119.4,430.6,51.5 +0.17097819892362495,0.17117838409559227,2.748893571891069,62.7,62.7,282.6,2536.9,251.7,31.6 +0.17099490634240097,0.17116311921627214,2.8797932657906435,46.6,94.9,474.6,2030.2,161.3,33.8 +0.1709947115817902,0.17116266553297144,3.010692959690218,48.2,235.0,1057.4,1785.3,106.4,93.1 +0.8711051172753922,0.37119483681523313,0.0,263.2,2051.3,2051.0,1498.9,771.0,771.0 +0.8710450687612221,0.37097778503217826,0.1308996938995747,298.6,2098.5,2157.3,1535.6,772.5,831.8 +0.8710449441415642,0.3709778959560781,0.2617993877991494,370.6,2322.3,2449.7,1706.3,829.8,494.0 +0.8710351634168318,0.37097184116648485,0.39269908169872414,506.8,2309.4,2090.5,1179.4,564.6,345.3 +0.8710352238911304,0.3709739539210215,0.5235987755982988,791.6,1846.9,1719.3,923.3,418.7,291.0 +0.8710460175748415,0.3709913479226541,0.6544984694978736,1683.1,1616.3,1557.1,793.2,336.5,277.4 +0.8710438917940372,0.3709885418110226,0.7853981633974483,2021.1,1529.0,1528.4,741.1,293.6,293.0 +0.8710436967704133,0.3710199487640511,0.916297857297023,2118.0,1556.8,1615.3,750.0,277.5,336.3 +0.8710445942025389,0.37101937514307104,1.0471975511965976,2401.6,1718.7,1449.0,792.7,290.3,417.6 +0.8710509237619753,0.371007343703184,1.1780972450961724,2098.0,1244.3,1023.2,507.5,345.4,564.3 +0.8710214084339466,0.3710347381144812,1.3089969389957472,1706.9,970.4,842.7,370.9,493.7,872.7 +0.8710061129177569,0.37104368648865416,1.4398966328953218,1534.3,830.8,772.3,297.7,1017.1,1845.4 +0.8710486502301348,0.3710339372306295,1.5707963267948966,1499.0,771.0,770.7,263.1,2051.7,2051.0 +0.871013533745181,0.3710325595467019,1.7016960206944713,1576.8,771.6,830.1,255.3,2096.9,2217.5 +0.8709844012723252,0.3710233756820782,1.832595714594046,1468.8,829.1,493.7,278.0,2322.6,2450.3 +0.8710186703788656,0.37104579092396306,1.9634954084936205,1020.1,564.3,345.3,346.8,2308.4,2089.2 +0.8710202431867801,0.37104928549064975,2.0943951023931953,829.9,417.7,290.3,516.3,1845.7,1718.3 +0.8710007699364535,0.3710117477994397,2.2252947962927703,750.4,336.3,277.5,1093.2,1615.3,1556.6 +0.8710016202332262,0.3710157202503268,2.356194490192345,741.5,293.1,293.6,2020.6,1528.5,1528.8 +0.8709991227092253,0.37102808128344167,2.4870941840919194,793.5,277.4,336.5,2053.2,1557.3,1615.9 +0.8710075323515152,0.3710031538923628,2.6179938779914944,515.8,290.9,418.6,2310.4,1719.4,1446.1 +0.8710024295522245,0.37100621798465094,2.748893571891069,345.3,345.4,565.3,2254.2,1241.6,1021.7 +0.8710215131177409,0.3709895619159853,2.8797932657906435,277.5,493.6,873.4,1799.4,970.3,842.8 +0.8710238365523144,0.3709886779101037,3.010692959690218,255.1,1009.0,1831.6,1577.9,831.0,772.2 +0.8710670204780503,0.4712811818704159,0.0,363.0,2050.7,2051.2,1398.9,771.0,771.0 +0.8710171144819376,0.47069549993263116,0.1308996938995747,402.2,2098.4,2157.4,1432.1,772.4,916.7 +0.8710448784986359,0.47070462678400116,0.2617993877991494,486.1,2322.5,2449.7,1590.8,842.9,693.2 +0.8710788954374172,0.4707266552046485,0.39269908169872414,648.4,2168.3,1949.3,1179.4,705.5,486.3 +0.8711062782612559,0.47075860916092305,0.5235987755982988,990.6,1731.4,1603.8,923.1,534.0,406.5 +0.8711331504601169,0.4708066678034375,0.6544984694978736,2069.1,1512.9,1453.7,793.3,439.9,380.9 +0.8711380951442415,0.4708346651366768,0.7853981633974483,2021.0,1428.9,1428.5,740.9,393.6,393.1 +0.8711370594516142,0.47089485373640816,0.916297857297023,2118.4,1453.7,1512.0,750.1,380.9,439.7 +0.8711304033905117,0.47091998717496764,1.0471975511965976,2401.5,1603.3,1449.0,830.1,405.7,533.1 +0.8711239482122486,0.47092926760988174,1.1780972450961724,1956.4,1244.1,1023.3,648.8,486.1,705.4 +0.8710782221283341,0.4709726396649698,1.3089969389957472,1591.4,970.3,842.7,486.3,692.8,1072.0 +0.871044531665898,0.4709921555923604,1.4398966328953218,1431.2,830.7,772.2,401.1,1406.5,2096.0 +0.871067780941755,0.4709876006874094,1.5707963267948966,1398.7,770.9,770.7,362.9,2051.1,2051.2 +0.8710144017961483,0.47098635965090097,1.7016960206944713,1473.3,771.6,875.5,358.7,2096.5,2155.4 +0.870968809554752,0.4709728876465451,1.832595714594046,1468.2,843.6,692.7,393.5,2322.7,2449.9 +0.870989154156942,0.4709872945713358,1.9634954084936205,1020.0,705.1,486.2,488.3,2167.4,1948.3 +0.8709802660587259,0.47098028089795174,2.0943951023931953,829.9,532.9,405.7,715.8,1730.3,1603.2 +0.8709540850789151,0.4709308470835092,2.2252947962927703,750.5,439.7,380.9,1480.3,1512.0,1453.3 +0.8709519157897369,0.4709223677426486,2.356194490192345,741.6,393.0,393.5,2020.6,1428.7,1429.4 +0.870949876174783,0.4709228189830559,2.4870941840919194,917.0,380.8,439.9,2075.7,1453.9,1512.6 +0.870961705125548,0.4708874756285002,2.6179938779914944,714.6,406.4,534.1,2310.2,1603.6,1445.8 +0.8709623182655947,0.47088210888163506,2.748893571891069,486.6,486.7,706.6,2113.0,1241.4,1021.6 +0.8709885779261868,0.47085945606106927,2.8797932657906435,393.0,693.1,1072.9,1684.0,970.4,842.7 +0.8709987699544428,0.4708550644681242,3.010692959690218,358.5,1395.9,2097.2,1474.3,831.1,772.2 +0.8710511139710737,0.5711545929380148,0.0,463.0,2051.1,2050.6,1299.1,771.1,771.0 +0.8710105444069631,0.5706722871428922,0.1308996938995747,505.8,2098.3,2157.2,1328.6,772.4,831.7 +0.8710428818350076,0.5706828829802628,0.2617993877991494,601.6,2322.2,2450.0,1475.3,985.1,892.6 +0.8711209404891458,0.5707288098256098,0.39269908169872414,790.0,2027.3,1808.0,1179.5,846.7,627.5 +0.8708504978435092,0.5710726377251041,0.5235987755982988,1190.9,1615.2,1487.9,923.0,649.6,522.0 +0.8708517633839861,0.5710719504034087,0.6544984694978736,2075.5,1408.8,1349.9,793.1,543.4,484.4 +0.8708442091019829,0.5710427190866334,0.7853981633974483,2020.9,1328.9,1328.5,740.6,493.6,493.0 +0.8708453961454803,0.57104680665096,0.916297857297023,2118.2,1349.6,1408.6,750.0,484.5,543.5 +0.8708544173874166,0.5710212242572978,1.0471975511965976,2401.9,1487.7,1447.9,903.8,521.5,648.9 +0.870874201578852,0.5709887780663556,1.1780972450961724,1813.8,1243.6,1023.0,790.5,627.8,847.0 +0.8708612763273195,0.5710010516395507,1.3089969389957472,1475.2,970.0,842.4,601.9,893.0,1272.4 +0.8708644319889437,0.5710001438417551,1.4398966328953218,1327.0,830.6,772.2,504.7,1799.2,2152.6 +0.8709260340948852,0.5709862275666053,1.5707963267948966,1299.1,770.8,770.7,463.0,2051.4,2051.4 +0.8709086667116859,0.5709853474206497,1.7016960206944713,1369.9,771.6,830.3,462.4,2222.9,2155.0 +0.870895415340549,0.5709804719775036,1.832595714594046,1467.5,983.8,891.7,509.4,2322.7,2450.5 +0.8709866309135815,0.5710340123633901,1.9634954084936205,1019.5,846.3,627.3,630.3,2025.3,1806.4 +0.8709758046429266,0.5710233957530959,2.0943951023931953,829.7,648.6,521.3,916.3,1614.3,1487.1 +0.8709599436224095,0.5709910862279084,2.2252947962927703,750.3,543.3,484.5,1870.9,1408.3,1349.5 +0.8709646018901669,0.5710083860474131,2.356194490192345,741.5,493.0,493.7,2020.5,1328.3,1329.1 +0.8709620726007496,0.5710363300645538,2.4870941840919194,793.4,484.5,543.6,2076.1,1350.0,1409.4 +0.870966732056554,0.5710259371247293,2.6179938779914944,913.7,522.3,650.0,2310.5,1488.4,1444.9 +0.8709542335985561,0.5710415320466375,2.748893571891069,627.8,628.5,848.6,1970.4,1241.0,1020.9 +0.8709638394480144,0.5710342576012701,2.8797932657906435,508.4,893.3,1273.2,1567.7,970.0,842.4 +0.8709552813578157,0.5710394336733138,3.010692959690218,462.1,1785.8,2136.7,1370.7,830.8,772.0 +0.870985042242532,0.6713216963391466,0.0,563.1,2051.0,2051.6,1198.9,770.8,770.8 +0.8709676290948469,0.6706893024377794,0.1308996938995747,609.1,2098.2,2157.5,1225.0,772.3,831.8 +0.8710024552086618,0.6707005453470969,0.2617993877991494,717.1,2321.9,2361.6,1359.7,842.7,970.1 +0.8710385103039638,0.6707237049682264,0.39269908169872414,931.6,1886.6,1667.3,1179.7,988.3,768.8 +0.871066445346867,0.6707560141729716,0.5235987755982988,1388.3,1525.8,1372.7,923.4,765.5,637.7 +0.8710936668420465,0.6708041665407858,0.6544984694978736,2076.2,1305.6,1246.7,793.3,647.0,588.0 +0.8710988041069027,0.6708320940521182,0.7853981633974483,2021.4,1228.9,1228.4,740.8,593.6,592.9 +0.8710980785857314,0.6708923440975187,0.916297857297023,2117.9,1246.2,1304.7,749.9,587.9,646.6 +0.8710749269579361,0.6709719988984149,1.0471975511965976,2401.2,1371.8,1449.4,830.0,636.7,764.0 +0.8710893677061647,0.6709483414842676,1.1780972450961724,1673.6,1244.4,1023.5,932.6,768.5,987.3 +0.8710136893136644,0.6710185739159735,1.3089969389957472,1360.3,970.5,843.0,717.6,1090.8,1469.7 +0.870976626474456,0.6710415069551996,1.4398966328953218,1224.1,830.9,772.4,608.0,2131.4,2095.9 +0.8710282933386498,0.6710304799650824,1.5707963267948966,1198.9,771.1,770.6,562.8,2051.3,2051.3 +0.8709754868301472,0.6710293045813847,1.7016960206944713,1266.2,771.7,830.0,565.5,2096.6,2155.2 +0.8709222099655679,0.6710136308332786,1.832595714594046,1453.1,843.4,971.0,624.7,2322.3,2359.3 +0.870933848636017,0.6710302596269526,1.9634954084936205,1020.2,987.5,768.7,771.4,1885.4,1666.3 +0.8711176108311833,0.6708252353817357,2.0943951023931953,830.1,764.5,637.0,1114.0,1499.7,1372.3 +0.8711178383571566,0.6708254446664428,2.2252947962927703,750.5,647.0,588.1,2118.1,1305.3,1246.4 +0.871127508186272,0.6708683369703567,2.356194490192345,741.5,593.0,593.5,2020.5,1228.6,1229.1 +0.8711239298844206,0.6709175029241399,2.4870941840919194,793.0,587.9,646.7,2075.3,1246.5,1305.4 +0.8711066930027449,0.6709766235513945,2.6179938779914944,923.3,637.5,764.9,2309.7,1371.9,1447.7 +0.8711051565092238,0.6709754491669921,2.748893571891069,770.0,768.9,988.8,1831.4,1242.3,1022.3 +0.8708823250123312,0.6708094991277747,2.8797932657906435,624.2,1092.2,1472.4,1452.3,970.2,842.6 +0.8708963879506009,0.670802829511205,3.010692959690218,565.6,2132.8,2097.4,1267.5,831.0,772.1 +0.8709718352275775,0.7711238045312196,0.0,662.9,2051.0,2050.9,1099.0,771.1,771.1 +0.870963643334784,0.7711237780619133,0.1308996938995747,712.8,2098.1,2157.6,1121.7,772.3,831.8 +0.870925046998205,0.7711125471652645,0.2617993877991494,832.9,2322.7,2160.8,1244.5,843.0,1047.9 +0.870884527003358,0.7710876630695227,0.39269908169872414,1073.4,1744.8,1525.5,1179.4,1023.5,909.6 +0.870851313564622,0.7710541765047014,0.5235987755982988,1588.4,1409.9,1256.7,923.2,880.9,753.2 +0.8708386811582868,0.7710278562350179,0.6544984694978736,2075.4,1202.2,1143.1,793.3,750.6,691.5 +0.8708258674359889,0.7709781973384264,0.7853981633974483,2021.3,1129.0,1128.5,740.9,693.6,693.0 +0.8708273820179264,0.7709648522979824,0.916297857297023,2118.4,1142.6,1201.5,750.1,691.6,750.4 +0.8708408859292142,0.7709242556658544,1.0471975511965976,2185.0,1256.6,1384.0,830.2,752.4,879.8 +0.8708682785351577,0.7708795400519295,1.1780972450961724,1531.0,1244.0,1023.3,1019.2,909.9,1129.2 +0.8708650646886045,0.7708830034235146,1.3089969389957472,1244.4,970.2,842.6,833.2,1291.0,1670.2 +0.8708791292197825,0.7708768012699434,1.4398966328953218,1120.4,830.8,772.2,711.6,2154.2,2096.1 +0.8709518968634827,0.7708606833915408,1.5707963267948966,1099.0,771.0,770.7,663.1,2051.3,2051.0 +0.8709448131603763,0.7708606698528386,1.7016960206944713,1163.0,771.7,830.1,669.1,2097.1,2155.5 +0.8709404394470571,0.7708592554328655,1.832595714594046,1337.3,843.5,1047.4,740.5,2323.1,2158.8 +0.8709952259280697,0.770894761804022,1.9634954084936205,1019.9,1024.6,909.5,913.8,1743.5,1524.6 +0.8710119575815962,0.7709146682642096,2.0943951023931953,829.8,879.6,752.3,1315.2,1383.6,1256.4 +0.8710022245147587,0.7708950877551168,2.2252947962927703,750.3,750.1,691.5,2170.6,1201.5,1142.7 +0.8710076343533796,0.7709175968224984,2.356194490192345,741.4,693.1,693.5,2020.3,1128.5,1129.3 +0.8710048411701574,0.7709477459931002,2.4870941840919194,793.3,691.5,750.7,2075.8,1143.3,1202.1 +0.8710089773457537,0.7709385541523279,2.6179938779914944,1025.4,753.3,880.9,2311.3,1256.9,1384.6 +0.8709961900917277,0.7709548730238258,2.748893571891069,910.9,911.1,1131.1,1688.3,1241.4,1021.3 +0.8710054058219142,0.7709482560346974,2.8797932657906435,739.7,1292.2,1671.6,1337.0,970.0,842.6 +0.8709964553526129,0.7709540619586175,3.010692959690218,669.0,2156.2,2097.5,1163.9,830.8,772.1 +0.8710255929592209,0.8712359462130568,0.0,762.8,2051.1,2051.3,999.0,771.0,770.9 +0.8709873557055191,0.8706653452383946,0.1308996938995747,816.4,2097.7,2157.2,1017.7,772.4,831.7 +0.8710206328872473,0.8706761880456431,0.2617993877991494,948.1,2322.2,1962.4,1128.6,842.9,970.5 +0.8710585316031482,0.8707006111941795,0.39269908169872414,1214.7,1604.3,1384.7,1179.7,1085.5,1051.3 +0.8710886308865284,0.8707353875306703,0.5235987755982988,1787.0,1269.0,1141.2,923.3,996.9,869.2 +0.8711173295514933,0.8707865454633601,0.6544984694978736,2076.0,1098.6,1039.5,793.4,854.2,795.1 +0.8711231286893206,0.870817693372409,0.7853981633974483,2021.3,1029.1,1028.5,740.8,793.6,793.0 +0.8711222084448456,0.8708809647548141,0.916297857297023,2118.2,1039.1,1098.0,749.9,795.0,853.7 +0.8711149206008681,0.8709089285197826,1.0471975511965976,1986.4,1141.1,1268.1,829.9,867.9,995.2 +0.8711071792732715,0.8709205220035015,1.1780972450961724,1390.0,1244.4,1023.6,1018.8,1050.7,1269.7 +0.8710597883594576,0.8709657231265258,1.3089969389957472,1129.0,970.5,842.7,948.7,1489.3,1868.2 +0.8710241469789877,0.8709865646995973,1.4398966328953218,1017.2,830.7,772.3,815.1,2154.4,2095.8 +0.871045275657571,0.8709825520641958,1.5707963267948966,998.8,771.0,770.7,762.9,2051.1,2050.8 +0.8709898856852876,0.8709813188730835,1.7016960206944713,1059.7,771.5,830.0,772.6,2097.1,2155.2 +0.8709424619300111,0.8709674362005742,1.832595714594046,1221.4,843.6,971.3,855.9,2322.2,1960.8 +0.8709613036815269,0.8709808848688505,1.9634954084936205,1020.1,1086.5,1050.9,1054.9,1603.1,1383.9 +0.8709513669684441,0.8709725818878611,2.0943951023931953,830.0,995.1,867.9,1514.2,1268.5,1141.1 +0.8709245338847496,0.8709218217903181,2.2252947962927703,750.4,853.8,794.9,2118.1,1098.1,1039.4 +0.870922150924354,0.870911981713798,2.356194490192345,741.5,793.0,793.5,2020.4,1028.4,1029.0 +0.8709203570282389,0.8709111190239747,2.4870941840919194,793.3,794.8,854.0,2075.9,1039.5,1098.6 +0.8709326406780492,0.870874738457907,2.6179938779914944,923.6,868.7,996.4,2301.4,1141.2,1268.8 +0.8709340424759736,0.8708685264491571,2.748893571891069,1052.3,1052.1,1272.2,1547.2,1242.0,1021.6 +0.8709610993921179,0.8708453441817197,2.8797932657906435,855.3,1490.4,1870.2,1247.0,970.1,842.9 +0.8709721277278065,0.8708406742055284,3.010692959690218,772.6,2156.4,2097.5,1060.6,831.0,772.2 +0.17092821699833122,0.17079889610385668,0.0,63.0,2751.2,2750.9,1699.1,71.0,71.0 +0.17091618662125754,0.17143227731027877,0.1308996938995747,91.5,2823.5,2882.2,823.9,47.5,106.7 +0.1709105638962032,0.17142976736183035,0.2617993877991494,139.5,3130.6,3258.2,349.2,187.8,95.3 +0.17086853013345432,0.1714024494591746,0.39269908169872414,223.7,2592.7,2372.9,191.3,110.1,63.0 +0.17082692894279336,0.17135851762385546,0.5235987755982988,393.0,2078.2,1950.5,114.0,50.8,59.8 +0.1708075985134846,0.17131819156586015,0.6544984694978736,912.0,1823.3,1764.1,68.6,129.5,70.4 +0.17079142934117544,0.17125317416176467,0.7853981633974483,2721.2,1728.8,1728.2,40.9,93.8,93.2 +0.1707933103468458,0.17122516185058778,0.916297857297023,2842.6,974.0,150.4,25.5,70.7,129.4 +0.170810327798885,0.1711712201434925,1.0471975511965976,3209.7,431.9,51.6,106.4,59.5,186.7 +0.1708437040281063,0.17111498252383006,1.1780972450961724,2381.5,252.4,31.4,31.2,63.3,282.4 +0.17084832325699875,0.17110941383326517,1.3089969389957472,1938.1,161.1,33.5,72.1,95.6,474.6 +0.1708715718315037,0.1710967782855104,1.4398966328953218,1740.9,106.5,93.6,91.1,238.2,1066.4 +0.17095432711776093,0.17107660595300755,1.5707963267948966,1699.0,71.0,70.7,63.3,2750.7,2751.3 +0.1709113100008543,0.17107888512209612,1.7016960206944713,234.0,47.4,105.8,48.6,2820.5,2997.7 +0.17094521770671256,0.17108781196987466,1.832595714594046,73.6,187.9,95.6,47.1,3130.9,3258.6 +0.17101313976118324,0.17113000191998973,1.9634954084936205,32.2,110.3,63.3,63.6,2590.7,2371.5 +0.17103505434439628,0.17115381544051078,2.0943951023931953,21.1,51.0,59.5,117.3,2077.1,1949.4 +0.17102763774815324,0.17113722827064848,2.2252947962927703,25.7,129.5,70.7,319.1,1822.2,1763.3 +0.17103393700143585,0.1711624398285987,2.356194490192345,41.5,93.3,93.8,2720.1,1728.3,1728.8 +0.17103101253188935,0.17119495442859467,2.4870941840919194,68.5,70.5,129.5,2800.9,969.5,149.7 +0.17103395495127643,0.17118772136132,2.6179938779914944,73.8,59.9,187.5,3119.4,430.7,51.4 +0.17101949312353354,0.17120518819380748,2.748893571891069,62.7,62.7,282.7,2537.5,251.6,31.6 +0.17102661714177897,0.17119889354838946,2.8797932657906435,46.6,94.9,474.6,2030.4,161.2,33.8 +0.1710156996924198,0.17120416481476886,3.010692959690218,48.2,235.0,1057.1,1784.7,106.4,93.1 +0.171001167897074,0.1712084755652845,0.0,63.2,2750.9,2751.0,1698.9,71.0,71.0 +0.1709407383498361,0.17120733026365764,0.1308996938995747,91.6,2823.1,2882.2,823.8,47.4,106.7 +0.1709578645261787,0.17121162166274018,0.2617993877991494,139.5,3130.6,3258.8,349.2,188.0,95.5 +0.17095484385606743,0.17120863953319754,0.39269908169872414,223.8,2592.2,2372.9,191.3,110.2,63.1 +0.1709475888984463,0.17120148781700406,0.5235987755982988,393.2,2078.0,1950.3,114.0,50.7,59.9 +0.1709512435180066,0.1712039841156967,0.6544984694978736,912.2,1823.3,1764.1,68.5,129.6,70.5 +0.17094563086795292,0.17118411735103378,0.7853981633974483,2721.3,1728.8,1728.2,40.9,93.8,93.2 +0.17094620862298535,0.17119902783253682,0.916297857297023,2842.3,973.7,150.1,25.4,70.7,129.5 +0.17095159155200546,0.17118354809869984,1.0471975511965976,3209.2,431.8,51.5,106.4,59.5,186.7 +0.17096527581169083,0.1711589841248855,1.1780972450961724,2381.8,252.3,31.3,31.1,63.3,282.4 +0.17094505263681514,0.17117683030299502,1.3089969389957472,1938.0,161.1,33.4,72.1,95.5,474.6 +0.1709403358920697,0.17117924640354332,1.4398966328953218,1740.8,106.5,93.6,91.1,238.1,1066.2 +0.17099407821366758,0.17116583483035575,1.5707963267948966,1698.9,70.9,70.7,63.3,2751.3,2751.2 +0.17092395321983989,0.17116475673010112,1.7016960206944713,234.0,47.4,105.8,48.6,2820.7,2997.7 +0.1709342730071557,0.17116656945991537,1.832595714594046,73.7,187.9,95.5,47.0,3131.5,3259.2 +0.17098265797395706,0.1711966023613367,1.9634954084936205,32.2,110.2,63.3,63.6,2591.4,2371.7 +0.17099016908308912,0.1712050462607302,2.0943951023931953,21.1,51.1,59.4,117.3,2076.7,1949.4 +0.17097362285299042,0.1711714721431763,2.2252947962927703,25.8,129.5,70.7,319.0,1822.3,1763.5 +0.17097582740761388,0.17117913567211307,2.356194490192345,41.5,93.3,93.8,2720.6,1728.3,1728.7 +0.17097347886741773,0.17119492203305464,2.4870941840919194,68.5,70.5,129.5,2800.6,969.4,149.8 +0.1709808962021019,0.1711729955154051,2.6179938779914944,73.8,59.9,187.5,3119.2,430.7,51.5 +0.17097402828583994,0.17117833005250227,2.748893571891069,62.7,62.7,282.7,2537.6,251.7,31.6 +0.17099076518448586,0.17116306360610856,2.8797932657906435,46.6,94.9,474.7,2030.2,161.3,33.8 +0.1709905912405167,0.17116261286489887,3.010692959690218,48.2,235.0,1057.2,1784.9,106.3,93.1 +0.9710877493256871,0.37118694860654244,0.0,263.2,1951.1,1951.3,1498.8,870.9,871.0 +0.9710382827863379,0.37098405946387336,0.1308996938995747,298.5,1994.3,2053.9,1535.6,875.9,917.0 +0.9710381757749312,0.370984149929791,0.2617993877991494,370.6,2206.6,2334.6,1706.2,873.6,494.0 +0.9710293635896402,0.3709786820478571,0.39269908169872414,507.0,2309.7,2090.3,1320.7,564.5,345.2 +0.9710290077614445,0.37098031827005906,0.5235987755982988,791.4,1847.1,1719.4,1038.8,418.6,290.9 +0.9710392944039812,0.3709967219266379,0.6544984694978736,1682.9,1616.5,1557.0,897.0,336.5,277.4 +0.9710369112884967,0.3709927255185279,0.7853981633974483,1921.4,1528.9,1528.3,840.9,293.7,293.0 +0.9710367690704876,0.3710229590838243,0.916297857297023,2014.4,1556.9,1615.5,853.6,277.5,336.3 +0.9710380009198466,0.37102132405601185,1.0471975511965976,2286.0,1718.2,1648.8,792.8,290.3,417.6 +0.9710448839876867,0.37100841688373043,1.1780972450961724,2097.9,1386.0,1165.0,507.5,345.3,564.3 +0.9710160603251473,0.3710351619393031,1.3089969389957472,1706.8,1085.9,958.4,370.8,493.6,872.8 +0.9710015399095143,0.37104368839557544,1.4398966328953218,1534.2,934.2,875.8,297.8,1016.7,1845.4 +0.9710448812658378,0.3710337420863865,1.5707963267948966,1498.8,871.2,870.8,263.1,1951.8,1951.0 +0.9710105195776133,0.3710323723406108,1.7016960206944713,1577.1,875.1,931.1,255.3,1993.4,2177.8 +0.9709820639263782,0.3710233718380396,1.832595714594046,1667.6,872.9,493.8,278.0,2207.3,2334.1 +0.9710169049839095,0.3710461183107918,1.9634954084936205,1161.0,564.3,345.2,346.8,2308.4,2089.1 +0.9710189104573761,0.37105004267359365,2.0943951023931953,945.5,417.6,290.3,516.3,1845.7,1718.3 +0.9709997219399025,0.37101298896938184,2.2252947962927703,853.9,336.3,277.5,1093.2,1615.3,1556.7 +0.9710007112979953,0.37101747021236253,2.356194490192345,841.5,293.1,293.7,1920.2,1528.5,1529.1 +0.9709982132371676,0.37103032379725787,2.4870941840919194,896.9,277.4,336.5,1972.1,1557.2,1616.7 +0.9710065024733938,0.37100583401905163,2.6179938779914944,515.7,290.9,418.6,2195.2,1719.2,1645.3 +0.9710011801597245,0.37100926196492856,2.748893571891069,345.3,345.3,565.3,2254.0,1383.3,1162.9 +0.9710199786622724,0.37099287403960224,2.8797932657906435,277.5,493.6,873.7,1799.1,1085.7,958.5 +0.9710219797863664,0.37099215700681176,3.010692959690218,255.1,1008.9,1831.8,1578.0,934.4,875.7 +0.9710647724864025,0.4712843599225447,0.0,363.1,1951.1,1951.0,1399.0,871.1,871.0 +0.9710154888631561,0.47069585729519026,0.1308996938995747,402.2,1994.7,2053.9,1432.0,876.2,935.3 +0.9710433455297134,0.4707050089612146,0.2617993877991494,486.1,2206.5,2334.1,1590.8,958.5,693.3 +0.9710773551758243,0.4707270258262448,0.39269908169872414,648.5,2168.9,1949.6,1320.8,705.6,486.4 +0.9711047113552953,0.47075894092070936,0.5235987755982988,990.8,1731.4,1603.8,1038.9,534.1,406.4 +0.9711315701919132,0.47080695228128944,0.6544984694978736,1972.2,1512.9,1453.6,896.9,440.0,380.9 +0.971136510428923,0.4708348968010918,0.7853981633974483,1921.2,1429.2,1428.5,840.9,393.5,393.0 +0.9711354876233573,0.4708950412710162,0.916297857297023,2014.6,1453.1,1512.0,853.5,380.9,439.7 +0.971128853350764,0.4709201388582498,1.0471975511965976,2285.7,1603.2,1648.6,945.8,405.8,533.1 +0.9711224230591912,0.47092938774011484,1.1780972450961724,1956.5,1385.8,1164.8,649.1,486.2,705.5 +0.971076726501363,0.47097274125443267,1.3089969389957472,1591.4,1085.9,958.2,486.4,692.8,1072.0 +0.9708911953557793,0.47082556738965287,1.4398966328953218,1430.7,934.0,875.8,401.1,1408.7,1992.3 +0.9711381391559077,0.47077140334707646,1.5707963267948966,1399.2,870.7,870.7,363.1,1950.8,1951.3 +0.9710166148739435,0.4707672307077948,1.7016960206944713,1473.5,875.1,933.5,358.9,1993.2,2051.8 +0.970996163580897,0.47076068192634013,1.832595714594046,1666.5,959.3,692.4,393.8,2207.6,2335.6 +0.971062323988798,0.47080338263191757,1.9634954084936205,1160.8,705.0,486.2,488.7,2166.5,1947.1 +0.9710936293838698,0.4708392338575418,2.0943951023931953,945.1,532.9,405.7,716.5,1730.0,1602.7 +0.9710945314769056,0.47083968562838496,2.2252947962927703,853.7,439.7,381.0,1482.7,1511.7,1453.1 +0.9711048430530379,0.47088380956463416,2.356194490192345,841.7,392.9,393.6,1920.4,1428.2,1429.1 +0.9711010784381738,0.47093492069862886,2.4870941840919194,942.5,380.9,440.0,1972.9,1453.9,1513.2 +0.9710995388666309,0.47094408361567486,2.6179938779914944,714.4,406.5,534.3,2195.0,1603.9,1644.2 +0.9710769860310215,0.47097564262815816,2.748893571891069,486.4,486.8,707.0,2111.6,1382.1,1162.4 +0.9708849260929544,0.4707941645578002,2.8797932657906435,392.9,693.5,1073.5,1683.5,1085.4,958.1 +0.9709051707730544,0.470784273951087,3.010692959690218,358.5,1397.7,1993.4,1474.1,934.3,875.5 +0.9709831327268359,0.5711054371949382,0.0,462.9,1951.0,1951.1,1299.1,870.8,871.0 +0.9709758132714968,0.5711055716021953,0.1308996938995747,505.6,1994.8,2054.4,1328.9,876.0,935.4 +0.9709375091454555,0.5710945566041614,0.2617993877991494,601.7,2206.9,2334.7,1475.8,1009.5,892.0 +0.9708970470605356,0.5710698540631818,0.39269908169872414,790.3,2026.8,1807.5,1320.2,846.3,627.3 +0.9708638413452612,0.571036528495559,0.5235987755982988,1190.2,1615.4,1487.7,1038.9,649.4,522.0 +0.9708510756803362,0.5710102646563457,0.6544984694978736,1972.3,1409.1,1350.0,896.6,543.3,484.3 +0.9708382270593409,0.5709606843999928,0.7853981633974483,1921.2,1329.0,1328.7,840.8,493.5,493.0 +0.9708396347187379,0.5709473041936706,0.916297857297023,2014.9,1349.9,1409.1,853.7,484.5,543.4 +0.9708530865447936,0.5709066447873132,1.0471975511965976,2286.4,1488.0,1615.1,945.9,521.4,648.6 +0.9708805258398792,0.5708619790867546,1.1780972450961724,1813.8,1385.6,1164.4,790.6,627.6,846.9 +0.9708773371046793,0.5708654429957192,1.3089969389957472,1475.3,1085.8,958.2,601.8,892.4,1272.3 +0.9708914303950092,0.5708591833675216,1.4398966328953218,1327.4,934.1,875.6,504.5,1798.4,2119.1 +0.9710095935457502,0.5708302509611389,1.5707963267948966,1298.7,871.0,870.8,463.0,1951.1,1951.2 +0.9709706872180477,0.5708292078274941,1.7016960206944713,1370.1,875.1,933.6,462.3,1993.2,2051.7 +0.9709599526671933,0.5708258491758933,1.832595714594046,1568.8,1027.5,891.6,509.3,2207.4,2335.3 +0.971015773991931,0.5708621623499184,1.9634954084936205,1160.9,846.2,627.2,630.3,2025.3,1806.5 +0.9710347836641537,0.5708848074220751,2.0943951023931953,945.3,648.5,521.2,916.0,1614.6,1487.1 +0.9710268504672206,0.5708687487191295,2.2252947962927703,853.7,543.2,484.4,1869.7,1408.5,1349.6 +0.9710330786753293,0.5708951040284702,2.356194490192345,841.5,492.9,493.5,1920.4,1328.7,1329.2 +0.9710300203632743,0.5709290319897831,2.4870941840919194,897.1,484.3,543.5,1972.3,1350.2,1409.5 +0.9710331582656284,0.5709230950712774,2.6179938779914944,913.5,522.2,649.8,2195.4,1488.4,1615.7 +0.9710185640552547,0.5708789108288461,2.748893571891069,627.9,628.3,848.4,1970.9,1382.3,1162.3 +0.9708903171247601,0.5708132346504888,2.8797932657906435,508.6,893.0,1273.1,1567.9,1085.7,958.2 +0.9709086747949257,0.5708042943568967,3.010692959690218,462.0,1785.0,2120.0,1370.8,934.4,875.8 +0.9709837263772103,0.6711225643608882,0.0,562.9,1951.2,1951.1,1199.1,870.9,871.0 +0.9709743856984587,0.6711225480043443,0.1308996938995747,609.2,1994.9,2054.1,1225.3,876.1,935.5 +0.9709346202273815,0.671111010002124,0.2617993877991494,717.4,2207.2,2334.6,1360.4,958.6,1047.6 +0.9708930779048748,0.6710855535568001,0.39269908169872414,932.0,1885.8,1666.5,1320.3,987.5,768.5 +0.9708590979386499,0.6710513216207752,0.5235987755982988,1389.6,1500.0,1372.3,1038.5,765.1,637.5 +0.9708458878197564,0.6710241122731466,0.6544984694978736,1972.1,1305.6,1246.7,896.7,646.9,587.9 +0.9708328276257702,0.6709735555964838,0.7853981633974483,1921.0,1229.0,1228.8,840.8,593.5,593.0 +0.9708342859223654,0.6709592881132251,0.916297857297023,2014.8,1246.2,1305.3,853.6,588.0,646.8 +0.9708479781916207,0.6709178396655142,1.0471975511965976,2286.3,1372.4,1499.3,1103.5,636.9,764.3 +0.9708757909826639,0.6708724816538867,1.1780972450961724,1672.6,1385.5,1164.8,932.2,768.8,987.9 +0.9708730923231208,0.6708754297979089,1.3089969389957472,1359.9,1085.6,958.0,717.6,1091.9,1471.4 +0.9708877483524412,0.670868837946551,1.4398966328953218,1223.8,934.0,875.8,608.1,2050.9,1992.6 +0.9709611558722108,0.6708526584237158,1.5707963267948966,1199.1,870.7,870.6,562.9,1951.3,1951.2 +0.9709546505187918,0.6708527166426463,1.7016960206944713,1266.5,875.1,933.6,565.6,1993.2,2051.8 +0.970950791625147,0.6708514382640569,1.832595714594046,1453.3,959.4,1047.0,625.0,2207.3,2335.0 +0.9710059673843373,0.6708872765694791,1.9634954084936205,1160.8,987.3,768.3,772.1,1884.7,1665.8 +0.9710487747808042,0.6709417640069155,2.0943951023931953,945.2,764.0,636.6,1115.8,1499.1,1371.7 +0.9710251766948816,0.6708961627906669,2.2252947962927703,853.7,646.8,587.9,2013.9,1304.9,1246.2 +0.971028981309013,0.670911806095694,2.356194490192345,841.4,593.0,593.7,1920.6,1228.6,1229.1 +0.9710261010303426,0.6709419681951738,2.4870941840919194,896.9,587.9,647.1,1972.2,1246.6,1305.9 +0.9710296304435647,0.6709346985143747,2.6179938779914944,1039.5,637.8,765.5,2195.3,1372.9,1500.5 +0.9710153813323252,0.6709532141089392,2.748893571891069,769.2,769.7,989.8,1829.5,1382.6,1162.7 +0.9710227096022186,0.6709483420003874,2.8797932657906435,624.1,1092.6,1472.7,1452.6,1085.5,958.0 +0.9710115890815969,0.6709553025920485,3.010692959690218,565.5,2052.5,1993.6,1267.3,934.5,875.7 +0.9710380967443356,0.7712351940184805,0.0,663.0,1951.0,1951.0,1099.1,871.0,870.9 +0.9709980964977942,0.7706618625543835,0.1308996938995747,712.8,1995.0,2053.8,1121.4,876.0,935.4 +0.9710313283236548,0.7706727172609109,0.2617993877991494,832.7,2206.3,2161.7,1244.2,958.4,1085.9 +0.9710695101509427,0.7706973689663832,0.39269908169872414,1073.3,1745.5,1525.8,1320.7,1129.3,910.0 +0.9710999018546085,0.7707325326019687,0.5235987755982988,1588.1,1384.3,1257.0,1039.0,881.0,753.3 +0.9711287436072178,0.7707841189885449,0.6544984694978736,1972.3,1202.2,1143.2,896.9,750.7,691.4 +0.9711345952531055,0.770815728722875,0.7853981633974483,1921.4,1128.9,1128.5,840.8,693.4,692.9 +0.9711335803597756,0.7708793903277942,0.916297857297023,2014.5,1142.6,1201.5,853.4,691.5,750.2 +0.9711261168903168,0.7708269867236708,1.0471975511965976,2186.3,1256.5,1383.8,945.6,752.3,879.6 +0.9711150909567503,0.770926698007752,1.1780972450961724,1531.5,1386.1,1165.1,1074.3,909.6,1128.6 +0.9710710479303744,0.7709686706040022,1.3089969389957472,1269.9,1086.0,958.4,833.1,1290.1,1669.6 +0.971035947789392,0.7709891457716802,1.4398966328953218,1120.4,934.2,875.7,711.5,2099.1,1992.5 +0.9710564976283261,0.7709852885323158,1.5707963267948966,1098.9,871.0,870.7,662.9,1951.1,1951.0 +0.971000186337328,0.7709840377310191,1.7016960206944713,1163.0,875.2,933.4,669.0,1993.0,2051.7 +0.9709518301804401,0.770969854512833,1.832595714594046,1337.5,959.1,1086.8,740.2,2206.9,2159.5 +0.9709698398566936,0.7709828296357508,1.9634954084936205,1161.3,1128.8,909.7,913.6,1743.8,1525.1 +0.9709592446447523,0.770973927271307,2.0943951023931953,945.5,879.6,752.3,1314.4,1384.0,1256.6 +0.9709319826238565,0.7709224455883696,2.2252947962927703,854.0,750.3,691.6,2140.3,1201.5,1142.8 +0.9709293745586107,0.7709118459947573,2.356194490192345,841.6,692.9,693.5,1920.6,1128.4,1129.1 +0.9709275271859442,0.7709102633406195,2.4870941840919194,896.9,691.5,750.5,1972.3,1143.1,1202.1 +0.970939974172641,0.7708732055594549,2.6179938779914944,1039.2,753.2,880.9,2195.0,1257.0,1384.6 +0.970941641851482,0.7708664387121178,2.748893571891069,911.1,910.7,1130.8,1688.6,1383.0,1162.9 +0.9709691132004735,0.7708428202206468,2.8797932657906435,739.6,1291.5,1671.1,1336.9,1085.8,958.4 +0.9709806188122355,0.7708378648947394,3.010692959690218,669.1,2084.3,1993.7,1164.1,934.5,875.7 +0.9710344584872107,0.8711385178090081,0.0,762.8,1950.9,1951.4,999.2,870.9,871.2 +0.9709965291040207,0.8706642161135982,0.1308996938995747,816.4,1994.7,2053.9,1017.9,876.0,935.3 +0.9710303835064764,0.8706752736871872,0.2617993877991494,948.4,2206.8,1962.4,1128.7,958.6,1204.0 +0.9710684282074308,0.8706998369081307,0.39269908169872414,1215.0,1604.0,1384.6,1320.8,1164.7,1051.1 +0.9710985507831114,0.8707347079407222,0.5235987755982988,1787.3,1294.4,1141.2,1038.7,996.6,868.9 +0.9711271835484222,0.8707859008173575,0.6544984694978736,1972.4,1098.7,1039.6,896.9,854.1,795.1 +0.9711329376672106,0.8708170808529021,0.7853981633974483,1921.3,1029.2,1028.4,840.9,793.4,793.0 +0.9711319351064369,0.8708803270529419,0.916297857297023,2014.7,1039.1,1098.1,853.4,795.0,853.7 +0.9711245835899383,0.8709082388363236,1.0471975511965976,1986.8,1141.0,1268.1,945.5,867.9,995.1 +0.9711168230089855,0.8709198075810547,1.1780972450961724,1389.8,1383.6,1165.2,1160.0,1050.5,1269.7 +0.9710694184732062,0.8709649524225409,1.3089969389957472,1129.4,1085.8,958.4,948.8,1489.5,1868.8 +0.971033784718321,0.8709857098276017,1.4398966328953218,1017.2,934.3,875.9,815.0,2051.1,1992.5 +0.9710549505218671,0.8709817073054469,1.5707963267948966,999.2,871.0,870.5,763.0,1951.6,1951.1 +0.9709995944178281,0.8709804827878487,1.7016960206944713,1059.4,874.9,933.4,772.5,1993.2,2051.6 +0.9709522078422322,0.8709665847682901,1.832595714594046,1221.7,959.2,1202.9,856.0,2206.6,1960.4 +0.9709710601837915,0.870980082367963,1.9634954084936205,1161.4,1166.1,1050.7,1055.1,1602.9,1383.8 +0.9709610971882279,0.8709718550660168,2.0943951023931953,945.4,995.1,867.9,1514.1,1268.3,1141.0 +0.9709342405249138,0.8709211215983206,2.2252947962927703,854.1,853.8,794.8,2014.1,1098.1,1039.1 +0.9709318157069381,0.870911297738941,2.356194490192345,841.7,792.9,793.4,1920.4,1028.7,1029.1 +0.9709299422834797,0.8709104575997335,2.4870941840919194,896.8,794.9,854.1,1972.4,1039.8,1098.7 +0.9709421928897831,0.8708740505860721,2.6179938779914944,1039.2,868.9,996.5,2194.3,1141.4,1269.0 +0.9709435214526703,0.8708678229581948,2.748893571891069,1052.4,1052.3,1272.3,1547.4,1383.0,1163.2 +0.9709705667426651,0.8708446019872658,2.8797932657906435,855.3,1490.8,1870.7,1221.6,1085.9,958.3 +0.9709815954246027,0.8708398997390001,3.010692959690218,772.6,2052.5,1993.7,1060.6,934.3,875.7 +0.17093882008905698,0.17080486442859621,0.0,63.0,2750.6,2750.8,1698.9,71.0,71.0 +0.1709196375910661,0.17143219469348137,0.1308996938995747,91.5,2822.8,2882.4,823.9,47.5,106.7 +0.17091343903417147,0.17142951034574905,0.2617993877991494,139.4,3130.8,3258.1,349.3,187.8,95.3 +0.1708712956474166,0.1714021341857095,0.39269908169872414,223.7,2592.0,2373.0,191.3,110.1,63.0 +0.17082969868641795,0.17135822731937367,0.5235987755982988,393.1,2077.8,1950.0,114.0,50.8,59.8 +0.17081038958186354,0.1713179686683559,0.6544984694978736,912.0,1823.3,1764.3,68.6,129.5,70.4 +0.17079421753264898,0.17125302528061392,0.7853981633974483,2720.8,1728.8,1728.3,40.9,93.8,93.2 +0.1707960818753344,0.1712250867696452,0.916297857297023,2842.5,974.2,150.3,25.5,70.7,129.4 +0.1708130656101091,0.17117120717774026,1.0471975511965976,3209.5,431.9,51.6,106.4,59.5,186.7 +0.17084639470606872,0.1711150086551465,1.1780972450961724,2381.2,252.4,31.4,31.2,63.3,282.3 +0.17085096732681151,0.17110946881872557,1.3089969389957472,1937.8,161.1,33.5,72.1,95.5,474.6 +0.1708741703543489,0.17109685611183933,1.4398966328953218,1741.1,106.5,93.6,91.1,238.2,1066.3 +0.17095688053662658,0.17107668354259897,1.5707963267948966,1698.6,71.0,70.7,63.3,2751.0,2751.1 +0.1709169370047475,0.17107634440417208,1.7016960206944713,234.0,47.4,105.8,48.6,2820.1,2998.0 +0.17094931888107373,0.17108476874749923,1.832595714594046,73.7,187.9,95.6,47.1,3131.5,3258.8 +0.17101737392167374,0.17112704085992902,1.9634954084936205,32.2,110.3,63.3,63.6,2591.0,2371.6 +0.17103977140940582,0.17115137684687842,2.0943951023931953,21.1,51.1,59.5,117.3,2076.7,1949.6 +0.17103273639345773,0.17113553467047793,2.2252947962927703,25.7,129.5,70.7,319.1,1822.4,1763.5 +0.17103920972799833,0.17116156865371535,2.356194490192345,41.5,93.3,93.8,2720.1,1728.2,1728.7 +0.17103624604423723,0.17119487602563055,2.4870941840919194,68.5,70.5,129.5,2800.1,969.7,149.7 +0.1710389563945245,0.17118834418110307,2.6179938779914944,73.9,59.9,187.5,3119.4,430.7,51.5 +0.17102412612622034,0.17120638244650777,2.748893571891069,62.7,62.7,282.6,2537.0,251.7,31.6 +0.171030782313652,0.17120050971513767,2.8797932657906435,46.6,94.9,474.7,2030.5,161.3,33.8 +0.17101934927180046,0.17120604823024954,3.010692959690218,48.2,235.0,1057.2,1785.0,106.4,93.1 +0.1710042845009696,0.17121047729393313,0.0,63.3,2751.1,2751.1,1698.7,71.0,70.9 +0.17094328748098275,0.171209314721662,0.1308996938995747,91.6,2823.2,2881.8,824.1,47.5,106.7 +0.17096001566935354,0.17121348689383709,0.2617993877991494,139.6,3131.1,3258.4,349.2,188.0,95.4 +0.17095663735003697,0.17121028924573367,0.39269908169872414,223.8,2592.4,2373.0,191.2,110.1,63.1 +0.17094910043003375,0.17120285206290808,0.5235987755982988,393.2,2078.1,1950.4,113.9,50.7,59.9 +0.17095257276880008,0.17120503127098163,0.6544984694978736,912.2,1823.3,1764.3,68.5,129.6,70.5 +0.17094686320201677,0.17118482596330797,0.7853981633974483,2721.7,1728.8,1728.4,40.9,93.8,93.2 +0.1709474379839391,0.17138345797185472,0.916297857297023,2842.5,973.8,150.2,25.5,70.7,129.4 +0.1709553953382194,0.17117367135706463,1.0471975511965976,3209.6,431.9,51.5,106.4,59.5,186.7 +0.17096567710812305,0.17115458440105158,1.1780972450961724,2381.9,252.3,31.3,31.1,63.3,282.4 +0.17094458376873992,0.17117322586690276,1.3089969389957472,1937.7,161.1,33.4,72.0,95.5,474.6 +0.17094029040914163,0.17117541014925686,1.4398966328953218,1741.1,106.5,93.6,91.1,238.1,1066.2 +0.17099497671595862,0.1711617698638297,1.5707963267948966,1698.8,71.0,70.7,63.3,2751.4,2751.2 +0.1709259986974376,0.17116072008222627,1.7016960206944713,234.0,47.4,105.8,48.6,2820.9,2998.1 +0.17093722550367763,0.1711628169322177,1.832595714594046,73.7,187.8,95.5,47.0,3131.5,3259.0 +0.17098642104685666,0.1711933642734349,1.9634954084936205,32.2,110.2,63.3,63.6,2591.1,2371.5 +0.17099454304762915,0.171202471895201,2.0943951023931953,21.2,51.1,59.4,117.3,2076.7,1949.6 +0.17097837684476194,0.1711696423073008,2.2252947962927703,25.8,129.5,70.7,319.0,1822.2,1763.8 +0.17098074185559003,0.1711780713782698,2.356194490192345,41.5,93.2,93.8,2720.8,1728.2,1728.8 +0.17097835636997627,0.17119457814830397,2.4870941840919194,68.5,70.5,129.5,2799.9,969.4,149.8 +0.17098556355198288,0.17117328348894834,2.6179938779914944,73.8,59.9,187.5,3119.2,430.7,51.5 +0.17097836430824004,0.17117913130669127,2.748893571891069,62.7,62.7,282.6,2537.4,251.7,31.6 +0.17099468129556097,0.1711642437356724,2.8797932657906435,46.6,95.0,474.6,2029.6,161.3,33.8 +0.17099404498455972,0.17116403341775066,3.010692959690218,48.2,235.1,1057.4,1784.7,106.4,93.1 +1.071078824454931,0.3711826384075627,0.0,263.3,1851.1,1850.8,1498.8,970.8,971.0 +1.0710344464853938,0.3709882249929306,0.1308996938995747,298.6,1890.9,1950.3,1535.6,979.5,1001.7 +1.0710343488770022,0.37098830338580124,0.2617993877991494,370.5,2091.2,2218.7,1706.5,873.6,494.0 +1.071025982797285,0.37098310219376285,0.39269908169872414,507.0,2309.9,2090.3,1461.8,564.5,345.2 +1.0710253285524702,0.37098439985963094,0.5235987755982988,791.6,1847.0,1719.3,1154.8,418.6,291.0 +1.0710352913410228,0.37100017285529496,0.6544984694978736,1683.2,1616.2,1557.5,1000.5,336.4,277.4 +1.0710327464178186,0.3709954323857654,0.7853981633974483,1821.0,1529.0,1528.3,940.8,293.6,293.1 +1.07103263599082,0.37102493610205234,0.916297857297023,1911.1,1556.5,1615.4,957.1,277.5,336.4 +1.0710340743624354,0.371022641639392,1.0471975511965976,2170.1,1718.7,1846.0,792.9,290.3,417.6 +1.071041299935311,0.37100919020419276,1.1780972450961724,2098.0,1527.6,1306.7,507.4,345.3,564.3 +1.0710129047833126,0.3710355313059823,1.3089969389957472,1706.9,1201.4,1074.0,370.9,493.8,872.9 +1.0709988650658402,0.37104379487182193,1.4398966328953218,1534.3,1037.6,979.2,297.8,1017.0,1845.8 +1.0710427055310094,0.3710337252768512,1.5707963267948966,1499.3,970.8,971.1,263.1,1851.0,1850.9 +1.0710088127043782,0.3710323598142513,1.7016960206944713,1576.7,978.6,1016.9,255.3,1889.6,1948.3 +1.0709807776432696,0.37102347292751214,1.832595714594046,1800.0,873.0,493.7,278.1,2091.6,2218.9 +1.0710159741209453,0.3710464251988055,1.9634954084936205,1302.4,564.3,345.3,346.8,2308.5,2089.3 +1.071018248244338,0.3710506168435217,2.0943951023931953,1061.1,417.6,290.3,516.4,1846.1,1718.7 +1.0709992361010745,0.3710138641947769,2.2252947962927703,957.4,336.3,277.5,1093.2,1615.6,1556.6 +1.0710003110023238,0.371018661762367,2.356194490192345,941.5,293.1,293.6,1820.3,1528.4,1529.1 +1.0709978115535737,0.3710318212383943,2.4870941840919194,1000.4,277.3,336.4,1868.6,1557.2,1616.1 +1.071006024855015,0.37100760282794454,2.6179938779914944,515.7,290.9,418.6,2078.9,1719.1,1844.8 +1.0710005652911792,0.37101125589964257,2.748893571891069,345.3,345.4,565.4,2254.2,1524.4,1304.2 +1.0710191861543483,0.370995033390942,2.8797932657906435,277.5,493.6,873.5,1799.4,1201.4,1074.0 +1.0710209869860687,0.3709944188777399,3.010692959690218,255.1,1008.9,1831.4,1577.7,1038.0,979.2 +1.0710635373202997,0.4712864350314985,0.0,363.0,1851.2,1850.8,1398.8,971.0,971.0 +1.0710145795006887,0.4706960972865799,0.1308996938995747,402.1,1890.9,1949.9,1432.2,979.7,1039.0 +1.071042482832652,0.4707052610726743,0.2617993877991494,486.2,2091.0,2218.6,1591.1,1073.0,693.4 +1.071076484321747,0.47072726873950743,0.39269908169872414,648.6,2168.7,1949.3,1461.7,705.6,486.3 +1.0711038226354173,0.4707591587133402,0.5235987755982988,990.6,1731.4,1603.4,1154.6,534.2,406.5 +1.0711306721753868,0.4708071399849707,0.6544984694978736,1868.5,1512.8,1453.8,1000.2,439.9,380.8 +1.0711356091330966,0.47083505123853153,0.7853981633974483,1821.5,1428.9,1428.6,940.8,393.5,393.0 +1.0711345936913639,0.4708951675543076,0.916297857297023,1911.3,1453.3,1512.1,957.0,380.9,439.8 +1.0711279725484586,0.47092024199788707,1.0471975511965976,2170.2,1603.1,1730.3,992.0,405.8,533.1 +1.0711215577367594,0.4709294706678657,1.1780972450961724,1956.4,1527.5,1306.6,649.0,486.4,705.4 +1.0710758796549937,0.47097281190289797,1.3089969389957472,1591.7,1201.4,1073.8,486.2,692.6,1071.8 +1.071042238140971,0.47099231714485645,1.4398966328953218,1431.1,1037.7,979.3,401.1,1406.4,1889.1 +1.0710655322203781,0.47098774777427255,1.5707963267948966,1399.1,970.8,970.7,362.9,1851.1,1851.1 +1.0710121953196134,0.47098650565834177,1.7016960206944713,1473.4,978.5,1037.0,358.7,1889.9,1948.5 +1.0709666396662105,0.4709730483115451,1.832595714594046,1684.1,1071.9,692.6,393.5,2091.5,2219.2 +1.0709870192791586,0.4709874667790219,1.9634954084936205,1302.5,705.3,486.2,488.4,2167.4,1948.0 +1.070978164536782,0.4709804658537651,2.0943951023931953,1061.0,532.9,405.7,715.7,1730.3,1603.0 +1.070952007067081,0.4709310579205943,2.2252947962927703,957.3,439.7,380.9,1480.1,1512.1,1453.6 +1.0709498555846908,0.47092260818238185,2.356194490192345,941.7,392.9,393.5,1820.2,1428.5,1429.0 +1.0709478320907244,0.4709230869700416,2.4870941840919194,1000.3,380.8,439.9,1868.7,1453.9,1513.0 +1.0709596602699571,0.4708877773828075,2.6179938779914944,714.7,406.4,534.1,2079.1,1604.1,1731.3 +1.0709602738891928,0.4708824376958256,2.748893571891069,486.6,486.5,706.6,2113.1,1524.4,1304.3 +1.0709865175375717,0.47085981027495816,2.8797932657906435,392.9,693.0,1072.8,1683.6,1201.3,1073.8 +1.0709966886073492,0.470855436217434,3.010692959690218,358.5,1395.8,1890.2,1474.4,1038.0,979.2 +1.071049000270197,0.5711549356092747,0.0,462.8,1851.6,1851.1,1299.0,971.0,970.9 +1.0710094969617507,0.5706660802242132,0.1308996938995747,505.7,1891.0,1950.5,1328.6,979.5,1038.8 +1.0710427847251232,0.5706769815142034,0.2617993877991494,601.6,2091.2,2218.8,1475.3,1074.2,892.8 +1.0710805229963718,0.5707014009437441,0.39269908169872414,790.1,2027.3,1808.2,1461.7,846.8,627.6 +1.0711104582893878,0.5707361459176057,0.5235987755982988,1189.9,1615.5,1488.1,1154.6,649.8,522.1 +1.0711389093740311,0.5707871808357301,0.6544984694978736,1984.1,1409.2,1350.0,1000.3,543.5,484.4 +1.0711445650250035,0.5708182133567663,0.7853981633974483,1821.1,1329.2,1328.3,940.7,493.6,493.0 +1.0711434676310978,0.5708812630145901,0.916297857297023,1910.8,1349.8,1408.5,956.8,484.4,543.2 +1.0711360802353518,0.5709089647885897,1.0471975511965976,2170.5,1487.9,1615.1,1061.3,521.3,648.5 +1.0711283645204848,0.5709203768382043,1.1780972450961724,1814.9,1527.6,1306.8,790.5,627.5,846.4 +1.0710810332509282,0.5709653582101764,1.3089969389957472,1475.8,1201.8,1074.0,601.9,892.2,1271.1 +1.071045512573746,0.5709859512087228,1.4398966328953218,1327.5,1037.7,979.2,504.6,1795.8,1889.1 +1.0710668332854079,0.5709819218853609,1.5707963267948966,1299.1,971.0,970.7,462.9,1851.3,1851.2 +1.0710116250725619,0.5709807006150343,1.7016960206944713,1370.0,978.7,1036.9,462.0,1889.6,1948.0 +1.0709643808850324,0.5709668079696613,1.832595714594046,1568.8,1074.9,891.8,509.1,2091.3,2218.9 +1.0709833305871683,0.5709804082958885,1.9634954084936205,1302.5,846.2,627.3,630.0,2026.3,1807.3 +1.070973401197781,0.5709723309852552,2.0943951023931953,1061.1,648.5,521.2,915.7,1614.9,1487.5 +1.0709465560531128,0.5709217018264523,2.2252947962927703,957.3,543.2,484.3,1867.6,1408.7,1349.8 +1.0709440973036723,0.57091197342902,2.356194490192345,941.5,492.9,493.5,1820.1,1328.7,1329.0 +1.0709421246844253,0.5709112305721726,2.4870941840919194,1000.4,484.4,543.4,1868.8,1350.3,1409.5 +1.0709543096794296,0.5708748539790638,2.6179938779914944,913.9,522.1,649.8,2079.2,1488.0,1616.1 +1.0709555146227694,0.5708686539299459,2.748893571891069,628.0,627.9,848.2,1971.6,1524.2,1304.5 +1.0709929323143468,0.5708353448111307,2.8797932657906435,508.5,892.6,1272.5,1568.2,1201.3,1073.7 +1.0709950948744882,0.5708352665906924,3.010692959690218,462.0,1782.8,1890.4,1371.3,1038.0,979.1 +1.0710463105233834,0.6711362516225701,0.0,562.8,1851.0,1851.2,1199.2,971.0,971.2 +1.0710187378758267,0.6711359687593146,0.1308996938995747,609.1,1890.9,1950.5,1225.4,979.7,1038.8 +1.0709646542596551,0.671120404991397,0.2617993877991494,717.0,2091.3,2218.2,1360.1,1184.4,1091.9 +1.0709118226116479,0.6710883145201068,0.39269908169872414,931.5,1886.6,1667.2,1461.9,987.8,768.5 +1.0708693826648756,0.6710455760114953,0.5235987755982988,1388.7,1500.2,1398.1,1154.5,765.2,637.5 +1.0708236620356706,0.6709561319772386,0.6544984694978736,1868.6,1305.8,1246.6,1000.5,646.9,587.8 +1.0708171752506337,0.6709352357790361,0.7853981633974483,1820.9,1229.1,1228.8,941.0,593.5,592.9 +1.0708183777265259,0.670920837378141,0.916297857297023,1911.1,1246.4,1305.0,957.1,587.9,646.8 +1.070834672693237,0.670870275295971,1.0471975511965976,2170.1,1371.9,1499.5,1147.9,636.8,764.3 +1.070868619679821,0.6708147520472747,1.1780972450961724,1673.0,1527.9,1306.8,932.4,768.6,987.8 +1.0708745188995397,0.6708096381333133,1.3089969389957472,1360.1,1201.4,1073.9,717.6,1091.5,1470.5 +1.0708991778508643,0.6707979126868915,1.4398966328953218,1224.0,1037.7,979.3,608.1,1947.4,1889.1 +1.0709830114339955,0.6707793991971085,1.5707963267948966,1198.9,971.2,970.7,563.1,1851.1,1850.9 +1.070986237390567,0.6707799834316344,1.7016960206944713,1266.4,978.7,1037.0,565.5,1889.7,1948.0 +1.0709908987642462,0.6707817049896851,1.832595714594046,1453.0,1183.7,1091.2,624.9,2091.5,2219.2 +1.0710788511707487,0.6708362402732357,1.9634954084936205,1302.4,987.6,768.5,771.9,1885.3,1666.2 +1.0710876088412753,0.670847963431539,2.0943951023931953,1060.9,764.2,636.9,1115.2,1499.2,1372.0 +1.0710537829700335,0.6707815934071455,2.2252947962927703,957.2,646.6,588.0,1910.7,1304.7,1246.1 +1.0710691572487132,0.6708493499273653,2.356194490192345,941.7,592.9,593.5,1820.2,1228.6,1229.2 +1.0710654579782222,0.6708969232287258,2.4870941840919194,1000.5,587.9,647.0,1868.7,1246.7,1305.9 +1.071067074402336,0.670895189856233,2.6179938779914944,1113.1,637.6,765.4,2079.0,1372.7,1500.5 +1.0710517928922625,0.6709153390710116,2.748893571891069,769.4,769.4,989.5,1829.9,1524.1,1304.4 +1.071058541953661,0.6709110209037168,2.8797932657906435,624.0,1091.9,1471.7,1452.4,1201.3,1073.9 +1.0710471457412327,0.6709182524345105,3.010692959690218,565.5,1948.9,1890.3,1267.6,1038.1,979.3 +1.0710734412340859,0.7711980884116165,0.0,662.8,1851.3,1851.0,1099.2,971.1,970.9 +1.070975579341894,0.7706756645897765,0.1308996938995747,712.9,1891.1,1950.7,1121.3,979.7,1038.9 +1.0710234233637081,0.7706910310989554,0.2617993877991494,833.0,2091.1,2205.1,1244.3,1074.0,1201.5 +1.071062982300769,0.7707165553601514,0.39269908169872414,1073.5,1744.9,1525.3,1462.1,1129.1,909.9 +1.0710916809315119,0.770749894429307,0.5235987755982988,1588.5,1384.5,1256.7,1154.3,880.8,753.3 +1.0711187769532575,0.7707982960664403,0.6544984694978736,1868.8,1202.1,1165.9,1000.3,750.6,691.5 +1.0711237855410363,0.7708262426649115,0.7853981633974483,1821.3,1128.9,1128.5,940.9,693.5,693.0 +1.071122830137463,0.7708862525088753,0.916297857297023,1910.8,1142.8,1201.6,957.2,691.4,750.3 +1.071116318447247,0.7709112133022311,1.0471975511965976,2169.8,1256.5,1384.0,1061.2,752.4,879.8 +1.0711100558798041,0.7709203983506161,1.1780972450961724,1531.0,1524.9,1306.6,1074.1,909.6,1128.6 +1.0710645159841268,0.7709637244257912,1.3089969389957472,1244.5,1201.5,1073.8,833.0,1290.6,1669.6 +1.0710309918246246,0.7709832274987147,1.4398966328953218,1120.7,1037.5,979.2,711.4,2073.2,1888.9 +1.071054382521723,0.7709787321716193,1.5707963267948966,1099.4,970.9,970.8,663.0,1851.4,1851.1 +1.0709503361433297,0.7709785474335544,1.7016960206944713,1163.1,978.6,1037.1,668.9,1889.7,1948.4 +1.0709375029271,0.7709750721147712,1.832595714594046,1337.3,1074.7,1202.8,740.3,2091.5,2193.3 +1.0709639345502178,0.7709933329790997,1.9634954084936205,1302.1,1128.8,909.3,913.5,1744.0,1525.1 +1.0709541624569971,0.7709853780051823,2.0943951023931953,1060.9,879.6,752.2,1314.8,1383.7,1256.3 +1.0709262638971182,0.7709326252760449,2.2252947962927703,957.3,750.2,691.4,1910.4,1201.4,1165.6 +1.0709231872607112,0.7709199094599692,2.356194490192345,941.6,692.9,693.6,1820.3,1128.8,1128.9 +1.070921372394145,0.7709160910355379,2.4870941840919194,1000.4,691.4,750.6,1868.9,1143.3,1202.1 +1.0709344699569496,0.7708769366834056,2.6179938779914944,1155.1,753.3,881.0,2079.2,1256.9,1384.5 +1.0709371385231687,0.7708684479279819,2.748893571891069,910.9,910.9,1130.9,1688.2,1524.4,1304.3 +1.0709659821054227,0.7708435098831374,2.8797932657906435,739.6,1291.6,1671.5,1336.9,1201.3,1073.7 +1.0709790189056407,0.7708376923046492,3.010692959690218,669.0,2075.2,1890.4,1163.8,1038.1,979.2 +1.0710347392245128,0.8712798133863642,0.0,763.0,1850.7,1851.0,999.1,971.0,971.0 +1.0709889095045226,0.8707951109541303,0.1308996938995747,816.3,1891.2,1950.2,1017.9,979.5,1038.9 +1.0710163198610465,0.8708039481063674,0.2617993877991494,948.6,2091.0,1962.1,1128.4,1074.1,1201.7 +1.0710406855498915,0.8708196796752217,0.39269908169872414,1215.2,1603.9,1384.8,1389.0,1270.7,1050.8 +1.0710585069312073,0.8708410723654587,0.5235987755982988,1787.8,1268.7,1141.5,1154.5,996.7,869.1 +1.071078840097414,0.870876554030044,0.6544984694978736,1868.8,1098.4,1039.6,1000.5,854.1,795.0 +1.0710808099216655,0.8708912336577965,0.7853981633974483,1821.2,1029.1,1028.5,940.8,793.6,793.0 +1.0710802395265695,0.8709387731128528,0.916297857297023,1911.3,1039.4,1098.1,956.9,794.9,853.7 +1.0710770297676913,0.8709525742886284,1.0471975511965976,1986.3,1141.0,1268.0,1061.3,867.9,995.2 +1.0710763368907827,0.8709524914942846,1.1780972450961724,1389.6,1384.0,1306.7,1216.0,1050.8,1270.1 +1.071037861990386,0.8709888839930569,1.3089969389957472,1128.8,1201.5,1074.0,948.9,1490.0,1869.0 +1.071012348437756,0.8710038235384208,1.4398966328953218,1017.0,1037.7,979.1,815.1,1947.2,1889.4 +1.0710441266319484,0.8709970728073544,1.5707963267948966,999.1,971.0,970.8,762.9,1851.8,1851.2 +1.070998788790281,0.8709958423920057,1.7016960206944713,1059.4,978.7,1037.1,772.6,1889.7,1948.0 +1.070960425802444,0.8709842909943062,1.832595714594046,1221.8,1074.9,1202.4,856.1,2091.6,1960.2 +1.0709868828174915,0.87100222638484,1.9634954084936205,1302.0,1269.7,1050.7,1055.5,1602.7,1383.8 +1.0709826015804984,0.8709998171012845,2.0943951023931953,1060.9,995.0,867.9,1514.4,1268.2,1140.7 +1.070959411661202,0.8709555818345858,2.2252947962927703,957.4,853.9,795.1,1910.5,1097.9,1039.3 +1.070958644315705,0.8709525550355257,2.356194490192345,941.6,793.0,793.6,1820.3,1028.7,1029.1 +1.070956496826856,0.8709582516614933,2.4870941840919194,1000.5,794.9,854.1,1868.8,1039.7,1098.6 +1.0709669274008577,0.8709275304641135,2.6179938779914944,1224.9,869.1,996.6,2078.9,1141.3,1269.1 +1.070965109527464,0.8709259546088319,2.748893571891069,1052.6,1052.4,1272.4,1547.2,1387.4,1304.5 +1.070988269001399,0.8709060460010529,2.8797932657906435,855.3,1491.2,1871.0,1221.4,1201.2,1074.1 +1.0709950116724634,0.8709033117037583,3.010692959690218,772.5,1949.0,1890.1,1060.4,1038.0,979.1 +1.1709993584172729,0.17079676495160134,0.0,63.1,1751.0,1750.9,1699.1,1071.0,1070.8 +1.171009135050403,0.17146666556101198,0.1308996938995747,91.6,1787.5,1846.8,1742.5,1049.3,233.6 +1.170955016879531,0.17144910304989236,0.2617993877991494,139.5,1975.5,2103.1,1937.2,474.9,95.3 +1.1709006598104466,0.1714140021365802,0.39269908169872414,223.8,2411.6,2372.2,1603.1,282.3,63.0 +1.1708570273250003,0.17136788695954253,0.5235987755982988,393.3,2078.1,1950.3,1270.2,187.5,59.8 +1.1708378569871911,0.17132805174356402,0.6544984694978736,912.8,1823.1,1763.7,1104.0,129.5,70.5 +1.1708220005983572,0.171264673058513,0.7853981633974483,1721.0,1728.9,1728.4,1040.7,93.8,93.2 +1.1708236565353827,0.1712384563415026,0.916297857297023,1807.9,1763.5,1822.5,917.9,70.7,129.5 +1.1708399840012125,0.17118616512896545,1.0471975511965976,2055.0,1949.0,2048.1,393.9,59.5,186.8 +1.1708723602259383,0.1711313409769235,1.1780972450961724,2381.4,1669.4,1448.8,224.4,63.4,282.4 +1.1708757357447892,0.17112670897978144,1.3089969389957472,1937.7,1316.9,1189.6,139.9,95.6,474.9 +1.1708976481219602,0.17120686555654085,1.4398966328953218,1740.8,1141.2,1082.7,91.1,238.5,1067.2 +1.1710764660778705,0.17121927167752293,1.5707963267948966,1698.8,1070.9,1070.8,63.1,1751.2,1751.3 +1.171014936228905,0.17121644172123052,1.7016960206944713,1783.8,1064.8,237.5,48.4,1786.3,1844.8 +1.1709647323347565,0.1712000339868074,1.832595714594046,2031.1,474.2,95.2,46.9,1976.0,2103.7 +1.1709823205973184,0.17121132357635305,1.9634954084936205,1443.0,282.0,63.1,63.5,2413.1,2370.9 +1.1709718478155278,0.17120131340417788,2.0943951023931953,1176.2,186.6,59.3,117.2,2076.1,1948.9 +1.1709449898187572,0.1711489949467866,2.2252947962927703,1060.9,129.3,70.6,319.4,1822.1,1763.4 +1.1709426493036696,0.17113794624038103,2.356194490192345,1041.7,93.1,93.8,1720.4,1728.3,1729.0 +1.1709406332184584,0.17113620387132222,2.4870941840919194,316.1,70.4,129.6,1765.3,1764.1,1823.4 +1.170952805645403,0.17109877734736,2.6179938779914944,117.4,59.8,187.6,1963.7,1950.7,2042.9 +1.1709537459881956,0.1710914973638158,2.748893571891069,62.6,62.7,282.8,2408.8,1665.5,1445.5 +1.1709806979074777,0.1710669183683653,2.8797932657906435,46.5,94.9,474.9,2029.9,1316.4,1189.2 +1.1709918825098315,0.17106067438423067,3.010692959690218,48.2,235.3,1059.3,1784.6,1141.4,1082.5 +1.1710460835306584,0.2713614452678861,0.0,163.2,1750.9,1751.4,1599.1,1071.1,1071.1 +1.171019054817385,0.27135949705691487,0.1308996938995747,195.1,1787.7,1846.9,1639.0,1083.5,616.6 +1.1709651473671348,0.2713425097793336,0.2617993877991494,255.1,1975.9,2103.2,1822.5,673.8,294.3 +1.1709126834640176,0.27130918716012364,0.39269908169872414,365.5,2412.3,2230.7,1602.8,423.2,204.0 +1.1708708709862927,0.2712656144067691,0.5235987755982988,592.7,1961.9,1834.3,1269.8,302.9,175.3 +1.1708527617373976,0.27122849980962616,0.6544984694978736,1299.4,1719.6,1660.4,1103.8,232.9,173.9 +1.1708374420563483,0.2711679461879051,0.7853981633974483,1721.1,1628.9,1628.3,1041.0,193.7,193.2 +1.1708389464714606,0.2711442620558113,0.916297857297023,1784.6,1659.9,1719.1,1060.7,174.1,232.9 +1.1708546789471812,0.2710942491629409,1.0471975511965976,2055.1,1834.0,1961.3,592.8,175.0,302.3 +1.1708861628783236,0.27104154463800034,1.1780972450961724,2238.8,1668.8,1448.2,365.8,204.4,423.6 +1.170888300723852,0.27103860360127796,1.3089969389957472,1821.7,1316.9,1189.5,255.3,294.8,674.3 +1.1709087105920324,0.2710276525349742,1.4398966328953218,1637.5,1141.0,1082.7,194.4,628.6,1458.0 +1.1709884873342373,0.271008824150887,1.5707963267948966,1598.6,1071.2,1070.7,163.2,1751.4,1750.9 +1.1709883352558326,0.2710079493426454,1.7016960206944713,1680.1,1082.1,627.0,152.0,1786.5,1844.9 +1.1709905160077188,0.27100739468955015,1.832595714594046,1915.6,673.5,294.6,162.6,1976.1,2103.7 +1.1710510362919249,0.271045562728252,1.9634954084936205,1443.1,423.3,204.3,205.3,2412.7,2229.3 +1.1710721462725393,0.27106943543505335,2.0943951023931953,1176.3,302.1,174.9,317.1,1960.5,1833.5 +1.1710652646311817,0.27105449654163016,2.2252947962927703,1060.9,232.9,174.1,707.3,1718.7,1659.9 +1.1710718519967003,0.27108201151039024,2.356194490192345,1041.4,193.2,193.8,1720.4,1628.1,1628.9 +1.171068538191392,0.2711170030118675,2.4870941840919194,701.4,174.0,233.1,1765.5,1660.7,1720.1 +1.1710708840964197,0.2711118388167999,2.6179938779914944,316.5,175.4,303.2,1963.6,1835.0,1962.5 +1.1710551809812582,0.2711312124290697,2.748893571891069,204.0,204.1,424.2,2408.1,1665.3,1445.6 +1.1710610668939987,0.27112637734022416,2.8797932657906435,162.0,294.4,674.5,1914.2,1316.7,1189.1 +1.1709048926051249,0.27086425531161873,3.010692959690218,151.6,621.5,1444.2,1681.5,1141.6,1082.7 +1.1709714511404485,0.3711420636240872,0.0,263.0,1750.7,1751.1,1498.8,1071.0,1071.2 +1.1709617860978005,0.37114172065316664,0.1308996938995747,298.4,1787.6,1846.8,1535.6,1083.0,1001.4 +1.1709253793308465,0.37113094237661226,0.2617993877991494,370.5,1975.4,2103.3,1706.3,873.6,493.9 +1.170887690698982,0.3711076184960902,0.39269908169872414,506.7,2309.9,2090.4,1603.1,564.4,345.1 +1.1708568432040758,0.3710764771543795,0.5235987755982988,791.3,1846.9,1719.3,1270.2,418.5,290.8 +1.1708458796916974,0.37105298009965226,0.6544984694978736,1682.3,1616.6,1557.1,1104.0,336.5,277.3 +1.1708337741261805,0.3710062697766139,0.7853981633974483,1721.1,1529.1,1528.2,1040.8,293.6,293.0 +1.17083524301598,0.3709958142993659,0.916297857297023,1807.5,1556.4,1615.4,1134.3,277.5,336.2 +1.1708479425349012,0.3709578075351714,1.0471975511965976,2054.4,1718.4,1845.8,792.7,290.3,417.6 +1.1708739006811215,0.37091508856414634,1.1780972450961724,2098.4,1669.5,1448.5,507.5,345.2,564.3 +1.1708689478084173,0.3709200114661202,1.3089969389957472,1706.9,1317.4,1189.7,370.8,493.7,872.9 +1.1708810970850687,0.3709147447864196,1.4398966328953218,1534.6,1141.2,1082.8,297.8,1016.5,1763.0 +1.170951906506089,0.37089879320807406,1.5707963267948966,1499.1,1070.9,1070.8,263.1,1751.2,1751.0 +1.1709430781475267,0.3708985008392587,1.7016960206944713,1576.8,1082.1,1017.1,255.3,1786.3,1844.5 +1.1709372040052737,0.3708965271319822,1.832595714594046,1799.2,873.0,493.6,278.0,1975.5,2103.3 +1.1709908291871625,0.37093107653351387,1.9634954084936205,1443.6,564.5,345.3,346.8,2308.8,2089.3 +1.171006788902897,0.37094983244334534,2.0943951023931953,1176.5,417.7,290.3,516.3,1846.0,1718.6 +1.1709965548388392,0.370929168588809,2.2252947962927703,1061.0,336.3,277.5,1092.9,1615.6,1556.6 +1.1710017519324063,0.37095060071606567,2.356194490192345,1041.5,293.1,293.6,1720.3,1528.5,1528.8 +1.1709990602146794,0.37097968328428355,2.4870941840919194,1087.7,277.3,336.3,1765.2,1557.2,1616.2 +1.17100338586275,0.3709696100566997,2.6179938779914944,515.7,290.9,418.5,1963.4,1719.4,1847.0 +1.1709910739124711,0.37098510532691087,2.748893571891069,345.3,345.3,565.2,2254.3,1666.2,1446.0 +1.1710007781288252,0.3709778478224546,2.8797932657906435,277.5,493.5,873.4,1799.4,1317.0,1189.6 +1.1709924263993452,0.3709831566735782,3.010692959690218,255.0,1008.5,1763.9,1577.9,1141.6,1082.5 +1.171022364844802,0.47126561873994,0.0,362.9,1750.9,1751.2,1399.1,1071.0,1071.0 +1.1709809353577991,0.47067442552550776,0.1308996938995747,402.0,1764.5,1846.4,1432.4,1083.1,1142.5 +1.1710126500982654,0.47068475015706635,0.2617993877991494,485.9,1975.4,2102.6,1590.6,1073.3,693.4 +1.1710494590573481,0.4707084354378366,0.39269908169872414,648.4,2168.9,1949.9,1603.4,705.7,486.4 +1.1710787986718112,0.47074232545786243,0.5235987755982988,990.1,1731.6,1603.8,1270.2,534.2,406.5 +1.1711070760497921,0.4707925576454075,0.6544984694978736,1765.4,1513.0,1453.7,1103.9,440.0,380.8 +1.171112696369358,0.47082275189474165,0.7853981633974483,1721.0,1429.0,1428.3,1040.9,393.6,393.0 +1.1711118648285601,0.4708851660951465,0.916297857297023,1899.8,1453.4,1512.0,1060.5,380.9,439.7 +1.1711048567413034,0.47091238422641135,1.0471975511965976,2054.7,1602.6,1730.3,992.8,405.7,533.0 +1.1710975216173465,0.47089307398451963,1.1780972450961724,1957.1,1669.7,1448.7,649.2,486.2,705.1 +1.1708437810420018,0.47085992149047984,1.3089969389957472,1590.8,1316.9,1189.1,486.3,693.5,1072.9 +1.170858264594129,0.47085312931195267,1.4398966328953218,1430.8,1141.1,1082.7,401.2,1408.4,1785.5 +1.1709374146644953,0.47083562240355414,1.5707963267948966,1398.9,1071.0,1070.8,363.0,1751.0,1751.0 +1.1709379150007861,0.47083584356954633,1.7016960206944713,1473.6,1082.1,1140.5,358.8,1786.4,1844.9 +1.1709408553552918,0.47083646561553305,1.832595714594046,1684.5,1071.4,692.4,393.7,1976.1,2104.2 +1.1710018761467411,0.4708758469643979,1.9634954084936205,1442.8,705.1,486.2,488.8,2166.4,1947.5 +1.1710232300396963,0.470900784787867,2.0943951023931953,1176.1,532.9,405.8,716.4,1730.0,1602.6 +1.1710165160579569,0.4708866531565914,2.2252947962927703,1060.8,439.6,380.9,1482.6,1511.9,1453.1 +1.1710233090358417,0.4709148288487075,2.356194490192345,1041.5,393.0,393.6,1720.6,1428.4,1429.2 +1.1710202768790319,0.47095047859297146,2.4870941840919194,1104.0,380.8,440.0,1765.3,1453.7,1513.0 +1.1710230280191374,0.4709460428506995,2.6179938779914944,714.4,406.5,534.3,1963.8,1604.0,1731.9 +1.1710076549579929,0.47096636781328005,2.748893571891069,486.4,486.8,707.0,2112.1,1665.2,1445.1 +1.1710137510407346,0.4709626655093846,2.8797932657906435,393.0,693.4,1073.7,1683.3,1316.4,1189.1 +1.1710012837727883,0.47097032091099145,3.010692959690218,358.5,1397.6,1786.4,1474.1,1141.3,1082.6 +1.1710261864341358,0.5712489895944748,0.0,462.9,1751.2,1750.7,1298.9,1070.8,1071.0 +1.1709923175846386,0.5706635242149831,0.1308996938995747,505.7,1787.1,1846.4,1328.5,1083.0,1216.8 +1.1710265879198054,0.5706746879938864,0.2617993877991494,601.6,1975.5,2103.0,1475.1,1189.4,892.7 +1.1710648323279707,0.5706993596099972,0.39269908169872414,790.0,2027.4,1808.5,1603.3,846.9,627.7 +1.1710950688992336,0.5707343273177472,0.5235987755982988,1189.2,1615.7,1488.3,1270.2,649.7,522.1 +1.17112378692733,0.5707856237307336,0.6544984694978736,1765.2,1409.2,1350.2,1103.8,543.5,484.3 +1.1711295845549687,0.5708169034242938,0.7853981633974483,1721.3,1329.2,1328.5,1040.9,493.4,492.9 +1.1711286087744435,0.5708802593530868,0.916297857297023,1807.7,1349.8,1408.8,1060.5,484.4,543.1 +1.171121253912782,0.5709082790727777,1.0471975511965976,2054.3,1487.5,1615.0,1148.0,521.2,648.5 +1.171113456560235,0.5709199323362402,1.1780972450961724,1815.2,1669.3,1448.4,790.8,627.4,846.3 +1.1710660001818167,0.5709651529186341,1.3089969389957472,1475.9,1317.3,1189.6,601.9,891.8,1271.0 +1.1710302990086496,0.5709859752037625,1.4398966328953218,1327.7,1141.2,1082.7,504.5,1795.3,1785.6 +1.1710513842470802,0.570981987893262,1.5707963267948966,1299.0,1070.7,1070.6,462.9,1751.3,1751.1 +1.1709959523180893,0.5709807600780077,1.7016960206944713,1369.9,1081.9,1234.9,462.1,1785.9,1844.8 +1.170948495900706,0.5709668496629858,1.832595714594046,1568.5,1190.3,892.0,509.0,1975.5,2103.3 +1.1709672968154397,0.5709803009331185,1.9634954084936205,1443.7,846.4,627.2,630.0,2026.1,1807.3 +1.1709573074572686,0.5709720103013141,2.0943951023931953,1176.8,648.6,521.3,915.3,1615.2,1487.7 +1.1709304378328043,0.5709212248987845,2.2252947962927703,1061.1,543.2,484.3,1784.4,1408.5,1349.9 +1.170928019353275,0.5709113516368711,2.356194490192345,1041.5,492.9,493.4,1720.6,1328.4,1329.3 +1.1709261761830172,0.5709104633783331,2.4870941840919194,1103.9,484.3,543.3,1765.0,1350.4,1409.2 +1.1709384519250339,0.570874030054241,2.6179938779914944,914.2,521.9,649.7,1963.3,1488.2,1615.9 +1.1709398251121472,0.5708677802803128,2.748893571891069,628.0,628.0,848.0,1971.7,1665.9,1446.2 +1.1709668992996056,0.5708445528318757,2.8797932657906435,508.5,892.3,1271.8,1568.3,1316.9,1189.7 +1.1709779543906338,0.5708398500399563,3.010692959690218,462.0,1782.4,1786.6,1371.1,1141.5,1082.7 +1.1710312370304465,0.671140074799611,0.0,562.8,1751.0,1751.2,1199.1,1071.0,1071.0 +1.1710034420870146,0.6711398062754215,0.1308996938995747,609.1,1787.4,1846.6,1224.9,1083.1,1142.5 +1.1709484532385526,0.6711239574602912,0.2617993877991494,717.1,1975.9,2103.1,1359.9,1189.6,1092.2 +1.1708947035084702,0.671091254897618,0.39269908169872414,931.5,1886.7,1667.3,1603.3,987.8,768.6 +1.1708515336897733,0.6710476676702739,0.5235987755982988,1388.7,1500.3,1372.7,1270.1,765.1,637.7 +1.170832530036204,0.671010121853125,0.6544984694978736,1765.0,1305.4,1246.8,1104.1,647.1,587.8 +1.1708166232246735,0.6709486376301659,0.7853981633974483,1721.0,1229.0,1228.7,1040.7,593.4,592.9 +1.1708183081464871,0.6709240911603156,0.916297857297023,1807.4,1246.2,1305.0,1060.6,587.9,646.7 +1.1708347610935033,0.6708734314599978,1.0471975511965976,2054.7,1372.0,1499.2,1176.8,636.9,764.1 +1.1708672551267933,0.670820335795512,1.1780972450961724,1673.1,1665.9,1448.8,932.6,768.5,987.5 +1.1708706145556533,0.6708177148448962,1.3089969389957472,1360.1,1317.5,1189.6,717.6,1091.2,1469.9 +1.1708921058682407,0.6708078041078123,1.4398966328953218,1224.0,1141.3,1082.9,608.1,1844.0,1785.8 +1.1709725128784867,0.6707900632832957,1.5707963267948966,1199.1,1070.9,1070.6,563.1,1751.0,1751.0 +1.1709725052310296,0.670790538797174,1.7016960206944713,1266.3,1082.1,1140.4,565.6,1763.3,1844.8 +1.1709742750479712,0.6707914239953883,1.832595714594046,1452.6,1190.4,1091.3,624.7,1975.3,2103.2 +1.1710340595575832,0.6708304430651353,1.9634954084936205,1443.7,987.7,768.7,771.8,1885.4,1666.5 +1.1710543803617322,0.6708545876766103,2.0943951023931953,1176.2,764.2,636.9,1114.9,1499.2,1372.0 +1.1710467369814097,0.6708396613850374,2.2252947962927703,1060.8,646.8,587.9,1807.5,1304.9,1246.3 +1.171052931567382,0.6708668300942588,2.356194490192345,1041.6,593.1,593.4,1720.7,1228.5,1228.9 +1.1710498500838387,0.670901253894197,2.4870941840919194,1104.2,587.9,646.9,1765.1,1246.7,1305.6 +1.1710526848179892,0.6708958283177906,2.6179938779914944,1113.4,637.6,765.3,1963.5,1372.6,1500.1 +1.171038034046705,0.6709151968266489,2.748893571891069,769.6,769.4,989.4,1830.1,1665.9,1445.7 +1.1710448405318636,0.6709109247677583,2.8797932657906435,624.3,1091.8,1471.8,1452.8,1316.9,1189.7 +1.1710332370284444,0.6709183358470592,3.010692959690218,565.5,1845.7,1786.7,1267.5,1141.5,1082.6 +1.1710591089288702,0.7711977963820744,0.0,662.9,1751.2,1751.1,1099.1,1070.9,1071.0 +1.171003269811917,0.7706509844977567,0.1308996938995747,712.9,1787.3,1846.7,1121.2,1083.3,1142.5 +1.171034574531782,0.7706612669019204,0.2617993877991494,832.9,1975.9,2103.0,1244.0,1189.7,1291.8 +1.1711146003568524,0.7707084139246978,0.39269908169872414,1073.3,1745.0,1526.0,1530.9,1129.4,909.9 +1.1711247138181393,0.7707216056781405,0.5235987755982988,1588.1,1384.4,1256.9,1270.2,881.0,753.4 +1.1707935429953837,0.7710238620925369,0.6544984694978736,1764.6,1201.7,1142.9,1103.8,750.4,691.4 +1.1707894317460767,0.771008708001919,0.7853981633974483,1721.3,1129.1,1128.6,1040.9,693.6,693.2 +1.1707907285054129,0.7709917789501401,0.916297857297023,1807.8,1142.9,1201.6,1060.8,691.7,750.5 +1.170806393056907,0.77096357997287,1.0471975511965976,2055.3,1256.6,1384.3,1343.5,752.7,880.3 +1.1708238475429218,0.7709353967860506,1.1780972450961724,1530.5,1525.5,1447.6,1073.5,910.3,1129.6 +1.17081423500899,0.7709448881713654,1.3089969389957472,1243.8,1316.8,1189.1,833.1,1291.9,1672.0 +1.170823594502074,0.7709408668454094,1.4398966328953218,1120.5,1140.9,1082.5,711.4,1843.6,1785.7 +1.1708924789866515,0.7709256088947676,1.5707963267948966,1099.0,1070.7,1070.7,663.1,1751.7,1751.1 +1.170882101896472,0.7709251938907289,1.7016960206944713,1163.1,1082.0,1140.6,669.2,1786.4,1844.9 +1.1708750993252337,0.7709223006834556,1.832595714594046,1338.0,1190.6,1289.8,740.8,1976.4,2104.4 +1.1709718854339066,0.7709794293326777,1.9634954084936205,1442.5,1128.1,909.3,914.0,1742.7,1524.0 +1.170964657050032,0.7709728178241559,2.0943951023931953,1176.3,879.4,752.2,1316.3,1383.2,1256.2 +1.1709512595667564,0.7709449889297308,2.2252947962927703,1060.6,750.1,691.6,1807.0,1201.2,1142.5 +1.1709571222837503,0.7709669839609625,2.356194490192345,1041.4,693.0,693.7,1720.8,1128.4,1129.1 +1.1709545356219653,0.7709995116204249,2.4870941840919194,1104.2,691.6,750.8,1765.7,1143.1,1202.6 +1.1709582068416118,0.7709931617151813,2.6179938779914944,1267.5,753.6,881.4,1964.3,1257.2,1385.1 +1.1709437523810395,0.7710122443509366,2.748893571891069,910.5,911.4,1131.8,1687.6,1529.6,1445.1 +1.1709508948557268,0.7710076344970882,2.8797932657906435,739.6,1292.8,1673.2,1336.6,1316.2,1188.9 +1.1709394658498666,0.7710146371682804,3.010692959690218,669.0,1845.4,1786.4,1163.7,1141.1,1082.6 +1.170965578425194,0.8712941446008347,0.0,763.0,1750.7,1751.0,998.9,1070.8,1070.9 +1.1709573213531852,0.8706770053063309,0.1308996938995747,816.2,1787.6,1846.6,1017.9,1083.2,1142.2 +1.1709953127455597,0.870689237773062,0.2617993877991494,948.1,1975.7,1962.5,1128.3,1189.3,1316.9 +1.171033112108942,0.8707134897473863,0.39269908169872414,1214.9,1604.4,1384.8,1388.7,1270.7,1051.1 +1.1710621236639591,0.8707469369621952,0.5235987755982988,1786.6,1269.1,1141.4,1270.3,996.9,869.1 +1.1710900135935616,0.8707962633828696,0.6544984694978736,1765.1,1098.8,1039.7,1104.0,854.1,795.3 +1.1710954580008035,0.8708253650344255,0.7853981633974483,1721.5,1029.0,1028.3,1040.7,793.5,793.0 +1.1710947551079882,0.8708867411869465,0.916297857297023,1807.6,1039.3,1098.0,1060.3,795.0,853.6 +1.171071325097985,0.870967547068004,1.0471975511965976,2029.3,1140.7,1268.1,1176.7,867.5,995.0 +1.1710853343801177,0.8709446568647774,1.1780972450961724,1389.8,1383.7,1448.8,1216.1,1050.4,1269.5 +1.1710089842514053,0.8710156076213398,1.3089969389957472,1129.3,1317.2,1189.7,949.1,1489.0,1868.1 +1.1709711830523877,0.8710390206341789,1.4398966328953218,1017.2,1141.1,1082.7,815.0,1844.4,1785.4 +1.1710221529757012,0.87102817949017,1.5707963267948966,999.1,1070.8,1070.7,762.8,1751.4,1751.0 +1.170968620993208,0.871027011806794,1.7016960206944713,1059.5,1082.1,1140.2,772.4,1786.1,1844.2 +1.1709146644323936,0.8710111776349996,1.832595714594046,1221.7,1190.2,1317.7,855.8,1975.4,1961.5 +1.1709257330405112,0.8710196677793265,1.9634954084936205,1443.7,1270.0,1051.1,1054.7,1603.3,1384.3 +1.170909517246049,0.8710044282560749,2.0943951023931953,1176.6,995.3,867.9,1513.7,1268.4,1141.1 +1.170878602286313,0.8709458475743879,2.2252947962927703,1060.8,853.9,794.9,1807.1,1098.2,1039.2 +1.1708744411442773,0.8709278732675323,2.356194490192345,1041.5,793.0,793.4,1720.4,1028.6,1029.0 +1.1708730704652284,0.8709192345223191,2.4870941840919194,1103.7,794.8,854.0,1764.9,1039.6,1098.5 +1.1708735923041185,0.8709213204969948,2.6179938779914944,1270.2,868.8,996.5,1963.3,1141.2,1268.7 +1.1708959826327623,0.870882227376065,2.748893571891069,1052.5,1052.0,1272.1,1547.6,1387.2,1446.2 +1.1709327792333395,0.870850045396466,2.8797932657906435,855.4,1490.7,1869.9,1221.7,1317.0,1189.7 +1.1709481566438715,0.870843101565846,3.010692959690218,772.5,1845.6,1786.5,1060.5,1141.4,1082.9 +1.2709519207562627,0.1707509824300979,0.0,63.0,1650.8,1651.3,1698.9,1171.0,1170.9 +1.2709886831099968,0.17145774315217843,0.1308996938995747,91.6,1684.1,1743.2,1742.8,1049.2,233.6 +1.2709416424335351,0.17144237449395217,0.2617993877991494,139.5,1860.5,1987.7,1937.3,474.8,95.3 +1.2708894395965986,0.1714086085312725,0.39269908169872414,223.8,2270.4,2372.3,1744.4,282.3,63.0 +1.2708464873298206,0.17136317035862625,0.5235987755982988,393.3,2078.0,1950.2,1385.8,187.5,59.8 +1.2708275562003968,0.17132368679960308,0.6544984694978736,912.8,1823.3,1764.2,1207.4,129.5,70.4 +1.2708118278870257,0.1712605540055181,0.7853981633974483,1621.0,1728.8,1728.3,1140.9,93.8,93.2 +1.2708135424909137,0.17123453348298878,0.916297857297023,1704.0,1763.7,1822.4,917.5,70.7,129.5 +1.2708298863784293,0.17118242799165073,1.0471975511965976,1939.1,1949.4,2076.9,393.8,59.5,186.8 +1.2708622414925363,0.17112779591939664,1.1780972450961724,2412.1,1811.3,1590.0,224.3,63.3,282.5 +1.2708655438959124,0.17112332156721677,1.3089969389957472,1937.4,1432.8,1305.0,139.9,95.6,474.8 +1.270887341384647,0.17111124880264605,1.4398966328953218,1741.2,1244.5,1186.5,91.1,238.5,1067.3 +1.2709686613246856,0.1710914245284021,1.5707963267948966,1698.7,1170.9,1170.6,63.3,1650.8,1650.8 +1.2709701516132057,0.17109001091545206,1.7016960206944713,1783.4,1066.7,238.4,48.6,1682.8,1740.9 +1.2709739690477855,0.17108947235006355,1.832595714594046,2030.0,474.8,95.6,47.1,1860.2,1987.9 +1.271036080089994,0.1711279763617206,1.9634954084936205,1584.8,282.4,63.3,63.7,2270.8,2370.9 +1.2710585815287616,0.1711525270166987,2.0943951023931953,1292.1,186.8,59.5,117.4,2076.6,1949.1 +1.2710526608665844,0.17113870013972843,2.2252947962927703,1164.3,129.5,70.7,319.5,1822.2,1763.4 +1.2710597714976892,0.17116752354137588,2.356194490192345,1141.6,93.3,93.8,1620.3,1728.3,1728.9 +1.271056580289324,0.17120377991685554,2.4870941840919194,316.8,70.5,129.6,1661.6,1764.0,1823.4 +1.2710584755295102,0.17119980719839578,2.6179938779914944,117.6,59.9,187.6,1847.8,1950.2,2078.4 +1.271042110252201,0.1712200145863041,2.748893571891069,62.7,62.7,282.8,2266.7,1806.8,1587.1 +1.2710470027758722,0.17121567399955784,2.8797932657906435,46.6,95.0,474.8,2029.9,1432.1,1305.0 +1.2710336083427944,0.17122215126992124,3.010692959690218,48.2,235.2,1058.3,1784.8,1245.0,1186.1 +1.2710582612518868,0.27150046722057763,0.0,163.2,1651.4,1651.0,1599.0,1171.1,1171.1 +1.2710070536316849,0.2707320486222664,0.1308996938995747,195.0,1683.9,1720.3,1639.1,1186.7,617.3 +1.2710303202429092,0.27073966883746925,0.2617993877991494,254.9,1860.0,1987.4,1821.7,674.2,294.5 +1.271060266797694,0.27075900664382613,0.39269908169872414,365.3,2269.5,2232.1,1744.4,423.3,204.0 +1.2710845341473718,0.270787449082023,0.5235987755982988,592.0,1962.5,1834.8,1385.9,302.9,175.3 +1.2711094894724502,0.2708316584064445,0.6544984694978736,1297.1,1719.7,1661.0,1207.6,232.9,173.8 +1.2711135854708828,0.2708556662897945,0.7853981633974483,1621.1,1628.9,1628.5,1140.8,193.6,193.0 +1.2711127576210142,0.2709121490340882,0.916297857297023,1704.0,1660.3,1719.2,1163.8,173.9,232.7 +1.2708286688015717,0.27090977945516914,1.0471975511965976,1939.7,1834.5,1962.4,592.3,174.8,302.2 +1.2708470265537681,0.2708800170207306,1.1780972450961724,2238.7,1810.2,1589.3,365.4,204.2,423.5 +1.2708408476642372,0.2708862708710047,1.3089969389957472,1822.0,1432.5,1304.8,255.1,294.6,674.3 +1.2708551131029024,0.27087977243499184,1.4398966328953218,1637.6,1244.4,1186.0,194.2,628.4,1458.4 +1.2709294215335185,0.2708634317332501,1.5707963267948966,1599.0,1170.9,1170.7,163.0,1651.2,1651.4 +1.2709241600653456,0.2708634514516448,1.7016960206944713,1680.3,1185.5,625.9,151.8,1682.8,1741.4 +1.2709216088217181,0.27086230051198745,1.832595714594046,1915.9,672.9,294.1,162.5,1860.9,1988.3 +1.2709779619861437,0.27089867884032093,1.9634954084936205,1583.6,422.9,204.0,205.2,2271.8,2229.3 +1.2709958621705226,0.27091982927708247,2.0943951023931953,1291.8,301.9,174.7,316.9,1960.7,1833.7 +1.2709870326714294,0.27090147043905644,2.2252947962927703,1164.3,232.6,174.0,707.2,1718.8,1660.1 +1.2709929503677269,0.270925323189388,2.356194490192345,1141.6,193.0,193.6,1620.5,1628.3,1629.1 +1.2709901362291869,0.2709569275190158,2.4870941840919194,700.3,173.7,232.9,1661.6,1660.7,1720.3 +1.2709940857403361,0.2709489396010354,2.6179938779914944,316.1,175.3,303.1,1848.3,1835.4,1963.3 +1.270980560933264,0.2709663883218423,2.748893571891069,203.7,203.9,424.1,2267.9,1806.3,1586.5 +1.2709890117789957,0.2709605522620586,2.8797932657906435,161.8,294.3,674.5,1913.9,1432.0,1304.6 +1.270979132476876,0.2709668429091727,3.010692959690218,151.5,622.5,1447.1,1681.2,1244.8,1186.1 +1.2710071360114172,0.3712478472621532,0.0,263.0,1650.9,1650.9,1498.9,1171.0,1171.0 +1.2709834200565853,0.3706669620858023,0.1308996938995747,298.5,1683.8,1743.5,1535.5,1264.5,1001.7 +1.2710194070464649,0.3706786403709341,0.2617993877991494,370.5,1860.1,1987.1,1706.6,873.8,494.0 +1.2710576730182312,0.3707032964334316,0.39269908169872414,506.8,2269.7,2090.6,1744.3,564.6,345.2 +1.2710875709120177,0.37073785660640657,0.5235987755982988,791.2,1847.2,1719.7,1385.9,418.6,290.9 +1.271116022772081,0.37078857004897325,0.6544984694978736,1639.0,1616.4,1557.2,1207.4,336.3,277.3 +1.2711217015614529,0.37081919462024526,0.7853981633974483,1621.1,1528.8,1528.7,1140.8,293.6,293.0 +1.271120787051661,0.3708819367396856,0.916297857297023,1703.9,1556.7,1615.6,1209.6,277.4,336.1 +1.2711136351522503,0.37090941645217623,1.0471975511965976,1939.6,1718.3,1846.0,792.5,290.2,417.4 +1.2711061394626748,0.37092062123295566,1.1780972450961724,2098.5,1811.1,1590.4,507.3,345.1,564.1 +1.2710590531556827,0.37096552381944203,1.3089969389957472,1707.3,1432.8,1305.1,370.7,493.3,872.5 +1.2710237564793103,0.37098615648905575,1.4398966328953218,1534.6,1244.8,1186.2,297.7,1015.8,1682.1 +1.2710452497981184,0.3709820650393221,1.5707963267948966,1499.1,1171.1,1170.7,262.9,1651.3,1651.1 +1.2709902004427072,0.3709808391297731,1.7016960206944713,1576.9,1284.4,1017.0,255.1,1682.7,1741.3 +1.2709430849246932,0.37096702842925366,1.832595714594046,1799.9,872.9,493.5,277.8,1860.0,1987.4 +1.2709621818725425,0.3709806340121824,1.9634954084936205,1584.9,564.4,345.1,346.5,2270.3,2089.2 +1.2709524297332084,0.3709725398801744,2.0943951023931953,1292.3,417.5,290.2,515.8,1846.2,1718.6 +1.2709257209782023,0.37092199605762666,2.2252947962927703,1164.4,336.2,277.4,1092.3,1615.6,1556.8 +1.2709233946667167,0.3709123822795348,2.356194490192345,1141.6,292.9,293.5,1620.6,1528.5,1528.9 +1.2709215835758962,0.3709117450266406,2.4870941840919194,1087.2,277.3,336.3,1661.2,1557.5,1616.6 +1.2709338126871752,0.3708755522563363,2.6179938779914944,515.5,290.8,418.4,1847.7,1719.6,1846.9 +1.2709350990262958,0.37086950249721196,2.748893571891069,345.2,345.1,565.1,2266.1,1807.3,1587.6 +1.2709620294831585,0.3708464331729351,2.8797932657906435,277.4,493.3,873.0,1799.3,1432.4,1305.3 +1.2709729151190945,0.3708418328955274,3.010692959690218,255.0,1008.0,1682.9,1578.2,1245.1,1186.3 +1.2710259782339806,0.4711418834370158,0.0,362.9,1651.1,1650.9,1399.2,1170.9,1170.8 +1.2709980421266147,0.4711416009445777,0.1308996938995747,402.0,1684.0,1743.4,1432.5,1186.6,1246.1 +1.2709429470964178,0.47112570313472824,0.2617993877991494,485.9,1860.0,1987.2,1590.9,1072.9,693.2 +1.2708891267283198,0.47109292966999927,0.39269908169872414,648.1,2168.7,1949.7,1744.9,705.5,486.2 +1.2708459137253685,0.4710492575274905,0.5235987755982988,990.0,1731.4,1603.9,1385.9,534.1,406.4 +1.270826909400185,0.4710116341641659,0.6544984694978736,1661.7,1513.0,1453.9,1207.5,439.9,380.8 +1.270811013971714,0.47095007276635514,0.7853981633974483,1620.9,1429.0,1428.8,1140.9,393.5,392.9 +1.2708127379284184,0.47092547421165043,0.916297857297023,1704.1,1453.4,1512.1,1164.2,380.9,439.7 +1.2708292355192556,0.47087478079251266,1.0471975511965976,1939.1,1603.1,1730.1,992.5,405.7,533.1 +1.2708617671043752,0.4708216541643484,1.1780972450961724,1956.4,1811.6,1590.5,649.1,486.2,705.2 +1.270865164899042,0.47081902230309103,1.3089969389957472,1591.5,1432.8,1305.3,486.5,692.6,1071.7 +1.2708866887738168,0.470809117265379,1.4398966328953218,1430.8,1244.7,1186.2,401.3,1406.0,1758.8 +1.2709671195061865,0.47079135948447104,1.5707963267948966,1399.1,1171.1,1170.7,363.0,1651.2,1651.1 +1.2709671360130308,0.47079182403161424,1.7016960206944713,1473.6,1185.6,1243.9,358.7,1682.8,1741.3 +1.2709689291303388,0.4707927110081984,1.832595714594046,1684.2,1072.3,693.1,393.6,1860.0,1987.6 +1.27102874536212,0.47083171844312877,1.9634954084936205,1584.6,705.4,486.4,488.3,2167.3,1948.4 +1.2710491076875001,0.4708558501851987,2.0943951023931953,1292.2,533.1,405.7,715.6,1730.5,1603.4 +1.2710415014080882,0.47084093336171073,2.2252947962927703,1164.3,439.7,380.9,1479.8,1512.2,1453.4 +1.271047732732899,0.4708681219863524,2.356194490192345,1141.7,393.0,393.6,1620.5,1428.6,1428.8 +1.2710446907684743,0.4709025689367661,2.4870941840919194,1207.6,380.7,439.9,1661.8,1453.8,1512.7 +1.271047540175868,0.4708971831801183,2.6179938779914944,714.8,406.4,534.0,1847.9,1603.6,1731.3 +1.2710329054035294,0.47091658630416955,2.748893571891069,486.6,486.6,706.5,2113.3,1807.4,1587.5 +1.271039699480828,0.47091234974478935,2.8797932657906435,393.1,692.7,1072.6,1683.7,1432.4,1305.0 +1.2710280733151609,0.4709197851883449,3.010692959690218,358.5,1394.8,1745.4,1474.9,1245.4,1186.2 +1.2710539022931209,0.5711992080923678,0.0,462.9,1651.0,1651.2,1299.0,1171.0,1170.8 +1.2709991982598967,0.5706512839913251,0.1308996938995747,505.6,1683.8,1720.5,1328.3,1186.7,1291.9 +1.2710307194457588,0.5706616254483758,0.2617993877991494,601.6,1859.9,1987.1,1475.3,1272.5,892.9 +1.2710695580981253,0.5706866944185811,0.39269908169872414,790.0,2027.7,1808.5,1744.4,846.9,627.5 +1.2711009635605612,0.5707229493971484,0.5235987755982988,1189.7,1615.9,1488.2,1386.0,649.8,522.1 +1.271130592993403,0.57077597000153,0.6544984694978736,1661.7,1409.3,1350.2,1207.5,543.5,484.5 +1.271136813472536,0.5708091287476007,0.7853981633974483,1621.0,1329.1,1328.3,1140.9,493.6,493.0 +1.2711357854950294,0.5708743024545071,0.916297857297023,1704.1,1349.5,1408.6,1164.0,484.4,543.1 +1.2711279450858668,0.5709039612910374,1.0471975511965976,1939.2,1487.7,1615.0,1192.0,521.2,648.6 +1.2711193166547528,0.5709169579887894,1.1780972450961724,1814.7,1807.1,1590.1,790.9,627.2,846.3 +1.2710708188182174,0.5709631904200829,1.3089969389957472,1475.9,1432.9,1305.2,602.0,891.9,1271.0 +1.2710339410599607,0.570984691486057,1.4398966328953218,1327.6,1244.6,1186.1,504.6,1718.0,1682.2 +1.2710537925499734,0.5709810097167078,1.5707963267948966,1299.0,1170.8,1170.8,462.9,1651.4,1651.2 +1.2709971996135185,0.5709797770598481,1.7016960206944713,1369.8,1185.5,1289.3,462.0,1682.8,1741.2 +1.2709486960017646,0.5709656024945349,1.832595714594046,1568.6,1271.1,892.3,509.0,1859.8,1987.5 +1.2709666158354795,0.5709785387789432,1.9634954084936205,1584.6,846.5,627.3,630.0,2026.6,1807.2 +1.2709559694580936,0.5709695700243371,2.0943951023931953,1292.1,648.6,521.2,915.2,1614.7,1487.7 +1.270928667845084,0.5709180380082892,2.2252947962927703,1164.4,543.2,484.4,1703.8,1408.7,1349.7 +1.2709260482070441,0.5709073809918639,2.356194490192345,1141.5,493.0,493.5,1620.6,1328.3,1329.2 +1.270924233510727,0.5709057300968783,2.4870941840919194,1303.4,484.3,543.4,1661.6,1350.1,1409.4 +1.2709367071616682,0.570868636174618,2.6179938779914944,914.0,522.0,649.6,1847.8,1487.9,1615.6 +1.270938446569765,0.5708618365518221,2.748893571891069,628.1,627.9,848.0,1971.9,1807.6,1587.3 +1.2709659658251184,0.5708382168128432,2.8797932657906435,508.5,892.2,1272.0,1568.5,1432.4,1305.3 +1.2709775178236218,0.5708332770876936,3.010692959690218,462.0,1719.1,1683.3,1371.1,1244.7,1186.0 +1.2710313873342298,0.6711339484377128,0.0,562.8,1651.4,1651.0,1199.3,1170.9,1171.0 +1.271004003476857,0.6711337313151777,0.1308996938995747,609.1,1684.0,1743.1,1225.2,1186.8,1245.8 +1.270949307930513,0.6711180084864681,0.2617993877991494,717.1,1860.0,1987.3,1359.9,1305.3,1092.1 +1.2708957692459186,0.6710854758731131,0.39269908169872414,931.3,1886.5,1667.2,1672.4,988.1,768.7 +1.2708527352678272,0.671042078356646,0.5235987755982988,1388.3,1500.8,1372.5,1386.0,765.4,637.6 +1.2708338196188467,0.6710047340172642,0.6544984694978736,1661.5,1305.8,1246.8,1207.5,646.9,587.9 +1.2708179362227456,0.6709434376260774,0.7853981633974483,1620.9,1229.1,1228.5,1141.0,593.6,592.8 +1.2708196144113693,0.6709190725834591,0.916297857297023,1703.5,1246.2,1305.0,1164.1,587.9,646.8 +1.2708360243954375,0.6708685759010382,1.0471975511965976,1939.0,1371.9,1499.1,1292.2,636.9,764.1 +1.2708684417864826,0.6708156057117374,1.1780972450961724,1673.2,1665.7,1590.5,932.6,768.5,987.6 +1.270871713070681,0.6708130942621904,1.3089969389957472,1360.2,1433.1,1305.2,717.6,1091.2,1470.4 +1.2708931022594323,0.6708032801129487,1.4398966328953218,1224.1,1244.5,1186.2,608.1,1740.4,1682.2 +1.2709733915783674,0.670785583464234,1.5707963267948966,1199.1,1171.1,1170.4,563.0,1651.1,1650.9 +1.270973266514249,0.6707860832248693,1.7016960206944713,1266.3,1185.4,1244.0,565.6,1682.7,1741.1 +1.2709749172892726,0.6707869790853902,1.832595714594046,1453.0,1305.9,1091.7,624.7,1860.0,1987.6 +1.2710345943191301,0.6708259625614392,1.9634954084936205,1585.1,987.7,768.6,771.7,1885.1,1666.0 +1.271054830876299,0.6708500391008796,2.0943951023931953,1292.0,764.1,636.7,1115.0,1499.3,1372.2 +1.2710471202667817,0.6708350405938541,2.2252947962927703,1164.5,646.8,588.0,1781.4,1305.1,1246.1 +1.2710532783668642,0.6708621232463379,2.356194490192345,1141.6,593.0,593.5,1620.6,1228.3,1229.3 +1.271050203287338,0.6708964508854578,2.4870941840919194,1207.5,587.9,647.0,1661.6,1246.8,1305.9 +1.2710530597093619,0.6708909498146101,2.6179938779914944,1113.6,637.6,765.3,1847.8,1372.6,1500.5 +1.2710384729453994,0.6709102528751214,2.748893571891069,769.4,769.3,989.3,1830.4,1670.1,1587.5 +1.271045342741908,0.6709059468156009,2.8797932657906435,624.1,1091.8,1471.6,1452.9,1432.6,1305.3 +1.2710338087093112,0.6709133501015785,3.010692959690218,565.5,1742.3,1683.1,1267.6,1245.2,1186.4 +1.2710597496319074,0.7711928659118836,0.0,663.0,1651.2,1650.8,1099.0,1171.0,1171.0 +1.271003022272532,0.7706497112551056,0.1308996938995747,712.8,1683.7,1743.2,1121.3,1186.8,1246.1 +1.2710343081336737,0.770659989647243,0.2617993877991494,832.7,1860.0,1987.5,1244.1,1384.4,1292.3 +1.2710732352501204,0.7706851310899394,0.39269908169872414,1073.3,1745.3,1525.7,1530.6,1129.5,910.1 +1.2711047783240952,0.7707215583384084,0.5235987755982988,1588.2,1384.9,1257.0,1386.0,881.1,753.3 +1.2711344926924368,0.7707747888819474,0.6544984694978736,1661.8,1202.1,1143.1,1207.4,750.6,691.6 +1.271140748393161,0.7708081767319892,0.7853981633974483,1621.1,1128.9,1128.5,1140.8,693.6,693.0 +1.2711396884368094,0.7708735552776163,0.916297857297023,1704.1,1142.6,1201.4,1163.9,691.4,750.3 +1.2711317708728798,0.7709033897560549,1.0471975511965976,1939.2,1256.6,1383.9,1343.1,752.2,879.5 +1.2711230384786936,0.7709165356607628,1.1780972450961724,1531.2,1524.7,1590.3,1074.4,909.5,1128.6 +1.2710744138638055,0.7709628684323981,1.3089969389957472,1244.4,1432.9,1305.2,833.2,1290.4,1669.3 +1.2710374003336287,0.7709844219684496,1.4398966328953218,1120.3,1244.6,1186.0,711.4,1740.6,1682.1 +1.2710963641343125,0.770969514307017,1.5707963267948966,1098.9,1171.0,1170.7,662.9,1651.2,1651.1 +1.2710121034195383,0.7709672641982381,1.7016960206944713,1162.9,1185.4,1243.9,669.1,1682.8,1741.2 +1.2709580064746697,0.7709513566847197,1.832595714594046,1337.3,1383.0,1290.4,740.3,1860.0,1987.6 +1.2709768066720213,0.7709648441448655,1.9634954084936205,1584.7,1128.8,909.6,913.2,1744.2,1525.0 +1.2709681872494154,0.7709580752681431,2.0943951023931953,1292.3,879.7,752.3,1314.5,1383.8,1256.6 +1.2709424754097995,0.7709095366179897,2.2252947962927703,1164.5,750.3,691.3,1703.6,1201.6,1142.8 +1.270940606259206,0.770902178312,2.356194490192345,1141.6,692.9,693.6,1620.4,1128.4,1129.1 +1.27093865477296,0.7709037417969493,2.4870941840919194,1207.6,691.6,750.4,1661.5,1142.9,1202.2 +1.27095025424783,0.770869478308779,2.6179938779914944,1312.6,753.3,880.8,1847.8,1256.7,1384.4 +1.2709505041386449,0.77086502536393,2.748893571891069,911.1,910.6,1130.8,1689.2,1528.4,1587.5 +1.2709761605814969,0.7708431376222566,2.8797932657906435,739.8,1291.1,1671.2,1337.2,1432.6,1305.0 +1.270985632910451,0.770839305521196,3.010692959690218,669.0,1741.8,1683.3,1164.0,1245.3,1186.2 +1.2710369934522454,0.8711380803937372,0.0,762.8,1651.0,1651.1,999.3,1171.0,1171.0 +1.2710078352208847,0.871137813819479,0.1308996938995747,816.1,1683.5,1743.2,1018.1,1186.5,1246.2 +1.2709518200243728,0.8711216971438034,0.2617993877991494,948.2,1859.9,1987.2,1128.7,1305.1,1432.6 +1.2708972691957625,0.8710885466677332,0.39269908169872414,1214.8,1604.1,1385.2,1389.1,1270.2,1051.1 +1.2708534984153572,0.871044380229167,0.5235987755982988,1786.7,1269.2,1141.5,1385.9,996.5,868.9 +1.2708341017992077,0.8710061839973442,0.6544984694978736,1661.3,1098.9,1039.7,1207.5,854.1,794.9 +1.2708179980828944,0.8709440090398428,0.7853981633974483,1621.1,1029.2,1028.5,1140.9,793.4,793.0 +1.2708196798548808,0.8709188009338793,0.916297857297023,1703.8,1039.1,1097.8,1164.3,794.9,853.7 +1.2708362999620464,0.870867543190488,1.0471975511965976,1938.9,1141.0,1268.1,1292.3,867.9,995.1 +1.2708690960931242,0.8708139518127498,1.1780972450961724,1389.7,1383.7,1590.1,1216.1,1050.6,1269.8 +1.2708728481460343,0.8708109728831612,1.3089969389957472,1129.1,1433.1,1305.1,948.8,1489.2,1835.5 +1.2708947841838298,0.8708008481621368,1.4398966328953218,1017.2,1244.5,1186.2,815.1,1740.7,1682.4 +1.2709756473755773,0.870783027286407,1.5707963267948966,998.8,1170.9,1170.8,762.9,1651.2,1651.2 +1.2709760569944886,0.8707835503149126,1.7016960206944713,1059.5,1185.5,1244.0,772.6,1682.9,1741.4 +1.2709781825869724,0.8707845881351184,1.832595714594046,1221.5,1305.9,1433.7,856.0,1860.2,1987.7 +1.2710382475441901,0.8708238313729526,1.9634954084936205,1550.2,1270.2,1050.8,1055.2,1602.8,1383.7 +1.271085188990962,0.8708831271730384,2.0943951023931953,1292.2,995.4,867.9,1514.3,1268.3,1140.8 +1.271063318878043,0.8708415106229697,2.2252947962927703,1164.2,853.7,795.0,1703.9,1098.2,1039.2 +1.27106786540892,0.8708615652987586,2.356194490192345,1141.5,792.9,793.3,1620.4,1028.4,1029.1 +1.2710647806239104,0.8708958708528263,2.4870941840919194,1207.6,794.9,853.9,1661.2,1039.7,1098.8 +1.271067022610153,0.870892357324486,2.6179938779914944,1386.3,868.9,996.4,1848.0,1141.4,1269.0 +1.271051018050849,0.8709138949219872,2.748893571891069,1052.3,1052.3,1272.1,1547.3,1387.5,1587.4 +1.27105595460747,0.8709113867938003,2.8797932657906435,855.1,1491.1,1834.5,1221.6,1432.5,1305.2 +1.2710421995089978,0.870919973164666,3.010692959690218,772.5,1742.3,1683.1,1060.6,1245.0,1186.3 +0.17092442219204945,0.17085178464513673,0.0,63.0,2751.0,2751.2,1699.1,71.0,71.0 +0.17096836028368106,0.171006579221618,0.1308996938995747,91.5,2823.0,2882.2,823.4,47.4,106.8 +0.17096845368049826,0.17100650915612614,0.2617993877991494,139.4,3131.9,3259.1,349.1,187.6,95.1 +0.17097688618653284,0.1710117647554632,0.39269908169872414,223.6,2592.4,2372.8,191.2,109.9,62.9 +0.17097642469307142,0.1710130972766546,0.5235987755982988,393.0,2078.3,1950.7,113.9,50.7,59.7 +0.1709838652172814,0.17102384668659032,0.6544984694978736,912.0,1823.3,1764.2,68.5,129.4,70.3 +0.17097985228689158,0.1710120879650614,0.7853981633974483,2721.3,1728.9,1727.9,40.8,93.6,93.1 +0.17098012617568176,0.17103441622451587,0.916297857297023,2842.3,973.2,150.0,25.4,70.5,129.3 +0.17098370440145375,0.17102557390435358,1.0471975511965976,3210.5,431.7,51.5,106.0,59.3,186.6 +0.17099443469821132,0.1710067283506982,1.1780972450961724,2381.4,252.2,31.3,31.1,63.1,282.2 +0.17097039025315322,0.1710290989364951,1.3089969389957472,1938.0,161.1,33.4,72.1,95.2,474.4 +0.17096119423808556,0.17103481707094925,1.4398966328953218,1741.3,106.5,93.6,90.9,237.6,1066.3 +0.17101002749561858,0.17102359626653207,1.5707963267948966,1698.8,70.9,70.7,63.1,2751.5,2751.3 +0.1709335114578418,0.1710233428923471,1.7016960206944713,233.8,47.4,105.8,48.4,2820.5,2997.1 +0.17094005533892465,0.1710249452057484,1.832595714594046,73.6,187.5,95.2,46.8,3132.0,3259.4 +0.1709843463959923,0.1710534881595327,1.9634954084936205,32.2,109.9,63.0,63.4,2590.5,2371.4 +0.1709883864044327,0.17105937784481817,2.0943951023931953,21.2,51.1,59.3,117.0,2076.7,1949.7 +0.17096945951044867,0.1710224499527624,2.2252947962927703,25.8,129.3,70.5,318.6,1822.5,1763.5 +0.1709704997827157,0.17102635808869793,2.356194490192345,41.6,93.1,93.6,2720.7,1728.3,1728.8 +0.1709681998520755,0.1710384797133364,2.4870941840919194,68.6,70.3,129.4,2800.5,968.8,149.7 +0.17097685025649248,0.1710133295007561,2.6179938779914944,73.5,59.7,187.3,3119.6,430.6,51.5 +0.1709719999858038,0.17101623484932382,2.748893571891069,62.5,62.5,282.5,2536.9,251.6,31.6 +0.170991315940011,0.17099947949293748,2.8797932657906435,46.4,94.7,474.5,2030.2,161.3,33.8 +0.17099384107608578,0.17099852942885962,3.010692959690218,48.1,234.6,1057.2,1785.1,106.4,93.1 +0.1709929523817046,0.1710006876261292,0.0,63.1,2751.0,2750.9,1698.9,71.0,71.0 +0.1709455455722573,0.1710009093597742,0.1308996938995747,91.5,2823.3,2882.3,823.4,47.4,106.8 +0.17097312328438083,0.17100941592896945,0.2617993877991494,139.4,3131.4,3258.4,349.1,187.6,95.1 +0.17097852986046916,0.1710127753239965,0.39269908169872414,223.6,2591.8,2373.1,191.2,109.9,62.9 +0.17097736174173017,0.17101324376644178,0.5235987755982988,393.0,2077.9,1950.5,113.9,50.7,59.7 +0.17098465525204937,0.17102375017321658,0.6544984694978736,912.0,1823.3,1764.2,68.5,129.4,70.3 +0.17098063056542803,0.17101194831152133,0.7853981633974483,2720.8,1729.0,1728.3,40.8,93.6,93.1 +0.17098090005537467,0.17103430970896327,0.916297857297023,2843.0,973.2,150.0,25.4,70.5,129.3 +0.17098445953981123,0.1710255187337275,1.0471975511965976,3210.2,431.7,51.5,106.0,59.3,186.6 +0.17099515700383316,0.17100672096731473,1.1780972450961724,2381.1,252.3,31.3,31.1,63.1,282.2 +0.17097107106109952,0.17102912792335845,1.3089969389957472,1938.0,161.1,33.4,72.1,95.2,474.4 +0.17096182884491928,0.17103486957600644,1.4398966328953218,1741.5,106.5,93.6,90.9,237.5,1066.2 +0.1710106146488473,0.17102365942971898,1.5707963267948966,1698.9,70.9,70.7,63.1,2751.6,2750.6 +0.17093404713281848,0.17102340505821134,1.7016960206944713,233.8,47.4,105.8,48.4,2820.7,2996.7 +0.17094055603736977,0.17102499829905438,1.832595714594046,73.6,187.4,95.2,46.8,3131.4,3259.7 +0.17098481404269206,0.17105352316105837,1.9634954084936205,32.2,110.0,63.0,63.4,2590.8,2371.7 +0.170988827571457,0.1710593885028875,2.0943951023931953,21.2,51.1,59.3,117.0,2076.8,1949.8 +0.17096988206943023,0.17102243260209793,2.2252947962927703,25.8,129.3,70.5,318.6,1822.5,1763.8 +0.17097091189348723,0.17102631058844886,2.356194490192345,41.6,93.1,93.6,2720.8,1728.2,1728.8 +0.17096860973473602,0.17103840220316635,2.4870941840919194,68.6,70.3,129.4,2800.8,968.9,149.8 +0.17097726532414734,0.17101322450246914,2.6179938779914944,73.5,59.7,187.4,3119.9,430.6,51.5 +0.1709724268705697,0.17101610616828267,2.748893571891069,62.5,62.5,282.5,2537.2,251.6,31.6 +0.17099175940227576,0.1709993326743824,2.8797932657906435,46.4,94.7,474.4,2030.0,161.3,33.8 +0.1709943042426763,0.1709983707686198,3.010692959690218,48.1,234.6,1057.4,1784.8,106.4,93.1 +0.17099343656327193,0.1710005237939185,0.0,63.1,2751.0,2750.9,1698.9,71.0,71.0 +0.17094605000139385,0.17100074648252073,0.1308996938995747,91.5,2823.2,2882.3,823.6,47.5,106.8 +0.17097364516031702,0.17100925980031856,0.2617993877991494,139.4,3131.6,3258.9,349.1,187.6,95.1 +0.17097906516445927,0.1710126300813284,0.39269908169872414,223.6,2592.3,2373.1,191.2,109.9,62.9 +0.17097790579725514,0.17101311186561774,0.5235987755982988,393.0,2078.0,1950.5,113.9,50.7,59.7 +0.17098520331141895,0.17102363224512618,0.6544984694978736,911.9,1823.0,1764.2,68.5,129.4,70.3 +0.1709811783761046,0.17101184374757028,0.7853981633974483,2721.1,1728.8,1728.4,40.8,93.7,93.1 +0.17098144429814496,0.17103421664238216,0.916297857297023,2843.0,973.2,150.0,25.4,70.5,129.3 +0.17098499792824104,0.17102543480986232,1.0471975511965976,3210.2,431.6,51.5,106.0,59.3,186.5 +0.1709956883441877,0.17100664360613216,1.1780972450961724,2381.2,252.2,31.3,31.1,63.1,282.1 +0.170971595147564,0.17102905482984831,1.3089969389957472,1938.1,161.1,33.4,72.1,95.2,474.4 +0.1709623459276165,0.17103479901900287,1.4398966328953218,1741.0,106.5,93.6,90.9,237.6,1066.2 +0.17101112515373867,0.1710235900965369,1.5707963267948966,1698.9,70.9,70.7,63.1,2751.2,2750.6 +0.17093454887922557,0.1710233358425839,1.7016960206944713,233.9,47.4,105.8,48.4,2820.6,2996.6 +0.17094105393769315,0.17102492933541624,1.832595714594046,73.6,187.5,95.2,46.8,3131.9,3259.4 +0.17098530670534967,0.17105345337611744,1.9634954084936205,32.2,109.9,63.0,63.4,2590.7,2371.2 +0.17098931484803817,0.17105931680553277,2.0943951023931953,21.2,51.1,59.2,117.0,2077.0,1949.1 +0.1709703642888363,0.17102235791584497,2.2252947962927703,25.8,129.3,70.5,318.6,1822.5,1763.5 +0.17097138983744897,0.17102623171008657,2.356194490192345,41.6,93.1,93.6,2720.3,1728.6,1729.0 +0.17096908471682454,0.1710383181330306,2.4870941840919194,68.6,70.3,129.4,2800.9,969.0,149.7 +0.17097773897844248,0.17101313479265134,2.6179938779914944,73.5,59.7,187.4,3120.1,430.6,51.5 +0.17097290115972633,0.17101601087410634,2.748893571891069,62.5,62.5,282.5,2537.3,251.6,31.6 +0.1709922360553249,0.17099923266825634,2.8797932657906435,46.4,94.6,474.4,2030.6,161.2,33.8 +0.17099478465583776,0.1709982675214765,3.010692959690218,48.1,234.6,1057.5,1784.6,106.3,93.1 +0.17099392149937917,0.1710004192230683,0.0,63.1,2751.2,2751.0,1699.0,71.0,71.0 +0.17094653785887864,0.17100064236940304,0.1308996938995747,91.5,2823.2,2882.7,823.6,47.4,106.8 +0.1709741376824197,0.1710091584744815,0.2617993877991494,139.4,3131.5,3259.1,349.1,187.6,95.1 +0.17097955999038825,0.1710125325949179,0.39269908169872414,223.6,2592.1,2373.2,191.2,109.9,62.9 +0.17097840096474856,0.17101301855374573,0.5235987755982988,393.0,2078.0,1950.7,113.9,50.7,59.7 +0.17098569716425902,0.1710235427322082,0.6544984694978736,912.0,1823.5,1764.1,68.5,129.4,70.3 +0.17098166966150327,0.17101175708023653,0.7853981633974483,2721.1,1729.0,1728.3,40.8,93.6,93.1 +0.17098193245141363,0.17103413157047243,0.916297857297023,2842.5,973.2,150.0,25.4,70.5,129.3 +0.17098548302428815,0.17102535007162234,1.0471975511965976,3210.1,431.7,51.5,106.0,59.3,186.6 +0.17099617100460165,0.17100655822485855,1.1780972450961724,2381.3,252.2,31.3,31.1,63.1,282.2 +0.17097207630078082,0.17102896841821158,1.3089969389957472,1937.9,161.1,33.4,72.1,95.2,474.4 +0.170962826494913,0.17103471175049312,1.4398966328953218,1741.4,106.4,93.6,90.9,237.6,1066.1 +0.17101160577033206,0.17102350253327048,1.5707963267948966,1699.1,71.0,70.7,63.1,2751.1,2751.0 +0.17093502771547536,0.17102324856690698,1.7016960206944713,233.8,47.4,105.8,48.4,2821.4,2996.5 +0.17094153391898725,0.17102484375672966,1.832595714594046,73.6,187.4,95.2,46.8,3131.6,3259.2 +0.17098578597117986,0.17105336969882012,1.9634954084936205,32.2,109.9,63.0,63.4,2590.5,2371.7 +0.17098979220654223,0.17105923478186114,2.0943951023931953,21.2,51.2,59.3,117.0,2076.4,1949.6 +0.17097083888129058,0.17102227690988792,2.2252947962927703,25.8,129.3,70.5,318.7,1822.4,1763.6 +0.17097186126748942,0.1710261507073314,2.356194490192345,41.6,93.1,93.6,2720.6,1728.4,1729.0 +0.1709695531742022,0.1710382359917999,2.4870941840919194,68.6,70.3,129.4,2800.7,968.8,149.8 +0.1709782051393061,0.17101305061697425,2.6179938779914944,73.5,59.7,187.4,3119.8,430.6,51.5 +0.17097336618855524,0.17101592413305222,2.748893571891069,62.5,62.5,282.5,2537.4,251.7,31.6 +0.17099270114846715,0.1709991434744378,2.8797932657906435,46.4,94.7,474.5,2030.1,161.2,33.8 +0.17099525089039438,0.17099817654174676,3.010692959690218,48.1,234.6,1057.3,1785.0,106.4,93.1 +1.371059879892572,0.5710182592916091,0.0,463.1,1551.1,1550.8,1298.8,1271.0,1270.8 +1.371025690686266,0.5709786920768711,0.1308996938995747,505.7,1580.4,1616.8,1328.4,1290.3,1349.6 +1.3710256230368525,0.5709787689361316,0.2617993877991494,601.8,1744.1,1872.0,1475.2,1272.5,892.9 +1.3710214897730075,0.5709762468658177,0.39269908169872414,790.3,2027.1,1807.9,1814.0,846.9,627.7 +1.3710220259947588,0.5709788312536299,0.5235987755982988,1189.9,1615.6,1487.8,1501.6,649.8,522.1 +1.3710323184966022,0.5709952103857727,0.6544984694978736,1558.0,1409.2,1350.2,1311.1,543.6,484.5 +1.3710298651128723,0.57099080011326,0.7853981633974483,1521.3,1329.0,1328.4,1241.0,493.7,493.2 +1.371029769811534,0.5710205247408466,0.916297857297023,1600.5,1349.5,1408.3,1267.7,484.5,543.3 +1.371031184150413,0.5710184070759501,1.0471975511965976,1823.7,1487.4,1614.9,1192.0,521.4,648.7 +1.3710383550434488,0.5710051056587877,1.1780972450961724,1814.5,1806.8,1732.0,791.0,627.5,846.5 +1.371009879501983,0.5710315701412803,1.3089969389957472,1475.6,1548.7,1420.7,602.1,892.2,1271.5 +1.3709957362708742,0.5710399280883529,1.4398966328953218,1350.0,1393.8,1289.6,504.7,1637.2,1578.7 +1.3710394559683665,0.5710299191691799,1.5707963267948966,1298.9,1271.2,1270.9,463.1,1551.2,1551.2 +1.3710054391950222,0.571028576975936,1.7016960206944713,1369.9,1288.9,1347.3,462.3,1579.6,1637.8 +1.3709772856638018,0.5710196754844641,1.832595714594046,1568.3,1271.3,892.1,509.3,1744.3,1872.2 +1.3710123792220188,0.5710425779165895,1.9634954084936205,1725.8,846.6,627.5,630.3,2026.3,1807.0 +1.371014578002892,0.5710466942906258,2.0943951023931953,1407.6,648.6,521.5,915.6,1614.6,1487.5 +1.3709955240722784,0.5710098521167588,2.2252947962927703,1267.9,543.3,461.7,1600.3,1408.2,1349.7 +1.370996591876895,0.5710145564053686,2.356194490192345,1241.8,493.0,493.6,1520.5,1328.4,1329.2 +1.3709941170802746,0.5710276317832748,2.4870941840919194,1356.8,484.5,543.6,1557.9,1349.8,1409.2 +1.3710023792236383,0.5710033486490667,2.6179938779914944,914.2,522.3,649.9,1732.5,1487.9,1615.6 +1.3709969828807513,0.5710069609911765,2.748893571891069,628.2,628.3,848.2,1971.4,1811.4,1728.9 +1.3710156703426786,0.570990722815105,2.8797932657906435,508.6,892.7,1272.4,1567.9,1547.9,1420.8 +1.3710175322501883,0.5709901139820546,3.010692959690218,462.1,1638.4,1579.6,1370.9,1348.8,1289.7 +1.371060131591408,0.6712821654067707,0.0,562.9,1550.9,1550.8,1198.9,1270.8,1271.1 +1.3710124470964073,0.6706929535792316,0.1308996938995747,609.2,1580.2,1639.6,1224.9,1290.4,1349.7 +1.3710410029700073,0.6707023226022879,0.2617993877991494,717.3,1744.5,1872.1,1359.7,1421.0,1092.2 +1.371075429049404,0.6707245967253581,0.39269908169872414,932.0,1886.5,1667.0,1672.5,988.1,768.7 +1.3711030541372795,0.6707567912837846,0.5235987755982988,1389.0,1500.0,1372.3,1501.4,765.5,637.8 +1.3711300873071102,0.6708050990723617,0.6544984694978736,1558.0,1305.7,1246.8,1311.0,647.0,588.0 +1.3711351086093522,0.670833341741544,0.7853981633974483,1521.4,1229.2,1228.5,1241.0,593.6,592.9 +1.371134096358903,0.6708937762795741,0.916297857297023,1600.3,1246.1,1305.1,1267.5,587.9,646.7 +1.3711274023550162,0.6709191397205951,1.0471975511965976,1823.7,1371.9,1499.2,1391.4,636.9,764.1 +1.3711208512420416,0.6709286062933171,1.1780972450961724,1672.8,1665.9,1731.8,932.5,768.4,987.7 +1.3710749980666046,0.6709721314740142,1.3089969389957472,1359.9,1548.5,1420.8,717.5,1091.3,1470.3 +1.3710411539981011,0.6709917650031827,1.4398966328953218,1246.9,1348.0,1289.3,608.0,1710.1,1578.7 +1.371064231237009,0.6709872523435767,1.5707963267948966,1199.1,1271.0,1270.8,562.9,1551.3,1551.3 +1.3710106888825322,0.6709860113043891,1.7016960206944713,1266.5,1288.8,1347.6,565.5,1579.0,1637.8 +1.3709649470296306,0.6709725089781333,1.832595714594046,1452.8,1421.7,1091.1,624.7,1744.7,1872.1 +1.3709851719374269,0.670986832539801,1.9634954084936205,1725.6,987.6,768.6,771.7,1884.8,1665.7 +1.370976205739924,0.6709797055008122,2.0943951023931953,1407.6,764.0,636.8,1115.2,1499.5,1372.3 +1.3709499781921726,0.6709301626331632,2.2252947962927703,1267.9,646.6,587.8,1726.4,1305.2,1246.4 +1.3709478001390591,0.670921573327379,2.356194490192345,1241.5,592.9,593.5,1520.5,1228.5,1228.9 +1.3709457935765204,0.6709219180654167,2.4870941840919194,1311.0,588.0,647.1,1557.9,1246.6,1305.6 +1.3709576650754263,0.6708864978501516,2.6179938779914944,1113.1,637.6,765.3,1732.0,1372.5,1500.1 +1.370958352473283,0.670881068436628,2.748893571891069,769.5,769.4,989.5,1829.8,1670.0,1729.0 +1.370984677313867,0.6708583813912243,2.8797932657906435,624.0,1091.9,1471.6,1452.6,1548.1,1420.9 +1.3709949351139445,0.6708539743370083,3.010692959690218,542.7,1697.7,1579.8,1267.7,1348.5,1289.6 +1.3710473416813975,0.771153542084444,0.0,662.9,1551.1,1551.0,1098.9,1271.0,1270.8 +1.3710189047834673,0.7711531612791951,0.1308996938995747,712.5,1580.4,1639.6,1121.6,1290.4,1350.0 +1.370963476574228,0.7711371203898889,0.2617993877991494,832.7,1744.4,1871.5,1244.5,1420.8,1291.3 +1.3709093967839423,0.7711041830542966,0.39269908169872414,1073.2,1745.2,1525.7,1530.8,1129.0,909.6 +1.3708659966174743,0.7710603497934665,0.5235987755982988,1588.1,1384.8,1256.9,1501.3,880.9,753.1 +1.3708467812749114,0.7710225227437306,0.6544984694978736,1557.8,1202.2,1143.1,1310.9,750.4,691.2 +1.3708307626472052,0.7709607749436873,0.7853981633974483,1521.0,1129.1,1128.7,1240.8,693.3,693.0 +1.3708323489312038,0.7709359240347087,0.916297857297023,1600.5,1142.8,1201.6,1267.7,691.4,750.3 +1.370848771331776,0.7708849503579238,1.0471975511965976,1823.6,1256.4,1383.7,1408.1,752.4,879.6 +1.3708813270848998,0.7708315961232322,1.1780972450961724,1531.1,1524.9,1731.7,1074.4,909.8,1128.9 +1.3708847906397286,0.7708287105883878,1.3089969389957472,1244.5,1548.6,1420.8,833.4,1290.6,1669.9 +1.3709064466419212,0.7708185383837218,1.4398966328953218,1120.5,1348.1,1289.9,711.6,1637.0,1578.5 +1.3709870845987575,0.7708006894558999,1.5707963267948966,1098.9,1271.2,1270.6,663.0,1551.3,1551.0 +1.3709873182292174,0.7708011101530425,1.7016960206944713,1162.6,1288.9,1347.4,669.1,1579.3,1637.9 +1.3709893350900606,0.7708019741300653,1.832595714594046,1337.3,1421.5,1290.5,740.4,1744.4,1872.4 +1.3710493203355205,0.7708411093263776,1.9634954084936205,1692.1,1128.7,909.6,913.5,1743.8,1524.7 +1.371069759475292,0.7708654527651926,2.0943951023931953,1407.5,879.6,752.3,1315.0,1383.7,1256.5 +1.3710621819557502,0.770850703825747,2.2252947962927703,1268.0,750.3,691.4,1600.4,1201.5,1142.8 +1.3710683578921532,0.7708780543909532,2.356194490192345,1241.5,693.0,693.6,1520.8,1128.5,1129.1 +1.3710651508966558,0.7709126579234715,2.4870941840919194,1311.1,691.5,750.4,1557.9,1143.1,1201.9 +1.3710678611441431,0.7709073229135279,2.6179938779914944,1312.4,753.3,881.0,1732.5,1256.9,1384.5 +1.3710530050124263,0.7709267480074686,2.748893571891069,910.7,910.9,1130.9,1688.4,1528.7,1728.7 +1.371059665489547,0.770922452924806,2.8797932657906435,739.7,1291.5,1671.2,1337.0,1548.2,1420.6 +1.3710479392681865,0.7709297999643461,3.010692959690218,669.0,1638.4,1579.6,1164.2,1348.5,1289.5 +1.3710737534211963,0.8712092166356644,0.0,762.7,1551.0,1550.7,999.1,1270.9,1270.9 +1.3710151971723106,0.8706540532139757,0.1308996938995747,816.3,1580.2,1639.4,1017.7,1290.1,1349.6 +1.371045600911259,0.8706640707608944,0.2617993877991494,948.4,1744.3,1871.8,1128.6,1446.4,1491.2 +1.3710839344214287,0.8706888790627727,0.39269908169872414,1215.0,1603.8,1384.5,1389.3,1270.4,1051.1 +1.3711150705738915,0.8707249331234044,0.5235987755982988,1732.3,1268.9,1141.3,1501.1,996.5,868.9 +1.3711232015222792,0.8707365967422986,0.6544984694978736,1558.1,1098.6,1039.5,1311.0,854.3,795.2 +1.3711364741613024,0.8708004581972455,0.7853981633974483,1521.1,1029.1,1028.6,1240.7,793.5,793.0 +1.3711350599868044,0.8708725873461554,0.916297857297023,1600.6,1039.4,1098.1,1267.5,794.9,853.6 +1.3711273267269413,0.8709014482308126,1.0471975511965976,1823.5,1140.9,1268.2,1503.3,867.7,995.1 +1.3711202560254176,0.8709118332759835,1.1780972450961724,1389.7,1383.8,1602.9,1215.8,1050.8,1269.8 +1.3710742821258302,0.8709555760982712,1.3089969389957472,1128.9,1548.2,1420.9,948.8,1489.7,1745.5 +1.3710404962774319,0.8709752930776802,1.4398966328953218,1017.1,1348.3,1289.8,814.9,1637.2,1578.6 +1.3710636768682485,0.8709708508630403,1.5707963267948966,999.2,1271.1,1270.7,763.0,1551.2,1551.0 +1.3710102222313034,0.8709697138944144,1.7016960206944713,1059.6,1289.0,1347.6,772.6,1579.3,1637.4 +1.3709645265214305,0.8709563397906241,1.832595714594046,1222.0,1581.8,1489.8,856.0,1744.6,1872.1 +1.370984761068066,0.8709707707894727,1.9634954084936205,1550.3,1269.7,1050.5,1055.3,1602.5,1383.9 +1.3709757813483223,0.8709637216964583,2.0943951023931953,1407.5,995.2,867.6,1514.2,1268.1,1141.0 +1.3709219051773078,0.8708596188542159,2.2252947962927703,1267.9,853.8,795.0,1600.1,1098.1,1039.3 +1.3709290536001537,0.8708920116492818,2.356194490192345,1241.6,792.8,793.5,1520.3,1028.3,1029.0 +1.3709266845820645,0.870901935244969,2.4870941840919194,1311.0,795.1,854.0,1557.9,1039.5,1098.6 +1.3709387325624307,0.8708659536370624,2.6179938779914944,1467.7,868.7,996.6,1732.1,1141.4,1268.8 +1.370941400477494,0.8708574546656809,2.748893571891069,1052.2,1052.4,1272.5,1547.2,1387.3,1607.4 +1.3709709258347607,0.8708318659818581,2.8797932657906435,855.2,1490.9,1744.2,1221.5,1548.3,1420.5 +1.3709850272273147,0.8708254987579334,3.010692959690218,772.5,1638.4,1579.4,1060.6,1348.3,1289.8 diff --git a/tools/localisation_machine_learning/data/sector3.csv b/tools/localisation_machine_learning/data/sector3.csv new file mode 100644 index 00000000..68f0a3c2 --- /dev/null +++ b/tools/localisation_machine_learning/data/sector3.csv @@ -0,0 +1,2496 @@ +2.8290387010639457,0.1708039118782665,0.0,63.0,93.0,93.0,1699.1,2729.1,2729.2 +2.829091608705104,0.17142191775350013,0.1308996938995747,91.6,119.3,129.6,1742.7,964.3,233.5 +2.8290042807064815,0.17139418441362575,0.2617993877991494,116.8,59.3,186.8,1937.8,474.7,95.2 +2.8289478052728394,0.17135789193280337,0.39269908169872414,62.7,63.0,283.8,2380.4,282.3,63.0 +2.828909087029326,0.1713172609735607,0.5235987755982988,150.3,95.2,474.4,3186.6,187.4,59.8 +2.828894348375713,0.17128609040658938,0.6544984694978736,48.3,234.5,1054.2,2820.5,129.5,70.5 +2.828880667263091,0.1712326474405561,0.7853981633974483,63.1,1728.4,1728.6,2699.1,93.8,93.2 +2.828881862539084,0.17121603706104538,0.916297857297023,91.3,1763.5,1822.1,917.3,70.7,129.5 +2.8288954401360242,0.17117238179263228,1.0471975511965976,139.1,1949.5,2076.7,393.6,59.5,94.9 +2.828923320128915,0.1711247239608289,1.1780972450961724,222.6,2371.4,2590.9,224.3,63.3,110.3 +2.828921050202843,0.17112536307889026,1.3089969389957472,393.3,3234.5,3106.6,139.9,95.6,200.7 +2.828936639367103,0.1711165423559371,1.4398966328953218,836.7,2856.9,2798.3,91.1,128.5,70.1 +2.8290115646096057,0.17109826943435125,1.5707963267948966,1698.7,2729.1,2728.5,63.3,93.2,93.0 +2.829007063980042,0.1710967684592013,1.7016960206944713,1783.2,1066.2,238.2,48.6,122.6,129.2 +2.829005528623743,0.17109472199283493,1.832595714594046,2030.6,474.6,95.6,47.1,58.8,186.5 +2.8290631011878515,0.17113061984764455,1.9634954084936205,2542.0,282.3,63.3,63.7,62.5,283.5 +2.8290821344743167,0.17115181987255945,2.0943951023931953,3091.9,186.8,59.5,117.4,95.5,475.8 +2.8290739219599126,0.1711341660761876,2.2252947962927703,2776.8,129.5,70.7,91.0,235.4,1058.8 +2.829079871225673,0.17115895775339607,2.356194490192345,2699.6,93.2,93.8,62.4,1728.2,1728.8 +2.8290765783628,0.17119131622602435,2.4870941840919194,316.7,70.5,129.6,48.3,1764.2,1823.2 +2.8290793698725993,0.1711838207204448,2.6179938779914944,117.6,59.9,94.5,46.5,1950.4,2078.1 +2.8290646440487666,0.1712010923574605,2.748893571891069,62.7,62.7,110.2,63.1,2377.4,2596.8 +2.829071770632288,0.1711945402213284,2.8797932657906435,46.6,95.0,200.4,117.1,3232.3,3105.1 +2.8290609313829234,0.17119960978359372,3.010692959690218,48.2,129.2,70.4,318.3,2857.3,2798.8 +2.8290887502404676,0.2714803528140084,0.0,163.2,93.0,93.0,1598.7,2729.2,2728.9 +2.829030405093865,0.27073057850273363,0.1308996938995747,195.0,70.2,129.6,1639.5,1432.8,617.0 +2.829052406034923,0.2707378497150368,0.2617993877991494,116.8,59.3,186.8,1822.1,673.9,294.4 +2.8290821772477606,0.27075716815264506,0.39269908169872414,64.2,63.0,283.7,2239.2,423.1,204.0 +2.8291065363249635,0.2707858465512183,0.5235987755982988,47.0,95.4,474.7,3177.1,302.8,175.2 +2.829131476765533,0.27083034557527563,0.6544984694978736,48.4,234.8,1054.3,2820.1,232.8,173.8 +2.829135542431696,0.27085470109753995,0.7853981633974483,63.2,1629.0,1628.5,2698.4,193.6,193.0 +2.829134536855386,0.270911422245796,0.916297857297023,91.4,1660.5,1719.0,1303.9,173.9,232.8 +2.8291287288450198,0.27093342586609004,1.0471975511965976,139.2,1834.0,1961.6,592.7,174.7,161.1 +2.829123785255402,0.27094011955285824,1.1780972450961724,222.7,2231.0,2449.5,365.6,204.0,92.2 +2.8290799891015457,0.2709815163579061,1.3089969389957472,393.3,3156.4,3105.9,255.0,187.4,59.8 +2.8290485117421578,0.27099256513568903,1.4398966328953218,922.7,2856.9,2798.1,194.2,151.4,70.1 +2.8290817475422765,0.27099265128522076,1.5707963267948966,1598.8,2729.1,2728.7,162.9,93.3,93.1 +2.829025215208115,0.2709911744585165,1.7016960206944713,1680.4,1454.5,626.5,151.7,70.8,129.2 +2.8289805347143675,0.2709778531982334,1.832595714594046,1915.9,673.2,294.2,162.3,58.8,186.5 +2.8290027367997586,0.27099335753834497,1.9634954084936205,2400.6,423.0,204.0,204.9,62.5,283.5 +2.8289954839722204,0.2709880855448492,2.0943951023931953,3092.6,301.9,174.6,139.3,95.4,475.6 +2.828970401807111,0.2709406816249573,2.2252947962927703,2776.8,232.7,173.9,217.2,235.2,1058.7 +2.8289687080740697,0.27093435219477824,2.356194490192345,2699.9,192.9,193.5,62.4,1628.5,1629.0 +2.828966522078063,0.2709368756220272,2.4870941840919194,701.0,173.7,232.9,48.3,1661.0,1719.6 +2.8289777365460504,0.2709033113018997,2.6179938779914944,316.2,175.2,161.8,46.4,1834.9,1962.8 +2.8289773095669624,0.27089939447345746,2.748893571891069,203.8,203.8,92.2,63.1,2235.8,2455.5 +2.8290023280038703,0.2708777580963009,2.8797932657906435,161.9,186.8,59.4,117.1,3161.4,3105.0 +2.8290111664855098,0.2708739640355695,3.010692959690218,151.5,129.2,70.4,318.2,2857.8,2798.8 +2.829061949358878,0.37117230314197447,0.0,262.9,93.0,93.0,1499.0,2729.0,2729.4 +2.829032351494212,0.3711717647567616,0.1308996938995747,298.4,70.2,129.5,1535.9,1816.0,1000.3 +2.8289761039284844,0.37115538760829714,0.2617993877991494,124.8,59.3,186.8,1706.7,873.2,493.5 +2.8289214152897277,0.3711220093617318,0.39269908169872414,62.7,63.0,283.7,2097.4,564.1,344.9 +2.828877590086141,0.3710776851324409,0.5235987755982988,46.9,95.2,474.3,2977.7,418.4,290.7 +2.8288580562676895,0.3710393237310152,0.6544984694978736,48.3,234.4,1054.0,2820.8,336.3,277.2 +2.8288418824135086,0.37097705619047283,0.7853981633974483,63.1,1529.1,1528.4,2698.6,293.5,293.0 +2.8288433930712302,0.3709516711358063,0.916297857297023,91.3,1556.9,1615.5,1690.4,277.4,236.1 +2.8288598548212507,0.37090018257227886,1.0471975511965976,139.1,1718.6,1845.9,792.5,290.2,172.1 +2.828892573505865,0.37084639677923414,1.1780972450961724,222.5,2089.5,2308.6,507.3,284.4,63.5 +2.8288962680871435,0.37084311785304536,1.3089969389957472,393.2,2956.9,3105.8,370.7,250.5,59.7 +2.828918231375867,0.37083259926507983,1.4398966328953218,922.2,2856.2,2798.1,297.7,128.5,70.1 +2.8289992494373646,0.370814580876365,1.5707963267948966,1499.0,2729.2,2728.6,263.0,93.3,93.0 +2.8289998716754243,0.37081492569291497,1.7016960206944713,1577.0,1844.6,1016.3,255.3,70.8,129.2 +2.829002273888274,0.3708157897018809,1.832595714594046,1799.9,872.9,493.5,278.0,58.8,186.5 +2.829062587081387,0.3708550866526874,1.9634954084936205,2259.0,564.2,345.2,221.5,62.5,283.5 +2.8290832517356113,0.3708796971695123,2.0943951023931953,3091.4,417.5,290.2,272.6,95.5,475.7 +2.8290758144776045,0.3708652207062497,2.2252947962927703,2776.9,336.2,277.4,91.0,235.4,1058.9 +2.8290820143888613,0.37089286051951764,2.356194490192345,2699.6,293.0,293.5,62.4,1528.5,1529.0 +2.829078695591477,0.3709277485167206,2.4870941840919194,1001.7,277.2,234.4,48.3,1557.5,1616.4 +2.829081255409417,0.37092260414410494,2.6179938779914944,515.5,290.9,172.8,46.5,1719.5,1847.2 +2.8290661499456813,0.3709421636507064,2.748893571891069,345.2,283.1,63.1,63.1,2094.6,2315.1 +2.8290725945921795,0.3709379009584304,2.8797932657906435,277.4,250.1,59.4,117.1,2961.1,3105.1 +2.829060668261429,0.37094521077285236,3.010692959690218,255.0,129.2,70.4,318.3,2857.6,2798.9 +2.829086334743422,0.47122451247767927,0.0,362.9,93.0,93.0,1399.1,2729.1,2729.6 +2.8290254149835627,0.4706580791826471,0.1308996938995747,314.4,70.2,129.5,1432.1,2200.8,1384.8 +2.8290548714904955,0.4706678121267751,0.2617993877991494,240.6,59.3,186.8,1590.9,1072.8,693.1 +2.8290926336976496,0.47069229254226874,0.39269908169872414,62.8,63.0,283.8,1956.3,705.6,486.4 +2.82912339882296,0.47072799887439354,0.5235987755982988,47.0,95.4,474.5,2778.4,534.1,406.5 +2.829152518277156,0.4707804130414095,0.6544984694978736,48.4,234.8,1054.3,2820.9,439.9,380.8 +2.8291584795635676,0.47081298900094093,0.7853981633974483,63.2,1429.0,1428.3,2699.0,393.5,393.0 +2.8291572750206284,0.47087750556133035,0.916297857297023,91.4,1453.2,1512.0,2078.1,380.9,236.6 +2.8291494363812415,0.47090651078351353,1.0471975511965976,139.2,1603.0,1730.8,992.0,405.7,95.2 +2.829141016417826,0.4709189994620986,1.1780972450961724,222.6,1948.3,2167.5,648.8,284.5,63.6 +2.8290928147456254,0.4709647611269532,1.3089969389957472,393.4,2757.7,3106.3,486.2,187.4,59.8 +2.829056331496448,0.47098584057793014,1.4398966328953218,922.4,2856.6,2798.8,401.1,128.5,70.2 +2.8290766678089634,0.47098205592356357,1.5707963267948966,1398.8,2728.8,2728.5,362.9,93.3,93.1 +2.829020536674546,0.4709808268542879,1.7016960206944713,1473.6,2234.1,1405.7,358.6,70.8,129.2 +2.828972467523072,0.4709667020921795,1.832595714594046,1684.6,1071.9,692.7,391.7,58.8,186.5 +2.8289907105404284,0.4709799135011139,1.9634954084936205,2117.6,705.2,486.1,315.4,62.5,283.4 +2.828980230450889,0.4709713362147645,2.0943951023931953,3062.1,532.9,405.6,139.3,95.4,475.8 +2.8289530163975978,0.4709201203919806,2.2252947962927703,2777.2,439.6,380.9,90.9,235.2,1058.6 +2.8289503605202295,0.47090976816349106,2.356194490192345,2699.9,392.9,393.6,62.4,1428.6,1428.9 +2.828948348924173,0.4709084208094425,2.4870941840919194,1387.3,380.8,234.2,48.3,1453.8,1512.9 +2.828960662370225,0.47087148601653306,2.6179938779914944,714.7,406.4,94.5,46.5,1603.9,1731.4 +2.828962106229011,0.4708648209724655,2.748893571891069,486.6,283.0,63.1,63.1,1953.0,2173.3 +2.828989437760208,0.4708412289460848,2.8797932657906435,393.0,186.8,59.4,117.0,2762.3,3105.4 +2.8290008197054175,0.47083627604077294,3.010692959690218,358.5,129.2,70.4,318.2,2857.8,2798.8 +2.8290545714259108,0.571136883989485,0.0,462.9,93.0,93.0,1299.2,2728.9,2729.1 +2.8290270515003444,0.5711366367632869,0.1308996938995747,314.4,70.2,129.6,1328.8,2584.4,1768.4 +2.828972282877753,0.5711209008375193,0.2617993877991494,116.8,59.3,186.8,1475.9,1271.8,892.3 +2.8289186650344877,0.571088370452145,0.39269908169872414,62.7,63.0,283.7,1814.5,846.5,627.3 +2.828875569557041,0.571045000209286,0.5235987755982988,46.9,95.2,474.3,2578.9,649.7,521.9 +2.8288564906266878,0.5710076268071562,0.6544984694978736,48.3,234.4,1053.8,2820.9,543.3,484.3 +2.8288405120983957,0.5709463249640798,0.7853981633974483,63.1,1329.1,1328.7,2698.6,493.5,492.9 +2.828842027712273,0.5709218530550879,0.916297857297023,91.2,1349.7,1408.6,2465.6,484.4,323.2 +2.8288583186059792,0.570871201728351,1.0471975511965976,139.1,1487.6,1614.8,1191.8,475.1,94.9 +2.828890712890083,0.5706334288618409,1.1780972450961724,191.5,1807.2,2026.4,790.7,296.5,63.5 +2.8288992748541872,0.5708109852039742,1.3089969389957472,393.1,2558.4,2937.4,602.0,187.3,59.7 +2.8289163291447843,0.570803242803227,1.4398966328953218,922.1,2856.2,2798.1,504.6,128.5,70.1 +2.828995686757583,0.570785775988585,1.5707963267948966,1299.1,2729.1,2728.7,463.0,93.2,93.0 +2.8289957453614214,0.5707862806344939,1.7016960206944713,1370.0,2624.1,1795.3,462.1,70.8,129.2 +2.8289979161366507,0.5707872688186493,1.832595714594046,1568.5,1271.2,891.9,391.6,58.9,186.5 +2.8290580846786804,0.5708266414290251,1.9634954084936205,1975.2,846.6,627.4,221.5,62.5,283.5 +2.829078637055301,0.5708512727929806,2.0943951023931953,2862.1,648.6,521.3,139.4,95.4,431.8 +2.829071110274135,0.57083678519034,2.2252947962927703,2777.7,543.3,484.4,91.0,150.1,1058.7 +2.8290772739219263,0.5708643751189886,2.356194490192345,2699.6,493.0,493.5,62.4,1328.3,1329.0 +2.8290739956701,0.5708991958331138,2.4870941840919194,1857.3,484.4,323.4,48.4,1350.3,1409.1 +2.829076635479786,0.57089402409475,2.6179938779914944,913.9,473.5,94.6,46.5,1488.2,1615.9 +2.829061668668432,0.5709135983883495,2.748893571891069,627.9,296.4,63.1,63.1,1811.8,2031.5 +2.829068237037898,0.5709094222882545,2.8797932657906435,508.5,186.8,59.4,117.1,2562.1,2942.4 +2.8290564072481903,0.570916876022395,3.010692959690218,462.0,129.2,70.4,318.3,2857.5,2798.5 +2.829082084778633,0.6711962037043899,0.0,562.7,93.0,93.0,1199.1,2728.6,2729.5 +2.829021662837321,0.6706503408964266,0.1308996938995747,389.1,70.2,129.5,1225.0,2800.0,2153.6 +2.8290520877226837,0.6706603845964536,0.2617993877991494,116.9,59.3,186.8,1359.8,1471.5,1092.2 +2.8290907441907334,0.6706854292476112,0.39269908169872414,62.8,63.1,283.8,1672.5,988.0,768.6 +2.8291221981058867,0.670721871877477,0.5235987755982988,47.0,95.4,474.5,2379.8,765.3,637.5 +2.828791036889227,0.6710224511678151,0.6544984694978736,48.5,235.5,1056.6,2820.2,646.9,587.9 +2.828786998278443,0.6710076186492304,0.7853981633974483,63.3,1229.0,1228.7,2698.8,593.6,593.1 +2.8287883058066825,0.6710104159898624,0.916297857297023,91.5,1246.4,1305.2,2761.9,588.0,427.0 +2.8287992996089475,0.6709789694033663,1.0471975511965976,114.0,1372.5,1499.8,1390.2,474.8,95.1 +2.8288231878457766,0.6709405444910892,1.1780972450961724,222.9,1666.8,1886.0,932.0,284.4,63.7 +2.828815645496047,0.6709481336639567,1.3089969389957472,350.0,2360.9,2740.8,717.4,187.3,59.8 +2.8288248877210735,0.6709441911124103,1.4398966328953218,924.5,2856.5,2797.6,608.0,128.5,70.3 +2.828892767717422,0.6709291799739905,1.5707963267948966,1198.8,2728.7,2728.6,562.9,93.3,93.2 +2.8288811707239154,0.6709287350158855,1.7016960206944713,1266.5,2797.5,2181.4,565.8,70.9,129.4 +2.828872995982254,0.6709254891538527,1.832595714594046,1453.4,1469.0,1090.4,484.0,59.0,186.8 +2.8289247743674046,0.6709585658851964,1.9634954084936205,1834.5,987.0,768.4,221.4,62.7,283.8 +2.8289394378851798,0.6709757103708032,2.0943951023931953,2664.6,763.9,636.7,139.4,95.8,476.5 +2.8289287532728027,0.6709530276562625,2.2252947962927703,2776.2,646.7,588.0,91.0,236.3,1061.2 +2.8289340433633234,0.6709725752147995,2.356194490192345,2700.0,593.0,593.7,62.5,1228.4,1229.1 +2.8289316338139727,0.6710002346487598,2.4870941840919194,2239.3,588.0,427.3,48.4,1246.5,1305.8 +2.8289368549146925,0.6709888422118955,2.6179938779914944,1112.3,473.3,94.7,46.6,1372.9,1500.7 +2.828925155139292,0.6709983656951315,2.748893571891069,769.0,283.0,63.3,63.3,1670.7,1890.9 +2.828844705297987,0.6708558598142509,2.8797932657906435,624.2,186.9,59.4,117.1,2362.2,2742.0 +2.8288703676746128,0.6708429648925078,3.010692959690218,565.6,129.3,70.5,318.3,2857.7,2799.0 +2.8289472998016447,0.7711599731297527,0.0,663.0,93.1,93.1,1099.0,2729.0,2728.9 +2.828938219585628,0.771159714180419,0.1308996938995747,492.7,70.3,129.6,1121.5,2885.0,2538.5 +2.8288982216128393,0.7711478339531863,0.2617993877991494,117.0,59.4,186.9,1244.4,1671.7,1291.7 +2.8288564621333645,0.7711219074624704,0.39269908169872414,62.8,63.1,252.6,1530.7,1129.4,909.9 +2.828822332845041,0.7710871229405902,0.5235987755982988,47.0,51.6,474.4,2180.2,881.1,753.3 +2.828809279676403,0.7710594922731824,0.6544984694978736,48.4,234.6,1053.6,2820.7,750.5,691.5 +2.8287963136694976,0.7710084956733896,0.7853981633974483,63.2,1128.9,1128.6,2699.1,693.5,693.0 +2.8287980501518,0.7709940193359714,0.916297857297023,91.3,1142.6,1201.3,2776.5,691.5,530.2 +2.828811976083756,0.7709524666125049,1.0471975511965976,139.2,1256.4,1383.7,1591.4,507.0,95.1 +2.8288398818677876,0.7709068866210349,1.1780972450961724,222.6,1524.5,1743.9,1074.4,284.6,63.6 +2.828837304728912,0.7709097372992404,1.3089969389957472,393.2,2159.0,2538.1,833.3,187.4,59.8 +2.828852065199521,0.7709031682037348,1.4398966328953218,922.0,2857.1,2798.1,711.4,128.6,70.2 +2.8289255385323817,0.7708866644916781,1.5707963267948966,1098.9,2728.8,2729.0,663.1,93.4,93.1 +2.828919176324116,0.7708864720606576,1.7016960206944713,1162.9,2843.1,2576.2,669.2,70.9,129.3 +2.828915493310378,0.7708851358766586,1.832595714594046,1336.9,1670.3,1290.9,494.7,58.9,186.6 +2.828970964459724,0.7709207749679947,1.9634954084936205,1691.6,1128.9,909.7,221.6,62.6,283.5 +2.8289883325527057,0.7709409161913843,2.0943951023931953,2462.2,879.8,752.4,139.5,51.7,475.8 +2.828979057947819,0.770921796617204,2.2252947962927703,2777.1,750.4,691.6,91.1,235.5,1058.5 +2.828984773181219,0.7709448604007794,2.356194490192345,2700.0,693.1,693.7,62.5,1128.4,1129.2 +2.8289821669459303,0.7709755495099766,2.4870941840919194,2630.4,691.5,530.5,48.4,1142.8,1202.3 +2.8289862011955837,0.7709669366162542,2.6179938779914944,1312.9,507.6,94.8,46.6,1256.7,1384.4 +2.8289732574192077,0.7709836927368685,2.748893571891069,910.9,283.3,63.2,63.2,1528.4,1748.3 +2.8289820913519796,0.7709774099770923,2.8797932657906435,739.8,186.9,59.5,117.2,2162.4,2542.4 +2.828972705952065,0.7709833745250598,3.010692959690218,669.0,129.3,70.5,233.2,2858.1,2798.5 +2.82900130734336,0.8712648095495867,0.0,762.9,93.1,93.1,999.0,2728.6,2729.2 +2.8289666622721734,0.8706723502453793,0.1308996938995747,596.3,70.3,129.5,1017.6,2799.9,2840.2 +2.8290000154262755,0.8706831616484427,0.2617993877991494,117.1,59.4,186.8,1128.5,1871.6,1491.9 +2.8290373658307324,0.8707071404951032,0.39269908169872414,62.9,63.1,283.7,1388.7,1270.7,1051.6 +2.8290669019454695,0.8707411684230666,0.5235987755982988,47.0,95.5,474.3,1980.0,996.8,869.1 +2.829095325407649,0.8707914998957553,0.6544984694978736,48.4,149.9,1052.9,2820.7,854.1,795.1 +2.829101024106659,0.8708217580323361,0.7853981633974483,63.2,1029.0,1028.4,2698.7,793.4,792.9 +2.8291002861602514,0.8708842776945172,0.916297857297023,91.4,1039.1,1097.8,2776.7,794.9,633.7 +2.829093336002851,0.8709116205795058,1.0471975511965976,139.2,1140.9,1268.0,1791.6,622.2,95.3 +2.829085999014901,0.8709226708125368,1.1780972450961724,222.6,1383.5,1602.1,1216.3,284.7,63.7 +2.8290390947501676,0.8709675371243879,1.3089969389957472,393.1,1959.4,2338.5,949.0,187.5,59.8 +2.8290039578338844,0.870988245890659,1.4398966328953218,921.2,2856.8,2797.7,815.0,128.6,70.2 +2.8290255578233103,0.8709840820431651,1.5707963267948966,999.2,2729.2,2728.7,762.8,93.4,93.1 +2.828970612510751,0.870982837933937,1.7016960206944713,1059.7,2797.3,2855.4,772.4,70.9,129.2 +2.828923575487995,0.8709691049985651,1.832595714594046,1221.5,1870.1,1490.5,392.0,58.9,186.4 +2.828942781323954,0.8709826874553666,1.9634954084936205,1549.8,1270.4,1050.8,221.7,62.5,283.3 +2.8289331811220704,0.8709745368271142,2.0943951023931953,2261.6,995.3,867.9,139.5,95.4,475.3 +2.8289065802586446,0.8709240534116318,2.2252947962927703,2777.7,853.8,794.9,91.0,149.9,1057.4 +2.828904364538376,0.8709145249372172,2.356194490192345,2699.6,793.0,793.4,62.5,1028.7,1029.0 +2.8289027116926335,0.8709139511910196,2.4870941840919194,2820.9,794.9,634.1,48.4,1039.6,1098.4 +2.8289149726515923,0.8708779101447621,2.6179938779914944,1468.4,623.1,94.7,46.5,1141.0,1268.8 +2.828916357982934,0.8708719684385349,2.748893571891069,1052.7,283.3,63.2,63.1,1387.1,1607.0 +2.8289432444582587,0.8708490334403061,2.8797932657906435,855.3,186.9,59.4,117.0,1962.5,2342.0 +2.8289540566654936,0.87084453154658,3.010692959690218,772.5,129.3,70.4,317.8,2858.1,2799.2 +2.7289406606438824,0.17075472612858045,0.0,63.0,193.1,193.0,1699.1,2628.9,2629.1 +2.7289856876140037,0.17145980994769805,0.1308996938995747,91.6,173.8,233.1,1742.7,1049.2,233.6 +2.7289408131357837,0.17144511104134974,0.2617993877991494,139.5,174.9,302.3,1937.4,474.9,95.3 +2.728888816377063,0.17141147796704903,0.39269908169872414,203.9,204.7,425.3,2379.9,282.3,63.0 +2.7288456029596584,0.17136576763543054,0.5235987755982988,162.5,294.6,629.8,3071.5,187.5,59.8 +2.728826423551052,0.1713258217899727,0.6544984694978736,151.9,620.0,1439.2,2717.4,129.5,70.5 +2.7288105563661595,0.17126213896569586,0.7853981633974483,163.1,1728.7,1728.3,2599.0,93.8,93.2 +2.728812285622372,0.17123558574014175,0.916297857297023,194.8,1763.4,1822.4,917.8,70.7,129.5 +2.7288287721903486,0.1711829965762377,1.0471975511965976,254.7,1949.5,2077.0,393.8,59.5,186.8 +2.7288613665702375,0.17112794990623525,1.1780972450961724,363.7,2371.1,2590.3,224.3,63.3,205.2 +2.728864981849481,0.1711231723980966,1.3089969389957472,592.4,3118.3,2990.9,139.9,95.6,231.7 +2.7288497955827524,0.17112695842379155,1.4398966328953218,1311.8,2752.9,2694.5,91.1,209.2,173.6 +2.7291307249874848,0.17106349000743482,1.5707963267948966,1698.6,2628.8,2628.6,63.3,193.4,193.1 +2.729018956600095,0.17105775655239586,1.7016960206944713,1783.3,1067.0,238.5,48.6,174.3,232.7 +2.728997294268438,0.17104934559274398,1.832595714594046,2030.5,474.8,95.7,47.1,174.5,302.2 +2.7290599902797243,0.17108815029423696,1.9634954084936205,2542.0,282.4,63.4,63.7,204.3,425.1 +2.7290884392857597,0.17111903790608296,2.0943951023931953,2976.6,186.8,59.5,117.4,295.2,631.5 +2.7290875075312226,0.17111453084343187,2.2252947962927703,2673.6,129.5,70.7,194.5,622.9,1446.1 +2.729097042875914,0.1711538178250862,2.356194490192345,2599.9,93.3,93.8,162.5,1728.0,1728.8 +2.729093494585363,0.17120031431855742,2.4870941840919194,316.9,70.5,129.6,151.9,1764.0,1823.0 +2.7290926162025673,0.1712054243322476,2.6179938779914944,117.6,59.9,187.6,162.2,1950.1,2077.7 +2.7290715534474694,0.1712331517628698,2.748893571891069,62.7,62.7,204.6,204.6,2376.9,2597.4 +2.729070483976115,0.1712343871502846,2.8797932657906435,46.6,95.0,231.4,316.7,3117.0,2990.0 +2.729007482010391,0.17126263529518315,3.010692959690218,48.2,210.0,173.9,620.3,2754.3,2695.4 +2.7290523727635003,0.27150586020323875,0.0,163.2,193.0,193.0,1598.7,2628.9,2629.4 +2.729004328537034,0.2707344911790279,0.1308996938995747,195.0,173.8,233.2,1639.4,1433.3,617.4 +2.729028420864289,0.270742360304677,0.2617993877991494,254.9,174.9,302.4,1822.2,674.1,294.5 +2.7290961028576373,0.2707877992493024,0.39269908169872414,204.0,204.7,425.5,2238.8,423.3,204.0 +2.7290985843300923,0.27079262266852977,0.5235987755982988,162.6,294.6,673.7,3071.9,302.9,175.2 +2.72911985405535,0.27082989201616203,0.6544984694978736,152.0,535.4,1439.4,2716.8,232.9,173.8 +2.7291356820497388,0.2709084942975637,0.7853981633974483,163.2,1629.0,1628.5,2599.1,193.5,192.9 +2.729136015365871,0.27092860216947834,0.916297857297023,194.9,1660.2,1718.9,1304.3,173.9,232.7 +2.729132223866869,0.2709446429179081,1.0471975511965976,254.8,1834.1,1961.5,593.0,174.7,294.9 +2.7291257298149,0.2709539955119984,1.1780972450961724,363.8,2230.7,2449.1,365.6,204.0,251.0 +2.7290778664215645,0.27099937312243205,1.3089969389957472,548.7,3118.2,2990.8,255.1,294.1,175.4 +2.7290409337367043,0.27102062808978067,1.4398966328953218,1311.7,2753.1,2695.0,194.2,232.0,173.6 +2.7290605163030817,0.2710168010052578,1.5707963267948966,1599.3,2628.8,2628.5,162.9,193.3,193.1 +2.729003652143547,0.2710153415069265,1.7016960206944713,1680.2,1455.6,626.9,151.7,174.3,232.7 +2.728954963437165,0.2710008649348339,1.832595714594046,1915.1,673.4,294.2,162.3,174.5,302.1 +2.729007768140335,0.27103795206571957,1.9634954084936205,2400.2,423.1,203.9,204.9,204.2,425.1 +2.7290007602193165,0.2710322955031128,2.0943951023931953,2976.5,302.0,174.7,254.9,295.1,675.2 +2.72895911970959,0.2709535232728846,2.2252947962927703,2673.6,232.7,173.9,232.9,537.3,1445.4 +2.7289661996564316,0.2709876955978545,2.356194490192345,2599.7,192.9,193.5,162.4,1628.5,1629.2 +2.7289657349002185,0.27095386146712097,2.4870941840919194,701.5,173.7,232.8,151.9,1660.7,1719.7 +2.728979048796577,0.27091386810193807,2.6179938779914944,316.4,175.2,293.8,162.1,1835.0,1962.7 +2.728977477930131,0.2709121027526489,2.748893571891069,203.7,203.8,251.2,204.6,2235.6,2455.7 +2.728998843512417,0.2708940093437142,2.8797932657906435,161.9,293.9,175.0,316.5,3117.4,2990.0 +2.7290027619923145,0.27089292676935894,3.010692959690218,151.5,232.8,173.9,705.2,2754.6,2695.7 +2.7290471555607323,0.37118625138170946,0.0,262.9,193.0,193.0,1499.1,2629.1,2628.6 +2.7290130544197493,0.37118556917487533,0.1308996938995747,298.4,173.8,233.1,1536.0,1816.9,916.5 +2.7289534145771417,0.37116812372162444,0.2617993877991494,316.3,174.9,302.4,1706.7,873.3,493.7 +2.728896160726732,0.37113307087556313,0.39269908169872414,205.6,204.7,425.2,2097.3,564.3,345.0 +2.728850485373386,0.3710866532290733,0.5235987755982988,162.5,294.5,673.4,2977.0,418.4,290.8 +2.7288299017173014,0.3710460599655301,0.6544984694978736,151.9,619.8,1438.8,2716.7,336.3,277.2 +2.728813280966507,0.3709814752588674,0.7853981633974483,163.1,1529.0,1528.5,2598.8,293.5,292.9 +2.7288150065486176,0.3709539959642476,0.916297857297023,194.8,1556.8,1615.5,1691.8,277.5,336.2 +2.72883216402234,0.37090068831700984,1.0471975511965976,254.6,1718.7,1845.8,792.7,290.2,294.7 +2.7288658980751244,0.37084537621111635,1.1780972450961724,363.6,2089.3,2308.2,507.5,345.2,233.3 +2.728870850372664,0.3708410370021482,1.3089969389957472,592.3,2956.8,2990.9,370.8,303.0,175.3 +2.7288941850911113,0.3708299195776439,1.4398966328953218,1311.4,2753.1,2694.5,297.8,232.0,173.6 +2.7289765726377775,0.3708115429513601,1.5707963267948966,1498.9,2629.0,2628.9,263.0,193.3,193.0 +2.7289784777381016,0.3708119014538198,1.7016960206944713,1576.5,1845.6,931.0,255.3,174.3,232.7 +2.728982011773907,0.37081313407374905,1.832595714594046,1799.9,872.9,493.7,278.0,174.5,302.1 +2.729043311543399,0.370852945389043,1.9634954084936205,2258.8,564.3,345.2,346.7,204.3,425.2 +2.7290647774260344,0.37087819199254923,2.0943951023931953,2976.8,417.6,290.2,254.9,295.1,675.3 +2.7290578748530803,0.3708645273370488,2.2252947962927703,2673.6,336.2,277.4,194.5,622.5,1445.7 +2.7290643883516186,0.3708930352715296,2.356194490192345,2599.5,292.9,293.5,162.5,1528.7,1529.0 +2.729061209879026,0.37092874891663974,2.4870941840919194,1087.0,277.3,336.4,151.9,1557.3,1616.1 +2.7290636234192918,0.37092442140380455,2.6179938779914944,515.5,290.8,293.9,162.2,1719.6,1846.9 +2.7290482736384,0.37094465419021283,2.748893571891069,345.2,345.2,233.5,204.6,2094.4,2314.4 +2.729054251275593,0.37094094494860785,2.8797932657906435,277.4,302.4,175.0,316.7,2960.7,2990.3 +2.7290417685193358,0.37094862715846166,3.010692959690218,255.0,232.8,173.9,620.1,2754.0,2695.6 +2.72906668655181,0.4712273467569421,0.0,362.9,193.0,193.0,1399.1,2628.4,2628.7 +2.729008681616777,0.4706578202642786,0.1308996938995747,402.1,173.8,233.1,1431.8,2201.7,1301.2 +2.729038811196153,0.4706677314850418,0.2617993877991494,316.4,174.9,302.4,1590.8,1029.2,693.3 +2.729076776083534,0.47069227198453767,0.39269908169872414,204.1,204.7,425.4,1955.6,705.7,486.4 +2.7291076020996607,0.47072794211652,0.5235987755982988,162.6,294.6,629.8,2777.9,534.1,406.5 +2.728788433029909,0.47102459746461767,0.6544984694978736,152.0,536.8,1443.2,2716.4,439.8,380.9 +2.7287844258261966,0.4710099072744074,0.7853981633974483,163.2,1428.8,1428.6,2598.5,393.6,393.0 +2.72878574935086,0.4710123780671003,0.916297857297023,195.0,1453.3,1512.0,2074.1,381.0,439.9 +2.728796877471563,0.4709804961192181,1.0471975511965976,255.0,1603.4,1730.9,991.6,405.9,392.4 +2.7288210104019393,0.4709416632948549,1.1780972450961724,333.1,1949.5,2168.4,648.7,426.0,205.3 +2.7288137914798503,0.4709489417675272,1.3089969389957472,549.6,2760.1,2990.0,486.2,443.9,175.4 +2.728823403375779,0.47094479984114535,1.4398966328953218,1315.0,2752.7,2693.8,401.2,232.0,173.7 +2.7288916684146596,0.47092968268948043,1.5707963267948966,1399.1,2628.9,2628.8,363.0,193.3,193.2 +2.728880436385399,0.4709292364640809,1.7016960206944713,1473.5,2230.4,1403.6,358.8,174.4,232.9 +2.728872588120839,0.47092608475526454,1.832595714594046,1684.7,1071.1,692.3,393.8,174.6,302.4 +2.728924644108845,0.4709593201956934,1.9634954084936205,2118.6,705.1,486.1,362.5,204.6,425.7 +2.728939519324571,0.47097666857564535,2.0943951023931953,2975.3,532.9,405.8,254.9,295.7,676.2 +2.7289289683815667,0.470954224650741,2.2252947962927703,2672.9,439.7,381.0,194.5,624.4,1449.2 +2.728934320317277,0.4709740215359379,2.356194490192345,2599.3,393.0,393.7,162.5,1428.4,1429.1 +2.728931909794174,0.4710019157792624,2.4870941840919194,1469.9,381.0,440.0,152.0,1454.0,1513.1 +2.7289370637772126,0.4709907349457587,2.6179938779914944,714.4,406.6,393.3,162.3,1604.1,1732.1 +2.7289252601967884,0.4710056028067855,2.748893571891069,486.4,424.5,204.6,204.8,1954.2,2174.3 +2.728935804829318,0.47099781971515586,2.8797932657906435,393.0,443.3,175.1,317.2,2763.9,2989.3 +2.7289281995825383,0.4710027811269122,3.010692959690218,358.5,232.8,174.1,707.4,2753.2,2694.7 +2.728958943253834,0.5712857972956809,0.0,463.0,193.0,193.2,1299.0,2628.4,2628.2 +2.7289543416156485,0.5706804092628499,0.1308996938995747,505.7,173.9,233.1,1328.4,2587.8,1771.3 +2.728992805924213,0.5706927793330117,0.2617993877991494,356.0,174.9,276.9,1475.2,1273.4,893.3 +2.7290303852281323,0.5707168794148096,0.39269908169872414,204.1,204.7,425.3,1813.6,847.1,627.7 +2.729059077938721,0.5707499655829316,0.5235987755982988,162.6,294.6,673.4,2577.7,649.8,522.1 +2.7290867392457763,0.5707988343780448,0.6544984694978736,152.0,619.9,1353.4,2717.2,543.6,484.5 +2.7290920800130585,0.5708274411823506,0.7853981633974483,163.2,1328.9,1328.4,2598.6,493.6,493.0 +2.7290914036968457,0.5708883489533012,0.916297857297023,194.9,1349.7,1408.6,2468.4,484.3,543.0 +2.729084901572449,0.5709142386438986,1.0471975511965976,254.8,1487.4,1614.5,1192.4,521.2,402.9 +2.7290783186380208,0.5709241033510692,1.1780972450961724,363.6,1806.6,2025.8,790.9,426.6,205.5 +2.729032350910494,0.570968082442147,1.3089969389957472,592.3,2556.2,2936.2,602.1,303.1,175.5 +2.7289982644964956,0.5709882009967602,1.4398966328953218,1310.7,2753.4,2694.5,504.6,232.1,173.7 +2.7290209597905344,0.5709837776951454,1.5707963267948966,1299.3,2629.2,2628.3,462.9,193.4,193.1 +2.7289670411480205,0.5709825452500499,1.7016960206944713,1369.9,2626.7,1797.1,462.2,174.3,232.7 +2.7289209285233333,0.5709690479147864,1.832595714594046,1568.3,1271.7,892.3,509.1,174.5,276.6 +2.7289409129081528,0.57098308349917,1.9634954084936205,1975.1,846.6,627.5,457.1,204.2,425.1 +2.728931896726292,0.5709755274999229,2.0943951023931953,2860.8,648.6,521.2,255.0,295.0,675.1 +2.728905686200693,0.5709256983283597,2.2252947962927703,2674.1,543.3,484.4,194.5,622.1,1359.3 +2.7289036613836286,0.5709168593821352,2.356194490192345,2599.4,493.0,493.5,162.4,1328.6,1328.9 +2.7289019987735617,0.570916961670372,2.4870941840919194,1860.1,484.3,543.4,151.9,1350.0,1409.1 +2.728914100552314,0.5708815119024431,2.6179938779914944,914.5,522.0,404.0,162.1,1488.0,1615.4 +2.728915174029459,0.5708760692344879,2.748893571891069,628.2,424.7,204.6,204.5,1811.1,2030.9 +2.7289416739342074,0.5708534968543009,2.8797932657906435,508.7,302.5,175.0,272.6,2560.9,2940.9 +2.728952047050669,0.5708492203843678,3.010692959690218,462.1,232.8,173.9,704.8,2754.4,2695.1 +2.7290044294483984,0.671148721881554,0.0,562.8,193.1,193.0,1199.1,2629.1,2628.9 +2.728976072182122,0.6711483893520038,0.1308996938995747,609.0,173.9,233.1,1225.1,2696.4,2154.9 +2.728920655452634,0.6711323299109155,0.2617993877991494,471.4,174.9,302.3,1359.8,1472.5,1092.3 +2.728866630128217,0.6710993244374968,0.39269908169872414,204.0,204.6,394.0,1672.3,987.9,768.7 +2.7288232910573873,0.6710553701738822,0.5235987755982988,162.6,294.4,673.3,2378.4,765.3,637.7 +2.7288043277795464,0.671017508692471,0.6544984694978736,151.9,619.4,1246.8,2717.9,647.0,587.9 +2.7287884833904963,0.6708867199051785,0.7853981633974483,163.1,1228.9,1228.3,2598.9,593.5,592.9 +2.7287904120180513,0.6709150459669941,0.916297857297023,194.8,1246.1,1305.0,2673.0,587.8,624.3 +2.7288038319859758,0.670874737813139,1.0471975511965976,254.6,1371.8,1499.1,1348.3,636.8,294.8 +2.7288352532482,0.6708234686371317,1.1780972450961724,363.6,1665.7,1884.7,932.8,437.5,205.4 +2.728839030325713,0.6708205748458227,1.3089969389957472,592.2,2357.6,2736.9,717.7,303.1,175.4 +2.7288616655860762,0.6708101822775314,1.4398966328953218,1224.7,2753.5,2694.8,608.2,232.1,173.6 +2.7289434651687268,0.6707920428831164,1.5707963267948966,1199.0,2628.7,2629.1,563.0,193.3,193.0 +2.728944854976429,0.6707924974940913,1.7016960206944713,1266.1,2693.7,2187.6,565.6,174.3,232.7 +2.7289478970737546,0.6707937570449225,1.832595714594046,1452.7,1471.1,1091.8,591.3,174.5,302.1 +2.72900881435936,0.6708333203510022,1.9634954084936205,1833.3,987.9,768.7,362.8,204.2,425.1 +2.7290300720516534,0.6708581587641738,2.0943951023931953,2661.3,764.2,636.9,255.0,295.0,675.1 +2.7290230685350076,0.6708441406051706,2.2252947962927703,2673.5,646.9,588.0,194.6,622.3,1246.6 +2.7290296495043784,0.6708722961911968,2.356194490192345,2599.9,593.0,593.5,162.5,1228.3,1228.9 +2.72902674819359,0.6709076695542662,2.4870941840919194,2245.5,587.9,620.8,151.9,1246.6,1305.4 +2.7290294239934867,0.6709031878747316,2.6179938779914944,1113.6,637.6,294.0,162.2,1372.4,1500.0 +2.729014489380829,0.6709233341549479,2.748893571891069,769.7,437.7,204.7,204.5,1669.9,1889.7 +2.7290207489574447,0.6709196941119462,2.8797932657906435,624.1,302.5,175.0,316.5,2361.6,2740.8 +2.729008493297584,0.6709275182310814,3.010692959690218,565.5,232.9,174.0,704.8,2754.1,2696.0 +2.729033494928019,0.7712062946467577,0.0,662.8,193.1,193.0,1099.2,2628.9,2628.8 +2.7289820464412866,0.7706520483857822,0.1308996938995747,699.5,173.9,233.1,1121.3,2802.5,2540.0 +2.7290142185667214,0.7706625575055521,0.2617993877991494,316.6,174.9,302.3,1244.1,1671.9,1292.3 +2.7290531675587593,0.7706876245270009,0.39269908169872414,204.1,204.7,425.3,1530.3,1129.5,910.1 +2.729084546575737,0.7707237445910897,0.5235987755982988,162.7,294.6,673.5,2179.6,881.0,753.2 +2.7287820347539538,0.7710228151248333,0.6544984694978736,152.0,621.7,1142.7,2716.5,750.4,691.5 +2.728778411376997,0.7710097540684415,0.7853981633974483,163.2,1129.0,1128.4,2599.0,693.4,693.0 +2.7287797524535025,0.771012090371685,0.916297857297023,195.0,1142.6,1201.7,2762.4,691.6,622.6 +2.728791091638207,0.7709795662383718,1.0471975511965976,255.0,1256.8,1384.2,1590.1,674.4,294.6 +2.7288156606131135,0.7709400598620659,1.1780972450961724,364.1,1525.3,1744.8,1073.8,426.0,205.3 +2.7288090247230037,0.7709468083990165,1.3089969389957472,593.3,2161.6,2540.4,832.9,302.9,175.4 +2.7288193021609,0.7709423227301537,1.4398966328953218,1120.3,2752.5,2694.0,711.4,232.0,173.7 +2.7288882576888533,0.7709270514124877,1.5707963267948966,1099.0,2628.8,2628.6,663.1,193.3,193.2 +2.728877670354623,0.7709266277923961,1.7016960206944713,1163.1,2836.9,2570.4,669.2,174.4,232.9 +2.7288703946511865,0.7709236486437971,1.832595714594046,1337.7,1668.5,1289.8,590.5,174.6,302.4 +2.7289229300914903,0.7709571766939673,1.9634954084936205,1692.8,1128.2,909.4,362.6,204.5,425.7 +2.728938165158757,0.7709748954155276,2.0943951023931953,2464.7,879.5,752.1,254.9,295.6,676.2 +2.7289278484515136,0.7709528645175971,2.2252947962927703,2673.2,750.1,691.6,194.6,624.4,1142.7 +2.728933314486795,0.7709730915583166,2.356194490192345,2599.3,693.1,693.6,162.5,1128.4,1129.0 +2.7289309056343005,0.7710013998859524,2.4870941840919194,2623.8,691.7,619.2,152.0,1143.0,1202.3 +2.7289359624200027,0.7709905893070657,2.6179938779914944,1311.2,672.4,293.6,162.3,1257.4,1385.1 +2.7289239827836003,0.7710057676439164,2.748893571891069,910.4,424.4,204.6,204.9,1529.6,1749.5 +2.728934294480926,0.7709982194986829,2.8797932657906435,739.6,302.4,175.1,273.3,2164.7,2544.8 +2.728926422743345,0.7710033345883287,3.010692959690218,669.2,232.8,174.0,707.3,2753.8,2694.9 +2.7289568344709645,0.8712860974651049,0.0,763.1,193.1,193.2,999.2,2628.6,2629.0 +2.7289527400147318,0.8706800552085794,0.1308996938995747,699.7,173.9,233.1,1017.8,2697.5,2756.1 +2.7289913489390707,0.8706924676440881,0.2617993877991494,316.6,174.9,302.3,1128.5,1871.7,1491.8 +2.7290289934364496,0.8707166032538327,0.39269908169872414,204.1,204.7,425.3,1388.7,1271.0,1051.4 +2.729057720842733,0.8707497182096999,0.5235987755982988,162.7,250.7,673.5,1979.9,996.9,869.1 +2.729085409281125,0.8707986170542383,0.6544984694978736,152.0,619.7,1039.5,2717.1,854.4,795.0 +2.729090763956975,0.8708272517590345,0.7853981633974483,163.2,1028.9,1028.5,2598.5,793.5,793.0 +2.729090098273399,0.87088819194303,0.916297857297023,194.8,1039.1,1097.8,2672.8,795.0,633.6 +2.7290835977533447,0.8709141144505881,1.0471975511965976,254.7,1140.6,1268.2,1791.7,726.7,295.0 +2.729077005444745,0.8709240044532351,1.1780972450961724,363.7,1383.6,1602.1,1216.0,426.4,205.5 +2.7290310238773334,0.8709680077686037,1.3089969389957472,592.2,1959.4,2338.4,948.8,303.2,175.5 +2.7289969182665907,0.8709881487472282,1.4398966328953218,1017.3,2753.6,2694.5,815.0,232.1,173.6 +2.729019589243949,0.8709837304060324,1.5707963267948966,999.0,2629.2,2628.2,762.8,193.4,193.1 +2.7289656474107398,0.8709824977052478,1.7016960206944713,1059.4,2693.9,2752.1,772.4,174.3,232.7 +2.728919512848083,0.8709689982291118,1.832595714594046,1221.6,1869.8,1446.5,610.2,174.5,302.1 +2.728939481299458,0.870983019286075,1.9634954084936205,1550.0,1270.4,1051.0,362.8,204.2,425.1 +2.7289304576595512,0.8709754425202358,2.0943951023931953,2261.8,995.2,867.9,255.0,295.0,675.0 +2.728904243565503,0.8709255972615173,2.2252947962927703,2673.9,853.8,795.0,194.5,622.0,1039.3 +2.7289022216896974,0.8709167430523785,2.356194490192345,2599.8,792.8,793.4,162.5,1028.4,1029.1 +2.728900570655781,0.8709168301225099,2.4870941840919194,2717.2,794.9,633.9,151.9,1039.6,1098.6 +2.7289126812468187,0.8708813732945639,2.6179938779914944,1512.5,727.6,294.0,162.1,1141.2,1268.7 +2.728913770882191,0.870875924652404,2.748893571891069,1052.5,424.8,204.6,204.5,1387.1,1606.8 +2.728940280305211,0.8708533520217361,2.8797932657906435,855.1,302.5,175.0,316.5,1962.5,2341.8 +2.728950661705163,0.8708490771573991,3.010692959690218,772.7,232.8,174.0,704.8,2754.4,2695.2 +2.6289364777437774,0.17075788602082476,0.0,63.0,293.1,293.0,1699.0,2528.7,2528.8 +2.628982468357271,0.17146048642418354,0.1308996938995747,91.5,277.4,336.7,1742.6,1049.1,233.6 +2.6289376992334788,0.17144581211233323,0.2617993877991494,139.5,290.5,418.0,1937.6,474.8,95.3 +2.6288856717569873,0.1714121449817687,0.39269908169872414,223.8,346.3,567.1,2380.3,282.3,63.0 +2.62884241608385,0.17136636282705542,0.5235987755982988,278.1,493.7,873.0,2955.6,187.5,59.8 +2.628823203987605,0.17132632334957032,0.6544984694978736,381.7,1005.7,1786.9,2614.5,129.5,70.5 +2.628807341212647,0.1712625527362739,0.7853981633974483,263.1,1729.0,1728.2,2499.1,93.8,93.2 +2.628809088972813,0.17123591441624386,0.916297857297023,298.3,1763.5,1822.3,832.5,70.7,129.5 +2.62882561313107,0.1711832545288965,1.0471975511965976,370.2,1949.2,2076.4,393.9,59.5,186.8 +2.6288582610781988,0.17112816589580393,1.1780972450961724,504.9,2371.4,2590.4,224.3,63.3,282.5 +2.6288619277297838,0.17112335564241588,1.3089969389957472,791.7,3002.5,2875.1,139.9,95.6,291.0 +2.628884131255777,0.17111106735233617,1.4398966328953218,1701.6,2649.6,2591.1,91.1,238.5,277.1 +2.628965870279027,0.17109114106605183,1.5707963267948966,1699.0,2528.9,2529.1,63.3,293.2,293.0 +2.6289677535465596,0.17108973226259683,1.7016960206944713,1783.5,1066.7,238.4,48.6,277.8,336.1 +2.628934890433151,0.17107518522450937,1.832595714594046,2030.6,474.8,95.6,47.1,290.1,417.8 +2.629175009532567,0.17122763190919144,1.9634954084936205,2541.5,282.4,63.3,63.6,346.0,567.0 +2.6291165299901604,0.17116467606808938,2.0943951023931953,2860.8,186.8,59.5,117.4,494.9,875.4 +2.629097643780216,0.17112618661009904,2.2252947962927703,2569.8,129.5,70.7,275.3,925.1,1786.2 +2.6291049733978644,0.1711556505647016,2.356194490192345,2499.8,93.3,93.8,262.5,1728.1,1729.0 +2.629101489204859,0.17120108620101981,2.4870941840919194,316.8,70.5,129.6,255.5,1763.9,1823.1 +2.629100156560805,0.17120777764813488,2.6179938779914944,117.6,59.9,187.6,277.8,1950.5,2078.1 +2.629077822578443,0.17123755783401706,2.748893571891069,62.7,62.7,282.8,346.1,2376.7,2597.0 +2.629074948423755,0.17124049985815382,2.8797932657906435,46.6,95.0,290.6,516.3,3001.6,2874.7 +2.6290527838632163,0.1712516791112717,3.010692959690218,48.2,235.2,277.5,1092.8,2650.8,2591.8 +2.6290667797288902,0.27152191391435454,0.0,163.1,293.1,293.1,1599.0,2528.4,2529.1 +2.6290086985977634,0.27072445172192294,0.1308996938995747,195.0,277.4,336.6,1639.1,1433.6,617.3 +2.6290313199302293,0.2707318814016375,0.2617993877991494,255.0,290.5,417.9,1821.7,674.1,294.5 +2.6290618676743827,0.27075160752651195,0.39269908169872414,345.2,346.4,567.0,2238.7,423.3,204.0 +2.6290868708217294,0.27078085226529613,0.5235987755982988,349.0,493.9,872.6,2956.0,302.9,175.3 +2.62911236399336,0.2708260683231811,0.6544984694978736,255.5,1005.6,1660.7,2613.7,232.8,173.7 +2.6291167087371123,0.2708511543706662,0.7853981633974483,263.2,1628.9,1628.4,2498.6,193.5,193.0 +2.6291158570800963,0.27090867558503784,0.916297857297023,298.4,1660.2,1719.2,1304.4,173.9,232.7 +2.629109990414016,0.27093145762121384,1.0471975511965976,370.2,1834.1,1961.1,593.1,174.7,302.0 +2.629104759090542,0.2709387605352995,1.1780972450961724,504.8,2230.9,2449.4,365.7,204.0,347.1 +2.629029660938231,0.27101480213353835,1.3089969389957472,747.9,3002.7,2875.3,255.1,294.1,430.2 +2.6290247573292103,0.271018936739553,1.4398966328953218,1660.5,2649.5,2591.4,194.2,335.4,277.1 +2.6290557789029227,0.2710125215563519,1.5707963267948966,1599.1,2528.9,2528.7,162.9,293.3,293.1 +2.6290025793531933,0.2710112146853507,1.7016960206944713,1680.2,1455.9,626.9,151.7,277.7,336.2 +2.628954920639765,0.2709970890888629,1.832595714594046,1915.2,673.4,294.2,162.3,290.0,417.7 +2.6289729425532284,0.271009919279279,1.9634954084936205,2400.6,423.2,204.0,204.9,346.0,566.8 +2.62896223415824,0.27100074889095627,2.0943951023931953,2861.8,302.0,174.6,316.3,494.7,874.8 +2.6289348783084883,0.2709489671068934,2.2252947962927703,2569.8,232.7,173.9,298.0,1009.5,1660.5 +2.6289322186548234,0.27093806921295815,2.356194490192345,2499.8,193.0,193.5,262.4,1628.6,1628.9 +2.628930357463246,0.270936201119214,2.4870941840919194,701.6,173.7,232.8,255.4,1660.7,1720.0 +2.6289428152701095,0.27089887391398193,2.6179938779914944,316.4,175.2,302.9,277.7,1835.0,1962.6 +2.6289445300044965,0.2708918395683151,2.748893571891069,203.8,203.8,346.0,345.9,2235.4,2455.9 +2.628972083795344,0.2708679611491398,2.8797932657906435,161.9,293.9,430.3,516.1,3002.3,2874.9 +2.628983722988316,0.2708627602986502,3.010692959690218,151.5,336.2,277.4,1092.4,2650.7,2592.0 +2.6290378139678476,0.3711635794799697,0.0,262.8,293.0,293.0,1499.2,2529.3,2529.1 +2.629010596859251,0.37116313827181346,0.1308996938995747,298.4,277.4,336.7,1535.8,1817.1,1000.9 +2.6289560950219366,0.37114728591501756,0.2617993877991494,370.3,290.4,417.9,1706.7,873.3,493.6 +2.628902758926157,0.3711147065926361,0.39269908169872414,345.2,346.2,566.9,2097.4,564.2,345.0 +2.6288599157782366,0.37107135218743315,0.5235987755982988,278.1,493.6,872.6,2955.8,418.5,290.7 +2.628841115745949,0.371034108067992,0.6544984694978736,255.4,1005.3,1557.2,2614.0,336.4,277.2 +2.6288252873113693,0.37097296808629054,0.7853981633974483,263.1,1529.2,1528.7,2498.7,293.5,293.0 +2.6288269130607986,0.3709487421093438,0.916297857297023,298.2,1556.7,1615.5,1691.9,277.4,336.2 +2.628843194833964,0.37089834294608703,1.0471975511965976,370.2,1718.5,1846.1,792.9,290.2,417.6 +2.6288754460446433,0.37084541943360705,1.1780972450961724,473.7,2089.1,2308.6,507.5,345.2,392.1 +2.6288785329681534,0.37084285601104483,1.3089969389957472,791.7,2956.3,2874.9,370.8,418.6,290.9 +2.6288997658793476,0.3708328962661349,1.4398966328953218,1534.3,2649.4,2591.2,297.7,461.6,277.0 +2.6289799655004575,0.370815041691543,1.5707963267948966,1499.0,2528.8,2528.8,263.0,293.3,293.0 +2.6289798203874497,0.37081535822413514,1.7016960206944713,1576.8,1845.5,1017.0,255.3,277.7,336.2 +2.6289815232916043,0.37081607189900034,1.832595714594046,1799.8,872.8,493.7,278.0,290.1,417.7 +2.629041292014103,0.37085495146226033,1.9634954084936205,2258.7,564.3,345.2,346.7,346.1,566.8 +2.629061621350955,0.3708790003867357,2.0943951023931953,2861.0,417.6,290.2,370.5,494.7,874.8 +2.6290539891481632,0.37086401100806965,2.2252947962927703,2570.2,336.2,277.5,298.1,1009.8,1556.7 +2.629060171610094,0.370891142602656,2.356194490192345,2499.8,293.0,293.5,262.4,1528.8,1528.9 +2.6290570406833904,0.3709255356699863,2.4870941840919194,1087.1,277.3,336.3,255.4,1557.1,1616.5 +2.6290598061597144,0.37092005359791,2.6179938779914944,515.5,290.8,418.5,277.7,1719.2,1846.8 +2.629045069025472,0.370939331911186,2.748893571891069,345.2,345.1,392.6,345.9,2094.1,2313.6 +2.629051811638727,0.3709349262185142,2.8797932657906435,277.4,418.1,290.6,516.2,2960.6,2874.4 +2.6290401824601006,0.3709421736067826,3.010692959690218,255.0,462.6,277.4,1092.3,2650.7,2592.4 +2.629066122208695,0.4712216690449422,0.0,362.9,293.0,293.0,1399.3,2528.9,2528.9 +2.6290082803508312,0.4706575289565835,0.1308996938995747,402.1,277.3,336.7,1432.0,2201.8,1385.8 +2.6290385060397328,0.4706674705387528,0.2617993877991494,486.0,290.5,418.0,1590.6,1073.1,693.4 +2.629076515986033,0.4706920387538325,0.39269908169872414,347.4,346.3,566.9,1955.5,705.8,486.4 +2.629107366750211,0.47074029373713144,0.5235987755982988,278.3,493.8,872.9,2777.5,534.2,406.5 +2.6288125869137056,0.4710397956772481,0.6544984694978736,255.6,1007.8,1453.5,2613.1,439.8,380.9 +2.628804854314647,0.4710092488287634,0.7853981633974483,263.2,1428.9,1428.4,2498.7,393.5,393.1 +2.6288062598223694,0.4710096759598028,0.916297857297023,298.5,1453.4,1512.2,2074.9,381.0,439.9 +2.6288166804237503,0.4709800974120617,1.0471975511965976,370.6,1603.8,1731.2,947.5,405.9,494.1 +2.6288388924112467,0.4709443120096124,1.1780972450961724,505.3,1949.2,2168.4,648.8,486.7,374.8 +2.6288289517839014,0.4709541446304748,1.3089969389957472,792.8,2758.6,2874.2,486.2,450.4,291.0 +2.628835381912957,0.47095172487069714,1.4398966328953218,1430.7,2648.7,2636.2,401.1,335.5,277.1 +2.628900300136684,0.4709373845953604,1.5707963267948966,1398.9,2528.7,2528.7,363.1,293.4,293.2 +2.6288859250308527,0.4709368573020358,1.7016960206944713,1473.5,2230.4,1318.6,358.8,277.9,336.4 +2.6288752700293725,0.4709328977752809,1.832595714594046,1684.6,1027.1,692.4,393.7,290.3,418.0 +2.6289249785444246,0.4709647004762252,1.9634954084936205,2118.3,705.0,486.2,488.9,346.3,567.5 +2.6289381071362796,0.47098021429360926,2.0943951023931953,2860.2,532.8,405.8,472.9,495.4,876.2 +2.628926428354969,0.4709557418841912,2.2252947962927703,2569.2,439.7,380.9,298.0,1012.3,1453.1 +2.6289312572436923,0.47097342947951115,2.356194490192345,2499.2,393.0,393.7,262.5,1428.4,1428.8 +2.628928898842173,0.4709992951831927,2.4870941840919194,1469.9,380.9,440.0,255.6,1453.8,1513.1 +2.6289345722538138,0.47098633191890205,2.6179938779914944,714.2,406.7,492.8,277.9,1604.1,1731.7 +2.628923689945889,0.47099971732300383,2.748893571891069,486.5,487.0,375.4,346.3,1953.7,2174.3 +2.628935398085097,0.47099084192501794,2.8797932657906435,392.9,450.2,290.6,516.9,2763.7,2873.5 +2.6289291014555642,0.4709951113614699,3.010692959690218,358.5,336.3,277.5,1095.2,2650.4,2591.5 +2.6289614295068495,0.571279332172919,0.0,463.0,293.1,293.1,1298.9,2528.7,2529.1 +2.628956023602689,0.5706806222296554,0.1308996938995747,505.7,277.5,336.7,1328.5,2587.5,1771.1 +2.628994338533808,0.5706929493823372,0.2617993877991494,516.0,290.5,417.9,1475.4,1273.0,893.1 +2.6290318644172097,0.5707170217274886,0.39269908169872414,345.3,346.3,566.9,1813.3,847.1,627.8 +2.629060535178014,0.570750093350731,0.5235987755982988,278.3,493.7,872.7,2577.6,649.9,522.2 +2.629088178130573,0.5707989493370567,0.6544984694978736,255.5,1005.2,1350.3,2613.2,543.5,484.4 +2.6290935089593055,0.570827546643021,0.7853981633974483,263.2,1329.1,1328.5,2498.8,493.5,493.0 +2.6290928211616125,0.570888439414404,0.916297857297023,298.4,1349.6,1408.4,2467.8,484.4,543.1 +2.629086312472339,0.5709143118411608,1.0471975511965976,344.9,1487.6,1614.8,1192.4,521.2,494.8 +2.6290797308739546,0.5709241641407317,1.1780972450961724,504.8,1806.6,2025.5,790.9,568.3,347.2 +2.629033766941269,0.5709681285457222,1.3089969389957472,791.6,2557.5,2875.5,602.0,418.7,291.1 +2.628999688415135,0.570988230822046,1.4398966328953218,1327.5,2649.6,2591.7,504.7,335.6,277.1 +2.629022396275112,0.5709838056244232,1.5707963267948966,1299.2,2529.0,2528.6,462.9,293.4,293.0 +2.6289684897631385,0.5709825735399237,1.7016960206944713,1369.9,2540.8,1797.1,462.0,277.8,336.2 +2.6289223891148623,0.5709690757450259,1.832595714594046,1568.3,1271.6,892.3,509.0,290.1,417.7 +2.6289423809035704,0.5709831211149037,1.9634954084936205,1975.1,846.7,627.5,504.0,345.9,566.7 +2.628933365585663,0.570975579731253,2.0943951023931953,2861.0,648.6,521.3,370.6,494.7,874.6 +2.6289071542338185,0.5709257595548691,2.2252947962927703,2569.9,543.1,484.4,298.1,1009.0,1350.0 +2.628905124278379,0.570916928292559,2.356194490192345,2499.4,493.0,493.5,262.4,1328.2,1329.1 +2.628903449945296,0.5709170384336457,2.4870941840919194,1859.4,484.3,543.3,255.4,1350.2,1409.5 +2.6289155446514254,0.5708815890917578,2.6179938779914944,914.2,522.0,493.3,277.8,1488.0,1615.4 +2.6289166052164457,0.5708761469155443,2.748893571891069,628.1,566.2,346.1,345.9,1811.1,2031.4 +2.6289430999333767,0.570853570720876,2.8797932657906435,508.6,418.1,290.6,515.9,2561.1,2874.3 +2.6289534697000487,0.5708492901729525,3.010692959690218,462.0,336.4,277.5,1091.7,2651.1,2592.2 +2.629005852924435,0.6711487930173952,0.0,562.9,293.0,293.0,1199.1,2528.8,2528.6 +2.6289774933253507,0.6711484595582433,0.1308996938995747,609.1,277.4,313.9,1225.1,2593.1,2154.5 +2.628922076441097,0.6711324013596003,0.2617993877991494,575.9,290.5,417.9,1359.7,1472.2,1092.4 +2.6288680493349177,0.6710993987119056,0.39269908169872414,345.3,346.3,566.8,1672.1,988.1,768.8 +2.6288247084158223,0.6710554490512073,0.5235987755982988,278.2,493.6,872.5,2378.6,765.4,637.7 +2.6288057362952797,0.6710175888338346,0.6544984694978736,255.4,1004.6,1247.0,2613.8,647.0,587.9 +2.6287898863068873,0.6709557817001559,0.7853981633974483,263.1,1229.3,1228.6,2498.9,593.6,592.9 +2.6287917607678626,0.6709310410559757,0.916297857297023,298.3,1246.2,1304.8,2569.1,587.9,646.6 +2.628808414821088,0.6708802702933974,1.0471975511965976,370.1,1372.0,1499.2,1392.1,636.7,518.4 +2.628841057248888,0.6708270506642313,1.1780972450961724,504.6,1665.6,1884.7,932.8,568.1,347.1 +2.6288445714803084,0.670824403460655,1.3089969389957472,791.4,2357.9,2736.7,717.8,418.7,290.9 +2.62886618810908,0.6708145510322363,1.4398966328953218,1224.0,2649.9,2592.1,608.1,335.6,277.1 +2.6289466729618685,0.6707967195310294,1.5707963267948966,1198.8,2528.3,2528.7,562.9,293.3,293.1 +2.628946751345459,0.670797135486271,1.7016960206944713,1266.2,2590.3,2187.7,565.6,277.8,336.2 +2.6289486030651523,0.6707980350348235,1.832595714594046,1452.9,1471.0,1091.8,624.7,290.1,417.7 +2.629008518884294,0.6708369798706926,1.9634954084936205,1832.7,987.9,768.8,598.8,346.0,566.8 +2.629029029353579,0.6708610329556737,2.0943951023931953,2660.7,764.1,636.9,370.6,450.8,874.7 +2.629021549800878,0.6708461386788072,2.2252947962927703,2570.6,646.8,588.0,298.1,1009.1,1246.2 +2.629027912637349,0.6708733871315375,2.356194490192345,2499.6,592.9,593.6,262.5,1228.6,1229.0 +2.6290250304647085,0.6709078958728176,2.4870941840919194,2245.6,587.9,646.9,255.5,1246.6,1305.6 +2.6290279324418493,0.6709026488094443,2.6179938779914944,1069.8,637.5,519.6,277.8,1372.2,1499.9 +2.6290133813421313,0.6709221628071329,2.748893571891069,769.6,566.2,346.1,346.0,1669.9,1889.5 +2.629020136514409,0.6709180510671751,2.8797932657906435,624.2,418.2,290.6,515.8,2361.6,2741.1 +2.6290084372434603,0.6709255722653928,3.010692959690218,565.6,336.4,277.5,1091.6,2651.0,2591.9 +2.6290341170789944,0.7712048620058023,0.0,662.8,293.1,293.0,1099.2,2529.0,2529.3 +2.628982913700008,0.7706524899586247,0.1308996938995747,712.9,277.4,336.6,1121.3,2592.7,2539.4 +2.629015106062339,0.7706630065252549,0.2617993877991494,587.0,290.5,417.9,1244.1,1672.2,1292.2 +2.628883577704402,0.7711108777482509,0.39269908169872414,345.1,346.5,567.4,1530.9,1098.0,909.8 +2.6288733661272663,0.7711008560347299,0.5235987755982988,278.2,494.2,873.5,2181.4,881.0,753.3 +2.628872588385744,0.7710956943131002,0.6544984694978736,255.5,1007.2,1142.9,2613.6,750.6,691.6 +2.6288648994408943,0.7710662507028039,0.7853981633974483,263.2,1129.0,1128.4,2498.6,693.8,693.2 +2.6288659818800353,0.7710714552169691,0.916297857297023,298.5,1142.7,1201.3,2680.1,691.6,750.5 +2.6288744602764633,0.7710472584808112,1.0471975511965976,370.4,1256.4,1383.8,1590.7,752.5,634.5 +2.6288933023913965,0.7710159626073985,1.1780972450961724,505.1,1525.3,1744.5,1043.0,579.1,347.0 +2.6288792456142986,0.7710290631405972,1.3089969389957472,792.4,2160.1,2539.7,833.2,418.4,291.0 +2.6288811848821685,0.7710286486835716,1.4398966328953218,1120.4,2649.2,2590.9,711.6,335.4,277.2 +2.628941578179116,0.7710147898602413,1.5707963267948966,1098.9,2528.9,2528.6,663.1,293.3,293.1 +2.628923150581379,0.7710137093596756,1.7016960206944713,1162.9,2590.2,2572.8,669.3,277.8,336.3 +2.6289089972138457,0.7710084759532718,1.832595714594046,1337.5,1669.2,1290.1,740.6,290.2,417.9 +2.628955898941006,0.7710382333609149,1.9634954084936205,1692.4,1128.5,909.6,503.7,346.2,567.1 +2.6289670100826386,0.7710512900055071,2.0943951023931953,2463.2,879.7,752.5,370.4,495.1,875.5 +2.628953948503819,0.7710243421891687,2.2252947962927703,2569.4,750.3,691.5,298.0,1011.2,1142.4 +2.628958031957931,0.7710394938223337,2.356194490192345,2499.5,693.2,693.8,262.5,1128.2,1128.9 +2.628955595334258,0.7710628253960687,2.4870941840919194,2542.0,691.6,750.8,255.5,1142.9,1202.4 +2.628961572209182,0.771047607681876,2.6179938779914944,1311.9,753.5,635.6,277.9,1257.0,1384.7 +2.6289516090801746,0.7710589039503264,2.748893571891069,910.8,579.7,345.9,346.2,1529.1,1748.8 +2.6289644840346527,0.7710483313288612,2.8797932657906435,739.8,417.9,290.6,516.5,2163.6,2543.5 +2.628959678439059,0.7710513009557529,3.010692959690218,669.0,336.3,277.5,1094.1,2650.1,2591.5 +2.628994104735301,0.871337084119068,0.0,763.1,293.1,293.1,999.1,2528.9,2529.2 +2.628972817887502,0.8706988587740712,0.1308996938995747,816.4,277.4,336.7,1017.7,2593.0,2652.4 +2.6290059743349086,0.8707095734197712,0.2617993877991494,516.1,290.5,418.0,1128.5,1871.6,1491.6 +2.629040842293389,0.8707319824046946,0.39269908169872414,345.3,346.4,566.9,1389.2,1270.5,1051.2 +2.629067943498529,0.8707633983141647,0.5235987755982988,278.3,493.7,872.9,1980.6,996.7,869.1 +2.6290946270093873,0.8708105807993369,0.6544984694978736,255.6,1005.4,1039.6,2613.8,854.3,795.0 +2.629099517647752,0.8708375188694677,0.7853981633974483,263.3,1029.0,1028.5,2499.1,793.5,793.1 +2.6290987887599298,0.8708968207269439,0.916297857297023,298.4,1039.0,1098.0,2569.4,794.9,853.6 +2.62909261818722,0.8709212431656665,1.0471975511965976,370.2,1140.9,1268.2,1791.4,867.8,494.6 +2.6290866980064282,0.8709298994112404,1.1780972450961724,504.8,1383.8,1602.4,1216.2,568.1,347.2 +2.6290415932191324,0.8709729275536686,1.3089969389957472,791.6,1959.6,2338.4,948.8,418.7,291.0 +2.629008518878588,0.8709923640808073,1.4398966328953218,1017.2,2649.2,2591.4,815.0,335.6,277.1 +2.6290323124783184,0.8709876443183633,1.5707963267948966,999.1,2528.9,2528.4,763.0,293.4,293.0 +2.628979439317089,0.8709863989321238,1.7016960206944713,1059.4,2590.5,2648.6,772.4,277.8,336.2 +2.628916614575714,0.8709705586329268,1.832595714594046,1221.8,1869.8,1490.5,790.6,290.1,417.6 +2.628947326165623,0.8709913103331159,1.9634954084936205,1550.1,1270.0,1050.7,503.9,345.9,566.8 +2.6289403132637776,0.8709859795329915,2.0943951023931953,2262.6,995.2,867.9,370.6,494.6,874.7 +2.6289140479430015,0.8709361154385797,2.2252947962927703,2570.4,853.9,795.1,298.0,1009.1,1039.5 +2.6289117502672346,0.8709263396530327,2.356194490192345,2499.6,792.9,793.5,262.5,1028.8,1029.1 +2.628910030883976,0.8709252570720891,2.4870941840919194,2613.3,795.0,854.0,255.4,1039.4,1098.4 +2.628922414191412,0.8708886231751503,2.6179938779914944,1512.3,868.7,493.2,277.8,1141.3,1268.9 +2.628923990756339,0.8708821616112563,2.748893571891069,1052.5,566.2,346.1,345.9,1387.1,1606.9 +2.6289512255371226,0.8708587787775393,2.8797932657906435,855.4,418.0,290.6,515.8,1962.9,2342.6 +2.6289624556583124,0.8708539467874878,3.010692959690218,772.7,336.3,277.4,1083.3,2650.9,2592.3 +2.528949997546069,0.17076573757034885,0.0,63.0,393.0,393.0,1698.8,2429.0,2428.5 +2.5289896070912503,0.17146305770067305,0.1308996938995747,91.6,381.0,440.3,1742.9,1049.3,233.6 +2.5289432995521324,0.17144791198827858,0.2617993877991494,139.5,406.1,533.5,1937.0,474.9,95.3 +2.5288907341298703,0.17141392278966494,0.39269908169872414,223.8,488.0,708.7,2380.3,282.2,63.0 +2.528847250157483,0.17136793002377604,0.5235987755982988,393.4,693.1,1072.2,2840.5,187.5,59.8 +2.5288279310357633,0.17132773952881886,0.6544984694978736,442.3,1391.3,1764.2,2510.0,129.5,70.5 +2.528811995222536,0.17126382250703354,0.7853981633974483,363.1,1728.8,1728.3,2399.0,93.8,93.2 +2.5288137177710115,0.1712370541399546,0.916297857297023,401.8,1763.4,1822.5,917.9,70.7,129.5 +2.5288302474958395,0.17118426970682132,1.0471975511965976,485.7,1949.3,2076.4,393.8,59.5,186.8 +2.5288629249097125,0.1711290529152898,1.1780972450961724,645.9,2371.1,2590.5,224.3,63.4,282.5 +2.5288666551606274,0.17112414535249298,1.3089969389957472,991.1,2887.4,2759.7,139.9,95.6,406.6 +2.52888894562457,0.17111179982439162,1.4398966328953218,1741.1,2546.3,2487.4,91.1,238.5,506.7 +2.5289707813244084,0.1710918224375808,1.5707963267948966,1698.6,2429.1,2429.0,63.3,393.3,393.1 +2.5289727630549175,0.17109040657482444,1.7016960206944713,1783.5,1066.7,238.4,48.6,381.2,439.7 +2.5289770169302828,0.17109000683151865,1.832595714594046,2030.5,474.7,95.6,47.1,405.7,533.3 +2.529039495191414,0.1711287334925522,1.9634954084936205,2542.2,282.4,63.3,63.7,487.7,708.7 +2.529062270590021,0.1711535650428082,2.0943951023931953,2745.1,186.8,59.5,117.4,694.6,1074.6 +2.5290565092897,0.17114006893784217,2.2252947962927703,2466.6,129.5,70.7,319.5,1397.6,1763.6 +2.529063679559791,0.17116922981482174,2.356194490192345,2399.4,93.3,93.8,362.5,1728.2,1728.8 +2.5290604684918483,0.1712057921043395,2.4870941840919194,316.9,70.5,129.6,359.0,1764.0,1823.1 +2.529062253157685,0.1712020913473462,2.6179938779914944,117.6,59.9,187.6,393.4,1950.2,2078.0 +2.5290457439519285,0.17122250534420536,2.748893571891069,62.7,62.7,282.8,487.5,2377.2,2597.3 +2.529050444155986,0.17121831457608017,2.8797932657906435,46.6,95.0,406.2,715.6,2886.1,2758.5 +2.529036847394465,0.17122487941355957,3.010692959690218,48.2,235.2,507.2,1479.9,2547.5,2488.7 +2.52906126745084,0.27150301565443513,0.0,163.2,393.0,393.0,1598.8,2429.0,2428.3 +2.529008074802774,0.2707322730958923,0.1308996938995747,195.0,380.9,440.3,1639.3,1433.3,617.4 +2.5290309829497084,0.27073978212817407,0.2617993877991494,254.9,406.1,533.6,1822.0,674.1,294.5 +2.5290608483144563,0.27075906944477457,0.39269908169872414,365.2,488.0,708.6,2238.8,423.3,204.0 +2.529085110044038,0.27078750755076086,0.5235987755982988,393.9,693.0,1071.8,2840.6,302.9,175.3 +2.529110072377144,0.27083173464539567,0.6544984694978736,359.0,1391.4,1660.6,2510.1,232.9,173.8 +2.529114172037075,0.2708557690762212,0.7853981633974483,363.1,1629.2,1628.8,2398.6,193.6,193.0 +2.529113340150569,0.27091227838067167,0.916297857297023,401.9,1660.3,1719.1,1304.3,173.9,232.7 +2.529107734140564,0.2709341472058213,1.0471975511965976,485.8,1834.1,1961.6,592.9,174.7,302.0 +2.5291309950365406,0.270895495020274,1.1780972450961724,645.9,2230.4,2449.8,365.6,204.0,423.0 +2.528927272153483,0.2710842164723577,1.3089969389957472,991.0,2886.7,2760.0,255.1,294.1,406.6 +2.5289989622457694,0.27104813940776906,1.4398966328953218,1637.9,2591.7,2488.3,194.2,438.9,380.6 +2.529052281774251,0.27103667778011586,1.5707963267948966,1599.4,2428.8,2428.7,162.9,393.3,393.1 +2.5290022794181084,0.2710354899106715,1.7016960206944713,1680.4,1455.8,626.6,151.7,381.2,439.6 +2.528951844937111,0.2710205122230447,1.832595714594046,1915.2,673.4,294.2,162.3,405.7,533.3 +2.528965920724224,0.2710308653117266,1.9634954084936205,2400.7,423.1,204.0,204.9,487.6,708.5 +2.528951883238416,0.27101812385566504,2.0943951023931953,2745.2,302.0,174.6,316.3,650.4,1074.6 +2.5289223292980765,0.27096222095845124,2.2252947962927703,2466.6,232.7,173.9,401.5,1396.8,1660.5 +2.528918669285947,0.2709470088164896,2.356194490192345,2399.4,193.0,193.5,362.4,1628.5,1628.9 +2.5289169423856697,0.27094101333305587,2.4870941840919194,701.6,173.7,232.8,358.9,1661.0,1720.3 +2.5289304988330166,0.27090004682132585,2.6179938779914944,316.4,175.2,302.9,393.3,1835.1,1962.4 +2.528963502365458,0.2708433048048704,2.748893571891069,203.8,203.8,423.8,487.3,2235.8,2455.9 +2.5289657012387283,0.27084285070140557,2.8797932657906435,161.9,294.0,406.1,715.6,2886.2,2758.9 +2.528972525942428,0.27084014388210553,3.010692959690218,151.5,439.8,380.9,1479.4,2547.0,2487.8 +2.5290314387839428,0.37114859031130276,0.0,263.0,393.0,393.0,1499.3,2428.4,2429.0 +2.529063294176238,0.37115398819629486,0.1308996938995747,298.4,380.9,440.3,1535.8,1817.0,1000.8 +2.5289774705843664,0.37112832879999025,0.2617993877991494,370.3,406.0,533.4,1706.6,873.3,493.7 +2.528920245033538,0.3710932373184026,0.39269908169872414,486.4,487.9,708.6,2097.4,564.5,344.9 +2.528880169460783,0.3710528011901637,0.5235987755982988,534.7,692.9,1071.9,2840.2,418.5,290.7 +2.5288643684276892,0.3710211226310136,0.6544984694978736,359.0,1391.0,1557.4,2510.0,336.3,277.3 +2.5288500962639002,0.37096661359805916,0.7853981633974483,363.1,1529.1,1528.5,2398.8,293.5,292.9 +2.528851515691053,0.37094892523219625,0.916297857297023,401.8,1556.8,1615.4,1691.7,277.4,336.2 +2.5288659891234846,0.37090445479432343,1.0471975511965976,485.7,1718.3,1845.9,792.8,290.2,417.5 +2.528895176518611,0.37085643440369975,1.1780972450961724,645.9,2089.1,2308.4,507.4,345.2,488.7 +2.5288943932295265,0.37085748633246785,1.3089969389957472,990.9,2887.1,2759.7,370.8,493.5,406.5 +2.528911273918907,0.3708498317321145,1.4398966328953218,1534.3,2546.4,2487.6,297.7,541.2,380.5 +2.5289869690887063,0.37083300542515407,1.5707963267948966,1498.8,2428.9,2428.7,263.0,393.3,393.1 +2.529030445841739,0.37083876278941186,1.7016960206944713,1576.9,1845.7,1017.0,255.3,381.3,439.6 +2.528996327930246,0.37082850189663485,1.832595714594046,1800.0,872.7,493.7,278.0,405.8,533.3 +2.5290462496960595,0.3708611555333641,1.9634954084936205,2258.5,564.3,345.2,346.7,487.7,708.7 +2.5290642191314414,0.37088264824071393,2.0943951023931953,2745.6,417.5,290.3,486.0,694.4,1074.7 +2.529056187603222,0.3708668870138059,2.2252947962927703,2467.2,336.2,277.5,401.5,1396.8,1556.9 +2.529062363882069,0.3708939796939186,2.356194490192345,2399.5,293.0,293.5,362.4,1528.5,1529.0 +2.529059215085011,0.3709285882209139,2.4870941840919194,1087.3,277.3,336.4,358.9,1557.2,1616.0 +2.5290618943110292,0.37092336163518635,2.6179938779914944,515.6,290.8,418.4,393.4,1719.5,1846.9 +2.529046988731385,0.37094287161407635,2.748893571891069,345.2,345.2,487.4,487.4,2094.5,2314.5 +2.5290535275847144,0.37093863164048124,2.8797932657906435,277.4,493.4,406.2,715.6,2886.3,2758.9 +2.5290416727427982,0.3709459759406577,3.010692959690218,255.0,536.1,380.9,1479.3,2547.0,2488.6 +2.529067352191116,0.4712252714217675,0.0,362.9,393.1,393.0,1399.0,2429.1,2428.9 +2.5290093927472923,0.47065817211938854,0.1308996938995747,402.1,381.0,440.3,1432.3,2201.2,1385.8 +2.529039527941727,0.4706680860212964,0.2617993877991494,486.1,406.0,533.6,1590.9,1073.0,693.5 +2.5290774618140244,0.47069260946083236,0.39269908169872414,486.4,488.0,708.6,1955.6,705.8,486.4 +2.5291082557636413,0.4707282490766227,0.5235987755982988,393.9,693.1,1072.0,2777.5,534.2,406.4 +2.5287894490263216,0.4710249044698722,0.6544984694978736,359.1,1394.4,1453.6,2509.6,439.9,380.9 +2.5287854643181986,0.4710103267089518,0.7853981633974483,363.2,1428.8,1428.6,2398.8,393.5,393.1 +2.5287867808330557,0.4710129027698071,0.916297857297023,402.1,1453.5,1512.4,2074.2,381.0,439.9 +2.5287978760655223,0.47098111278894916,1.0471975511965976,486.1,1603.5,1730.6,991.3,406.0,533.4 +2.5288219560985423,0.47094235109171945,1.1780972450961724,646.4,1948.8,2168.4,648.8,486.7,533.8 +2.528814674521111,0.4709496808531868,1.3089969389957472,992.3,2759.8,2759.1,486.3,534.1,406.6 +2.528824218515778,0.4709455714574511,1.4398966328953218,1430.6,2545.8,2487.2,401.1,438.8,380.6 +2.52889241475596,0.47093046334712985,1.5707963267948966,1399.0,2428.7,2428.6,363.0,393.3,393.2 +2.528881120606225,0.470930011042336,1.7016960206944713,1473.4,2230.7,1403.5,358.8,381.3,439.9 +2.5288732177388167,0.4709268425962527,1.832595714594046,1684.6,1071.3,692.3,393.8,405.9,533.7 +2.5289252290064623,0.4709600484201173,1.9634954084936205,2118.0,705.1,486.1,488.9,488.2,709.3 +2.5289400712893633,0.4709773598855602,2.0943951023931953,2744.5,532.8,405.8,485.9,695.3,1076.2 +2.528929496944192,0.4709548782942563,2.2252947962927703,2465.9,439.7,381.0,401.6,1400.6,1452.9 +2.528934835858486,0.4709746356136375,2.356194490192345,2399.5,392.9,393.7,362.6,1428.3,1428.9 +2.528932423772065,0.47100248954952106,2.4870941840919194,1469.6,380.9,440.0,359.2,1453.7,1513.3 +2.5289375825621305,0.4709912730720478,2.6179938779914944,714.1,406.7,534.5,393.6,1603.9,1731.8 +2.5289257947640347,0.47100610809344245,2.748893571891069,486.4,486.9,534.8,487.8,1954.2,2174.2 +2.5289363589578446,0.47099829926076864,2.8797932657906435,392.9,533.4,406.2,716.5,2763.5,2758.2 +2.528867866028734,0.4708367015763497,3.010692959690218,358.6,439.8,381.0,1479.0,2547.5,2488.1 +2.528944678521581,0.5711263369275912,0.0,462.9,393.1,393.1,1299.1,2428.7,2429.3 +2.528939938843884,0.5711262302874223,0.1308996938995747,505.6,381.1,440.2,1328.5,2489.6,1770.4 +2.528905984465739,0.5711162321618086,0.2617993877991494,601.6,406.1,533.5,1475.4,1228.8,892.7 +2.528869772443791,0.5710938212049215,0.39269908169872414,488.9,488.0,708.6,1814.3,847.0,627.5 +2.5288398967254584,0.5710636641447508,0.5235987755982988,393.9,692.9,1071.7,2578.2,649.8,522.0 +2.5288295926524946,0.5710412142610406,0.6544984694978736,359.0,1390.4,1350.3,2510.2,543.5,484.4 +2.528817826838647,0.5709955640629587,0.7853981633974483,363.2,1329.1,1328.4,2399.1,493.6,493.1 +2.5288193977224087,0.5709861617216843,0.916297857297023,401.9,1349.5,1408.4,2381.8,484.4,543.3 +2.5288319456630366,0.5709491450802524,1.0471975511965976,485.6,1487.3,1614.6,1148.5,521.3,648.5 +2.5288575167741136,0.570907260288416,1.1780972450961724,645.9,1806.9,2025.4,790.9,627.4,515.6 +2.5288520272349944,0.5709128672037609,1.3089969389957472,990.7,2557.6,2759.9,602.0,648.9,406.7 +2.528863515325705,0.5709081154653037,1.4398966328953218,1327.5,2546.0,2487.7,504.8,439.0,380.6 +2.5289335798081316,0.5708923958849321,1.5707963267948966,1299.2,2428.8,2428.8,463.0,393.4,393.0 +2.5289240301520435,0.5708921313922164,1.7016960206944713,1369.9,2487.3,1797.1,462.2,381.3,439.6 +2.5289174933410217,0.5708900163600454,1.832595714594046,1568.0,1271.7,892.4,509.3,405.8,533.3 +2.5289705799742364,0.5709242088975326,1.9634954084936205,1975.1,846.7,627.6,630.0,487.7,708.5 +2.5289861804032623,0.5709424780419219,2.0943951023931953,2746.0,648.7,521.4,486.1,694.5,1074.4 +2.528975749906327,0.570921313946253,2.2252947962927703,2466.6,543.3,484.5,401.6,1396.4,1349.7 +2.528980926913807,0.5709422446996266,2.356194490192345,2399.7,493.0,493.6,362.5,1328.6,1328.9 +2.528978390652051,0.5709708636150732,2.4870941840919194,1859.1,484.3,543.5,359.0,1350.4,1409.2 +2.5289829450763297,0.5709604505468331,2.6179938779914944,914.3,522.1,649.8,393.4,1488.2,1615.6 +2.5289709677424006,0.5709756970875437,2.748893571891069,628.1,628.0,516.3,487.5,1811.1,2031.3 +2.5289809858228427,0.5709683166662394,2.8797932657906435,508.7,649.0,406.3,715.5,2560.7,2758.9 +2.5289729341930416,0.5709735927951463,3.010692959690218,462.0,439.8,381.0,1371.2,2547.3,2488.6 +2.5290031388533074,0.6712562444464387,0.0,562.9,393.1,393.1,1199.0,2428.6,2428.9 +2.5289665830056465,0.6706719866705599,0.1308996938995747,609.2,381.0,440.2,1224.8,2489.5,2156.0 +2.528999661214804,0.6706827132800453,0.2617993877991494,715.7,406.1,533.5,1359.7,1472.4,1092.7 +2.529036996943085,0.6707066805400381,0.39269908169872414,486.6,488.0,708.7,1671.5,988.5,768.7 +2.5290665761047633,0.6707407514488222,0.5235987755982988,393.9,692.8,1071.6,2378.3,765.6,637.7 +2.52909504348399,0.6707911553342816,0.6544984694978736,359.1,1305.7,1246.9,2511.1,647.1,587.9 +2.529100763783085,0.6708214952408356,0.7853981633974483,363.3,1229.1,1228.3,2398.5,593.6,592.9 +2.5291000287430596,0.670884098644821,0.916297857297023,402.0,1246.4,1305.1,2465.8,587.8,646.6 +2.5290930604693824,0.670911519151993,1.0471975511965976,485.8,1371.8,1498.9,1392.4,636.7,694.7 +2.529085686673618,0.6708917850900527,1.1780972450961724,645.7,1665.8,1884.5,932.8,709.9,488.9 +2.528835573623219,0.6708644430226722,1.3089969389957472,991.6,2359.8,2739.8,717.5,534.1,406.5 +2.528850201310648,0.6708576019277468,1.4398966328953218,1223.7,2545.5,2487.7,608.2,438.9,380.5 +2.52892965939211,0.6708399660863453,1.5707963267948966,1199.0,2429.0,2428.4,563.0,393.3,393.0 +2.5289305157275783,0.6708401535507291,1.7016960206944713,1266.7,2532.8,2183.6,565.6,381.3,439.8 +2.5289337954579034,0.6708408654003777,1.832595714594046,1453.4,1469.7,1047.0,625.0,405.9,533.6 +2.528995131936214,0.6708803727120991,1.9634954084936205,1834.4,987.2,768.5,644.8,487.9,709.0 +2.5290167570874873,0.6709054785663053,2.0943951023931953,2663.6,764.0,636.8,485.9,694.8,1075.5 +2.529010224008695,0.6708915959968134,2.2252947962927703,2466.1,646.7,588.1,401.5,1313.8,1245.9 +2.529017124873491,0.6709200461538529,2.356194490192345,2399.6,593.1,593.7,362.5,1228.4,1229.2 +2.529014148199865,0.6709559527826265,2.4870941840919194,2240.9,588.0,647.1,359.1,1246.8,1305.8 +2.52901684152053,0.6709517797537243,2.6179938779914944,1112.6,637.8,692.1,368.1,1372.6,1500.4 +2.529001391140148,0.6709723078050671,2.748893571891069,769.2,707.3,487.4,487.7,1670.5,1890.2 +2.529007323141665,0.6709687677479332,2.8797932657906435,624.0,533.5,406.1,716.2,2363.7,2744.0 +2.528994669065424,0.6709765188214738,3.010692959690218,565.6,439.7,381.0,1267.3,2547.0,2488.2 +2.529019332104719,0.7712549924929568,0.0,662.8,393.0,393.1,1099.2,2428.8,2429.3 +2.5289858778261505,0.7706647081713043,0.1308996938995747,712.8,381.0,440.3,1121.4,2489.2,2538.9 +2.529020193910363,0.7706758703206087,0.2617993877991494,715.4,406.1,533.5,1244.0,1671.8,1292.0 +2.529058370573999,0.7707004690158865,0.39269908169872414,486.5,487.9,708.6,1530.6,1129.3,910.0 +2.529088530109525,0.7707353098834766,0.5235987755982988,394.0,693.1,1071.7,2179.6,881.1,753.4 +2.528853949824131,0.7709839182206193,0.6544984694978736,359.1,1201.9,1142.9,2509.7,750.5,691.3 +2.528851910216341,0.7709785616647897,0.7853981633974483,363.3,1129.0,1128.6,2398.6,693.4,693.0 +2.5288527454175287,0.770991637082328,0.916297857297023,401.9,1142.8,1201.7,2466.6,691.6,750.5 +2.5288606885417653,0.7709697853229063,1.0471975511965976,486.1,1256.8,1383.9,1590.0,752.7,739.2 +2.528879480647474,0.7709393343625768,1.1780972450961724,646.5,1525.9,1744.9,1073.5,709.3,488.6 +2.5288655649914737,0.7709528398774621,1.3089969389957472,992.3,2161.5,2540.8,833.0,534.1,406.7 +2.528867672037911,0.7709527269291565,1.4398966328953218,1120.4,2545.8,2487.4,711.5,438.8,380.6 +2.5289281638369694,0.7709394555182132,1.5707963267948966,1099.0,2428.5,2428.6,663.1,393.3,393.2 +2.5289096529992188,0.7709388764914202,1.7016960206944713,1163.0,2487.5,2484.5,669.2,381.2,439.9 +2.528895296485891,0.7709339087206741,1.832595714594046,1337.7,1668.0,1290.0,740.6,405.8,533.7 +2.5289418699217077,0.7709639140590352,1.9634954084936205,1692.9,1128.1,909.5,741.2,488.0,709.1 +2.528952611245046,0.7709771002519552,2.0943951023931953,2464.9,879.4,752.3,485.8,695.3,1075.9 +2.5289393466698695,0.7709499927299515,2.2252947962927703,2466.2,750.1,691.5,401.6,1201.2,1142.3 +2.528943376577776,0.7709649001132328,2.356194490192345,2399.8,692.9,693.8,362.5,1128.5,1128.9 +2.528940973693554,0.7709880649670524,2.4870941840919194,2510.7,691.7,750.7,359.1,1143.3,1202.4 +2.528947271138448,0.7709726813396018,2.6179938779914944,1311.4,753.6,740.2,393.5,1257.1,1385.0 +2.5289357781727304,0.7709879920867686,2.748893571891069,910.6,738.9,487.2,487.8,1529.5,1749.6 +2.5289511126387003,0.7709756231334068,2.8797932657906435,739.5,533.2,406.1,716.6,2164.6,2544.9 +2.5289470854895146,0.7709786771705711,3.010692959690218,668.9,439.8,381.1,1163.6,2547.1,2488.5 +2.5289813271060906,0.8712638630828755,0.0,762.9,393.1,393.1,999.0,2428.6,2429.1 +2.528967366318295,0.8706744258273749,0.1308996938995747,816.3,381.0,440.2,1017.9,2489.4,2548.8 +2.5290046698474336,0.8706864711804512,0.2617993877991494,807.2,406.0,533.5,1128.4,1871.6,1491.6 +2.529042556775397,0.8707108190803319,0.39269908169872414,486.5,487.9,708.6,1388.7,1270.8,1051.3 +2.5290718008889566,0.8707445761736123,0.5235987755982988,394.0,693.0,1071.9,1980.1,996.5,869.0 +2.529099825994564,0.8707942875067811,0.6544984694978736,359.1,1098.7,1039.5,2510.3,854.1,795.1 +2.529105323973643,0.8708238176285872,0.7853981633974483,363.2,1029.0,1028.4,2399.4,793.4,793.0 +2.529104540846339,0.8708855658685737,0.916297857297023,402.0,1039.2,1098.1,2465.9,794.9,853.7 +2.52909774271614,0.8709121849508603,1.0471975511965976,485.8,1140.9,1268.4,1791.4,867.8,724.1 +2.529090742505056,0.8709226649253421,1.1780972450961724,645.9,1383.4,1602.5,1216.3,719.7,489.0 +2.529044262412173,0.870967068343772,1.3089969389957472,990.7,1959.8,2338.6,949.0,534.3,406.7 +2.5290096208383805,0.870987423105978,1.4398966328953218,1017.1,2546.5,2487.4,815.1,439.1,380.6 +2.5290317643736717,0.8709831517021185,1.5707963267948966,999.0,2428.7,2428.7,762.9,393.3,393.0 +2.5289773268589344,0.870981921482066,1.7016960206944713,1059.4,2487.0,2545.7,772.4,381.2,439.6 +2.528930754412837,0.8709682791140669,1.832595714594046,1221.8,1869.2,1490.3,855.9,405.6,533.3 +2.5289503325606946,0.8709821158024567,1.9634954084936205,1550.1,1270.0,1050.8,645.0,487.6,708.5 +2.5289409802471514,0.870974311615478,2.0943951023931953,2261.9,995.4,867.9,486.0,694.2,1074.2 +2.528914543056742,0.8709241539528878,2.2252947962927703,2466.2,853.8,794.9,401.5,1098.3,1039.1 +2.5289123820649184,0.8709149595263086,2.356194490192345,2399.6,793.1,793.4,362.4,1028.5,1029.2 +2.5289106532760637,0.8709147231756391,2.4870941840919194,2510.2,795.0,854.1,359.0,1039.6,1098.8 +2.5289228146285474,0.870878933765858,2.6179938779914944,1512.0,868.8,725.3,393.3,1141.3,1268.9 +2.5289239863844655,0.8708732139435125,2.748893571891069,1021.1,720.7,487.5,487.4,1387.0,1606.9 +2.5289506834943953,0.8708504147018659,2.8797932657906435,855.1,533.7,406.2,715.4,1963.1,2342.3 +2.5289612909357295,0.8708459902582317,3.010692959690218,772.4,439.9,381.0,1060.5,2547.0,2488.2 +2.4289476199999,0.17075563973970453,0.0,63.0,493.0,493.0,1699.2,2329.3,2328.8 +2.4289880199850327,0.17146005195513103,0.1308996938995747,91.5,484.6,543.8,1742.7,964.8,233.6 +2.4289421761022663,0.1714450538503527,0.2617993877991494,139.6,521.6,649.2,1937.3,474.9,95.3 +2.4288899749235924,0.17141129436790936,0.39269908169872414,223.8,629.6,850.3,2380.5,282.3,63.0 +2.42884676143984,0.17136558840841776,0.5235987755982988,393.3,892.2,1271.4,2724.8,187.5,59.8 +2.4288276126957267,0.1713257096356906,0.6544984694978736,462.5,1776.8,1764.1,2406.5,129.5,70.5 +2.428811761846981,0.1712621185641754,0.7853981633974483,463.2,1728.9,1728.3,2298.8,93.8,93.2 +2.4288134823384024,0.171418788593114,0.916297857297023,505.3,1763.5,1822.7,917.7,70.7,129.5 +2.4288358992050463,0.17115564420555596,1.0471975511965976,601.4,1949.5,2077.0,393.9,59.5,186.8 +2.428858607515287,0.17111643661006704,1.1780972450961724,756.1,2371.4,2590.1,224.3,63.4,282.4 +2.428859419426704,0.1711142605248841,1.3089969389957472,1190.2,2772.0,2644.0,139.9,95.6,474.9 +2.4288823096568968,0.17110159387913693,1.4398966328953218,1741.2,2442.2,2384.7,91.1,238.5,591.8 +2.428966165298406,0.17108116322125677,1.5707963267948966,1699.0,2328.6,2328.7,63.3,493.3,493.1 +2.4289704725396564,0.17107983081911393,1.7016960206944713,1783.4,1066.9,238.5,48.6,484.7,543.1 +2.428976929695947,0.17108009846542305,1.832595714594046,2030.8,474.8,95.6,47.1,521.3,648.9 +2.42904128017064,0.17112000100317748,1.9634954084936205,2541.9,282.4,63.3,63.7,629.4,850.3 +2.4290654490453214,0.17114633184786232,2.0943951023931953,2630.0,186.8,59.5,117.4,894.2,1274.4 +2.4290605780129515,0.17113449004822323,2.2252947962927703,2363.0,129.5,70.7,319.5,1784.7,1763.3 +2.4290681521044597,0.17116536117108194,2.356194490192345,2299.3,93.2,93.8,462.5,1728.3,1729.0 +2.4290648895415883,0.17120355872107607,2.4870941840919194,316.9,70.5,129.6,462.6,1764.0,1822.8 +2.4290662494508055,0.17120129503284098,2.6179938779914944,117.7,59.9,187.6,509.0,1950.3,2078.3 +2.4290490050601754,0.17122290372965954,2.748893571891069,62.7,62.7,282.8,628.9,2376.2,2596.7 +2.4290527753989384,0.17121960146503246,2.8797932657906435,46.6,95.0,474.8,915.3,2770.7,2643.1 +2.4290381330016033,0.17122674045262132,3.010692959690218,48.2,235.3,585.9,1781.9,2443.8,2384.7 +2.4290612788349666,0.2715039123522436,0.0,163.2,493.0,493.1,1598.9,2328.6,2328.6 +2.4290077961190466,0.2707308878249348,0.1308996938995747,195.0,484.5,543.8,1639.4,1433.3,617.4 +2.42903079307162,0.27073842590059427,0.2617993877991494,255.0,521.6,649.1,1822.1,674.3,294.5 +2.4290608068664663,0.270757807605259,0.39269908169872414,365.2,629.6,850.4,2238.5,423.3,204.0 +2.4290851981473622,0.27078638551254985,0.5235987755982988,509.6,892.3,1271.1,2724.8,302.9,175.2 +2.429110248993069,0.2708307753120609,0.6544984694978736,462.6,1742.7,1660.7,2406.5,232.8,173.8 +2.4291143894283,0.27085497996739094,0.7853981633974483,463.2,1629.0,1628.5,2298.8,193.5,193.0 +2.4291135556946792,0.27091165269608686,0.916297857297023,505.3,1660.1,1719.0,1304.6,173.9,232.7 +2.4291079089114485,0.2709336692274824,1.0471975511965976,601.4,1833.9,1961.4,592.9,174.7,301.9 +2.429103059606093,0.2709403430687525,1.1780972450961724,787.0,2230.4,2449.2,365.7,204.0,423.0 +2.429059355699251,0.2709818025374211,1.3089969389957472,1190.3,2771.9,2643.9,255.1,294.2,522.2 +2.4290279323137436,0.27100010469708513,1.4398966328953218,1637.7,2521.9,2384.5,194.2,542.4,484.1 +2.4290535255932526,0.27099489338020044,1.5707963267948966,1599.1,2328.8,2328.7,163.0,493.3,493.0 +2.4290023683150417,0.2709936218698221,1.7016960206944713,1680.3,1455.6,626.9,151.7,484.7,543.1 +2.4289587729642146,0.2709806922519038,1.832595714594046,1915.0,673.5,294.3,162.3,521.3,648.9 +2.4289808327063453,0.2709960296041136,1.9634954084936205,2400.5,423.2,204.0,204.9,629.2,850.2 +2.428973274417749,0.2709902273266782,2.0943951023931953,2630.0,301.9,174.6,316.4,894.1,1274.1 +2.428947957137648,0.27094223388067884,2.2252947962927703,2363.2,232.7,173.9,505.1,1741.9,1660.4 +2.4289462160079904,0.2709352777724361,2.356194490192345,2299.7,193.0,193.5,462.4,1628.6,1628.9 +2.428944215151223,0.27093718056384164,2.4870941840919194,616.8,173.7,232.8,462.4,1660.7,1719.8 +2.4289556617565626,0.2709031604303116,2.6179938779914944,316.4,175.2,302.8,508.9,1834.7,1962.2 +2.428955650849312,0.27089885959394366,2.748893571891069,203.8,203.8,423.7,628.8,2235.4,2455.9 +2.428981033857288,0.27087699615409355,2.8797932657906435,161.9,293.9,521.6,914.9,2770.8,2643.4 +2.428990248426792,0.27087307665055094,3.010692959690218,151.5,543.3,484.4,1681.7,2443.6,2384.8 +2.4290414149082027,0.3711716782092138,0.0,262.9,493.0,493.0,1498.8,2329.2,2329.1 +2.429012138734819,0.37117115419164026,0.1308996938995747,298.4,484.6,543.9,1536.0,1816.7,1000.9 +2.4289561109611184,0.37115482054576,0.2617993877991494,370.4,521.6,649.1,1706.6,873.2,493.6 +2.4289016155580043,0.3711215027111181,0.39269908169872414,506.7,629.4,818.9,2097.4,564.2,345.0 +2.4288579376656525,0.3710772398569788,0.5235987755982988,548.0,848.3,1271.2,2724.9,418.5,290.8 +2.428838607739902,0.3710390028874664,0.6544984694978736,462.5,1616.5,1557.4,2406.6,336.4,277.2 +2.4288225448757945,0.3709768459101359,0.7853981633974483,463.1,1529.1,1528.6,2298.8,293.5,293.0 +2.42882419377175,0.3709516555744732,0.916297857297023,505.3,1556.6,1615.4,1691.8,277.4,336.2 +2.4288407273601003,0.37090039158794985,1.0471975511965976,601.3,1718.4,1845.8,792.8,290.2,417.5 +2.4288734124713147,0.3708467587616413,1.1780972450961724,787.0,2089.2,2308.6,507.5,345.1,564.2 +2.4288770458936177,0.37084366133964064,1.3089969389957472,1190.1,2771.6,2643.6,370.8,493.5,629.6 +2.428863006911695,0.3708485924272724,1.4398966328953218,1534.3,2442.5,2384.6,297.8,542.4,483.9 +2.42914373735412,0.37078646256276016,1.5707963267948966,1499.0,2329.5,2328.7,263.0,493.3,493.0 +2.4290291299890296,0.3707827205567502,1.7016960206944713,1576.8,1845.6,1016.8,255.2,484.6,543.1 +2.42900537376073,0.370775579952517,1.832595714594046,1799.6,873.0,493.7,278.0,521.3,649.0 +2.429066056614159,0.37081496387002333,1.9634954084936205,2258.4,564.4,345.3,346.7,629.5,850.2 +2.4290926541402627,0.3708457014194484,2.0943951023931953,2629.5,417.5,290.3,516.0,894.1,1274.2 +2.4290902442577447,0.3708404360351836,2.2252947962927703,2363.5,336.3,277.5,620.3,1615.5,1556.8 +2.429098962496943,0.37087846728319507,2.356194490192345,2299.5,293.0,293.5,462.5,1528.8,1529.0 +2.429095450415531,0.3709235348484463,2.4870941840919194,1002.4,277.3,336.4,462.5,1557.1,1616.4 +2.4290953354206093,0.37092750547098885,2.6179938779914944,515.6,290.8,418.4,509.0,1719.4,1847.0 +2.4290756857683524,0.37095461985420175,2.748893571891069,345.2,345.2,565.2,628.7,2094.5,2314.3 +2.429076218632901,0.37095601364546527,2.8797932657906435,277.4,493.3,629.7,915.1,2771.2,2643.6 +2.429057645629426,0.37096696570430066,3.010692959690218,255.0,543.4,484.6,1578.1,2443.5,2385.0 +2.4290751878769545,0.47124009862912675,0.0,362.9,493.1,493.0,1399.1,2328.8,2329.1 +2.429011562281265,0.47065205072153593,0.1308996938995747,402.1,484.5,543.9,1432.2,2201.5,1385.6 +2.429041128923331,0.47066179756145776,0.2617993877991494,486.1,521.7,649.2,1591.1,1073.2,693.4 +2.4291187660184015,0.47071376629674044,0.39269908169872414,627.6,629.7,850.3,1955.8,705.7,486.4 +2.4291277911068674,0.4707258218176156,0.5235987755982988,509.4,892.2,1271.3,2724.6,534.1,406.4 +2.4287985663544758,0.47102600311000287,0.6544984694978736,462.6,1512.2,1453.5,2406.2,439.8,380.9 +2.428803513880607,0.4710804013840941,0.7853981633974483,463.2,1428.9,1428.3,2299.0,393.5,393.1 +2.4288065345653265,0.4710099189960779,0.916297857297023,505.6,1453.5,1512.4,2074.7,381.0,439.9 +2.428815844685281,0.47098377726744123,1.0471975511965976,601.7,1603.7,1731.0,991.3,406.0,533.4 +2.428837733778534,0.47094845691433496,1.1780972450961724,787.7,1949.4,2168.5,648.8,486.6,630.2 +2.4288280238810236,0.47095802705929657,1.3089969389957472,1191.6,2759.6,2643.3,486.2,649.7,522.1 +2.4288349784926235,0.47095528513586205,1.4398966328953218,1430.6,2442.3,2383.8,401.2,542.5,484.0 +2.428900545083456,0.4709407569522084,1.5707963267948966,1398.7,2329.1,2328.4,363.0,493.3,493.2 +2.428886817646915,0.47094021394281427,1.7016960206944713,1473.5,2230.9,1403.5,358.9,484.9,543.4 +2.4288767594743708,0.47093639998582226,1.832595714594046,1684.6,1071.2,692.4,393.8,521.6,649.4 +2.428966093167312,0.47099577775566437,1.9634954084936205,2118.2,705.1,486.1,488.7,629.8,851.1 +2.4289832929489,0.4710151583822899,2.0943951023931953,2628.7,533.0,405.7,601.4,895.2,1275.6 +2.4289560204886285,0.4709612821402982,2.2252947962927703,2362.3,439.7,381.0,505.0,1511.6,1453.2 +2.428971380341999,0.471027568804522,2.356194490192345,2299.0,392.9,393.6,462.5,1428.3,1429.1 +2.428970479555756,0.471019576396857,2.4870941840919194,1469.8,380.9,440.1,462.6,1454.0,1513.1 +2.4289769158294687,0.47100419783458713,2.6179938779914944,714.2,406.6,534.5,509.4,1604.1,1732.0 +2.428962252110502,0.4710236171777029,2.748893571891069,486.5,487.0,628.7,629.4,1953.5,2173.9 +2.428966984501005,0.47102123236474625,2.8797932657906435,392.9,648.9,521.7,916.2,2763.7,2642.0 +2.428952035444629,0.4710300942766972,3.010692959690218,358.6,543.3,484.7,1474.3,2443.1,2384.7 +2.428973521799986,0.5713059369030244,0.0,463.0,493.1,493.1,1298.7,2329.2,2329.3 +2.4289601108152317,0.5706741425252084,0.1308996938995747,505.6,484.6,543.9,1328.3,2385.6,1771.0 +2.428997386457567,0.5706861586159448,0.2617993877991494,601.6,521.7,649.1,1475.0,1273.1,849.4 +2.4290353311602515,0.5707105103447185,0.39269908169872414,627.8,629.6,850.2,1813.3,847.2,627.8 +2.429064638419041,0.5707442872919211,0.5235987755982988,509.6,892.0,1270.8,2577.3,649.9,522.1 +2.4290927535032187,0.57079405321019,0.6544984694978736,462.7,1409.1,1350.3,2406.7,543.6,484.4 +2.42909830169915,0.5708236356856404,0.7853981633974483,463.3,1329.0,1328.5,2298.6,493.6,493.0 +2.429097577327247,0.5708854720247847,0.916297857297023,505.4,1349.9,1408.3,2362.6,484.4,543.1 +2.429090808510509,0.5709121912334569,1.0471975511965976,601.3,1487.1,1614.6,1148.5,521.3,648.4 +2.429083792639349,0.5709227408594328,1.1780972450961724,786.9,1806.5,2026.0,790.8,627.2,674.0 +2.429037284667467,0.5709672249316908,1.3089969389957472,1190.0,2556.7,2644.5,602.0,650.1,522.4 +2.4290025940509197,0.5709876684903572,1.4398966328953218,1327.4,2442.4,2384.1,504.6,542.6,484.0 +2.4290246640938995,0.5709834036384474,1.5707963267948966,1298.9,2329.2,2328.3,463.0,493.4,493.1 +2.4289701574192484,0.570982169037993,1.7016960206944713,1369.5,2383.1,1797.2,462.1,484.8,543.2 +2.4289235171057437,0.570968529189029,1.832595714594046,1568.2,1271.8,892.5,509.1,521.4,648.9 +2.4289430526670173,0.570982311368263,1.9634954084936205,1974.9,846.5,627.3,629.9,629.3,850.2 +2.4289336932185766,0.5709744262786876,2.0943951023931953,2630.4,648.7,521.2,671.6,893.7,1273.8 +2.4289072561195675,0.5709242200623168,2.2252947962927703,2363.3,543.3,484.4,505.1,1408.6,1349.9 +2.4289051181143075,0.5709149829044842,2.356194490192345,2299.7,493.0,493.5,462.4,1328.6,1328.8 +2.4291805067821857,0.5709392464885776,2.4870941840919194,1863.3,484.3,543.3,462.4,1350.0,1408.8 +2.4291791883853273,0.5709448531884287,2.6179938779914944,915.3,521.9,649.3,508.7,1487.4,1614.9 +2.4291580873894465,0.5709739524358628,2.748893571891069,628.6,627.7,674.9,628.3,1810.2,2030.0 +2.4291563093260096,0.5709769811074097,2.8797932657906435,508.8,649.5,521.8,914.0,2558.6,2644.3 +2.429135331720357,0.5709889291368526,3.010692959690218,462.1,543.5,484.4,1371.5,2444.5,2385.6 +2.4291501459258873,0.6712600167916116,0.0,562.9,493.1,492.9,1198.9,2329.3,2328.9 +2.429042450226129,0.6706545302688529,0.1308996938995747,609.2,484.5,543.9,1225.0,2431.7,2153.5 +2.4290629285708434,0.6706614870287968,0.2617993877991494,717.2,521.6,649.1,1359.9,1471.9,1092.4 +2.429099359012064,0.6706851335897315,0.39269908169872414,630.7,629.6,850.4,1672.4,988.0,768.7 +2.429130678823108,0.6707214533093186,0.5235987755982988,509.4,892.3,1271.5,2379.6,765.3,637.8 +2.428796355544884,0.6710266547045487,0.6544984694978736,462.6,1305.5,1246.5,2406.1,646.9,587.9 +2.4287924575661144,0.6710125426843374,0.7853981633974483,463.2,1229.1,1228.6,2299.1,593.7,593.1 +2.4287937312363526,0.6710157674312611,0.916297857297023,505.6,1246.3,1305.3,2362.9,588.1,647.0 +2.4288046053984096,0.6709846089884453,1.0471975511965976,601.7,1372.2,1499.5,1390.7,637.1,764.5 +2.42882831475013,0.67094635452534,1.1780972450961724,787.8,1666.6,1886.2,931.9,768.9,657.3 +2.428820587432199,0.6709540586017315,1.3089969389957472,1191.7,2360.6,2643.2,717.3,649.7,522.2 +2.4288296440854173,0.6709501926988843,1.4398966328953218,1223.7,2442.3,2384.0,608.1,542.3,484.1 +2.428897342598569,0.6709351573374385,1.5707963267948966,1199.0,2329.1,2329.3,563.0,493.4,493.2 +2.428885595773818,0.6709346673463941,1.7016960206944713,1266.6,2448.4,2181.9,565.7,484.8,543.3 +2.428877292232571,0.6709313831204295,1.832595714594046,1453.3,1469.3,1090.7,625.1,521.7,649.3 +2.4289289739126847,0.6709643761588777,1.9634954084936205,1834.6,956.0,768.2,772.3,629.9,850.9 +2.428943573358429,0.6709814180812748,2.0943951023931953,2629.0,764.0,636.8,601.4,895.1,1276.2 +2.4289328268486505,0.670958660009088,2.2252947962927703,2362.6,646.5,588.0,505.1,1304.7,1246.3 +2.4289380713198585,0.670978126412435,2.356194490192345,2299.3,593.0,593.7,462.5,1228.4,1229.1 +2.4289356513090836,0.6710056841534211,2.4870941840919194,2239.8,588.1,647.2,462.7,1246.8,1306.1 +2.4289408500686256,0.6709942075571644,2.6179938779914944,1068.5,638.0,765.6,509.2,1372.7,1500.5 +2.428929183255063,0.6710088047769529,2.748893571891069,769.1,770.0,658.4,629.3,1670.8,1891.2 +2.428939894955828,0.6710008125877824,2.8797932657906435,624.0,648.9,521.7,916.4,2364.0,2642.6 +2.4289324968562447,0.6710056255311216,3.010692959690218,565.6,543.3,484.4,1267.3,2443.2,2384.7 +2.428963514938267,0.7712888469134989,0.0,663.0,493.1,493.2,1098.8,2329.0,2329.1 +2.4289522928731517,0.7706770778316008,0.1308996938995747,712.8,484.5,543.8,1121.5,2386.3,2445.0 +2.428989842481874,0.7706891626847154,0.2617993877991494,832.8,521.7,649.1,1244.0,1672.3,1292.2 +2.429027589411185,0.7707133550659861,0.39269908169872414,627.8,629.5,850.3,1530.2,1129.5,910.2 +2.4290566424060382,0.7707468079955511,0.5235987755982988,509.6,892.1,1270.9,2179.0,881.3,753.4 +2.4290846109617874,0.7706204039826252,0.6544984694978736,462.6,1202.3,1143.4,2406.3,750.6,691.3 +2.4288004147489093,0.7709732337750173,0.7853981633974483,463.2,1129.0,1128.5,2299.0,693.4,693.1 +2.4287917814763342,0.7711965452720684,0.916297857297023,505.5,1142.9,1201.7,2363.2,691.5,750.3 +2.4288446517018243,0.7710301387115153,1.0471975511965976,601.7,1256.7,1384.1,1589.7,752.6,880.0 +2.428885582820742,0.7709646130633165,1.1780972450961724,787.6,1525.5,1744.8,1073.6,850.8,630.2 +2.4288766681045253,0.7709736060952606,1.3089969389957472,1191.7,2161.1,2541.0,833.0,649.8,522.2 +2.428875221607239,0.7709755107935796,1.4398966328953218,1120.3,2442.1,2383.8,711.4,542.3,484.1 +2.4289286994271464,0.7709638881035759,1.5707963267948966,1099.2,2328.7,2328.7,663.0,493.3,493.2 +2.428902581645665,0.770963091210642,1.7016960206944713,1163.0,2383.9,2442.3,669.2,484.8,543.4 +2.428881128892242,0.7709560155620729,1.832595714594046,1337.8,1668.4,1289.8,740.5,521.6,649.3 +2.4289217097262537,0.7709822582061097,1.9634954084936205,1693.1,1128.3,909.3,785.7,629.9,851.0 +2.4289280205832378,0.7709906300939109,2.0943951023931953,2464.2,879.4,752.3,601.2,895.1,1275.6 +2.4289119571858215,0.770958220058791,2.2252947962927703,2362.6,750.0,691.6,505.0,1201.4,1142.6 +2.428914770629024,0.7709676568767871,2.356194490192345,2299.1,693.0,693.7,462.4,1128.4,1129.2 +2.4289126309636773,0.7709856114557787,2.4870941840919194,2407.0,691.6,750.8,462.7,1143.2,1202.4 +2.428920376083121,0.7709656920689392,2.6179938779914944,1311.7,753.5,881.5,509.2,1257.1,1384.9 +2.428913096293129,0.7709733205648175,2.748893571891069,879.4,848.5,628.5,629.2,1529.3,1749.5 +2.4289293691060743,0.7709602090253429,2.8797932657906435,739.6,648.9,521.7,916.1,2164.7,2544.5 +2.4289281860396383,0.7709618086008911,3.010692959690218,669.0,543.3,484.6,1163.8,2443.6,2384.8 +2.4289666834517116,0.87125072222463,0.0,762.9,493.1,493.2,999.1,2328.7,2329.0 +2.4289286409517636,0.8712494810805549,0.1308996938995747,816.6,484.6,544.1,1017.9,2386.3,2445.6 +2.428866215309367,0.8712306280741506,0.2617993877991494,914.1,521.8,649.5,1129.0,1869.2,1489.6 +2.428807110038511,0.8711936848931343,0.39269908169872414,627.2,630.0,850.8,1389.8,1269.6,1050.5 +2.4287605220637825,0.8711452393954191,0.5235987755982988,509.4,893.0,1140.8,1983.0,996.2,868.4 +2.4287394919539387,0.8711025348070638,0.6544984694978736,462.5,1098.3,1039.5,2406.0,853.9,794.9 +2.4287232406376065,0.8710362180547886,0.7853981633974483,463.3,1029.1,1028.6,2299.2,793.5,793.2 +2.4287254949457933,0.8710071546619715,0.916297857297023,505.5,1039.1,1098.2,2363.1,795.0,854.1 +2.4287434407191033,0.8709525932275017,1.0471975511965976,601.6,1141.0,1268.8,1789.3,868.1,893.0 +2.428778177623812,0.8708966149920121,1.1780972450961724,787.7,1384.2,1603.4,1215.4,850.9,630.2 +2.428783977472707,0.8708916668503892,1.3089969389957472,1147.4,1962.1,2341.1,948.6,649.6,522.2 +2.4288080927821527,0.8708798489209115,1.4398966328953218,1016.9,2442.4,2384.3,815.1,542.4,484.0 +2.4288913168167388,0.8708613309779256,1.5707963267948966,999.1,2328.9,2329.0,763.1,493.3,493.1 +2.428894015270207,0.8708614429243045,1.7016960206944713,1059.5,2383.4,2442.2,772.6,484.9,543.3 +2.428898466299941,0.8708622076690975,1.832595714594046,1221.9,1868.0,1488.8,856.5,521.6,649.3 +2.428960697995726,0.8709019977130987,1.9634954084936205,1551.0,1269.4,1050.4,882.8,629.8,851.0 +2.428983035368457,0.8709275573021402,2.0943951023931953,2264.7,995.0,867.7,601.4,895.1,1140.5 +2.428977114733905,0.8709141680021617,2.2252947962927703,2362.6,853.5,794.9,505.1,1097.7,1039.0 +2.428984446992583,0.8709432393389158,2.356194490192345,2300.0,793.0,793.7,462.6,1028.3,1029.1 +2.4289816244480833,0.8709798857147395,2.4870941840919194,2455.7,795.2,854.3,462.6,1039.6,1098.8 +2.4289843284321955,0.8709763808155826,2.6179938779914944,1510.9,869.1,891.1,509.2,1141.6,1269.3 +2.428968558436162,0.8709975485993784,2.748893571891069,1052.0,880.1,628.7,629.3,1387.8,1607.8 +2.4289740849880403,0.8709944547002613,2.8797932657906435,855.1,649.1,521.6,916.2,1964.7,2344.5 +2.4289609043217193,0.8710024515183408,3.010692959690218,772.5,543.3,484.6,1060.3,2443.1,2384.8 +2.328908432703637,0.17083548370433976,0.0,63.1,593.0,593.1,1698.6,2229.0,2228.6 +2.328938868317846,0.17147137779687727,0.1308996938995747,91.6,588.2,647.7,1742.8,1047.4,233.1 +2.328889013882835,0.17145498093782896,0.2617993877991494,139.7,637.3,765.1,1937.6,474.4,95.2 +2.3288352494294053,0.17141995702221058,0.39269908169872414,224.0,771.7,992.5,2381.4,282.1,63.0 +2.328791535660341,0.171373212690213,0.5235987755982988,393.7,1048.6,1472.3,2608.2,187.4,59.8 +2.3287721642694605,0.1713323275862344,0.6544984694978736,566.0,1822.8,1763.9,2302.9,129.4,70.5 +2.328756620353242,0.1712680351230107,0.7853981633974483,563.2,1728.9,1728.2,2198.9,93.7,93.3 +2.328758645622291,0.1712409033896416,0.916297857297023,609.0,1763.6,1822.8,831.0,70.7,129.6 +2.3287755403097004,0.1711879090303905,1.0471975511965976,717.0,1949.9,2077.0,393.4,59.5,186.9 +2.328808659846091,0.17113285681269952,1.1780972450961724,928.7,2372.1,2591.5,224.2,63.4,282.7 +2.3288126252901296,0.17112802923196346,1.3089969389957472,1390.9,2654.7,2527.6,139.8,95.8,475.4 +2.3288350274594336,0.1711155669570541,1.4398966328953218,1740.7,2338.7,2280.6,91.0,239.0,587.5 +2.328916958388566,0.171095846034925,1.5707963267948966,1698.6,2229.3,2228.5,63.3,593.3,593.3 +2.32891896175546,0.17109446020427188,1.7016960206944713,1783.9,979.3,237.9,48.6,588.3,646.7 +2.3289233189311185,0.1710937414768341,1.832595714594046,2031.5,474.3,95.5,47.1,637.2,764.9 +2.3289859175227736,0.17113236055025194,1.9634954084936205,2543.1,282.2,63.3,63.7,771.5,992.6 +2.3290088313299777,0.17115720263418743,2.0943951023931953,2513.6,186.7,59.5,117.5,1094.7,1475.5 +2.3290034345261725,0.17114353175299146,2.2252947962927703,2259.0,129.4,70.7,320.2,1821.9,1763.5 +2.329011004026087,0.17117265082293853,2.356194490192345,2199.4,93.2,93.9,562.5,1728.1,1728.9 +2.329008000591845,0.17120944865106225,2.4870941840919194,316.3,70.5,129.7,566.2,1764.3,1823.4 +2.3290101507298737,0.1712059276099327,2.6179938779914944,117.5,59.9,187.7,624.9,1950.9,2078.5 +2.328993571694969,0.17122672898689917,2.748893571891069,62.7,62.8,282.9,770.7,2377.6,2598.5 +2.328998298324213,0.171222817153297,2.8797932657906435,46.6,95.1,475.2,1115.7,2654.1,2526.5 +2.328984559789334,0.17122959325642229,3.010692959690218,48.3,235.7,588.0,1784.3,2339.9,2281.1 +2.3290086776708896,0.27150746144929894,0.0,163.2,593.0,593.1,1598.6,2229.0,2229.1 +2.3289841298691827,0.2707326860227828,0.1308996938995747,195.0,588.0,647.4,1639.2,1433.7,532.9 +2.3290127308625115,0.27074192847587875,0.2617993877991494,254.9,637.2,764.6,1822.0,674.3,294.5 +2.3288863708752907,0.2711245101468307,0.39269908169872414,365.4,771.5,961.3,2239.4,423.2,204.0 +2.328874007842523,0.2711121866594055,0.5235987755982988,592.6,1092.0,1471.5,2608.8,302.9,175.3 +2.3288723942515768,0.27110543337532933,0.6544984694978736,566.2,1719.6,1660.2,2302.7,232.9,173.9 +2.328864386195094,0.27107469567168163,0.7853981633974483,563.2,1628.6,1628.2,2198.9,193.6,193.1 +2.3288654883243427,0.2710788013821839,0.916297857297023,609.0,1660.1,1719.1,1303.5,174.0,232.9 +2.328874228426843,0.27105365057733377,1.0471975511965976,717.1,1834.3,1961.4,548.9,174.9,302.2 +2.328893512679919,0.2710215467635728,1.1780972450961724,928.5,2231.1,2450.2,365.7,204.3,423.5 +2.3288800356021775,0.27103404302547185,1.3089969389957472,1390.6,2655.0,2528.3,255.3,294.7,637.9 +2.3288826435095507,0.2710332352898388,1.4398966328953218,1637.5,2339.1,2280.6,194.4,628.2,587.4 +2.3289437422934043,0.2710191495092058,1.5707963267948966,1598.9,2229.2,2228.8,163.1,593.3,593.1 +2.3289259932210054,0.2710180440990606,1.7016960206944713,1680.5,1454.4,541.2,151.9,588.2,646.8 +2.328912451824187,0.27101297677842484,1.832595714594046,1915.5,629.6,294.4,162.5,637.0,764.9 +2.3289598758947783,0.2710430263131509,1.9634954084936205,2400.9,423.2,204.2,205.2,771.4,992.3 +2.328971382545041,0.27105646555375995,2.0943951023931953,2513.9,302.1,174.8,316.9,1094.4,1474.8 +2.328958559599478,0.2710299733427399,2.2252947962927703,2259.0,232.8,174.1,608.6,1718.9,1660.0 +2.3289627381071916,0.27104559779162196,2.356194490192345,2199.5,193.1,193.7,562.6,1628.1,1629.2 +2.3289602749811484,0.27106936498711165,2.4870941840919194,701.2,173.9,233.1,566.2,1660.7,1719.7 +2.3289660954355114,0.2710545317037494,2.6179938779914944,316.4,175.4,303.1,624.7,1835.1,1962.8 +2.3289559164845604,0.27106611928173097,2.748893571891069,203.9,204.0,424.2,770.4,2236.3,2456.1 +2.32896850968091,0.2710557491213348,2.8797932657906435,162.0,294.4,637.3,1115.2,2654.6,2527.1 +2.3289634087149547,0.27105882602079423,3.010692959690218,151.6,622.4,588.0,1681.5,2340.5,2280.8 +2.328997505638519,0.37134435406729316,0.0,263.0,593.1,593.1,1499.0,2228.6,2229.1 +2.3289564104732836,0.37134236728914827,0.1308996938995747,298.5,588.1,647.5,1535.9,1815.3,1000.2 +2.3288412825511897,0.3713031867678185,0.2617993877991494,370.6,637.4,739.4,1706.6,872.9,493.7 +2.328812424115268,0.37128486439806063,0.39269908169872414,507.0,771.3,992.4,2098.1,564.3,345.1 +2.328770879974983,0.37124155068638576,0.5235987755982988,625.0,1092.0,1471.2,2608.5,418.4,290.9 +2.328749275567418,0.37119752418621865,0.6544984694978736,566.1,1616.2,1557.4,2302.9,336.4,277.4 +2.32873198963915,0.3711271874573614,0.7853981633974483,563.1,1529.1,1528.6,2198.9,293.6,293.1 +2.328734240236133,0.37109353941827394,0.916297857297023,609.0,1556.7,1615.7,1690.4,277.6,336.4 +2.3287532377845173,0.3710345279733085,1.0471975511965976,716.8,1718.3,1846.4,792.6,290.4,417.7 +2.3287898860796834,0.37097453306165273,1.1780972450961724,928.5,2089.4,2309.5,507.4,345.5,564.7 +2.328798320244166,0.37096643081837266,1.3089969389957472,1390.3,2655.5,2527.6,370.9,494.1,637.9 +2.328825587618066,0.37095241527645406,1.4398966328953218,1534.1,2338.9,2280.4,297.9,645.9,587.5 +2.3289122527761394,0.37093242594676457,1.5707963267948966,1498.9,2228.5,2228.7,263.2,593.4,593.1 +2.3289183827394524,0.3709320888258185,1.7016960206944713,1576.8,1844.0,1016.2,255.4,588.2,646.8 +2.3288904894465468,0.3709198464150003,1.832595714594046,1800.1,872.7,493.7,278.2,637.0,764.8 +2.329131828595366,0.3710736939301573,1.9634954084936205,2259.2,564.2,345.3,346.9,771.4,992.4 +2.329075333958996,0.37101363644320773,2.0943951023931953,2514.5,417.6,290.4,516.7,1094.5,1474.6 +2.3290576856163083,0.3709777703300452,2.2252947962927703,2259.5,336.3,277.6,608.6,1615.4,1556.5 +2.329065701258896,0.3710098034153382,2.356194490192345,2199.6,293.0,293.7,562.6,1528.5,1528.7 +2.329062385583264,0.3710577645092099,2.4870941840919194,1086.6,277.5,336.6,566.2,1557.2,1616.5 +2.3290609297297054,0.37106677809350375,2.6179938779914944,515.5,291.0,418.8,624.9,1719.2,1847.1 +2.329037962244731,0.3710988186348314,2.748893571891069,345.3,345.4,565.5,739.4,2094.7,2315.0 +2.3290341659751657,0.37110378655856247,2.8797932657906435,277.5,494.0,637.3,1115.1,2654.2,2527.2 +2.3290106655451077,0.37111672083390235,3.010692959690218,255.1,646.9,588.1,1577.7,2340.2,2281.1 +2.329022457909036,0.47138535186802444,0.0,363.0,593.0,593.2,1399.1,2229.2,2228.8 +2.3289822198410794,0.47068410152060913,0.1308996938995747,402.1,588.3,647.4,1432.2,2202.6,1386.4 +2.329012891633137,0.4706940726590072,0.2617993877991494,486.0,637.3,764.6,1590.5,1073.4,693.5 +2.329048680085889,0.47071709730036804,0.39269908169872414,648.4,771.2,991.9,1955.8,705.9,486.5 +2.3290772220362705,0.4707501106785468,0.5235987755982988,747.1,1091.3,1470.2,2609.3,534.3,406.5 +2.3291049797164844,0.4707993628694871,0.6544984694978736,566.3,1512.7,1453.8,2303.0,439.9,380.9 +2.3291103648621805,0.470828543641999,0.7853981633974483,563.2,1429.2,1428.6,2198.6,393.6,393.0 +2.329109553302905,0.4708899950639407,0.916297857297023,609.0,1453.2,1512.0,2080.3,380.9,439.6 +2.329102790726397,0.4709163470219402,1.0471975511965976,716.8,1602.7,1730.1,992.4,405.7,532.9 +2.3290958811839135,0.4709265914629368,1.1780972450961724,928.2,1947.8,2166.7,649.2,486.1,705.1 +2.329018181114943,0.4710053590393568,1.3089969389957472,1389.2,2656.1,2528.6,486.4,692.5,637.9 +2.3290111477225657,0.47101087231474814,1.4398966328953218,1431.0,2339.3,2281.1,401.2,646.0,587.5 +2.329039584487576,0.47100514504392366,1.5707963267948966,1398.9,2228.9,2228.8,363.0,593.3,593.2 +2.3289838348153067,0.4710038599277573,1.7016960206944713,1473.5,2236.5,1407.0,358.6,588.1,646.5 +2.328933831272406,0.4709891743690582,1.832595714594046,1683.9,1072.0,692.9,393.4,636.9,764.5 +2.3289498930205204,0.47100081183851294,1.9634954084936205,2116.7,705.5,486.3,488.3,770.9,992.0 +2.3289377680074934,0.47099004919769727,2.0943951023931953,2514.6,533.0,405.7,715.4,1093.5,1473.5 +2.3289095208274926,0.47093655737707674,2.2252947962927703,2259.5,439.8,380.9,608.5,1512.3,1453.2 +2.328906521182293,0.4709238895918484,2.356194490192345,2199.7,392.9,393.5,562.5,1428.7,1429.0 +2.3289048715523313,0.47092032223332314,2.4870941840919194,1473.4,380.8,439.9,566.0,1453.7,1512.7 +2.3289178808934747,0.47088159115517225,2.6179938779914944,715.1,406.3,534.0,624.6,1603.6,1731.3 +2.3289205302088893,0.4708734203793814,2.748893571891069,486.6,486.6,706.4,770.2,1952.6,2172.7 +2.3289491164605867,0.47084878827007115,2.8797932657906435,393.0,692.7,637.3,1114.1,2655.5,2527.7 +2.3289618568483528,0.4708431727060114,3.010692959690218,358.5,646.9,588.1,1474.4,2340.2,2281.5 +2.3290171622747713,0.5711448984154932,0.0,462.9,593.0,593.2,1299.3,2229.1,2228.9 +2.3289908328633593,0.5711446121339645,0.1308996938995747,505.5,588.2,647.4,1328.8,2282.0,1770.1 +2.3289369409535343,0.5711290284325556,0.2617993877991494,601.4,637.1,764.4,1475.2,1272.7,892.8 +2.3288840610005908,0.5710967790177488,0.39269908169872414,769.0,771.0,991.4,1814.0,846.8,627.4 +2.328841535569511,0.5710537722770639,0.5235987755982988,625.0,1091.0,1470.2,2577.6,649.8,522.1 +2.328823018276405,0.5710169202552839,0.6544984694978736,566.0,1409.3,1350.4,2303.1,543.5,484.3 +2.3288073383774535,0.5709561494258568,0.7853981633974483,563.0,1329.0,1328.7,2198.7,493.5,492.9 +2.328809088498228,0.5709323410710492,0.916297857297023,608.7,1349.7,1408.5,2258.9,484.4,543.1 +2.32882540289814,0.5708823687774034,1.0471975511965976,716.8,1487.1,1614.8,1192.1,521.2,648.6 +2.328857565790654,0.5708297995141001,1.1780972450961724,928.0,1806.7,2025.7,790.9,627.3,772.3 +2.3288605066964285,0.5708275936902001,1.3089969389957472,1389.0,2557.1,2528.6,602.0,765.5,637.9 +2.3288815130104936,0.5708179828546533,1.4398966328953218,1327.4,2339.1,2281.1,504.8,646.0,587.6 +2.32896139888259,0.5708002794442861,1.5707963267948966,1298.9,2228.7,2228.8,463.0,593.4,593.1 +2.3289609254720935,0.5708006736431879,1.7016960206944713,1369.8,2280.0,1797.1,462.2,588.2,646.5 +2.3289622925250137,0.5708014150205525,1.832595714594046,1568.4,1271.7,892.5,509.1,636.9,764.5 +2.329021785046165,0.5708401420714668,1.9634954084936205,1974.8,815.6,627.5,630.1,771.0,992.0 +2.3290419461121874,0.5708639283989405,2.0943951023931953,2514.5,648.7,521.3,717.2,1093.3,1473.8 +2.329034218217277,0.5708486987311452,2.2252947962927703,2260.1,543.3,484.5,608.6,1408.4,1349.8 +2.329040418900861,0.5708755817192963,2.356194490192345,2199.7,493.0,493.6,562.5,1328.6,1328.9 +2.3290374481696294,0.5709097295306489,2.4870941840919194,1859.4,484.3,543.5,566.1,1350.3,1408.9 +2.3290403793139838,0.5709041177395096,2.6179938779914944,914.3,522.0,649.7,624.5,1487.9,1615.7 +2.329025914205374,0.5709233145188743,2.748893571891069,628.1,628.0,770.2,770.2,1810.9,2031.0 +2.3290328562936184,0.5709189336880451,2.8797932657906435,508.5,764.8,637.3,1114.3,2561.0,2527.3 +2.3290213967746904,0.5709262636896772,3.010692959690218,462.0,646.9,588.1,1370.8,2340.5,2281.4 +2.329047420644386,0.6712058190446129,0.0,562.9,593.0,593.0,1199.3,2228.9,2228.9 +2.328993010811503,0.6706531865051011,0.1308996938995747,609.3,588.2,647.4,1225.0,2417.5,2154.7 +2.3290244944789342,0.6706634997959946,0.2617993877991494,717.3,637.2,764.4,1359.8,1472.5,1092.7 +2.32906318502333,0.670688444653591,0.39269908169872414,768.9,771.0,991.7,1672.3,988.1,768.9 +2.3290944508645763,0.6707245050867063,0.5235987755982988,625.3,1091.4,1372.3,2378.6,765.4,637.7 +2.328785156932167,0.6710234799489279,0.6544984694978736,566.2,1305.4,1246.5,2302.3,647.0,587.9 +2.328781420327362,0.6710099510611769,0.7853981633974483,563.3,1229.0,1228.5,2199.0,593.4,593.1 +2.328782748710412,0.671012439234923,0.916297857297023,609.1,1246.0,1305.5,2305.0,588.1,647.0 +2.3287939813125806,0.6709802344754545,1.0471975511965976,717.3,1372.4,1499.9,1390.3,637.0,764.6 +2.32881834456386,0.6709410394381654,1.1780972450961724,928.9,1666.6,1885.8,931.9,769.1,816.2 +2.328811440436553,0.6709480284884874,1.3089969389957472,1385.1,2360.9,2527.2,717.4,849.2,637.7 +2.3288214144928627,0.6709436980850301,1.4398966328953218,1223.7,2338.9,2280.7,608.0,645.8,587.5 +2.328890056431805,0.6709284930882449,1.5707963267948966,1199.1,2228.9,2228.6,563.0,593.3,593.2 +2.3288791777326696,0.6709280572103153,1.7016960206944713,1266.7,2280.5,2181.4,565.8,588.3,646.8 +2.3288716435654058,0.6709250003014136,1.832595714594046,1453.3,1469.2,1090.5,625.0,637.2,765.0 +2.328923963047408,0.6709583953786225,1.9634954084936205,1834.6,987.1,768.3,772.5,771.8,992.8 +2.328939036304413,0.6709759461254887,2.0943951023931953,2513.7,763.8,636.7,857.8,1095.0,1371.3 +2.3289286130018807,0.6709537300067969,2.2252947962927703,2259.0,646.5,588.0,608.5,1304.5,1246.0 +2.3289340261514435,0.6709737637414952,2.356194490192345,2199.5,593.0,593.7,562.5,1228.4,1228.9 +2.32893161575488,0.6710018845498145,2.4870941840919194,2239.7,588.0,647.2,566.2,1246.8,1306.0 +2.328936713762481,0.670990906641846,2.6179938779914944,1112.3,637.9,765.7,624.9,1372.6,1500.7 +2.3289248133144183,0.6710059429539703,2.748893571891069,738.1,769.8,817.6,770.7,1670.9,1891.1 +2.3289352287669693,0.6709982869837361,2.8797932657906435,624.0,849.3,637.1,1116.0,2364.5,2527.0 +2.328927477060452,0.6710033307511105,3.010692959690218,565.5,646.8,588.0,1267.4,2339.7,2280.6 +2.3289580384578312,0.7712862041676227,0.0,663.0,593.1,593.3,1098.9,2228.7,2228.7 +2.328948220059391,0.7706747398213913,0.1308996938995747,712.8,588.1,647.4,1121.5,2282.0,2341.8 +2.328986315556567,0.7706869908621852,0.2617993877991494,832.7,637.1,764.5,1244.0,1672.4,1292.4 +2.3290243936114714,0.7707113808161332,0.39269908169872414,772.0,771.1,991.7,1530.4,1129.7,910.4 +2.3290536628421514,0.7707450479973859,0.5235987755982988,625.2,1091.1,1256.9,2178.9,881.3,753.3 +2.3290817813070706,0.7707946645994757,0.6544984694978736,566.2,1202.3,1143.2,2303.0,750.7,691.6 +2.3290873444320948,0.7708240671360913,0.7853981633974483,563.3,1129.1,1128.5,2198.9,693.5,692.8 +2.329086707539408,0.7708857744166893,0.916297857297023,609.0,1142.7,1201.2,2259.1,691.3,750.3 +2.329080046646892,0.7709124048300957,1.0471975511965976,716.9,1256.5,1383.7,1592.1,752.3,879.5 +2.3290731272709415,0.770922869897108,1.1780972450961724,928.0,1524.7,1743.0,1074.5,909.4,797.5 +2.329026725272675,0.7709673274084674,1.3089969389957472,1244.7,2158.5,2528.7,833.2,765.7,637.9 +2.328992128952843,0.7709877974413366,1.4398966328953218,1120.6,2339.2,2280.5,711.6,646.0,587.5 +2.329014267947041,0.7709835059855039,1.5707963267948966,1099.0,2228.6,2228.4,662.9,593.4,593.0 +2.328959824540419,0.7709822687842052,1.7016960206944713,1163.1,2279.8,2338.1,669.0,588.2,646.4 +2.3289132344215435,0.7709686648768379,1.832595714594046,1336.9,1670.7,1291.1,740.3,636.8,764.4 +2.32893283106964,0.7709824434073835,1.9634954084936205,1691.6,1098.1,910.0,913.1,770.8,991.8 +2.3289235497479948,0.7709745423703951,2.0943951023931953,2461.7,879.9,752.4,717.2,1093.2,1256.7 +2.3288971738056485,0.7709243686117817,2.2252947962927703,2259.5,750.4,691.4,608.6,1201.5,1142.6 +2.328895097656891,0.7709151777196817,2.356194490192345,2199.7,693.0,693.6,562.5,1128.5,1129.1 +2.3288935070308714,0.7709149374078061,2.4870941840919194,2302.9,691.4,750.4,566.1,1142.9,1202.2 +2.32890572531562,0.7708792228662988,2.6179938779914944,1313.2,753.3,880.8,624.6,1256.6,1384.4 +2.328907009391601,0.7708735603100949,2.748893571891069,911.1,910.5,798.9,770.0,1528.3,1748.2 +2.3289337127191225,0.7708508515511296,2.8797932657906435,739.8,764.9,637.4,1114.0,2161.7,2528.1 +2.3289442999955603,0.7708465013757293,3.010692959690218,669.0,647.0,588.1,1164.1,2340.3,2281.8 +2.329001544693374,0.8711586911475271,0.0,762.9,593.1,593.1,999.0,2228.8,2228.9 +2.3289701665988822,0.8711582689692694,0.1308996938995747,816.3,588.2,647.3,1018.0,2282.4,2387.2 +2.32891185878192,0.8711413313162435,0.2617993877991494,947.9,637.2,764.5,1128.3,1871.4,1491.7 +2.3288554162016863,0.8711068104328683,0.39269908169872414,769.0,771.0,991.7,1388.9,1270.5,1051.2 +2.328810260582672,0.8710608934310515,0.5235987755982988,625.0,1091.0,1141.6,1980.0,996.8,868.8 +2.3287901789885255,0.8710208736852287,0.6544984694978736,566.1,1098.9,1039.8,2303.1,854.0,795.0 +2.3287738328457928,0.8709568142429049,0.7853981633974483,563.1,1028.9,1028.3,2198.9,793.5,792.9 +2.3287758323022776,0.8709299829804675,0.916297857297023,585.9,1039.3,1097.9,2258.7,794.7,853.6 +2.3287931087611726,0.8708773648876353,1.0471975511965976,716.7,1140.8,1268.2,1792.2,867.7,995.1 +2.3288267368271827,0.8708226121217908,1.1780972450961724,927.7,1383.4,1602.5,1216.3,993.4,772.4 +2.3288314867577813,0.8708188672706874,1.3089969389957472,1129.1,1958.9,2338.0,949.0,765.7,637.9 +2.3288544736563694,0.8708083545269183,1.4398966328953218,1017.2,2339.7,2280.9,815.0,646.1,587.6 +2.328936352285723,0.870790195016957,1.5707963267948966,999.0,2229.0,2228.4,762.9,593.4,593.0 +2.3289377298471345,0.8707906554943492,1.7016960206944713,1059.6,2280.4,2406.9,772.7,588.1,646.4 +2.3289407255599293,0.8707919310686452,1.832595714594046,1221.6,1870.1,1490.6,855.8,636.9,764.5 +2.3290016073301096,0.8708314527732264,1.9634954084936205,1549.7,1270.1,1051.1,927.7,771.0,991.8 +2.3290228587273156,0.8708562206591561,2.0943951023931953,2261.4,995.5,867.9,717.3,1093.5,1141.2 +2.3290158552618156,0.8708421597783298,2.2252947962927703,2259.4,853.9,794.9,608.7,1098.3,1039.2 +2.3290224600544804,0.8708702761391618,2.356194490192345,2199.6,793.0,793.4,562.7,1028.6,1028.8 +2.3290196205882827,0.8709056067867369,2.4870941840919194,2302.7,794.9,854.0,566.2,1039.5,1098.5 +2.329022334904544,0.8709011226761243,2.6179938779914944,1512.6,868.7,996.3,624.5,1140.9,1268.8 +2.329007474315359,0.8709212672604842,2.748893571891069,1052.8,990.6,770.6,770.2,1386.7,1606.6 +2.3290137666217707,0.8709176519068738,2.8797932657906435,855.4,764.9,637.4,1114.2,1962.5,2341.9 +2.3290015337109686,0.8709255057669893,3.010692959690218,772.5,647.0,588.1,1060.5,2340.4,2281.3 +2.82907496401081,0.1708281859172951,0.0,63.0,93.1,93.1,1699.0,2729.0,2728.8 +2.8290903600703063,0.17141028533996594,0.1308996938995747,91.6,119.2,129.6,1742.7,963.7,233.3 +2.8289969945026643,0.17138065243769018,0.2617993877991494,116.7,59.3,186.9,1937.7,474.6,95.2 +2.828940551081692,0.17134433198369625,0.39269908169872414,62.7,63.0,283.8,2380.8,282.1,63.0 +2.8289032055822894,0.1713050787513648,0.5235987755982988,150.4,95.3,474.6,3186.6,187.4,59.8 +2.8288895993923564,0.17127593046792922,0.6544984694978736,48.3,234.7,1054.7,2820.4,129.5,70.5 +2.828876580492458,0.17122484944944305,0.7853981633974483,63.1,1728.7,1728.5,2698.8,93.7,93.3 +2.8288777634186726,0.1712105071122385,0.916297857297023,91.3,1763.7,1822.4,916.7,70.6,129.5 +2.8288907832942423,0.1711689231024558,1.0471975511965976,139.2,1949.7,2076.9,393.6,59.5,94.9 +2.828917694537876,0.17112308102330642,1.1780972450961724,222.7,2371.7,2591.2,224.2,63.3,110.3 +2.828914112020535,0.1711250512632423,1.3089969389957472,393.4,3233.8,3106.1,139.8,95.6,200.7 +2.828928181148598,0.1711170393606476,1.4398966328953218,837.2,2856.2,2798.2,91.0,128.5,70.1 +2.8290015230566308,0.17109924924436304,1.5707963267948966,1698.9,2729.3,2728.7,63.3,93.2,93.1 +2.828995513099733,0.1710977450086597,1.7016960206944713,1783.6,1065.4,238.0,48.6,122.5,129.3 +2.8289926512789214,0.17109522650695186,1.832595714594046,2031.3,474.4,95.5,47.1,58.9,186.6 +2.829049112480108,0.17113042519694077,1.9634954084936205,2542.8,282.3,63.3,63.7,62.5,283.6 +2.8290673194213665,0.17115076664317308,2.0943951023931953,3091.5,186.7,59.5,117.4,95.5,475.9 +2.8290586532850046,0.17113208221073717,2.2252947962927703,2776.6,129.4,70.7,90.9,235.6,1059.9 +2.82906445421117,0.17115583623186303,2.356194490192345,2699.6,93.2,93.8,62.4,1728.2,1728.8 +2.829061231059869,0.17118728146852047,2.4870941840919194,316.4,70.5,129.6,48.3,1764.4,1823.1 +2.8290643874282755,0.1711789646782924,2.6179938779914944,117.5,59.9,94.5,46.5,1950.5,2078.4 +2.8290500821412494,0.17119563370185364,2.748893571891069,62.7,62.7,110.3,63.2,2377.9,2597.2 +2.829057793794338,0.1711886367822706,2.8797932657906435,46.6,95.0,200.4,117.2,3232.1,3104.9 +2.8290475582998433,0.17119344444085582,3.010692959690218,48.2,129.2,70.4,318.6,2857.8,2798.9 +2.829033921785187,0.17119755031961414,0.0,63.3,93.0,93.0,1698.8,2728.9,2729.1 +2.8290590420956034,0.1711999304896643,0.1308996938995747,91.6,118.9,129.6,1742.5,964.1,233.6 +2.829021250983699,0.17118730783115232,0.2617993877991494,116.8,59.3,186.9,1937.9,474.8,95.3 +2.829007725446448,0.17117784917495538,0.39269908169872414,62.7,63.0,283.8,2380.4,282.2,63.1 +2.829001647909438,0.17117214068904985,0.5235987755982988,150.4,95.4,474.7,3186.3,187.5,59.9 +2.8290077587492317,0.17117977234694992,0.6544984694978736,48.4,234.9,1054.8,2820.4,129.5,70.5 +2.829003591431956,0.17116666228130795,0.7853981633974483,63.2,1728.7,1728.3,2699.0,93.8,93.3 +2.829003675662168,0.171188170895622,0.916297857297023,91.4,1763.5,1822.6,916.7,70.6,129.5 +2.8290069930468507,0.17117863156485624,1.0471975511965976,139.2,1950.0,2076.9,393.5,59.4,95.0 +2.8290174977342866,0.17115913977671138,1.1780972450961724,222.7,2371.8,2590.9,224.1,63.3,110.3 +2.8289932372914826,0.1711805886653055,1.3089969389957472,393.5,3233.5,3106.1,139.8,95.5,200.7 +2.8289840351847486,0.17118510652287533,1.4398966328953218,923.2,2856.0,2798.3,91.0,128.5,70.1 +2.8290332326075776,0.17117292004905793,1.5707963267948966,1698.8,2728.8,2728.4,63.2,93.3,93.1 +2.829004660143493,0.1711707369889517,1.7016960206944713,1784.0,1065.7,237.8,48.5,122.7,129.3 +2.828981749693134,0.17116221987386004,1.832595714594046,2030.9,474.4,95.4,47.0,58.8,186.5 +2.8290215160549685,0.17118701716841644,1.9634954084936205,2542.8,282.2,63.2,63.6,62.5,283.5 +2.8290273762559943,0.17119414884468642,2.0943951023931953,3091.1,186.6,59.4,117.4,95.5,475.9 +2.8290108732866557,0.17116086433369504,2.2252947962927703,2776.7,129.4,70.7,90.9,235.5,1059.5 +2.829013166304002,0.17116953166976723,2.356194490192345,2699.5,93.2,93.8,62.4,1727.9,1728.7 +2.82901046299703,0.17118658839603507,2.4870941840919194,316.4,70.4,129.6,48.3,1763.9,1823.1 +2.8290174762537315,0.17116564733816508,2.6179938779914944,117.5,59.9,94.5,46.5,1950.6,2078.2 +2.8290097262570755,0.1711718898432557,2.748893571891069,62.7,62.7,110.2,63.1,2377.4,2597.8 +2.829025709804532,0.1711571933403666,2.8797932657906435,46.6,95.0,200.4,117.2,3232.7,3104.9 +2.829024715612753,0.17131559054428447,3.010692959690218,48.2,129.2,70.4,318.5,2857.6,2798.3 +2.2288652505549025,0.37120229944974836,0.0,263.3,692.8,692.9,1498.7,2128.9,2129.0 +2.2289395011375808,0.3710190393035857,0.1308996938995747,298.7,691.6,751.0,1535.4,1817.6,1001.5 +2.2290911447210475,0.3710668840239706,0.2617993877991494,370.5,752.8,880.4,1706.5,873.6,494.0 +2.229014430176658,0.37101843493798214,0.39269908169872414,506.9,912.9,1133.8,2097.2,533.5,345.3 +2.2289972964372353,0.37100154575274225,0.5235987755982988,740.6,1290.8,1669.9,2493.3,418.6,291.0 +2.2290044598352106,0.3710115348740879,0.6544984694978736,669.7,1616.2,1557.1,2199.4,336.5,277.4 +2.229002020655298,0.37100608907369925,0.7853981633974483,663.3,1529.0,1528.3,2098.8,293.6,293.1 +2.2290021193899334,0.3710366960499798,0.916297857297023,712.5,1556.6,1615.6,1691.5,277.5,336.4 +2.229003294473264,0.3710359993177055,1.0471975511965976,832.5,1718.3,1845.7,792.9,290.3,417.7 +2.22900976732134,0.3710240737530872,1.1780972450961724,1069.5,2089.3,2308.1,476.4,345.4,564.4 +2.2289802646053354,0.371051611728032,1.3089969389957472,1589.0,2540.3,2413.0,370.9,493.7,753.4 +2.2289648832009785,0.371060651920746,1.4398966328953218,1534.0,2235.7,2177.4,297.8,749.3,690.9 +2.2290072861982813,0.3710508991848551,1.5707963267948966,1499.1,2129.0,2128.3,263.1,693.3,693.2 +2.2289720521896683,0.3710494132306956,1.7016960206944713,1576.8,1845.7,931.3,255.3,691.6,750.0 +2.2289428667405207,0.371040035742338,1.832595714594046,1799.3,872.9,493.7,278.1,752.5,880.2 +2.2289771801118596,0.37106221611538026,1.9634954084936205,2258.5,564.4,345.3,346.9,912.9,1133.9 +2.2289789025208973,0.3710654916946441,2.0943951023931953,2398.7,417.7,290.3,516.3,1293.4,1674.0 +2.2289596625753973,0.37102779884816917,2.2252947962927703,2155.7,336.3,277.5,712.0,1615.4,1556.9 +2.228960786624613,0.37103171379799194,2.356194490192345,2099.5,293.1,293.6,662.6,1528.4,1528.8 +2.228958547709415,0.3710441225370482,2.4870941840919194,1087.4,277.4,336.5,669.5,1557.0,1616.4 +2.2289671530645085,0.37101932348890876,2.6179938779914944,515.7,291.0,418.6,740.2,1719.3,1846.9 +2.2289621477780606,0.37102255702154063,2.748893571891069,345.4,345.3,565.3,911.7,2094.2,2314.5 +2.228981228323801,0.3710060548784764,2.8797932657906435,277.5,493.7,752.8,1314.4,2539.6,2412.2 +2.2289834674010853,0.3710052621661595,3.010692959690218,255.1,750.4,691.6,1577.9,2236.8,2177.6 +2.2290264633562265,0.4712975697531905,0.0,363.0,693.0,693.1,1399.2,2129.1,2128.9 +2.228991561946271,0.47129602487706945,0.1308996938995747,402.1,691.7,751.2,1432.2,2116.1,1385.2 +2.228931576236414,0.47127771480015257,0.2617993877991494,486.1,752.7,880.3,1591.4,1073.0,693.4 +2.228874332046531,0.4712418763373012,0.39269908169872414,648.5,913.0,1133.6,1955.7,705.7,486.3 +2.228828903960984,0.4711948604603562,0.5235987755982988,740.7,1290.6,1625.6,2493.5,534.1,406.5 +2.2288086340339364,0.47115388314808837,0.6544984694978736,669.6,1512.5,1453.7,2199.5,439.9,380.9 +2.228792303561469,0.471089141052621,0.7853981633974483,663.2,1428.9,1428.3,2098.6,393.7,393.1 +2.228794159628968,0.4710616148125164,0.916297857297023,712.4,1453.3,1511.7,2079.2,381.0,439.8 +2.228811270800912,0.4710082772114217,1.0471975511965976,832.3,1603.1,1730.2,992.5,405.9,533.2 +2.228877706583318,0.4709001634299739,1.1780972450961724,1069.4,1948.0,2167.4,649.4,486.5,705.6 +2.22885130222161,0.47092455737294925,1.3089969389957472,1588.7,2540.4,2412.9,486.5,693.1,829.1 +2.22886607269597,0.4709173448651345,1.4398966328953218,1431.0,2235.6,2177.4,401.3,875.3,690.9 +2.228949361495079,0.47089812338709147,1.5707963267948966,1398.8,2129.2,2128.7,363.2,693.2,693.0 +2.2289553501591666,0.4708979305885834,1.7016960206944713,1473.2,2149.4,1406.8,358.8,691.6,750.0 +2.2289637266546816,0.4708998780210314,1.832595714594046,1684.0,1072.3,649.4,393.8,752.6,880.0 +2.2290295807837657,0.47094177070643095,1.9634954084936205,2117.1,705.7,486.5,488.7,912.8,1133.9 +2.229054691203004,0.4709701108193223,2.0943951023931953,2398.9,533.3,405.8,715.9,1293.5,1603.0 +2.229050293271689,0.47096014827063426,2.2252947962927703,2155.9,439.9,381.1,711.9,1512.0,1453.2 +2.2290580621420912,0.47099270809240257,2.356194490192345,2099.8,393.1,393.6,662.5,1428.4,1428.9 +2.2290548602794322,0.47103241994763034,2.4870941840919194,1473.1,380.9,440.0,669.7,1453.4,1512.6 +2.2290561649698466,0.4710315988825202,2.6179938779914944,715.0,406.6,534.3,740.4,1603.5,1731.2 +2.2290656293697544,0.47101213051791,2.748893571891069,486.8,486.7,706.7,911.8,1952.7,2172.6 +2.229043775876333,0.4710336927219516,2.8797932657906435,393.1,693.1,829.6,1314.1,2539.6,2411.4 +2.2290217037951376,0.4710458744480246,3.010692959690218,358.6,838.5,691.5,1474.5,2236.6,2177.6 +2.2290449564412413,0.5713268564136571,0.0,463.0,693.0,693.1,1298.8,2128.3,2128.9 +2.2290223577673696,0.5707029742629304,0.1308996938995747,505.7,691.7,750.9,1328.6,2178.8,1770.5 +2.2290358539821526,0.5707076323065587,0.2617993877991494,601.6,752.9,880.3,1475.2,1272.8,893.1 +2.2290665705409767,0.5707274851201778,0.39269908169872414,790.0,912.8,1133.6,1813.6,847.1,627.8 +2.2290936549190614,0.5707589914229281,0.5235987755982988,740.8,1290.4,1488.2,2493.3,649.8,522.1 +2.2291209587891334,0.5708075419721841,0.6544984694978736,669.8,1409.1,1350.5,2199.0,543.5,484.4 +2.229126161999612,0.5708363349017536,0.7853981633974483,663.3,1329.0,1328.6,2098.9,493.5,492.8 +2.229125252206411,0.5708975009686248,0.916297857297023,712.3,1350.0,1408.7,2155.7,484.4,543.1 +2.2291184481303374,0.5709235927657583,1.0471975511965976,832.4,1487.5,1614.7,1192.5,521.2,648.4 +2.229111558461402,0.5709335923738519,1.1780972450961724,1069.0,1807.0,2026.0,790.8,627.1,846.4 +2.2290652936579853,0.5709775826765884,1.3089969389957472,1475.9,2540.9,2413.2,602.0,855.7,753.5 +2.229030963204677,0.5709976153521843,1.4398966328953218,1327.4,2235.7,2222.8,504.7,749.4,690.9 +2.2290534889647464,0.5709931467998226,1.5707963267948966,1299.1,2129.0,2128.7,462.9,693.3,693.1 +2.228999446771633,0.5709918562384899,1.7016960206944713,1369.8,2176.8,1797.1,462.1,691.7,749.9 +2.2289532443001696,0.5709782883076471,1.832595714594046,1568.2,1271.4,892.1,509.1,752.5,880.1 +2.2289731243944235,0.5709923237162804,1.9634954084936205,1975.0,846.5,627.4,629.7,912.7,1133.3 +2.228963963548622,0.5709847984279846,2.0943951023931953,2398.8,648.6,521.3,832.9,1293.0,1487.8 +2.2289375941531557,0.5709349485003479,2.2252947962927703,2155.8,543.3,484.5,712.1,1408.7,1349.8 +2.228935381643122,0.5709260502533466,2.356194490192345,2099.8,493.1,493.5,662.5,1328.4,1329.2 +2.2289335025355137,0.5709260559034728,2.4870941840919194,1859.3,484.3,543.4,669.5,1350.1,1409.5 +2.228945455200774,0.5708904237159427,2.6179938779914944,914.3,522.0,649.5,740.2,1488.1,1615.5 +2.2289463966594316,0.5708847741448078,2.748893571891069,628.1,627.9,847.9,911.5,1811.2,2030.8 +2.228972883706021,0.5708619667341166,2.8797932657906435,508.5,855.0,752.8,1313.6,2540.5,2412.1 +2.2289833238466077,0.5708574822702315,3.010692959690218,462.1,750.4,691.4,1371.0,2237.0,2178.0 +2.2290359183410104,0.6711571622898993,0.0,562.8,693.2,692.9,1199.2,2129.1,2128.7 +2.22900765857432,0.6711567633574889,0.1308996938995747,609.1,691.6,751.0,1225.1,2178.7,2154.3 +2.2289523500705966,0.6711407300572234,0.2617993877991494,717.1,752.7,880.1,1359.7,1472.2,1048.4 +2.2288983800912554,0.6711078148472263,0.39269908169872414,910.3,912.6,1133.3,1672.4,987.9,768.7 +2.22885504012945,0.6710639946676578,0.5235987755982988,740.8,1290.1,1372.7,2378.9,765.3,637.6 +2.2288359668678055,0.6710262480388081,0.6544984694978736,669.5,1305.8,1246.9,2199.9,646.9,587.9 +2.2288199800981237,0.6709645381680251,0.7853981633974483,663.2,1229.1,1228.6,2098.7,593.5,592.9 +2.22882165577033,0.6709398111851723,0.916297857297023,712.2,1246.0,1304.8,2297.0,587.8,646.7 +2.228838115831466,0.6708889785630026,1.0471975511965976,832.3,1372.0,1499.0,1392.0,636.8,764.0 +2.2288706173682966,0.6708356627237575,1.1780972450961724,1069.2,1665.6,1884.5,932.7,768.4,914.0 +2.2288740392020503,0.6708328633257374,1.3089969389957472,1360.2,2358.1,2413.0,717.8,881.1,753.4 +2.228895634651332,0.6708228323170404,1.4398966328953218,1223.9,2235.8,2177.1,608.0,749.5,690.9 +2.2289761722425143,0.6708049109328418,1.5707963267948966,1199.1,2128.8,2128.7,563.1,693.3,693.0 +2.228976331781202,0.6708052815622576,1.7016960206944713,1266.3,2177.1,2187.3,565.6,691.6,750.0 +2.2289782721800164,0.6708061748351362,1.832595714594046,1452.6,1470.9,1091.6,624.7,752.4,880.1 +2.229038234947592,0.6708452105010057,1.9634954084936205,1833.1,987.8,768.8,771.7,912.7,1133.5 +2.2290587189157645,0.6708694041923158,2.0943951023931953,2398.6,738.7,637.0,871.3,1293.2,1372.3 +2.2290511580607504,0.6708546193720923,2.2252947962927703,2156.0,646.8,588.1,712.1,1305.0,1246.4 +2.229057375697106,0.67088194501064,2.356194490192345,2099.5,593.0,593.4,662.4,1228.3,1228.9 +2.2290542903249175,0.6709164870637689,2.4870941840919194,2160.0,588.0,646.8,669.6,1246.7,1305.9 +2.229057017948513,0.6709111817493212,2.6179938779914944,1113.5,637.6,765.2,740.2,1372.5,1499.9 +2.2290422908373837,0.6709305925172753,2.748893571891069,769.6,769.3,911.8,911.7,1670.1,1889.7 +2.229048960731211,0.6709263295655605,2.8797932657906435,624.1,880.4,752.8,1313.8,2361.3,2411.9 +2.229037242504315,0.670933699653306,3.010692959690218,565.6,750.3,691.5,1267.5,2236.8,2177.9 +2.229063026142413,0.7712130774061705,0.0,662.9,693.0,693.1,1099.2,2129.2,2129.0 +2.2290034262971523,0.7706549105229306,0.1308996938995747,712.7,668.9,750.9,1121.2,2178.7,2238.1 +2.2290336656971763,0.770664851484828,0.2617993877991494,832.6,752.8,880.2,1244.0,1671.4,1291.9 +2.2290719408555204,0.7706895681322838,0.39269908169872414,910.0,913.0,1133.5,1530.2,1129.2,910.2 +2.229103053388162,0.7707255159758155,0.5235987755982988,740.7,1290.4,1257.1,2179.8,881.2,753.4 +2.2287881435196897,0.7710244043868737,0.6544984694978736,669.6,1201.8,1143.1,2199.2,750.4,691.6 +2.2287843169504526,0.7710105126008584,0.7853981633974483,663.4,1129.1,1128.4,2099.0,693.5,693.1 +2.2287856328661113,0.7710131486957126,0.916297857297023,712.6,1142.6,1202.0,2156.1,691.7,750.4 +2.2287967694347177,0.7709812269901211,1.0471975511965976,832.7,1256.7,1383.8,1589.8,752.7,879.9 +2.228820949634251,0.7709423017872292,1.1780972450961724,1070.1,1525.7,1744.7,1073.8,910.4,957.4 +2.2288138097579417,0.7709494985579406,1.3089969389957472,1243.7,2161.1,2412.0,832.9,1022.0,753.3 +2.2288235187394476,0.7709453026049617,1.4398966328953218,1120.2,2235.7,2176.8,711.5,749.3,691.0 +2.2288918873913364,0.7709301508830213,1.5707963267948966,1098.8,2128.7,2128.9,663.1,693.3,693.1 +2.228880755979194,0.7709297014763983,1.7016960206944713,1163.0,2176.9,2235.4,669.2,691.7,727.6 +2.228872997893331,0.7709265772346954,1.832595714594046,1337.7,1668.3,1289.5,740.6,752.8,880.7 +2.2289251311425406,0.770959855917607,1.9634954084936205,1692.8,1128.3,878.3,914.1,913.4,1134.5 +2.228940065500792,0.7709772597436957,2.0943951023931953,2398.1,879.4,752.2,832.4,1295.0,1255.9 +2.2289295492418204,0.7709548843165832,2.2252947962927703,2155.6,750.3,691.4,711.9,1201.1,1142.6 +2.228934915121353,0.7709747517116308,2.356194490192345,2099.7,692.9,693.8,662.5,1128.3,1129.2 +2.228932502592804,0.7710027094979848,2.4870941840919194,2199.9,691.6,750.7,669.8,1143.0,1202.4 +2.228937633136769,0.7709915865177741,2.6179938779914944,1311.1,753.7,881.3,740.6,1257.0,1384.8 +2.2289258006408947,0.7710064974381667,2.748893571891069,910.5,911.5,958.9,912.4,1529.2,1749.7 +2.2289363039739283,0.7709987456473191,2.8797932657906435,739.5,1021.0,752.7,1315.6,2164.9,2411.1 +2.228928655533019,0.7710037246163874,3.010692959690218,669.2,750.3,691.5,1163.6,2236.5,2177.4 +2.2289593483467294,0.871286697144432,0.0,762.8,693.0,693.1,999.0,2129.0,2128.9 +2.2289475877094667,0.8706726441546402,0.1308996938995747,816.1,691.6,750.9,1017.6,2179.2,2371.6 +2.2289855424594784,0.870684853318793,0.2617993877991494,948.1,752.7,880.1,1128.4,1872.1,1491.9 +2.2290237980275025,0.8707093533048293,0.39269908169872414,913.6,912.9,1133.5,1388.8,1270.8,1051.5 +2.2290532747082206,0.8707432396943937,0.5235987755982988,740.7,1290.5,1141.6,1980.0,996.8,869.0 +2.2290815482667123,0.8707931319389113,0.6544984694978736,669.8,1098.6,1039.6,2199.7,854.2,794.9 +2.2290871854169674,0.8708228293329126,0.7853981633974483,663.2,1029.1,1028.6,2098.8,793.5,793.1 +2.2290865497465226,0.8708848244039502,0.916297857297023,712.3,1038.9,1097.9,2155.7,795.0,853.7 +2.2290798205302296,0.8709117170234579,1.0471975511965976,832.3,1140.7,1267.9,1791.8,867.7,995.0 +2.229072774941402,0.8709223974228855,1.1780972450961724,1069.2,1383.5,1602.3,1216.2,1050.3,938.3 +2.229026211770658,0.8709670204544993,1.3089969389957472,1129.1,1959.2,2338.3,948.9,881.4,753.9 +2.228991430125047,0.8709876049038194,1.4398966328953218,1017.1,2235.9,2177.7,815.2,749.6,691.0 +2.2290133717941725,0.8709833627743919,1.5707963267948966,999.0,2128.7,2128.8,762.9,693.3,693.1 +2.228958742195605,0.8709821246518767,1.7016960206944713,1059.4,2176.4,2234.9,772.4,691.7,750.1 +2.228911983909102,0.8709684787536378,1.832595714594046,1221.6,1870.0,1490.7,855.9,752.4,879.9 +2.228931441086725,0.8709821709422965,1.9634954084936205,1550.1,1270.1,1051.0,1054.8,912.6,1133.5 +2.228922059178329,0.8709741559589423,2.0943951023931953,2261.4,995.4,867.9,832.7,1292.6,1141.0 +2.228895619485554,0.870923860644196,2.2252947962927703,2156.0,853.7,795.1,712.2,1098.1,1039.5 +2.228893518147588,0.8709145440618489,2.356194490192345,2099.5,793.0,793.4,662.5,1028.5,1029.1 +2.2288919410253043,0.8709141826355968,2.4870941840919194,2198.9,794.9,854.0,669.7,1039.5,1098.3 +2.228904196412231,0.870878367403233,2.6179938779914944,1512.6,868.8,996.4,740.1,1141.1,1268.7 +2.2289055451666955,0.8708726222003722,2.748893571891069,1052.6,1052.0,940.5,911.3,1386.7,1606.7 +2.22893232047561,0.8708498573178041,2.8797932657906435,855.4,880.4,752.9,1221.7,1962.4,2341.6 +2.228942985576865,0.8708454747077992,3.010692959690218,772.7,750.6,691.5,1060.7,2236.6,2178.1 +2.8290009978485706,0.17078341001690034,0.0,63.0,93.1,93.0,1699.1,2729.4,2729.2 +2.8290688755866595,0.17141838752339167,0.1308996938995747,91.6,119.2,129.6,1743.0,964.0,233.3 +2.8289853656292405,0.17139180327448056,0.2617993877991494,116.8,59.3,186.8,1937.7,474.6,95.2 +2.828930015869494,0.17135615083582945,0.39269908169872414,62.7,63.0,283.8,2381.0,282.1,63.0 +2.8288916701700515,0.17131578973576533,0.5235987755982988,150.3,95.3,474.6,3186.7,187.4,59.8 +2.8288770626204314,0.17128469086240283,0.6544984694978736,48.3,234.7,1054.7,2820.5,129.5,70.5 +2.828863530635592,0.17123131095767286,0.7853981633974483,63.1,1728.8,1728.1,2699.5,93.7,93.2 +2.828864819906947,0.1712147356729048,0.916297857297023,91.3,1763.5,1822.6,916.9,70.7,129.5 +2.8288784807382563,0.1711711394745472,1.0471975511965976,139.2,1949.5,2077.3,393.6,59.5,94.9 +2.8289064381479054,0.17112361716660263,1.1780972450961724,222.6,2372.0,2591.0,224.3,63.3,110.3 +2.8289041767379053,0.17112435751597177,1.3089969389957472,393.4,3233.9,3105.9,139.8,95.6,200.7 +2.828919726722349,0.17111557282378276,1.4398966328953218,837.2,2856.3,2797.8,91.0,128.5,70.1 +2.828994595380952,0.17109739658971423,1.5707963267948966,1698.9,2728.7,2728.5,63.3,93.2,93.0 +2.828990019669013,0.1710959121736395,1.7016960206944713,1783.7,1066.0,238.1,48.6,122.5,129.3 +2.828988434339802,0.17109377400817016,1.832595714594046,2030.5,474.6,95.5,47.1,58.9,186.6 +2.8290459754311836,0.17112960447388859,1.9634954084936205,2542.3,282.3,63.3,63.7,62.5,283.5 +2.8290650041175858,0.17115074940136155,2.0943951023931953,3091.9,186.7,59.5,117.4,95.5,475.9 +2.8290568644977565,0.17113299269815374,2.2252947962927703,2776.9,129.5,70.7,91.0,235.6,1059.7 +2.8290629187583827,0.17115771528916368,2.356194490192345,2699.2,93.2,93.8,62.4,1728.0,1728.8 +2.8290597058520577,0.17119008051047757,2.4870941840919194,316.5,70.5,129.6,48.4,1764.2,1823.1 +2.829062624759883,0.17118259624339793,2.6179938779914944,117.5,59.9,94.5,46.5,1950.3,2078.1 +2.8290479293386297,0.17119994485553547,2.748893571891069,62.7,62.7,110.3,63.2,2377.4,2598.3 +2.8290551037705733,0.17119345999098834,2.8797932657906435,46.6,95.0,200.4,117.2,3233.2,3104.9 +2.829044264504704,0.1711985912155456,3.010692959690218,48.2,129.2,70.4,318.6,2857.1,2798.5 +2.8290299869520665,0.1712028330918871,0.0,63.3,93.0,93.0,1698.5,2729.3,2728.8 +2.829054416305752,0.17120516147459353,0.1308996938995747,91.7,119.0,129.6,1742.8,964.3,233.7 +2.829016176456989,0.17119237708797064,0.2617993877991494,116.8,59.3,186.9,1937.6,474.8,95.4 +2.8290022549919978,0.1711826342951539,0.39269908169872414,62.7,63.0,283.8,2381.0,282.2,63.1 +2.8289958767681918,0.17117655764697104,0.5235987755982988,150.4,95.4,474.7,3187.0,187.5,59.9 +2.829001828376681,0.17118380232668096,0.6544984694978736,48.4,234.8,1054.9,2820.9,129.5,70.5 +2.8289975928904774,0.17117028825175362,0.7853981633974483,63.2,1728.8,1728.3,2698.7,93.8,93.3 +2.8289989215770195,0.17119618180220209,0.916297857297023,91.4,1763.7,1822.5,916.8,70.6,129.5 +2.8290032710305617,0.17118331535642906,1.0471975511965976,139.2,1949.4,2077.1,393.6,59.4,95.0 +2.8290142046153126,0.1711631619338141,1.1780972450961724,222.7,2371.9,2591.1,224.2,63.3,110.3 +2.828989879794052,0.17118468951281818,1.3089969389957472,393.5,3233.0,3106.4,139.8,95.5,200.8 +2.828980363007394,0.17118940042752184,1.4398966328953218,923.1,2856.1,2798.2,91.0,128.5,70.1 +2.829029139749703,0.17117728244979724,1.5707963267948966,1699.0,2728.7,2728.8,63.2,93.3,93.1 +2.8290001540498997,0.17117506485045308,1.7016960206944713,1783.5,1065.7,238.0,48.6,122.7,129.3 +2.8289768701573936,0.17116643330709014,1.832595714594046,2030.7,474.5,95.5,47.0,58.8,186.6 +2.829016339111686,0.1711910062606372,1.9634954084936205,2542.5,282.2,63.2,63.6,62.5,283.6 +2.8290220004188895,0.1711978540842105,2.0943951023931953,3091.7,186.7,59.5,117.4,95.5,475.9 +2.8290053760415566,0.17116429248347864,2.2252947962927703,2776.6,129.4,70.7,90.9,235.5,1059.2 +2.829007631121303,0.1711726830586433,2.356194490192345,2699.5,93.2,93.8,62.4,1728.2,1728.9 +2.829004977366465,0.17118947270570883,2.4870941840919194,316.5,70.4,129.6,48.3,1764.2,1823.1 +2.829012070176423,0.17116832043555386,2.6179938779914944,117.6,59.9,94.5,46.5,1951.0,2078.4 +2.8290044673944053,0.17117438080144765,2.748893571891069,62.7,62.7,110.3,63.1,2377.1,2597.8 +2.829020595688756,0.17115955830212126,2.8797932657906435,46.6,95.0,200.4,117.2,3232.8,3105.2 +2.829019760207617,0.17115937753956145,3.010692959690218,48.2,129.2,70.4,318.5,2857.9,2798.7 +2.12888344963668,0.37119166612315535,0.0,263.3,793.0,793.1,1498.7,2029.1,2029.0 +2.1289482023926203,0.3710218288227798,0.1308996938995747,298.6,795.2,854.4,1535.7,1817.6,1001.5 +2.1290976314433223,0.3710690004023467,0.2617993877991494,370.6,868.4,996.0,1706.6,873.6,450.0 +2.1290190725510256,0.371019396043343,0.39269908169872414,506.9,1054.6,1275.3,2097.2,564.5,345.2 +2.1290015926359978,0.37100214852004454,0.5235987755982988,791.3,1490.0,1719.1,2377.5,418.6,291.0 +2.129008754809066,0.37101216628033096,0.6544984694978736,773.2,1616.1,1557.1,2095.8,336.5,277.4 +2.1290063383417075,0.3710069020932145,0.7853981633974483,763.1,1528.9,1528.3,1999.0,293.7,293.1 +2.129006408617461,0.3710377243990395,0.916297857297023,816.1,1556.4,1614.9,1692.0,277.5,336.3 +2.1290074990345698,0.37103722776065906,1.0471975511965976,948.0,1718.3,1845.4,749.1,290.3,417.6 +2.129013845428346,0.3710254626011136,1.1780972450961724,1210.5,2089.0,2308.3,507.4,345.3,564.5 +2.1289841940633423,0.3710531123455809,1.3089969389957472,1706.9,2424.7,2297.3,370.9,493.7,843.7 +2.1289686548681575,0.371062217966287,1.4398966328953218,1534.1,2177.9,2073.4,297.8,852.7,794.4 +2.1290109019173524,0.37105248855344364,1.5707963267948966,1498.8,2029.1,2028.5,263.1,793.3,793.1 +2.128975526723274,0.3710509912068265,1.7016960206944713,1576.3,1846.0,1017.0,255.3,795.0,853.5 +2.128946217214458,0.3710415752562133,1.832595714594046,1799.7,872.9,493.8,278.0,868.2,995.8 +2.1289804250750985,0.37106369548581464,1.9634954084936205,2258.9,564.4,345.3,346.8,1054.7,1275.4 +2.1289820636520767,0.37106689659480585,2.0943951023931953,2283.2,417.6,290.3,516.3,1493.2,1718.7 +2.128962761513452,0.3710617485614631,2.2252947962927703,2052.5,336.3,277.5,815.7,1615.4,1556.8 +2.12896373272481,0.37103228414891176,2.356194490192345,1999.8,293.1,293.7,762.4,1528.5,1528.9 +2.1289615160965503,0.3710450798225866,2.4870941840919194,1087.4,277.4,336.5,773.2,1557.0,1616.1 +2.128970094396931,0.37102027505834667,2.6179938779914944,471.9,291.0,418.7,855.8,1719.2,1847.0 +2.1289651161078855,0.37102342638061514,2.748893571891069,345.4,345.4,565.3,1052.8,2094.3,2314.4 +2.1289842620592516,0.3710068352789888,2.8797932657906435,277.5,493.6,843.1,1513.7,2424.0,2296.3 +2.128986591957067,0.37100597500213994,3.010692959690218,255.1,854.0,795.0,1577.7,2133.0,2074.7 +2.1290297154640814,0.47129838114400746,0.0,363.0,793.1,793.1,1398.9,2029.1,2029.1 +2.1289948995958734,0.4712968309387804,0.1308996938995747,402.0,795.1,854.6,1432.2,2075.1,1385.0 +2.1289349814906893,0.47127854068335506,0.2617993877991494,486.0,868.3,996.0,1590.9,1072.9,693.2 +2.1288777860176165,0.4712427386864957,0.39269908169872414,648.6,1054.4,1275.2,1955.7,705.6,486.3 +2.1288323871148984,0.4711957695687188,0.5235987755982988,856.3,1489.8,1603.6,2378.0,534.2,406.4 +2.1288121265261,0.4711548419598486,0.6544984694978736,773.2,1512.9,1453.6,2096.1,440.0,381.0 +2.128795787448342,0.47109014659771953,0.7853981633974483,763.2,1429.0,1428.6,1998.8,393.7,393.1 +2.128797620960576,0.47106265786391943,0.916297857297023,815.8,1453.2,1511.9,1994.0,381.1,439.8 +2.1288147010661724,0.4710093456813349,1.0471975511965976,947.9,1603.0,1730.1,992.7,405.9,533.2 +2.1288482173786636,0.47095394327743234,1.1780972450961724,1210.3,1948.4,2166.8,649.5,486.4,705.6 +2.128852880456871,0.4709493149889441,1.3089969389957472,1591.0,2424.9,2297.2,486.6,693.2,869.0 +2.128875975764971,0.4709376907865861,1.4398966328953218,1430.8,2132.4,2074.0,401.3,931.4,794.4 +2.1289582934095432,0.470918698763084,1.5707963267948966,1399.1,2029.1,2028.7,363.1,793.2,793.0 +2.128960349746384,0.47091838138559505,1.7016960206944713,1473.3,2073.2,1406.8,358.8,795.1,853.5 +2.1289642752661186,0.4709189885809595,1.832595714594046,1684.0,1072.4,693.1,393.8,868.1,995.8 +2.1290261430394826,0.4709583969618423,1.9634954084936205,2116.7,705.6,486.4,488.7,1023.3,1275.2 +2.1290482301265867,0.470983513040232,2.0943951023931953,2283.5,533.4,405.9,716.0,1493.2,1602.9 +2.1290418905804667,0.47096995676370135,2.2252947962927703,2052.4,439.9,381.0,942.0,1511.6,1453.0 +2.12904877497673,0.47099879027951586,2.356194490192345,1999.4,393.1,393.7,762.4,1428.3,1429.0 +2.129045677232848,0.4710349401166938,2.4870941840919194,1473.1,380.9,439.9,773.0,1453.4,1512.8 +2.129047913329631,0.4710309820718066,2.6179938779914944,715.0,406.5,534.3,855.9,1603.6,1731.5 +2.1290321273274513,0.47105142704226277,2.748893571891069,486.8,486.7,706.8,1053.3,1952.8,2172.7 +2.1290375809160764,0.4710476612319945,2.8797932657906435,393.1,693.1,868.3,1513.8,2423.9,2296.5 +2.129024593107176,0.47105501209842093,3.010692959690218,358.6,923.7,795.0,1474.2,2133.3,2074.4 +2.1290491732341676,0.5713333824301616,0.0,463.0,793.0,793.0,1299.0,2029.3,2028.8 +2.1289983608085534,0.5706860708436248,0.1308996938995747,505.7,795.2,854.6,1328.7,2075.1,1770.4 +2.129026910085255,0.5706954130122075,0.2617993877991494,601.6,868.5,995.7,1475.1,1272.9,849.1 +2.1290620545466923,0.5707180841867823,0.39269908169872414,790.0,1054.4,1275.1,1813.7,847.0,627.6 +2.129090398815719,0.5705507147356075,0.5235987755982988,946.6,1489.6,1488.0,2378.1,649.7,522.1 +2.128786577117599,0.5710733923577911,0.6544984694978736,773.2,1408.9,1349.8,2095.6,543.4,484.4 +2.128778575978906,0.5710409734720834,0.7853981633974483,763.3,1328.9,1328.4,1998.8,493.5,493.2 +2.1287801225932714,0.5710367309083164,0.916297857297023,816.2,1349.7,1408.8,2052.7,484.5,543.5 +2.128792095999511,0.5710019641543842,1.0471975511965976,948.4,1487.8,1615.3,1190.9,521.5,649.0 +2.1288170912749793,0.5709616078665474,1.1780972450961724,1211.5,1808.1,2027.2,790.3,627.9,847.3 +2.1288107335309254,0.5709679457908903,1.3089969389957472,1474.9,2423.8,2296.3,576.4,893.0,985.6 +2.1287832159915183,0.5709793631337801,1.4398966328953218,1327.1,2131.5,2073.5,504.6,852.8,794.6 +2.129059453601581,0.5709184276560288,1.5707963267948966,1298.9,2028.5,2028.7,463.2,793.4,793.1 +2.1289306084852524,0.5709134965813971,1.7016960206944713,1370.0,2118.6,1793.0,462.4,795.2,853.7 +2.128896748240766,0.5709021716906737,1.832595714594046,1569.0,1270.5,891.5,509.4,868.5,996.4 +2.1289499744593883,0.5709359409337065,1.9634954084936205,1976.7,815.0,627.2,630.7,1055.2,1276.5 +2.1289715124858364,0.5709602684917368,2.0943951023931953,2282.4,648.4,521.3,916.6,1494.7,1487.1 +2.1289664797761594,0.5709480055941931,2.2252947962927703,2052.1,543.1,484.6,815.5,1408.1,1349.4 +2.1289745087105656,0.5709792274817367,2.356194490192345,1999.3,493.1,493.6,762.6,1328.3,1329.1 +2.1289717007476847,0.5710183053692892,2.4870941840919194,1854.4,484.4,543.8,773.4,1350.2,1409.6 +2.1289737921023413,0.5710170288753431,2.6179938779914944,913.4,522.4,650.1,856.2,1488.5,1616.2 +2.128956799340762,0.5710400707016956,2.748893571891069,627.8,628.5,848.6,1054.0,1812.3,2032.5 +2.1289607759380407,0.5710383008873436,2.8797932657906435,508.5,893.5,986.2,1515.1,2423.2,2295.6 +2.128945853609343,0.5710470476523077,3.010692959690218,462.1,853.6,795.0,1370.9,2133.0,2074.1 +2.128967804586722,0.6713233819831896,0.0,563.0,793.0,793.2,1198.9,2028.7,2029.2 +2.128956589254166,0.670679553166275,0.1308996938995747,609.1,795.3,854.7,1224.8,2075.0,2071.2 +2.1289937544051436,0.6706915174678492,0.2617993877991494,717.1,868.3,995.5,1359.4,1472.7,1092.9 +2.129070254969403,0.6707425174743884,0.39269908169872414,931.5,1054.5,1275.0,1672.1,988.3,769.0 +2.1290768262990523,0.670751654582594,0.5235987755982988,856.5,1489.3,1372.7,2377.9,765.5,637.7 +2.1291010260342573,0.6707940212865571,0.6544984694978736,773.3,1305.8,1246.7,2096.2,647.0,587.9 +2.129118396466384,0.6708785373345041,0.7853981633974483,763.4,1229.1,1228.4,1999.2,593.5,592.9 +2.1291188373812955,0.6709034516949919,0.916297857297023,815.9,1246.2,1304.9,2051.6,587.9,646.7 +2.1291139371786656,0.6709241808191224,1.0471975511965976,947.8,1371.8,1499.1,1392.3,636.8,763.9 +2.129105237553573,0.6709374742194156,1.1780972450961724,1210.1,1665.7,1884.3,932.8,768.2,987.2 +2.1290544995842526,0.6709859534379135,1.3089969389957472,1360.4,2357.6,2297.5,717.6,996.9,869.3 +2.129014207810924,0.6710094144364871,1.4398966328953218,1224.1,2132.6,2074.0,608.1,852.8,794.6 +2.1290301630721937,0.6710065490545556,1.5707963267948966,1199.2,2029.2,2028.7,563.0,793.4,793.0 +2.128969853163346,0.6710051190586868,1.7016960206944713,1266.4,2072.6,2102.1,565.6,795.0,853.5 +2.128918032486305,0.6709899118627318,1.832595714594046,1452.5,1471.1,1091.7,624.7,868.0,995.7 +2.128968108630095,0.6710252656724316,1.9634954084936205,1833.1,987.8,768.6,771.4,1054.2,1275.1 +2.1289589457365437,0.6710171182738167,2.0943951023931953,2283.9,764.3,636.8,948.3,1492.5,1372.3 +2.1289163477333095,0.6709364612698823,2.2252947962927703,2052.5,646.7,587.9,815.6,1305.0,1246.4 +2.1289229656867708,0.6709680179582083,2.356194490192345,1999.6,592.9,593.4,762.5,1228.7,1229.3 +2.1289228171159995,0.6709321701371613,2.4870941840919194,2095.8,587.8,646.9,773.1,1246.6,1305.6 +2.1289368897805425,0.6708903622866129,2.6179938779914944,1113.7,637.5,765.2,855.8,1372.5,1500.0 +2.128936644735365,0.6708870722283984,2.748893571891069,769.6,769.4,989.1,1052.9,1669.8,1889.6 +2.1289594447736673,0.6708679752919875,2.8797932657906435,624.1,996.1,868.5,1469.4,2361.6,2296.7 +2.1289648862192045,0.6708663480039472,3.010692959690218,565.5,853.9,795.0,1267.8,2133.1,2074.8 +2.1290109327271276,0.7711609017359975,0.0,662.9,793.0,793.1,1099.1,2028.8,2028.9 +2.128978063239118,0.771160435691892,0.1308996938995747,712.5,795.3,854.7,1121.7,2075.1,2134.4 +2.1289192618483233,0.7711433491443282,0.2617993877991494,832.3,868.2,995.6,1244.1,1671.6,1292.1 +2.128862645669282,0.7711087312714351,0.39269908169872414,1051.4,1054.2,1275.0,1530.8,1129.5,909.9 +2.12881742147913,0.7710627659331997,0.5235987755982988,856.5,1385.1,1257.2,2179.4,881.2,753.3 +2.1287972737660477,0.7710227028974252,0.6544984694978736,773.2,1202.5,1143.2,2096.2,750.6,691.3 +2.1287808912269797,0.7709586150473964,0.7853981633974483,763.1,1129.2,1128.5,1999.0,693.5,692.8 +2.128782840708439,0.7709317303232583,0.916297857297023,815.8,1142.5,1201.4,2052.2,691.5,750.2 +2.1288000836797427,0.770879046631314,1.0471975511965976,947.7,1256.1,1383.5,1592.1,752.3,879.4 +2.1288337095329264,0.770824246122527,1.1780972450961724,1210.4,1524.4,1743.6,1074.7,909.4,1055.7 +2.1288384664898556,0.7708204389249118,1.3089969389957472,1244.4,2158.6,2297.4,833.2,1047.2,869.1 +2.128861479117153,0.7708098528485032,1.4398966328953218,1120.7,2132.6,2074.2,711.6,852.9,794.5 +2.12894340622557,0.7707916810522151,1.5707963267948966,1099.0,2028.8,2028.8,663.0,793.4,792.9 +2.128944832922096,0.7707921378449727,1.7016960206944713,1162.9,2073.0,2131.2,669.0,795.1,853.4 +2.12894787947135,0.7707934065789932,1.832595714594046,1337.2,1670.7,1291.1,740.3,868.0,995.7 +2.1290087931523094,0.7708329685640001,1.9634954084936205,1691.7,1128.9,909.9,913.3,1054.4,1275.3 +2.1290300474861477,0.7708577998594397,2.0943951023931953,2283.5,879.9,752.3,1070.6,1383.9,1256.6 +2.12902303823522,0.7708437787028932,2.2252947962927703,2052.8,750.4,691.5,815.6,1201.7,1142.7 +2.129029615927241,0.7708719292914814,2.356194490192345,1999.4,693.0,693.4,762.5,1128.5,1128.9 +2.129026718062351,0.7709072937167747,2.4870941840919194,2141.2,691.5,750.4,773.2,1143.1,1202.2 +2.1290293935628446,0.7709028079847295,2.6179938779914944,1313.0,753.1,880.9,856.0,1256.7,1384.4 +2.129014468270149,0.7709229481342779,2.748893571891069,911.1,910.6,1053.4,1053.0,1528.6,1748.4 +2.1290207320972647,0.7709193064532005,2.8797932657906435,739.6,1047.5,868.5,1337.5,2161.8,2296.6 +2.129008481956006,0.770927130970571,3.010692959690218,669.1,854.0,795.1,1164.4,2132.9,2074.8 +2.129033486444695,0.8712059047136471,0.0,762.9,793.0,793.0,999.4,2029.0,2029.1 +2.1289802553778707,0.8706502706226962,0.1308996938995747,816.4,795.2,854.5,1017.7,2075.4,2134.3 +2.129012344056234,0.870660752461405,0.2617993877991494,948.2,868.3,995.7,1128.3,1871.7,1491.9 +2.1290514634361166,0.87068591917696,0.39269908169872414,1051.3,1054.3,1274.9,1388.6,1270.6,1051.5 +2.129083030614047,0.8707222295003245,0.5235987755982988,856.5,1269.1,1141.5,1980.4,996.8,869.1 +2.1287820190342455,0.8710228618350719,0.6544984694978736,773.2,1098.3,1039.5,2095.8,853.9,795.0 +2.128778485712769,0.8710102017811354,0.7853981633974483,763.4,1028.9,1028.5,1998.4,793.5,793.0 +2.1287798221457104,0.8710126258996884,0.916297857297023,816.0,1039.2,1098.3,2052.4,795.0,854.1 +2.1287911628622584,0.8709800870903892,1.0471975511965976,948.3,1141.1,1268.8,1789.5,868.4,995.5 +2.1288157511958836,0.8709405377446575,1.1780972450961724,1211.5,1384.5,1603.7,1215.1,1051.5,1098.7 +2.128809150525565,0.8709472476544595,1.3089969389957472,1128.2,1961.7,2296.3,948.5,996.5,868.8 +2.1288194722046474,0.8709427364256281,1.4398966328953218,1016.6,2131.4,2073.6,814.9,852.6,794.4 +2.1288884753697177,0.8709274466385712,1.5707963267948966,999.0,2028.7,2028.6,763.2,793.3,793.2 +2.1288779352084553,0.8709270200966768,1.7016960206944713,1059.3,2073.5,2131.8,772.8,795.3,853.6 +2.128870702013208,0.8709240537933627,1.832595714594046,1222.0,1867.5,1488.5,856.4,868.6,996.3 +2.1289232742628537,0.8709576013843447,1.9634954084936205,1551.1,1269.3,1019.3,1055.9,1055.4,1276.2 +2.1289385378119894,0.8709753454985671,2.0943951023931953,2264.7,995.0,867.7,947.9,1267.5,1140.7 +2.1289282371865133,0.8709533475581137,2.2252947962927703,2052.3,853.6,794.9,815.4,1097.7,1039.1 +2.1289337092582263,0.8709736083640738,2.356194490192345,1999.9,793.0,793.7,762.5,1028.2,1029.0 +2.1289312993026956,0.8710019463388177,2.4870941840919194,2095.7,795.1,854.3,773.4,1039.5,1098.7 +2.1289363435693116,0.8709911631148357,2.6179938779914944,1510.2,869.2,997.2,856.3,1141.4,1269.1 +2.1289243502943003,0.8710063608039689,2.748893571891069,1051.8,1053.1,1100.7,1053.8,1388.1,1608.3 +2.128934641629458,0.8709988265407951,2.8797932657906435,855.2,995.4,868.3,1221.1,1964.9,2295.9 +2.1289267492630963,0.8710039488635584,3.010692959690218,772.6,853.8,794.9,1060.2,2132.9,2073.9 +2.8289971166060472,0.17094092413849005,0.0,63.1,93.1,93.2,1698.8,2728.8,2728.9 +2.829015950061986,0.17143871198364136,0.1308996938995747,91.7,118.6,129.8,1743.1,961.5,232.7 +2.8289179140302605,0.171407338552509,0.2617993877991494,116.7,59.4,187.1,1938.3,473.9,95.1 +2.8288582696519002,0.17136857379941817,0.39269908169872414,62.7,63.1,284.2,2382.7,281.9,63.0 +2.8288190003754536,0.17132652654251013,0.5235987755982988,150.7,95.6,475.5,3185.5,187.3,59.8 +2.828804219244886,0.17129431649598503,0.6544984694978736,48.4,235.7,1057.9,2819.7,129.4,70.5 +2.8287912168589657,0.1712404687310478,0.7853981633974483,63.2,1728.8,1728.6,2698.3,93.7,93.3 +2.8287928871153567,0.17122349377722745,0.916297857297023,91.5,1763.8,1822.9,914.4,70.6,129.6 +2.8288069821674853,0.1711797072326613,1.0471975511965976,139.4,1950.5,2077.7,393.0,59.5,94.9 +2.8288354600116743,0.17113249109373596,1.1780972450961724,223.0,2373.4,2592.7,224.0,63.4,110.5 +2.828833422134309,0.17113338265318556,1.3089969389957472,394.2,3232.6,3105.2,139.6,95.8,200.7 +2.828849027573317,0.1711244412633086,1.4398966328953218,839.6,2855.7,2797.3,91.0,128.5,70.2 +2.8289239416081915,0.17110661001882632,1.5707963267948966,1698.8,2729.1,2728.5,63.2,93.2,93.2 +2.828919325728854,0.17110513828745777,1.7016960206944713,1784.3,1063.1,237.4,48.6,121.9,129.4 +2.8289178307835665,0.17110251615343275,1.832595714594046,2031.8,473.9,95.4,47.1,58.9,186.8 +2.8289754974713373,0.17113815901102303,1.9634954084936205,2544.6,282.1,63.3,63.8,62.7,283.9 +2.8290016401232276,0.17116380214889348,2.0943951023931953,3090.7,186.5,59.5,117.6,95.8,476.8 +2.828991443899233,0.171141063293907,2.2252947962927703,2776.7,129.3,70.8,91.0,236.6,1062.7 +2.828997838652869,0.17116485100495815,2.356194490192345,2700.2,93.2,93.9,62.5,1728.1,1728.6 +2.8289948759363215,0.1711980178830661,2.4870941840919194,315.6,70.4,129.7,48.4,1764.3,1823.7 +2.8289980312859546,0.17119158584675698,2.6179938779914944,117.4,59.9,94.6,46.6,1951.3,2079.0 +2.8289827200074957,0.1712102426220392,2.748893571891069,62.6,62.8,110.5,63.3,2378.7,2599.5 +2.8289892613258556,0.17120473143198933,2.8797932657906435,46.6,95.2,200.4,117.5,3231.2,3104.6 +2.82897747584533,0.17121052540625747,3.010692959690218,48.2,129.2,70.5,319.8,2857.3,2798.0 +2.828962329153319,0.1712150407843538,0.0,63.3,93.0,93.2,1698.6,2728.6,2729.0 +2.8289860021033446,0.1712172672250878,0.1308996938995747,91.7,118.4,129.8,1742.9,961.8,233.1 +2.8289467047264543,0.17120394911464887,0.2617993877991494,116.7,59.4,187.1,1938.5,474.2,95.2 +2.82893216787052,0.17119348917585886,0.39269908169872414,62.8,63.2,284.1,2381.8,282.0,63.0 +2.8289256703261745,0.17118669283184573,0.5235987755982988,150.8,95.7,475.5,3185.3,187.3,59.9 +2.8289315303992915,0.17119309984442888,0.6544984694978736,48.5,235.7,1057.6,2820.4,129.4,70.5 +2.8289277447888064,0.17117907649709085,0.7853981633974483,63.3,1729.0,1728.4,2698.7,93.7,93.3 +2.8289282157278297,0.17119969526219503,0.916297857297023,91.5,1763.9,1822.7,914.6,70.6,129.6 +2.8289320949459262,0.17118949483461754,1.0471975511965976,139.4,1950.6,2077.8,393.1,59.4,95.0 +2.8289433302482285,0.17116986168461956,1.1780972450961724,223.0,2373.0,2592.3,223.9,63.3,110.5 +2.828919596581403,0.1711911410575604,1.3089969389957472,394.1,3232.6,3105.0,139.6,95.7,200.8 +2.828910804182813,0.17119532158597295,1.4398966328953218,925.7,2855.7,2797.4,90.9,128.5,70.2 +2.8289604116697102,0.17118332139183812,1.5707963267948966,1699.0,2729.0,2729.0,63.2,93.3,93.2 +2.828932158082789,0.1711811180106224,1.7016960206944713,1784.2,1063.1,237.3,48.5,122.1,129.4 +2.8289096575237562,0.17117222168234814,1.832595714594046,2031.9,473.8,95.3,47.0,58.9,186.8 +2.8289498363663523,0.17119696146318208,1.9634954084936205,2543.7,281.9,63.2,63.7,62.7,284.0 +2.8289560938961307,0.17120423490408143,2.0943951023931953,3089.6,186.5,59.5,117.6,95.7,476.7 +2.8289402132090116,0.17117091146051577,2.2252947962927703,2777.2,129.3,70.7,90.9,236.4,1062.1 +2.8289431108099574,0.17117973654434904,2.356194490192345,2699.4,93.1,93.9,62.4,1728.1,1729.0 +2.8289407104531192,0.17119730294129654,2.4870941840919194,315.7,70.4,129.7,48.4,1764.3,1823.9 +2.828948150088802,0.17117679407030795,2.6179938779914944,117.4,59.9,94.5,46.6,1951.2,2079.2 +2.828940233708725,0.17118369365022823,2.748893571891069,62.6,62.8,110.4,63.3,2378.4,2599.0 +2.8289561210729364,0.1711694747558663,2.8797932657906435,46.6,95.2,200.4,117.5,3231.3,3104.5 +2.828954797465392,0.171169715482542,3.010692959690218,48.2,129.2,70.5,319.7,2856.6,2798.0 +2.028831420210248,0.3711948480394798,0.0,263.3,893.1,893.2,1498.7,1928.8,1928.9 +2.028931511302122,0.3710222339671527,0.1308996938995747,298.6,898.8,958.0,1535.8,1817.4,1001.7 +2.0290830364495696,0.37107001139775164,0.2617993877991494,370.5,983.9,1111.6,1706.6,873.7,493.9 +2.029008188433646,0.37102272018214943,0.39269908169872414,507.0,1196.3,1417.3,2097.2,564.6,345.3 +2.0289910094751957,0.37100575567356686,0.5235987755982988,791.6,1689.1,1719.1,2262.0,418.6,290.9 +2.028997835721388,0.37101507193689964,0.6544984694978736,876.8,1616.1,1557.0,1992.2,336.5,277.4 +2.028995207936557,0.37100871873875896,0.7853981633974483,863.2,1529.0,1528.7,1898.8,293.6,293.1 +2.028995355900232,0.37103840523134823,0.916297857297023,919.6,1556.7,1615.4,1692.2,277.6,336.3 +2.028996803979373,0.3710368704968121,1.0471975511965976,1063.5,1718.4,1845.6,792.9,290.4,417.7 +2.029003723868691,0.37102425529242833,1.1780972450961724,1351.6,2089.1,2308.1,507.6,345.3,564.5 +2.028974775664557,0.37105128433297785,1.3089969389957472,1706.8,2308.9,2181.2,345.4,493.7,872.9 +2.02896001194721,0.37105999613773544,1.4398966328953218,1534.2,2131.7,1970.5,297.8,933.8,897.9 +2.0290030526689655,0.37105009386683463,1.5707963267948966,1498.9,1928.9,1928.6,263.1,893.2,893.0 +2.028968415090029,0.37104861842670367,1.7016960206944713,1576.6,1845.8,1016.9,255.3,898.4,957.0 +2.0289397636142192,0.3710393868045403,1.832595714594046,1799.5,872.9,493.8,278.1,983.8,1111.4 +2.0289745284424665,0.37106182809260346,1.9634954084936205,2258.0,564.3,345.3,346.8,1165.1,1417.3 +2.0289765938957927,0.3710654411692975,2.0943951023931953,2167.8,417.6,290.3,516.3,1692.9,1718.5 +2.0289575830804933,0.37102812759731285,2.2252947962927703,1949.1,336.3,277.5,919.1,1615.2,1556.6 +2.0289588236140825,0.3710324426271372,2.356194490192345,1899.8,293.0,293.6,862.6,1528.4,1528.8 +2.028956591885004,0.3710452414997538,2.4870941840919194,1087.5,277.4,336.5,876.8,1557.4,1616.1 +2.0289651104321305,0.37102079170335944,2.6179938779914944,515.8,290.9,418.7,971.6,1718.8,1847.1 +2.0289599376019147,0.3710243194571743,2.748893571891069,345.4,345.4,565.3,1194.5,2094.2,2314.4 +2.028978796697817,0.37100803731002974,2.8797932657906435,277.5,493.6,873.5,1713.0,2308.3,2181.4 +2.028980781376404,0.371007384869096,3.010692959690218,255.1,934.5,898.6,1578.0,2029.6,1970.6 +2.0290234621340484,0.4712994486875486,0.0,363.0,893.1,893.0,1399.1,1928.8,1928.9 +2.0289883465346477,0.47129788719029553,0.1308996938995747,402.0,898.8,958.2,1432.0,1971.7,1385.4 +2.0289282029667826,0.4712795146737696,0.2617993877991494,486.1,983.9,1111.4,1591.0,1073.0,693.3 +2.0288708461715332,0.471243585200102,0.39269908169872414,648.6,1196.2,1417.1,1955.6,705.7,455.3 +2.028825346439945,0.4711964624288485,0.5235987755982988,971.8,1689.2,1603.5,2262.3,534.1,406.5 +2.0288050419592354,0.4711553745760906,0.6544984694978736,876.8,1513.1,1453.6,1992.4,439.9,380.9 +2.028788709816258,0.4710905270443535,0.7853981633974483,863.0,1428.8,1428.5,1898.7,393.6,393.1 +2.028790589160993,0.47106290865171707,0.916297857297023,919.3,1452.9,1512.0,1948.7,381.0,439.8 +2.028807741566971,0.4710094956836761,1.0471975511965976,1063.5,1603.0,1730.4,992.6,405.9,533.2 +2.028841343195471,0.47095402445643475,1.1780972450961724,1351.4,1948.2,2167.5,649.4,486.4,705.6 +2.028846091857019,0.4709493548286088,1.3089969389957472,1591.3,2309.3,2181.9,486.5,692.9,984.6 +2.0288692671667836,0.47093770916574385,1.4398966328953218,1430.9,2029.0,1969.9,401.3,956.4,897.7 +2.0289516572552957,0.470918710508077,1.5707963267948966,1399.1,1928.9,1928.7,363.2,893.2,893.3 +2.0289537776061963,0.4709183938211621,1.7016960206944713,1473.1,1969.7,1407.0,358.9,898.7,957.0 +2.0289577629259794,0.47091900552633104,1.832595714594046,1683.8,1072.1,649.2,393.7,983.9,1111.3 +2.0290196894378254,0.4709584245772702,1.9634954084936205,2116.9,674.6,486.4,488.6,1196.5,1417.2 +2.0290418345152945,0.4709835589647371,2.0943951023931953,2167.9,533.2,405.9,716.1,1692.7,1602.7 +2.0290355516005185,0.4709700303033244,2.2252947962927703,1949.2,439.8,381.1,1008.1,1511.9,1452.8 +2.029042487122041,0.4709989047687433,2.356194490192345,1900.1,393.0,393.6,862.6,1428.3,1429.0 +2.0290394283607562,0.47103510868169196,2.4870941840919194,1472.9,381.0,440.0,876.8,1453.4,1512.4 +2.0290416871327737,0.4710312122721618,2.6179938779914944,671.2,406.5,534.2,971.6,1603.2,1731.2 +2.029025901431526,0.47105172168628795,2.748893571891069,486.6,486.8,706.9,1194.6,1953.0,2172.8 +2.0290313349220352,0.4710480130306902,2.8797932657906435,393.1,693.2,983.9,1708.8,2308.6,2181.1 +2.0290183088912888,0.47105540617425845,3.010692959690218,358.6,957.5,898.6,1474.4,2029.5,1970.8 +2.0290428217221397,0.5713337204037923,0.0,463.0,893.0,893.3,1298.9,1929.0,1928.5 +2.028992941292135,0.5706832648731277,0.1308996938995747,505.7,898.9,958.1,1328.5,2033.3,1770.4 +2.029022013254923,0.5706927645509154,0.2617993877991494,601.6,983.9,1111.4,1475.1,1272.7,893.1 +2.0290575383162555,0.5707156589380211,0.39269908169872414,790.1,1196.1,1416.9,1814.1,847.0,627.6 +2.029086152890837,0.5707488046912053,0.5235987755982988,972.2,1615.8,1488.3,2262.7,649.9,522.2 +2.02911397333477,0.5707982929103042,0.6544984694978736,876.9,1409.1,1350.4,1992.6,543.4,484.4 +2.029119380876453,0.5708277611786954,0.7853981633974483,863.2,1328.9,1328.6,1898.6,493.5,493.1 +2.0291184982374606,0.5708894620115996,0.916297857297023,919.5,1349.7,1408.4,1993.8,484.4,543.2 +2.029111612064763,0.570916019384361,1.0471975511965976,1063.5,1487.5,1614.9,1192.1,521.2,648.4 +2.029104557997802,0.5709264409180428,1.1780972450961724,1351.5,1807.2,2026.0,790.9,627.3,846.2 +2.0290580448296645,0.5709707583413186,1.3089969389957472,1475.9,2309.5,2181.4,602.1,891.7,1027.9 +2.0290234046706574,0.5709910102401183,1.4398966328953218,1327.5,2028.6,1970.4,504.7,956.4,897.9 +2.0290455881126905,0.5709866998270574,1.5707963267948966,1299.0,1929.0,1929.0,462.9,893.4,893.1 +2.028991201651939,0.570985449216963,1.7016960206944713,1369.8,2064.8,1796.4,462.0,898.4,956.8 +2.028903026852372,0.5709558032068673,1.832595714594046,1568.3,1271.4,892.1,509.0,983.8,1111.3 +2.0291256496499295,0.5710988653391433,1.9634954084936205,1975.5,846.6,627.4,629.9,1196.2,1417.1 +2.029023349013333,0.5709913405477094,2.0943951023931953,2168.0,648.6,521.3,915.1,1614.9,1487.8 +2.0289818597415237,0.5709128053909946,2.2252947962927703,1949.5,543.2,484.4,919.1,1408.4,1349.9 +2.0289798120953937,0.5709041524280918,2.356194490192345,1899.7,492.9,493.5,862.4,1328.6,1329.0 +2.028977642141753,0.5709142427110288,2.4870941840919194,1859.0,484.3,543.3,876.7,1350.4,1409.2 +2.0289860770601114,0.5708904571210469,2.6179938779914944,914.3,522.1,649.6,971.4,1488.0,1615.7 +2.0289804071235844,0.5708955108580898,2.748893571891069,628.1,628.0,847.7,1194.5,1811.3,2031.4 +2.0289982855271953,0.5708808731532149,2.8797932657906435,508.6,892.3,1028.5,1568.3,2308.9,2181.4 +2.0289989693725676,0.5708816976668507,3.010692959690218,462.0,957.3,898.6,1371.0,2029.6,1970.8 +2.02903966134897,0.6711723479582785,0.0,562.9,893.1,893.1,1199.1,1928.8,1928.8 +2.029003020860567,0.6711717517527185,0.1308996938995747,609.0,898.8,958.1,1225.1,1971.5,2030.9 +2.028941453372027,0.67115384427112,0.2617993877991494,716.9,958.5,1111.3,1359.8,1471.8,1092.1 +2.0288827052592264,0.6711179617826515,0.39269908169872414,931.4,1196.1,1416.7,1672.1,988.0,768.7 +2.0288359167489154,0.6710704373052752,0.5235987755982988,1113.0,1500.1,1372.5,2262.3,765.4,637.6 +2.0288146747768727,0.6710286166360275,0.6544984694978736,876.6,1305.8,1246.8,1992.6,646.9,587.8 +2.028797757406844,0.6709627182597395,0.7853981633974483,863.1,1229.2,1228.4,1898.8,593.4,592.9 +2.0287995994450627,0.6709340369086123,0.916297857297023,919.5,1246.2,1304.9,1948.5,587.9,646.7 +2.0288171846477785,0.6708796895743747,1.0471975511965976,1063.2,1371.9,1499.2,1392.1,636.7,764.2 +2.0288515552485387,0.6708235296743899,1.1780972450961724,1351.4,1665.8,1884.8,932.4,768.4,987.5 +2.028831304632188,0.6708474027237088,1.3089969389957472,1360.2,2309.4,2181.8,717.7,1091.0,984.6 +2.0288782661063185,0.6708238673705573,1.4398966328953218,1224.0,2029.1,1970.5,608.2,956.3,897.9 +2.0289664864932053,0.6708042827653988,1.5707963267948966,1198.8,1928.8,1928.7,563.1,893.3,893.1 +2.028967812153859,0.6708047526774896,1.7016960206944713,1266.4,1969.5,2027.8,565.6,898.5,956.8 +2.02896889105335,0.6708054035723041,1.832595714594046,1452.8,1471.0,1091.7,624.8,983.6,1111.3 +2.0290275790714247,0.6708436653703389,1.9634954084936205,1833.4,987.9,768.6,771.7,1196.1,1417.0 +2.029046981859719,0.6708667174140257,2.0943951023931953,2168.0,764.3,636.9,1063.7,1499.4,1372.2 +2.0290387309945603,0.6708505826155629,2.2252947962927703,1949.3,646.9,587.9,919.2,1305.2,1246.5 +2.0290446650817033,0.6708764984041031,2.356194490192345,1899.1,593.0,593.5,862.6,1228.3,1229.1 +2.0290416665691393,0.6709097158318118,2.4870941840919194,1992.8,587.9,647.0,876.6,1246.8,1305.5 +2.02904481742882,0.670903253289227,2.6179938779914944,1113.4,637.5,765.2,971.4,1372.5,1500.1 +2.0290307300099077,0.6709217449673235,2.748893571891069,769.6,769.3,989.3,1194.7,1670.0,1889.9 +2.0290382038269668,0.6709168227268703,2.8797932657906435,624.2,1091.7,983.8,1452.6,2308.5,2180.9 +2.029027352392226,0.6709237994359667,3.010692959690218,565.5,957.2,898.7,1267.6,2029.9,1970.9 +2.0290541388330747,0.7712039349986668,0.0,662.9,893.1,893.1,1099.1,1929.0,1929.1 +2.028996656775831,0.7706480433128091,0.1308996938995747,712.8,898.7,958.2,1121.5,1971.9,2031.0 +2.0290281329288598,0.7706583700312815,0.2617993877991494,832.7,983.9,1111.3,1244.2,1671.8,1292.0 +2.029067303094543,0.7706836378738677,0.39269908169872414,1073.2,1196.1,1416.7,1530.2,1129.3,909.9 +2.0290990499062893,0.7707202437996712,0.5235987755982988,972.0,1384.5,1257.1,2179.7,881.0,753.4 +2.028785801677546,0.7710224024620531,0.6544984694978736,876.7,1202.0,1142.9,1991.9,750.4,691.5 +2.028782128592067,0.7710091488766468,0.7853981633974483,863.2,1128.8,1128.4,1898.6,693.6,693.2 +2.0287834488365806,0.7710118177157501,0.916297857297023,919.5,1142.8,1201.7,1948.8,691.7,750.5 +2.028794639238346,0.7709797481336029,1.0471975511965976,1063.8,1256.8,1384.1,1589.7,752.7,880.1 +2.028818938265578,0.7709406585942613,1.1780972450961724,1352.5,1525.7,1744.7,1073.7,910.3,1129.6 +2.0288119549114625,0.7709477236970546,1.3089969389957472,1243.9,2161.0,2180.6,833.0,1111.8,984.3 +2.028821840440103,0.7709434415751382,1.4398966328953218,1120.2,2028.5,1970.2,711.6,956.1,897.9 +2.028890390728553,0.7709282617509976,1.5707963267948966,1099.1,1928.7,1928.8,663.2,893.3,893.1 +2.028879425432829,0.7709278267156467,1.7016960206944713,1163.0,1970.0,2074.0,669.2,875.9,957.2 +2.028871813571739,0.7709247485268202,1.832595714594046,1337.6,1668.3,1289.7,740.6,984.3,1112.0 +2.028924066789086,0.7709581064250777,1.9634954084936205,1692.6,1128.3,878.3,914.1,1197.0,1418.1 +2.028939089300862,0.7709756090096855,2.0943951023931953,2167.3,879.4,726.9,1063.2,1383.4,1256.3 +2.0289286334061996,0.7709533366927084,2.2252947962927703,1948.8,750.3,691.7,919.0,1201.1,1142.4 +2.028934031165982,0.7709733112909134,2.356194490192345,1899.6,693.0,693.7,862.6,1128.4,1129.2 +2.028931620828703,0.7710013758689642,2.4870941840919194,2069.8,691.5,750.7,876.9,1143.4,1202.3 +2.0289367343606823,0.7709903474852564,2.6179938779914944,1311.4,753.6,881.6,971.9,1257.3,1385.2 +2.028924859173551,0.7710053432340935,2.748893571891069,910.5,911.4,1131.7,1195.4,1529.2,1749.5 +2.0289353085866337,0.7709976576170752,2.8797932657906435,739.5,1111.0,983.9,1336.4,2164.7,2180.2 +2.0289275944539633,0.7710026838341559,3.010692959690218,669.0,957.1,898.7,1163.7,2029.3,1970.6 +2.0289581996540242,0.8712855885475348,0.0,763.1,893.1,893.2,999.1,1929.1,1928.8 +2.0289146524958697,0.8712840157596655,0.1308996938995747,816.6,899.1,958.4,1017.8,1971.7,2031.4 +2.0288481631072215,0.8712637562925118,0.2617993877991494,948.7,984.3,1112.0,1129.0,1868.8,1489.6 +2.028786027855449,0.8712247235509074,0.39269908169872414,1191.7,1196.8,1414.8,1389.9,1269.6,1050.5 +2.028737325448919,0.8711737635594743,0.5235987755982988,971.7,1268.6,1141.0,1982.7,996.2,868.7 +2.028715017581527,0.8711283618074752,0.6544984694978736,876.7,1098.4,1039.4,1991.9,854.0,795.0 +2.028698283162429,0.8710593418395516,0.7853981633974483,863.2,1028.9,1028.5,1898.7,793.5,793.0 +2.028700712706549,0.8710277601457612,0.916297857297023,919.6,1039.2,1098.0,1948.9,795.1,854.0 +2.028719397787603,0.8709709775241055,1.0471975511965976,1064.0,1141.2,1268.6,1789.5,868.2,995.6 +2.0287553059867296,0.8709132024996731,1.1780972450961724,1352.3,1384.2,1603.6,1215.5,1051.4,1196.9 +2.028762525401654,0.8709068982215413,1.3089969389957472,1128.4,1961.9,2181.0,948.7,1247.9,984.5 +2.028788219125695,0.8708941477716861,1.4398966328953218,1016.9,2028.5,1970.4,815.0,956.2,897.9 +2.0288730951572944,0.8708751737836247,1.5707963267948966,998.8,1928.7,1928.5,763.1,893.5,893.2 +2.0288773642356954,0.8708752179036765,1.7016960206944713,1059.5,1969.8,2028.4,772.8,898.8,957.1 +2.0288832649297683,0.8708762457833628,1.832595714594046,1221.7,1867.7,1488.8,856.3,984.1,1111.8 +2.02894675972354,0.8709166451546966,1.9634954084936205,1551.0,1269.2,1050.4,1056.1,1197.0,1414.2 +2.0289700888901474,0.8709430610064086,2.0943951023931953,2167.1,995.1,867.7,1063.5,1267.6,1140.6 +2.0289648740226065,0.8709306572134141,2.2252947962927703,1948.6,853.7,795.0,919.1,1097.7,1039.0 +2.028972595011128,0.8709608104857898,2.356194490192345,1899.5,793.0,793.7,862.4,1028.1,1029.0 +2.0289698209123044,0.8709985510735738,2.4870941840919194,1992.6,795.2,854.3,876.9,1039.6,1098.7 +2.028972303463115,0.8709960211475858,2.6179938779914944,1510.4,869.3,997.0,971.8,1141.5,1269.2 +2.0289560309344865,0.871018014484104,2.748893571891069,1052.0,1053.1,1194.2,1195.4,1387.8,1608.2 +2.028960908613623,0.8710155061665892,2.8797932657906435,855.2,1249.0,983.7,1221.1,1965.0,2180.4 +2.028946982671858,0.8710238360044853,3.010692959690218,772.5,957.2,898.3,1060.4,2029.3,1970.2 +2.8290163667550017,0.17097030202400743,0.0,63.1,93.1,93.2,1699.1,2728.8,2729.3 +2.8290260089008012,0.17143811313699908,0.1308996938995747,91.7,118.6,129.8,1743.3,961.5,232.7 +2.8289250648912017,0.17140584296229733,0.2617993877991494,116.7,59.4,187.1,1938.4,474.0,95.1 +2.828864908535651,0.17136677711886783,0.39269908169872414,62.7,63.1,284.2,2382.4,281.9,62.9 +2.8288257306573557,0.1713248691517435,0.5235987755982988,150.7,95.6,475.5,3185.4,187.3,59.8 +2.828811106090062,0.17129301305685352,0.6544984694978736,48.4,235.6,1057.7,2819.6,129.4,70.5 +2.828798162208911,0.1712395884134701,0.7853981633974483,63.2,1728.6,1728.4,2699.3,93.7,93.3 +2.828799787150319,0.17122303147990636,0.916297857297023,91.5,1763.7,1822.8,914.5,70.6,129.6 +2.8288137373929936,0.17117961434911821,1.0471975511965976,139.4,1950.2,2078.0,393.0,59.5,94.9 +2.8288419944704652,0.17113268375281443,1.1780972450961724,223.0,2373.2,2592.8,224.0,63.4,110.5 +2.828839701534894,0.1711337837738809,1.3089969389957472,394.1,3233.3,3105.2,139.7,95.8,200.8 +2.8288550339178613,0.17112498055410574,1.4398966328953218,839.8,2855.7,2797.1,91.0,128.4,70.2 +2.828929670751998,0.17110719719353673,1.5707963267948966,1698.9,2728.3,2728.2,63.2,93.2,93.2 +2.828924800437884,0.1711057169952439,1.7016960206944713,1784.1,1063.2,237.4,48.6,121.9,129.4 +2.8289230747264553,0.17110304603324855,1.832595714594046,2031.6,473.8,95.4,47.1,58.9,186.8 +2.8289805435657347,0.17113858536583249,1.9634954084936205,2544.1,282.0,63.3,63.8,62.7,284.0 +2.828999575183565,0.17115957062104115,2.0943951023931953,3090.3,186.5,59.5,117.7,95.8,476.8 +2.8289917963797078,0.17114138303778859,2.2252947962927703,2776.5,129.4,70.8,90.9,236.5,1062.5 +2.828998306517694,0.1711658420094151,2.356194490192345,2699.5,93.2,93.9,62.5,1727.9,1729.0 +2.8289953371529273,0.1711983174813616,2.4870941840919194,315.6,70.4,129.7,48.4,1764.7,1823.8 +2.8289987638158,0.171190874858693,2.6179938779914944,117.4,59.9,94.6,46.6,1951.3,2079.4 +2.82898403068816,0.17120856421484132,2.748893571891069,62.6,62.8,110.4,63.3,2379.2,2599.5 +2.8289913408905325,0.17120230247400348,2.8797932657906435,46.6,95.2,200.4,117.5,3231.3,3104.1 +2.8289804418162148,0.1712076052705802,3.010692959690218,48.3,129.2,70.5,319.7,2857.2,2798.4 +2.8289662173290013,0.17121189850969065,0.0,63.3,93.0,93.2,1698.9,2728.4,2729.3 +2.82899086872821,0.17121416944002665,0.1308996938995747,91.7,118.4,129.8,1742.8,962.0,233.0 +2.828952290498529,0.17120108180410787,0.2617993877991494,116.7,59.4,187.1,1938.4,474.1,95.3 +2.8289383726337842,0.17119102908045614,0.39269908169872414,62.8,63.2,284.2,2382.3,282.0,63.0 +2.828932330479102,0.17118475748609518,0.5235987755982988,150.8,95.7,475.4,3185.3,187.3,59.9 +2.8289384730800196,0.17119174658937242,0.6544984694978736,48.5,235.7,1057.7,2820.1,129.5,70.5 +2.828934788874713,0.1711783121341155,0.7853981633974483,63.3,1728.6,1728.6,2698.6,93.7,93.3 +2.828935213038147,0.17119948236861515,0.916297857297023,91.5,1764.2,1822.9,914.7,70.6,129.6 +2.8289389154507636,0.1711897641205684,1.0471975511965976,139.4,1950.2,2077.8,393.0,59.4,95.0 +2.8289498753999682,0.17117050903432718,1.1780972450961724,223.0,2373.2,2592.4,224.0,63.3,110.5 +2.8289258163123274,0.1711920640346798,1.3089969389957472,394.1,3232.4,3104.4,139.7,95.7,200.8 +2.828916671062579,0.17119642416536807,1.4398966328953218,925.5,2855.7,2797.7,90.9,128.5,70.2 +2.8289659188415053,0.1711844913545646,1.5707963267948966,1698.5,2728.6,2728.4,63.2,93.3,93.2 +2.828937333829223,0.17118227594752433,1.7016960206944713,1783.9,1063.2,237.4,48.5,122.1,129.4 +2.828914535141755,0.1711733070690269,1.832595714594046,2031.5,473.8,95.3,47.0,58.9,186.8 +2.8289544607320276,0.1711979062490383,1.9634954084936205,2543.8,282.0,63.2,63.7,62.6,283.9 +2.828960522496012,0.17120499482612916,2.0943951023931953,3091.0,186.5,59.5,117.6,95.7,476.6 +2.8289444986193857,0.17117147038403613,2.2252947962927703,2776.7,129.4,70.7,90.9,236.4,1062.0 +2.8289473114655768,0.17118007736846286,2.356194490192345,2699.8,93.2,93.9,62.4,1728.1,1728.8 +2.8289448914917195,0.1711974191871719,2.4870941840919194,315.6,70.4,129.7,48.4,1764.1,1823.6 +2.828952357746622,0.1711767069943151,2.6179938779914944,117.4,59.9,94.5,46.6,1951.1,2079.0 +2.828944529099704,0.17118342342963389,2.748893571891069,62.6,62.8,110.4,63.3,2378.8,2598.6 +2.8289605336177495,0.17116906403483445,2.8797932657906435,46.6,95.1,200.4,117.5,3231.2,3104.4 +2.828959354937457,0.17116921025837373,3.010692959690218,48.2,129.1,70.5,319.6,2856.6,2798.0 +1.9288474950024368,0.3711891725999359,0.0,263.3,992.8,993.1,1498.8,1829.0,1829.3 +1.9289382427592532,0.37102466869589534,0.1308996938995747,298.6,1002.3,1061.8,1535.9,1817.6,1001.4 +1.9290883217282373,0.37107200937169416,0.2617993877991494,370.6,1099.7,1227.2,1706.3,873.7,493.9 +1.9290118473360922,0.3710236983564532,0.39269908169872414,506.9,1337.8,1558.6,2096.8,564.6,345.3 +1.9289943427649154,0.37100639403182867,0.5235987755982988,791.5,1872.2,1719.2,2146.6,418.6,290.9 +1.9290011513956689,0.3710157009128823,0.6544984694978736,980.2,1616.2,1557.1,1888.7,336.5,277.4 +1.9289985368356555,0.37100946950825375,0.7853981633974483,963.2,1529.1,1528.5,1798.6,293.7,293.1 +1.9289986629804856,0.3710393093276385,0.916297857297023,1022.9,1556.3,1615.5,1692.0,277.6,336.3 +1.9290000483681005,0.3710379188135249,1.0471975511965976,1178.9,1718.6,1845.6,792.8,290.3,417.7 +1.9290068751581608,0.371025419244265,1.1780972450961724,1492.9,2089.2,2308.2,507.5,345.3,564.4 +1.9289778179225772,0.3710525283141288,1.3089969389957472,1706.2,2193.5,2066.1,370.8,493.8,872.9 +1.9289629390012508,0.3710612862246232,1.4398966328953218,1534.0,1925.6,1867.2,297.8,1016.8,1001.4 +1.9290058664719134,0.37105139962469025,1.5707963267948966,1499.0,1829.2,1828.5,263.1,993.4,993.1 +1.9289711267843948,0.3710499149580937,1.7016960206944713,1576.7,1845.4,1017.0,255.3,1002.1,1060.5 +1.9289423858919983,0.37104065488310156,1.832595714594046,1799.6,872.9,493.7,278.0,1099.2,1227.1 +1.9289770747442794,0.3710630526106564,1.9634954084936205,2258.8,564.4,345.3,346.8,1337.9,1559.1 +1.9289790795869128,0.3710666122054689,2.0943951023931953,2052.1,417.6,290.2,516.3,1871.0,1718.4 +1.928960023381732,0.37102923866590576,2.2252947962927703,1845.2,336.4,277.5,1022.4,1615.6,1556.6 +1.9289612335802613,0.37103348842535877,2.356194490192345,1799.6,293.1,293.6,962.6,1528.4,1529.0 +1.9289589873375996,0.3710462198334179,2.4870941840919194,1087.3,277.4,336.5,980.1,1557.1,1616.4 +1.9289675072069017,0.37102170444007965,2.6179938779914944,515.9,291.0,418.6,1087.1,1718.9,1846.9 +1.9289623518198664,0.37102517128850354,2.748893571891069,345.3,345.4,565.4,1335.9,2094.1,2314.2 +1.9289812422366939,0.3710088378250733,2.8797932657906435,277.6,493.7,873.4,1798.9,2192.9,2065.4 +1.9289832695755476,0.3710081472373652,3.010692959690218,255.1,1009.1,1001.9,1578.0,1926.2,1867.0 +1.9290260131036558,0.4713002589119588,0.0,363.0,993.0,992.9,1399.1,1828.7,1828.8 +1.9289909381061556,0.4712986916428139,0.1308996938995747,402.1,1002.4,1061.7,1432.4,1868.5,1385.3 +1.928930827854254,0.47128032797423836,0.2617993877991494,486.0,1099.7,1227.0,1590.9,1072.9,693.1 +1.928873494419123,0.4712444170888703,0.39269908169872414,648.6,1338.0,1558.6,1955.6,674.6,486.3 +1.9288280070416903,0.47119731885774585,0.5235987755982988,990.5,1731.4,1603.5,2146.3,534.1,406.6 +1.928807703392442,0.4711562569296366,0.6544984694978736,980.2,1512.6,1453.7,1888.5,439.9,380.9 +1.928791361781122,0.4710914328103568,0.7853981633974483,963.2,1429.0,1428.5,1798.8,393.6,393.0 +1.928793223980008,0.4710638314260731,0.916297857297023,1022.9,1453.4,1512.1,1845.2,381.1,439.8 +1.9288103553682991,0.47101042731359977,1.0471975511965976,1179.0,1602.6,1730.1,992.4,405.9,533.2 +1.9288439362973484,0.4709549567470679,1.1780972450961724,1492.7,1947.9,2167.2,649.3,486.5,705.5 +1.9288486679095052,0.4709502814643154,1.3089969389957472,1591.0,2193.6,2066.0,486.6,693.1,1072.3 +1.9288718316553437,0.4709386268642668,1.4398966328953218,1430.8,1925.0,1867.1,401.3,1059.9,1001.1 +1.9289542158999722,0.47091961943128324,1.5707963267948966,1398.7,1829.1,1828.4,363.1,993.1,993.1 +1.928956334386292,0.4709192968667091,1.7016960206944713,1473.4,1866.2,1406.9,358.8,1002.0,1060.3 +1.928960319293902,0.47091990694632946,1.832595714594046,1684.0,1072.4,693.0,393.7,1099.5,1201.5 +1.929022244003265,0.47095932855769895,1.9634954084936205,2116.8,705.6,486.5,488.6,1338.0,1559.1 +1.9290443835177307,0.4709844678999797,2.0943951023931953,2052.2,533.2,406.0,716.1,1729.9,1602.8 +1.929038090438366,0.4709709439129497,2.2252947962927703,1845.5,439.9,381.0,1022.6,1511.8,1453.4 +1.9290450118433424,0.470999820026091,2.356194490192345,1799.4,393.1,393.7,962.6,1428.4,1429.0 +1.9290419370607192,0.471036020501888,2.4870941840919194,1472.9,380.9,440.0,980.2,1453.7,1512.8 +1.9290441807857812,0.4710321150084418,2.6179938779914944,715.1,406.6,534.3,1087.1,1603.8,1731.1 +1.929028384060411,0.47105261051532876,2.748893571891069,486.8,486.8,706.7,1336.1,1952.7,2172.7 +1.9290338124660278,0.4710488856192754,2.8797932657906435,393.1,693.0,1073.0,1683.6,2192.7,2066.0 +1.929020788039411,0.4710562632971518,3.010692959690218,358.6,1060.9,1002.0,1474.4,1926.1,1867.3 +1.9290453136954018,0.5713345873575557,0.0,463.0,993.0,993.0,1299.1,1829.0,1829.1 +1.9289944462784236,0.5706828993444193,0.1308996938995747,505.6,1002.3,1061.5,1328.5,1868.2,1770.1 +1.929023370850585,0.5706923562994626,0.2617993877991494,601.8,1099.6,1226.9,1475.5,1272.8,893.0 +1.929058900357656,0.5707152590939211,0.39269908169872414,790.0,1337.7,1558.5,1813.7,847.0,627.6 +1.9290875504076943,0.570748451356651,0.5235987755982988,1087.7,1615.8,1488.3,2146.8,649.9,522.1 +1.92911539371183,0.570798000738511,0.6544984694978736,980.2,1409.2,1350.1,1889.1,543.6,484.4 +1.9291208106129214,0.5708275376700211,0.7853981633974483,963.4,1329.1,1328.6,1798.7,493.6,493.0 +1.9291199164714798,0.5708892993698056,0.916297857297023,1023.1,1349.8,1408.4,1909.4,484.4,543.1 +1.9291130054598205,0.5709159083827513,1.0471975511965976,1178.9,1487.4,1614.6,1192.0,521.2,648.6 +1.9291059193418678,0.5709263740062518,1.1780972450961724,1492.9,1806.8,2026.3,759.6,627.3,846.4 +1.9290593674627476,0.5709707200802356,1.3089969389957472,1475.9,2193.7,2066.1,602.0,891.8,1100.4 +1.9288741491220458,0.5708306841245843,1.4398966328953218,1327.2,1925.2,1866.8,504.6,1059.6,1001.2 +1.9291212255704175,0.570776381369483,1.5707963267948966,1298.8,1829.1,1828.6,463.0,993.4,993.1 +1.9290003686873125,0.570772189281102,1.7016960206944713,1369.7,1866.2,1794.6,462.3,1002.1,1060.5 +1.9289804666961072,0.5707658066693915,1.832595714594046,1568.4,1270.9,891.8,509.3,1099.7,1227.2 +1.9290471268693412,0.5708086979139195,1.9634954084936205,1975.8,846.3,627.4,630.5,1338.4,1559.4 +1.9290788706300377,0.5708447908174121,2.0943951023931953,2051.8,648.6,521.3,916.1,1614.4,1487.1 +1.929080071520772,0.5708456230961769,2.2252947962927703,1845.4,543.2,484.5,1022.5,1408.3,1349.3 +1.9290905770707654,0.5708901713334498,2.356194490192345,1799.4,493.0,493.6,962.4,1328.2,1329.1 +1.929086938444303,0.5709416814278707,2.4870941840919194,1856.0,484.3,543.5,980.4,1350.0,1409.4 +1.9290853343323784,0.5709512725110086,2.6179938779914944,913.6,522.1,649.9,1087.5,1488.5,1616.0 +1.92906269604957,0.5709831692317822,2.748893571891069,627.8,628.3,848.4,1336.7,1812.1,2032.1 +1.9290595730693902,0.5709880444144797,2.8797932657906435,508.5,892.7,1099.4,1567.7,2192.0,2065.2 +1.9290368283828925,0.5710011859969961,3.010692959690218,461.9,1060.9,1002.2,1371.1,1925.9,1867.0 +1.9290493099632493,0.6712704421123754,0.0,562.8,993.2,993.0,1198.9,1828.8,1828.9 +1.9290007770352162,0.670653657138035,0.1308996938995747,609.2,1002.3,1061.7,1225.0,1868.5,1927.6 +1.9290331479132,0.6706642532643758,0.2617993877991494,717.2,1099.5,1227.1,1359.5,1472.1,1092.3 +1.9290719673217984,0.6706893174334256,0.39269908169872414,931.7,1337.8,1558.5,1672.3,988.2,768.7 +1.9291031771702989,0.6707253743605175,0.5235987755982988,1145.8,1499.8,1372.4,2146.4,765.3,637.8 +1.9287865172991245,0.6710232406106964,0.6544984694978736,980.4,1305.2,1246.2,1888.4,646.9,587.9 +1.9287825922287083,0.6710088832271579,0.7853981633974483,963.3,1228.8,1228.7,1798.7,593.6,593.1 +1.9287839210634423,0.6710113258845831,0.916297857297023,1023.2,1246.3,1305.5,1845.5,588.0,646.9 +1.928795095787063,0.6709793133566269,1.0471975511965976,1179.4,1372.5,1499.7,1390.3,637.1,764.6 +1.9288508305242111,0.6708896859866826,1.1780972450961724,1493.6,1666.9,1885.9,932.0,769.1,988.3 +1.9286619636189581,0.6710640258415397,1.3089969389957472,1359.7,2192.6,2065.4,717.3,1092.7,1228.9 +1.9287890391090328,0.6709979723129471,1.4398966328953218,1223.8,1925.1,1866.6,608.0,1059.5,1001.3 +1.9288888067691816,0.6709757819375279,1.5707963267948966,1198.9,1828.9,1828.7,563.0,993.3,993.2 +1.9288788231272882,0.6709754389850959,1.7016960206944713,1266.6,1866.5,1924.9,565.8,1002.1,1037.9 +1.9288631351665917,0.6709699372382827,1.832595714594046,1453.3,1468.9,1090.4,625.0,1099.9,1227.5 +1.928906061556715,0.6709974672373586,1.9634954084936205,1834.8,987.1,768.2,772.3,1338.6,1560.0 +1.9289135347310962,0.671006877698753,2.0943951023931953,2051.6,764.0,636.7,1116.3,1498.8,1371.6 +1.9288981520252908,0.6709753859081917,2.2252947962927703,1845.4,646.6,587.9,1022.3,1304.7,1245.9 +1.9289013259734946,0.6709857424113455,2.356194490192345,1799.7,593.1,593.6,962.5,1228.5,1229.0 +1.9288992446515372,0.6710046120197424,2.4870941840919194,1889.1,587.9,647.3,980.6,1246.6,1306.1 +1.9289068288674194,0.6709854987622963,2.6179938779914944,1112.2,637.9,765.8,1087.6,1372.7,1500.9 +1.9289271051318697,0.6709106657267245,2.748893571891069,769.0,770.0,990.3,1336.9,1671.1,1890.8 +1.9289110665924805,0.6709685359012487,2.8797932657906435,624.0,1093.1,1229.9,1452.1,2192.2,2064.7 +1.9289074414960847,0.6709713316070218,3.010692959690218,565.5,1060.6,1002.1,1267.3,1926.1,1866.8 +1.928947422529654,0.7712622233583966,0.0,663.0,993.1,993.1,1099.0,1828.9,1828.8 +1.928965726763184,0.7712666037882479,0.1308996938995747,712.9,1002.8,1062.2,1121.5,1868.3,1980.5 +1.9288691144117107,0.7712369205573084,0.2617993877991494,833.1,1100.2,1227.5,1244.5,1669.6,1290.6 +1.9288040696674074,0.771196007575615,0.39269908169872414,1073.9,1338.9,1556.0,1531.5,1128.5,909.4 +1.9287588486015024,0.7711487545344693,0.5235987755982988,1087.1,1384.2,1256.5,2145.6,880.7,753.1 +1.9287399898034525,0.7711097797420401,0.6544984694978736,980.2,1202.0,1142.9,1888.3,750.4,691.5 +1.9287250100449431,0.7710482724369769,0.7853981633974483,963.3,1129.1,1128.4,1798.8,693.6,693.2 +1.9287272093159926,0.7710240616789663,0.916297857297023,1000.5,1142.9,1201.6,1844.9,691.6,750.5 +1.928743867327705,0.7709739545947323,1.0471975511965976,1179.6,1256.8,1384.1,1589.9,752.7,880.1 +1.9287763386865386,0.7709216983545135,1.1780972450961724,1493.4,1525.5,1744.7,1073.6,910.1,1129.6 +1.928779217104092,0.7709194738229137,1.3089969389957472,1243.9,2161.2,2065.8,832.9,1227.6,1100.1 +1.9288000242275285,0.7709093395033246,1.4398966328953218,1120.2,1925.2,1866.5,711.4,1059.7,1001.2 +1.9288798339112652,0.7708915397492211,1.5707963267948966,1099.0,1828.4,1828.8,662.9,993.3,993.1 +1.9288793694651583,0.7708914355661962,1.7016960206944713,1163.1,1866.6,2010.7,669.3,1002.1,1060.8 +1.9288810681270525,0.7708911921867803,1.832595714594046,1337.9,1668.3,1289.7,740.8,1099.7,1227.5 +1.9289410647742535,0.7709294061929284,1.9634954084936205,1692.8,1128.5,909.3,914.1,1338.6,1555.0 +1.9289618063234715,0.7709530533457094,2.0943951023931953,2051.5,879.3,752.3,1178.8,1383.3,1256.2 +1.9289549534480313,0.7709375845192341,2.2252947962927703,1844.9,750.1,691.5,1022.5,1201.2,1142.3 +1.9289619426042237,0.7709645732965382,2.356194490192345,1799.5,693.0,693.7,962.7,1128.3,1128.9 +1.928959274182695,0.7709993010491234,2.4870941840919194,1889.1,691.5,750.9,980.7,1143.3,1202.2 +1.9289625670443926,0.7709941232690394,2.6179938779914944,1311.4,753.5,881.3,1087.4,1257.1,1385.0 +1.9289476601750033,0.771013932459371,2.748893571891069,910.5,911.4,1131.7,1336.6,1529.3,1749.9 +1.9289542699524942,0.7710098070785949,2.8797932657906435,739.6,1226.7,1099.4,1336.6,2164.3,2064.9 +1.928942278718008,0.7710171041971114,3.010692959690218,669.1,1060.5,1001.9,1163.6,1926.1,1867.4 +1.928967722357767,0.8712960999311303,0.0,762.9,993.1,993.3,998.8,1828.7,1829.2 +1.9289520588956017,0.8706707524515027,0.1308996938995747,816.4,1002.3,1061.6,1017.9,1868.2,1927.3 +1.9289893855718419,0.8706827751030988,0.2617993877991494,948.0,1099.4,1226.8,1128.4,1871.7,1491.8 +1.9290276930626264,0.8707073237609395,0.39269908169872414,1214.3,1337.3,1384.8,1388.5,1270.6,1051.7 +1.9290573528950405,0.8707414307686043,0.5235987755982988,1087.8,1269.2,1141.4,1979.8,996.9,869.0 +1.9290857594365654,0.8707916189141898,0.6544984694978736,980.5,1098.8,1039.8,1889.0,854.2,795.1 +1.929091454135818,0.8708216434073659,0.7853981633974483,963.2,1029.1,1028.4,1798.7,793.6,792.9 +1.9290907855377073,0.8708839420594006,0.916297857297023,1022.8,1039.2,1097.8,1845.2,794.9,853.7 +1.9290839537869018,0.8708328637745828,1.0471975511965976,1178.9,1140.7,1267.9,1791.9,867.7,994.8 +1.9290741540825962,0.8709287038641598,1.1780972450961724,1390.0,1383.3,1602.6,1216.4,1050.5,1269.6 +1.929030698255724,0.8709703619546603,1.3089969389957472,1129.1,1959.4,2065.9,948.9,1228.5,1100.7 +1.928996422368994,0.870990654333984,1.4398966328953218,1017.0,1925.6,1867.0,815.1,1059.9,1001.3 +1.9290178154120545,0.8709865448251708,1.5707963267948966,999.2,1829.1,1828.7,762.8,993.4,993.0 +1.9289623213751583,0.8709852845967281,1.7016960206944713,1059.6,1866.2,1924.7,772.5,1002.0,1060.2 +1.928914684601855,0.8709713744194787,1.832595714594046,1221.4,1869.8,1490.5,855.8,1099.2,1226.7 +1.9289333716712431,0.8709846017080076,1.9634954084936205,1549.6,1270.3,1051.0,1054.7,1337.5,1384.3 +1.9289234019272226,0.8709759890022264,2.0943951023931953,2052.8,995.2,868.2,1269.7,1268.5,1141.2 +1.9288965817678156,0.8709250162165716,2.2252947962927703,1845.6,853.7,794.9,1022.7,1098.0,1039.4 +1.9288942981199038,0.8709149932133353,2.356194490192345,1799.3,793.0,793.5,962.5,1028.6,1028.9 +1.9288927207913125,0.8709139559569739,2.4870941840919194,1888.8,794.9,854.1,980.2,1039.5,1098.5 +1.9289051441418736,0.8708775352900096,2.6179938779914944,1512.5,868.9,996.2,1087.1,1141.1,1268.9 +1.9289067828833377,0.870871288521097,2.748893571891069,1052.4,1052.1,1271.8,1335.6,1387.0,1606.9 +1.928933944807336,0.8708481457366812,2.8797932657906435,855.2,1227.2,1099.7,1222.0,1962.1,2065.6 +1.9289450478150314,0.8708435196347344,3.010692959690218,772.6,1061.0,1002.1,1060.7,1926.1,1867.2 +1.828932105110453,0.17075452796946067,0.0,63.0,1093.2,1092.9,1699.0,1729.0,1728.9 +1.8289809046952665,0.1714599419232976,0.1308996938995747,91.6,1106.0,1165.2,1742.9,1049.2,233.6 +1.8289367036910942,0.17144544420608532,0.2617993877991494,139.5,1215.1,1342.6,1937.3,431.0,95.3 +1.8288848326417004,0.17141187498061372,0.39269908169872414,223.8,1479.5,1700.2,2380.4,282.3,63.0 +1.8288416143561663,0.1713661303831433,0.5235987755982988,393.3,2087.5,1950.2,2031.3,187.5,59.8 +1.828822409238435,0.17132609883405014,0.6544984694978736,912.7,1823.1,1764.0,1785.4,129.5,70.4 +1.8288065497767767,0.1712623253760226,0.7853981633974483,1062.9,1728.8,1728.5,1698.7,93.8,93.3 +1.8288083015334395,0.17123568096447817,0.916297857297023,1126.4,1763.6,1822.1,917.7,70.7,129.5 +1.8288248314505635,0.1711830157733638,1.0471975511965976,1294.5,1949.3,2076.8,349.9,59.5,186.8 +1.828857486541565,0.1711279247400994,1.1780972450961724,1634.0,2371.2,2380.9,224.3,63.4,282.5 +1.8288611597958593,0.17112311355809462,1.3089969389957472,1937.4,2078.1,1950.4,139.9,95.6,474.8 +1.8288833687130017,0.17111082487054952,1.4398966328953218,1740.8,1822.2,1763.6,91.1,238.5,1067.2 +1.8289651121040411,0.17109090027994434,1.5707963267948966,1699.0,1728.9,1728.8,63.3,1093.1,1093.2 +1.8289669988715451,0.17108949295652742,1.7016960206944713,1783.3,1066.7,238.4,48.6,1105.6,1163.8 +1.8289711715316113,0.17108905097388294,1.832595714594046,2030.8,474.8,95.6,47.1,1215.1,1342.5 +1.8290335842947167,0.17112772559496348,1.9634954084936205,2371.6,282.4,63.3,63.7,1479.8,1700.9 +1.8290563170106964,0.17115249757924955,2.0943951023931953,1936.8,186.8,59.5,117.4,2092.1,1949.5 +1.8290505521751366,0.17113892231503325,2.2252947962927703,1741.8,129.5,70.7,319.6,1822.1,1763.4 +1.8290577447959906,0.171168012095549,2.356194490192345,1699.6,93.2,93.8,1062.5,1727.8,1728.6 +1.829054563948102,0.1712045288848183,2.4870941840919194,316.8,70.5,129.6,1084.0,1764.1,1823.0 +1.829056404393286,0.17120079200299165,2.6179938779914944,73.8,59.9,187.6,1202.9,1950.3,2078.0 +1.8290399314723835,0.17122119877676045,2.748893571891069,62.7,62.7,282.8,1477.5,2377.0,2376.2 +1.829044676851192,0.17121700900083137,2.8797932657906435,46.6,95.0,474.9,2030.2,2077.7,1949.8 +1.8290311119902094,0.17122358351041234,3.010692959690218,48.2,235.3,1058.5,1785.1,1822.5,1763.8 +1.8290555478264539,0.2715017229643919,0.0,163.2,1093.0,1093.2,1598.9,1728.9,1729.1 +1.8290036636264386,0.2707245840743282,0.1308996938995747,195.0,1106.1,1165.4,1639.1,1433.6,617.4 +1.8290277968644675,0.2707324797451811,0.2617993877991494,255.0,1215.1,1342.4,1822.0,674.1,294.5 +1.8290586369928605,0.27075237911698125,0.39269908169872414,365.2,1479.5,1699.9,2238.7,423.3,204.0 +1.829083614755039,0.27078157893814225,0.5235987755982988,592.0,1962.9,1835.0,2031.1,303.0,175.2 +1.829109048371038,0.27082664853375116,0.6544984694978736,1083.7,1719.8,1660.7,1785.4,232.9,173.8 +1.8291133658058423,0.2708515482756382,0.7853981633974483,1063.0,1629.0,1628.8,1698.7,193.5,193.0 +1.8291125384812212,0.27090888994259865,0.916297857297023,1126.2,1660.1,1719.3,1304.7,173.9,232.7 +1.8291067378696761,0.2709315143310247,1.0471975511965976,1294.5,1834.1,1961.2,593.0,174.7,302.0 +1.8291016011186219,0.27093868852387737,1.1780972450961724,1633.9,2230.4,2380.9,365.7,203.9,423.1 +1.8290575281011057,0.27098053436558356,1.3089969389957472,1822.5,2077.9,1950.2,255.2,294.1,673.2 +1.8290256780288108,0.27099910538084715,1.4398966328953218,1637.6,1822.0,1763.5,194.2,626.6,1104.8 +1.8290508149246654,0.27099401239825416,1.5707963267948966,1599.2,1728.7,1728.7,162.9,1093.4,1093.2 +1.8289992256456804,0.2709927420679026,1.7016960206944713,1680.4,1455.7,627.1,151.7,1105.5,1163.9 +1.8289552392053305,0.27097971681168276,1.832595714594046,1915.2,673.5,294.2,162.3,1215.0,1342.7 +1.828976974272781,0.270994854008449,1.9634954084936205,2372.2,423.1,204.0,204.9,1479.6,1700.7 +1.8289691823042784,0.27098878640306867,2.0943951023931953,1937.0,301.9,174.6,316.4,1961.8,1833.9 +1.8289437183102872,0.2709405093415247,2.2252947962927703,1742.3,232.7,173.9,705.2,1719.2,1660.4 +1.8289419216123004,0.27093326014260977,2.356194490192345,1699.7,193.0,193.5,1062.2,1628.4,1629.1 +1.8289399561807873,0.2709348815907979,2.4870941840919194,701.6,173.7,232.8,1083.8,1661.0,1719.9 +1.828951493471026,0.27090062916521696,2.6179938779914944,316.4,175.2,302.8,1202.5,1835.2,1962.5 +1.8289516368736924,0.2708961397576575,2.748893571891069,203.8,203.7,423.9,1477.1,2235.4,2376.6 +1.828977189837688,0.2708741506372059,2.8797932657906435,161.9,293.9,673.6,1914.9,2077.7,1949.8 +1.8289865861114798,0.2708701610830573,3.010692959690218,151.5,621.2,1105.5,1681.4,1822.7,1763.8 +1.829037951987057,0.37116890628295485,0.0,262.9,1093.0,1093.0,1498.7,1728.9,1728.9 +1.829008824451091,0.3711684059598117,0.1308996938995747,298.4,1105.7,1165.2,1535.8,1732.4,1001.1 +1.8289528997404418,0.3711521158647768,0.2617993877991494,370.3,1214.9,1342.2,1706.7,873.3,493.6 +1.8288984820880791,0.3711188525618263,0.39269908169872414,506.7,1479.4,1700.1,2097.4,533.2,345.0 +1.8288548586800066,0.37107464784242605,0.5235987755982988,790.9,1846.9,1719.4,2030.9,418.5,290.7 +1.8288355770157243,0.3710364771416288,0.6544984694978736,1210.0,1616.3,1557.3,1785.2,336.3,277.2 +1.8288195391153226,0.3709743827837779,0.7853981633974483,1063.1,1529.1,1528.1,1698.6,293.5,292.9 +1.8288212082305604,0.37094926314611687,0.916297857297023,1126.4,1557.0,1615.5,1691.8,277.4,336.2 +1.828837745879716,0.370898070920209,1.0471975511965976,1294.3,1718.3,1845.6,792.8,290.2,417.5 +1.8288704145037422,0.37084449677116593,1.1780972450961724,1633.5,2089.1,2308.2,507.5,345.1,564.1 +1.8288740220380144,0.3708414577735375,1.3089969389957472,1707.1,2077.9,1950.3,370.8,493.5,872.8 +1.8288958350340536,0.37083119719011504,1.4398966328953218,1534.5,1822.0,1763.7,297.8,1016.5,1104.8 +1.8289766315163063,0.3708132042299135,1.5707963267948966,1498.9,1728.9,1729.0,263.0,1093.2,1093.1 +1.8289770437973722,0.37081353628742475,1.7016960206944713,1576.6,1760.0,1017.0,255.2,1105.5,1163.9 +1.8289792423163298,0.3708143967764008,1.832595714594046,1799.8,873.0,449.7,278.0,1215.0,1342.7 +1.8290394278793989,0.3708535250601621,1.9634954084936205,2258.9,564.4,345.2,346.7,1479.9,1700.4 +1.8290600722610344,0.3708778903717269,2.0943951023931953,1936.9,417.6,290.2,516.1,1845.8,1718.8 +1.829052645855585,0.3708632578644082,2.2252947962927703,1741.7,336.2,277.4,1092.7,1615.5,1556.7 +1.8290589302862328,0.3708907622427011,2.356194490192345,1699.8,293.0,293.5,1062.5,1528.7,1529.0 +1.8290558046235224,0.3709255141390495,2.4870941840919194,1087.3,277.3,336.4,1083.8,1556.9,1616.3 +1.8290584864266588,0.37092035498841125,2.6179938779914944,515.6,290.8,418.5,1202.7,1719.3,1846.9 +1.8290435987896305,0.37093990332845506,2.748893571891069,345.2,345.2,565.1,1477.7,2094.4,2314.3 +1.8290501383982378,0.3709357024146831,2.8797932657906435,277.4,493.3,873.3,1799.5,2077.3,1950.0 +1.8290382769689673,0.3709430832134957,3.010692959690218,254.9,1008.0,1105.5,1578.4,1822.5,1763.5 +1.8290639248070648,0.47122234912949934,0.0,362.9,1093.1,1092.9,1399.2,1729.3,1728.8 +1.8290051643111216,0.4706506238814283,0.1308996938995747,402.1,1106.0,1165.4,1432.0,1764.6,1385.5 +1.8290360835402022,0.47066078685917034,0.2617993877991494,486.0,1214.9,1342.5,1590.6,1073.2,693.6 +1.829074897405295,0.47068585936072727,0.39269908169872414,648.3,1479.5,1700.2,1955.4,705.8,486.4 +1.829106405596748,0.4707222544981524,0.5235987755982988,990.5,1731.3,1603.7,2031.0,534.1,406.4 +1.8287876370199743,0.47102299673763004,0.6544984694978736,1083.8,1512.4,1453.7,1784.9,439.8,380.9 +1.8287838036690987,0.47100905351142597,0.7853981633974483,1063.2,1429.0,1428.3,1698.4,393.5,393.0 +1.828785121194513,0.4710117071556923,0.916297857297023,1103.8,1453.2,1512.4,1741.9,381.0,439.9 +1.8287962513839606,0.47097982349808776,1.0471975511965976,1295.0,1603.7,1730.8,991.3,405.9,533.4 +1.8288204173469482,0.4709409445900177,1.1780972450961724,1635.1,1949.1,2168.5,648.8,486.7,705.9 +1.8288132514585969,0.47094817798400435,1.3089969389957472,1590.6,2077.1,1949.4,486.2,693.8,1073.5 +1.8288229266390736,0.47094400499068834,1.4398966328953218,1430.7,1821.6,1763.2,401.1,1163.0,1104.8 +1.828891258021988,0.47092887696319075,1.5707963267948966,1398.8,1728.9,1728.7,363.0,1093.1,1093.2 +1.8288800874443745,0.4709284364069828,1.7016960206944713,1473.3,1763.2,1403.5,358.8,1105.6,1164.2 +1.8288722932218617,0.4709253027148228,1.832595714594046,1684.4,1070.8,692.4,393.7,1215.5,1343.2 +1.8289243933051023,0.4709585678865722,1.9634954084936205,2118.2,705.1,486.2,488.8,1480.7,1701.8 +1.8289393005331434,0.4709759532836255,2.0943951023931953,1935.9,533.0,405.7,716.8,1729.6,1602.6 +1.828928770758078,0.4709535484173095,2.2252947962927703,1741.6,439.6,381.0,1125.9,1511.6,1452.7 +1.8289341334679672,0.47097338519826004,2.356194490192345,1699.7,393.1,393.7,1062.6,1428.4,1429.2 +1.8289317232507254,0.47100131842492776,2.4870941840919194,1469.5,380.9,440.1,1084.1,1453.8,1512.9 +1.8289368700100326,0.4709901722607377,2.6179938779914944,714.2,406.6,534.5,1203.2,1604.2,1731.6 +1.8289250511560189,0.47100507085553023,2.748893571891069,486.5,487.1,707.4,1478.4,1953.7,2174.2 +1.8289355759893557,0.470997312008258,2.8797932657906435,392.9,693.8,1073.9,1683.1,2076.7,1949.2 +1.8289279470384867,0.47100229117230175,3.010692959690218,358.6,1164.3,1105.4,1474.0,1821.7,1763.1 +1.8289586565687552,0.5712852739668746,0.0,463.0,1092.9,1093.1,1299.2,1728.8,1728.7 +1.8289151818270188,0.5712837042941372,0.1308996938995747,505.8,1106.1,1165.5,1329.0,1764.8,1765.4 +1.8288487468970536,0.5712634630449076,0.2617993877991494,601.8,1215.5,1343.0,1475.8,1271.2,891.8 +1.8287866521789513,0.5712244582808907,0.39269908169872414,790.5,1480.6,1701.6,1815.0,846.2,627.2 +1.8287379785934472,0.5711735329162364,0.5235987755982988,1191.0,1615.0,1487.7,2030.2,649.5,522.0 +1.8287156856770617,0.5711281672436455,0.6544984694978736,1083.8,1409.1,1350.1,1784.9,543.4,484.4 +1.8286989571002303,0.5710591845633277,0.7853981633974483,1063.3,1328.9,1328.4,1698.8,493.5,493.1 +1.8287013814703463,0.5710276355010848,0.916297857297023,1126.7,1350.1,1408.8,1741.8,484.5,543.4 +1.8287200542412465,0.5709708805733762,1.0471975511965976,1294.9,1487.7,1614.9,1191.1,521.5,648.9 +1.8287559460883978,0.5709131290595821,1.1780972450961724,1634.6,1807.2,2027.0,790.4,627.9,847.2 +1.8287631456241626,0.5709068404904911,1.3089969389957472,1475.1,2077.0,1950.0,601.8,892.9,1215.4 +1.8287888181101029,0.5708940981210835,1.4398966328953218,1327.3,1821.7,1763.2,504.7,1289.5,1104.7 +1.8288736734406212,0.5708751302336108,1.5707963267948966,1298.8,1728.8,1728.4,463.0,1093.5,1093.1 +1.828877923049928,0.5708751748184462,1.7016960206944713,1370.2,1762.9,1792.8,462.3,1105.8,1164.3 +1.8288838065317214,0.5708761972149101,1.832595714594046,1568.9,1270.2,891.6,509.4,1215.3,1343.1 +1.8289472857247269,0.5709165898521578,1.9634954084936205,1976.6,846.0,627.4,630.7,1480.4,1701.9 +1.8289706013607432,0.5709429974479336,2.0943951023931953,1935.9,648.5,521.2,916.4,1614.4,1487.2 +1.8289653770977161,0.5709305816261101,2.2252947962927703,1741.5,543.2,484.6,1125.7,1408.4,1349.6 +1.8289730919227492,0.5709607215359571,2.356194490192345,1699.4,493.0,493.6,1062.6,1328.3,1329.0 +1.828970313877349,0.5709984493363787,2.4870941840919194,1770.1,484.4,543.7,1083.9,1350.3,1409.3 +1.8289727979278623,0.5709959058531286,2.6179938779914944,913.4,522.4,650.1,1203.2,1488.4,1616.4 +1.8289565280609017,0.5710178881027972,2.748893571891069,627.7,628.5,848.6,1478.1,1812.4,2032.7 +1.8289614130753042,0.5710153703214784,2.8797932657906435,508.5,893.3,1215.0,1567.6,2077.0,1949.1 +1.8289474961844048,0.5710236938883406,3.010692959690218,462.0,1290.5,1105.5,1370.8,1822.4,1763.3 +1.8289706119959468,0.6713009256672091,0.0,563.0,1093.3,1093.3,1199.1,1728.6,1729.1 +1.8289549586900387,0.6706714552004827,0.1308996938995747,609.1,1106.0,1165.3,1224.8,1764.3,1823.9 +1.8289921812310475,0.670683448939301,0.2617993877991494,717.0,1215.1,1342.4,1359.7,1472.5,1093.0 +1.829030394074417,0.6707079488538452,0.39269908169872414,931.5,1479.2,1698.7,1671.8,988.4,768.9 +1.8290599808136807,0.6707419941527,0.5235987755982988,1203.4,1500.4,1372.6,2031.3,765.6,637.8 +1.829088324596042,0.6707921056677641,0.6544984694978736,1084.1,1306.0,1246.8,1785.4,647.2,587.9 +1.8290939862633036,0.6708220522776498,0.7853981633974483,1063.3,1229.1,1228.5,1698.6,593.6,593.1 +1.8290932974686813,0.6708842642573738,0.916297857297023,1103.6,1246.2,1304.9,1741.3,587.9,646.6 +1.8290864688505504,0.6709113370973303,1.0471975511965976,1294.4,1371.8,1498.8,1392.3,636.8,763.8 +1.8290793023206997,0.6709221707007498,1.1780972450961724,1633.5,1665.5,1884.8,932.7,768.2,987.2 +1.829032596819106,0.6709668886205427,1.3089969389957472,1360.1,2078.1,1950.3,717.8,1090.8,1216.0 +1.8289976688099934,0.670987512487977,1.4398966328953218,1224.1,1821.6,1808.9,608.2,1163.6,1105.0 +1.8290194736857597,0.6709833081542722,1.5707963267948966,1199.2,1729.1,1728.7,563.0,1093.4,1092.9 +1.8289647167059235,0.6709820707113261,1.7016960206944713,1266.5,1762.7,1821.3,565.6,1105.6,1163.7 +1.8289178472149037,0.6709683845809724,1.832595714594046,1452.7,1471.2,1091.7,624.5,1214.7,1342.4 +1.8289372003643898,0.6709820378307112,1.9634954084936205,1832.9,987.9,768.7,771.4,1479.2,1697.6 +1.8289277226761556,0.6709739776676737,2.0943951023931953,1937.1,764.2,636.8,1114.3,1499.6,1372.2 +1.8289012136619582,0.6709236057305312,2.2252947962927703,1742.0,646.9,587.9,1126.4,1305.1,1246.2 +1.8288990608297218,0.6709142014362595,2.356194490192345,1699.6,593.0,593.5,1062.4,1228.6,1229.1 +1.8288974418473922,0.6709137551725572,2.4870941840919194,1785.0,587.8,646.9,1083.7,1246.7,1305.7 +1.8289096982822035,0.6708778418447405,2.6179938779914944,1113.8,637.5,765.2,1202.4,1372.4,1499.8 +1.8289110522061203,0.6708720147109619,2.748893571891069,738.5,769.2,989.0,1477.3,1669.7,1889.5 +1.8289378740995677,0.6708491752392518,2.8797932657906435,624.2,1091.6,1215.4,1452.6,2077.9,1950.3 +1.8289486012378404,0.6708447405516003,3.010692959690218,542.8,1164.5,1105.8,1267.8,1822.6,1764.0 +1.8290013892688546,0.7711445391898002,0.0,662.9,1093.1,1093.2,1099.0,1729.0,1728.4 +1.8289733265793575,0.7711442428810793,0.1308996938995747,712.5,1105.8,1165.0,1121.5,1764.4,1823.9 +1.8289181187221881,0.7711282683924277,0.2617993877991494,832.3,1214.9,1342.3,1244.1,1671.7,1292.0 +1.828864248261764,0.7710953762902895,0.39269908169872414,1072.8,1479.1,1526.4,1530.3,1129.4,910.1 +1.8288210126275148,0.7710515470702848,0.5235987755982988,1344.2,1384.8,1257.0,2030.9,881.0,753.3 +1.8288021303760014,0.7710138252000158,0.6544984694978736,1083.7,1202.7,1143.3,1785.3,750.6,691.4 +1.8287863169571423,0.7709521456328818,0.7853981633974483,1063.1,1129.3,1128.4,1698.5,693.5,692.9 +1.8287882173325503,0.7709275456799729,0.916297857297023,1126.2,1142.9,1201.3,1741.7,691.4,750.2 +1.8288048645170656,0.7708769121410992,1.0471975511965976,1294.3,1256.3,1383.6,1592.0,752.5,879.4 +1.8288374606660844,0.770823796138397,1.1780972450961724,1531.9,1524.3,1743.6,1074.6,909.3,1128.4 +1.8288409159815835,0.7708212502859506,1.3089969389957472,1244.6,2078.5,1950.2,833.4,1290.0,1216.1 +1.8288268654227702,0.7708265778563732,1.4398966328953218,1120.6,1822.3,1763.6,711.6,1163.3,1104.8 +1.8291075018004799,0.7707644688444752,1.5707963267948966,1098.9,1728.8,1728.7,663.0,1093.4,1093.1 +1.8289919513743975,0.7707608863383519,1.7016960206944713,1163.0,1762.6,1821.1,669.1,1105.5,1163.9 +1.8289676001454434,0.770753777821938,1.832595714594046,1336.8,1670.9,1291.3,740.3,1214.8,1342.4 +1.8290279170151025,0.7707929209066218,1.9634954084936205,1691.6,1129.2,909.9,913.3,1479.3,1525.2 +1.8290543565806718,0.7708232728035369,2.0943951023931953,1936.8,879.8,752.5,1295.0,1384.2,1256.8 +1.829051885964776,0.7708177080267078,2.2252947962927703,1742.1,750.6,691.4,1126.2,1201.7,1142.5 +1.829060704707963,0.7708554486384134,2.356194490192345,1699.6,693.1,693.5,1062.4,1128.6,1128.9 +1.8290575034391046,0.7709002329460506,2.4870941840919194,1784.8,691.4,750.4,1083.5,1143.0,1202.3 +1.8290576534851277,0.7709041204171281,2.6179938779914944,1313.2,753.0,880.8,1202.7,1256.7,1384.2 +1.8290384277027687,0.7709312091112241,2.748893571891069,911.3,910.5,1130.5,1477.6,1528.3,1748.5 +1.8290392179011494,0.7709327344609687,2.8797932657906435,739.7,1290.8,1215.4,1337.3,2077.5,1950.3 +1.8290208351735033,0.7709438799932218,3.010692959690218,669.1,1164.6,1105.6,1164.1,1822.6,1763.6 +1.8290383891296398,0.8712170138670732,0.0,763.0,1093.4,1093.2,999.3,1729.0,1729.2 +1.8289816152036378,0.8706454710863027,0.1308996938995747,816.4,1105.9,1165.1,1017.8,1764.6,1823.5 +1.829013454182148,0.8706558823975898,0.2617993877991494,948.2,1214.9,1342.3,1128.0,1871.4,1491.7 +1.829092415278528,0.8707085663847771,0.39269908169872414,1214.6,1479.4,1384.8,1388.7,1270.8,1051.5 +1.8291019574187355,0.8707210367342919,0.5235987755982988,1203.3,1269.1,1141.5,1980.0,996.9,869.0 +1.8287911253562648,0.8710243135784399,0.6544984694978736,1083.9,1098.5,1039.2,1784.5,854.0,795.1 +1.8287965511427215,0.871053622700869,0.7853981633974483,1063.3,1028.9,1028.7,1698.2,793.6,793.1 +1.8287988144888376,0.8710268407435406,0.916297857297023,1126.7,1039.4,1097.9,1741.6,795.1,854.0 +1.8288118457401585,0.870988744750177,1.0471975511965976,1294.9,1141.1,1268.6,1789.5,868.3,995.7 +1.828835623916197,0.8709504499478005,1.1780972450961724,1388.7,1384.2,1603.8,1215.4,1051.6,1270.8 +1.8288264176988978,0.8709595742842209,1.3089969389957472,1128.4,1961.5,1949.6,948.7,1343.0,1215.7 +1.8288331847275692,0.8709569497624707,1.4398966328953218,1016.8,1821.5,1763.2,814.8,1162.9,1104.7 +1.8288982815407537,0.8709425337613894,1.5707963267948966,999.0,1728.7,1728.7,763.1,1093.3,1093.3 +1.8288840285890458,0.8709419748518394,1.7016960206944713,1059.4,1763.0,1821.6,772.7,1083.1,1164.2 +1.8288734767798447,0.8709380110971232,1.832595714594046,1221.9,1867.5,1488.8,856.4,1215.6,1343.4 +1.828962352413771,0.870997086513384,1.9634954084936205,1550.9,1269.2,1050.3,1055.9,1480.6,1383.1 +1.8289792342294664,0.8710161053795911,2.0943951023931953,1935.8,994.9,867.6,1294.5,1267.9,1140.5 +1.8289518004284786,0.870961899956469,2.2252947962927703,1741.2,853.7,795.0,1125.9,1097.7,1038.9 +1.8289670805020846,0.8710277631192826,2.356194490192345,1699.4,793.0,793.7,1062.4,1028.5,1029.2 +1.8289662104016042,0.8710194410374319,2.4870941840919194,1785.4,795.2,854.5,1084.0,1039.5,1098.6 +1.8289727585284483,0.8710037548235157,2.6179938779914944,1510.8,869.2,997.1,1203.2,1141.5,1269.3 +1.8289582784240728,0.871022916797604,2.748893571891069,1051.9,1053.0,1273.2,1478.4,1387.9,1607.8 +1.828963231138217,0.8710203458896995,2.8797932657906435,855.0,1342.0,1214.7,1221.2,1965.1,1949.6 +1.828948522280459,0.8710290923736781,3.010692959690218,772.5,1164.4,1105.6,1060.2,1821.9,1763.5 +1.728893986344678,0.1708553704143041,0.0,63.2,1193.1,1193.2,1698.9,1628.9,1628.7 +1.728925502704109,0.1714758726371779,0.1308996938995747,91.6,1209.8,1269.4,1743.0,1046.9,233.0 +1.72887520984913,0.1714592979860705,0.2617993877991494,139.7,1330.9,1458.6,1938.2,474.3,95.2 +1.7288210061060134,0.1714239254021046,0.39269908169872414,224.0,1622.3,1843.3,2381.5,282.0,31.9 +1.7291375820324915,0.17095364092597576,0.5235987755982988,393.7,2077.1,1949.8,1914.6,187.3,59.7 +1.729238051283428,0.17114480118574682,0.6544984694978736,914.2,1822.7,1763.9,1681.4,129.3,70.3 +1.7292107000981032,0.17103403461659905,0.7853981633974483,1163.4,1729.1,1728.2,1599.1,93.6,93.2 +1.7292106560016245,0.1710495141072652,0.916297857297023,1230.1,1764.2,1822.9,914.8,70.5,129.4 +1.7292071116685677,0.17106187935627593,1.0471975511965976,1410.7,1950.2,2077.2,392.9,59.3,186.7 +1.729201622180928,0.1710683393226211,1.1780972450961724,1775.8,2372.9,2238.3,223.8,63.1,282.4 +1.7291551615462313,0.17111103643554548,1.3089969389957472,1937.6,1961.7,1834.3,139.5,95.3,475.0 +1.7291201430968697,0.1711298322200019,1.4398966328953218,1740.8,1718.0,1660.0,90.8,238.2,1068.9 +1.729142179006418,0.17112479173212125,1.5707963267948966,1698.9,1629.1,1628.7,63.0,1193.3,1193.0 +1.729087867599217,0.17112269145968972,1.7016960206944713,1783.9,1063.6,236.8,48.4,1208.8,1267.7 +1.7290417767924715,0.17110802075019116,1.832595714594046,2031.6,473.8,95.0,46.8,1305.4,1458.8 +1.7290618366088604,0.1711216717700934,1.9634954084936205,2230.0,281.8,63.0,63.4,1621.8,1843.2 +1.7290527061683514,0.1711142464118447,2.0943951023931953,1820.9,186.4,59.3,117.2,2076.2,1949.1 +1.7290264345167041,0.17106429613103002,2.2252947962927703,1638.5,129.2,70.5,319.5,1822.2,1763.8 +1.729024041612854,0.17105542032920606,2.356194490192345,1599.8,93.0,93.7,1162.4,1728.2,1729.2 +1.7290214250135547,0.1710556134254979,2.4870941840919194,230.8,70.3,129.5,1187.7,1764.6,1823.5 +1.7290328684431209,0.17101966394035317,2.6179938779914944,117.2,59.7,187.5,1318.8,1951.2,2078.7 +1.7290327673131234,0.17101363706324357,2.748893571891069,62.5,62.6,282.7,1619.6,2378.1,2233.8 +1.729058767030375,0.17098999997624142,2.8797932657906435,46.4,94.8,475.2,2029.6,1961.3,1833.8 +1.7290689442997758,0.1709845194766153,3.010692959690218,48.1,235.3,1059.8,1784.5,1718.9,1660.0 +1.729121923421948,0.2712844948735227,0.0,163.1,1192.9,1193.1,1599.1,1629.2,1629.1 +1.7290938221891525,0.27128310538173683,0.1308996938995747,195.1,1209.6,1269.2,1639.3,1429.9,615.7 +1.7290389962115598,0.27126647124997394,0.2617993877991494,255.0,1331.0,1458.5,1822.6,673.3,294.1 +1.728985559163594,0.2712333097320727,0.39269908169872414,365.5,1621.8,1842.7,2240.5,422.9,203.9 +1.7289428073935913,0.2711896776381222,0.5235987755982988,592.9,1961.7,1834.3,1914.8,302.8,175.2 +1.7289237181134975,0.2711521677547619,0.6544984694978736,1187.0,1719.4,1660.7,1681.5,232.8,173.8 +1.7289077332912095,0.27109102893686066,0.7853981633974483,1163.0,1629.1,1628.6,1598.9,193.5,193.1 +1.7289087646334123,0.27106650088522977,0.916297857297023,1229.8,1660.3,1719.5,1301.7,174.0,232.9 +1.7289244139403734,0.2710155812802604,1.0471975511965976,1410.5,1834.6,1962.1,592.5,174.9,302.2 +1.7289562468855657,0.2709622069683568,1.1780972450961724,1775.8,2231.7,2238.3,365.6,204.3,423.7 +1.7289589466778548,0.27095876349745995,1.3089969389957472,1821.4,1961.5,1834.4,255.2,294.9,674.5 +1.7289800648083757,0.2709475339691083,1.4398966328953218,1637.5,1718.2,1659.8,194.4,628.8,1207.9 +1.7290605885392387,0.27092901705824257,1.5707963267948966,1598.5,1629.1,1628.6,163.1,1193.1,1193.0 +1.7290609904498697,0.2709286837725524,1.7016960206944713,1680.2,1453.0,626.0,152.0,1208.9,1267.4 +1.7290634921279788,0.2709287229574504,1.832595714594046,1915.8,672.9,294.3,162.5,1330.8,1458.7 +1.729123998679326,0.2709676805613095,1.9634954084936205,2230.3,422.9,204.1,205.3,1622.2,1843.3 +1.7291447754572875,0.27099231117442546,2.0943951023931953,1820.7,302.0,149.4,317.1,1960.3,1833.3 +1.7291374544914702,0.2709778013433837,2.2252947962927703,1638.2,232.7,174.1,707.6,1718.5,1660.0 +1.7291435414303298,0.27100551622963853,2.356194490192345,1599.9,193.1,193.7,1162.5,1628.2,1629.1 +1.7291397056626017,0.27104057005273696,2.4870941840919194,700.3,173.9,233.1,1187.5,1661.0,1720.2 +1.7291418198331223,0.27103524814497204,2.6179938779914944,316.2,175.4,303.2,1318.7,1835.1,1963.2 +1.7291259243605293,0.27105451876622055,2.748893571891069,203.8,204.0,424.2,1619.6,2236.7,2233.4 +1.7291319175250481,0.27104961892671553,2.8797932657906435,161.9,294.5,674.6,1914.3,1961.2,1834.1 +1.7291197250814987,0.2710561252234349,3.010692959690218,151.6,623.0,1208.8,1681.1,1718.8,1660.4 +1.7291456491583581,0.3713355708543611,0.0,263.1,1192.7,1193.0,1499.2,1628.9,1629.0 +1.7290883610013608,0.37081644765409094,0.1308996938995747,298.6,1209.6,1269.2,1535.5,1661.3,999.4 +1.7291004459487718,0.37082062413465455,0.2617993877991494,370.7,1331.0,1458.5,1706.5,872.5,493.5 +1.7291199258460128,0.37083353758036597,0.39269908169872414,507.3,1622.2,1842.7,2098.4,564.1,345.1 +1.7291360882153173,0.37085357480803127,0.5235987755982988,792.2,1846.0,1718.9,1915.0,418.3,290.8 +1.7291553971893006,0.3708881932259873,0.6544984694978736,1215.1,1615.9,1556.6,1681.2,336.3,277.4 +1.7291568394438948,0.37090232503619647,0.7853981633974483,1162.8,1529.1,1528.4,1599.0,293.5,293.1 +1.7291556837544433,0.3709491075774134,0.916297857297023,1230.1,1556.8,1615.7,1602.8,277.5,336.4 +1.7291521229257558,0.37096204839601077,1.0471975511965976,1410.7,1719.2,1846.6,791.9,290.3,417.7 +1.7291514591048889,0.3709613217894847,1.1780972450961724,1776.3,2090.6,2238.2,507.0,345.3,564.7 +1.7291131475538835,0.37099695661167265,1.3089969389957472,1706.2,1961.7,1834.2,370.6,494.0,873.5 +1.7290880152760268,0.37101106682426654,1.4398966328953218,1534.3,1718.0,1659.8,297.6,1018.9,1334.3 +1.7291204184698616,0.3710041734909426,1.5707963267948966,1521.2,1629.0,1628.9,262.9,1193.2,1193.3 +1.7290756984223945,0.37100292890078235,1.7016960206944713,1577.1,1659.5,1014.5,255.2,1209.0,1267.4 +1.7290379490038248,0.3709913558008784,1.832595714594046,1800.3,871.8,493.1,278.0,1330.9,1458.6 +1.729064795707762,0.37100977902113597,1.9634954084936205,2230.0,563.9,345.0,346.9,1622.0,1843.3 +1.7290605754345132,0.3710081021656191,2.0943951023931953,1820.8,417.4,290.2,516.7,1845.0,1717.9 +1.729037337903279,0.3709643430798242,2.2252947962927703,1638.2,336.1,277.4,1095.1,1615.0,1556.6 +1.7290362907958863,0.3709617261246334,2.356194490192345,1599.9,292.9,293.6,1162.5,1528.2,1528.9 +1.7290335328712052,0.37096782144315954,2.4870941840919194,1084.8,277.4,336.6,1187.4,1557.5,1616.7 +1.7290435612419757,0.3709371244387871,2.6179938779914944,515.1,290.9,418.6,1318.5,1719.5,1847.6 +1.7290410700675916,0.37093554786896443,2.748893571891069,345.0,345.4,565.6,1619.5,2095.5,2234.0 +1.7290639343578118,0.3709154159307284,2.8797932657906435,277.4,494.0,874.1,1798.9,1961.2,1834.0 +1.7290704907086085,0.37091243491485293,3.010692959690218,232.3,1010.5,1335.3,1577.6,1719.0,1660.0 +1.729118801839425,0.47120892757483324,0.0,363.0,1192.8,1193.0,1398.9,1629.0,1629.0 +1.729087358165755,0.4712080743829019,0.1308996938995747,402.1,1209.8,1268.9,1432.3,1707.3,1382.0 +1.7290298607672436,0.4711911694866524,0.2617993877991494,486.1,1330.6,1458.3,1591.4,1071.7,692.6 +1.7289742176624392,0.471157151724205,0.39269908169872414,648.7,1622.0,1842.4,1957.0,705.1,486.1 +1.7289297320218353,0.47111217348722856,0.5235987755982988,991.2,1730.7,1603.3,1914.8,508.4,406.3 +1.7289095131185852,0.4710730160894381,0.6544984694978736,1187.1,1512.6,1453.5,1681.5,439.7,380.8 +1.7288929915837596,0.47101002769375633,0.7853981633974483,1163.0,1429.0,1428.7,1598.8,393.5,393.1 +1.7288941377010236,0.47098373751951916,0.916297857297023,1229.9,1453.5,1512.1,1638.7,380.9,439.8 +1.7289104533277857,0.47093129175406157,1.0471975511965976,1410.3,1603.3,1730.7,991.6,405.9,533.4 +1.7289433470585165,0.4708767607141069,1.1780972450961724,1775.6,1948.8,2168.6,648.7,486.7,705.8 +1.728947332039894,0.4708726753857664,1.3089969389957472,1590.9,1961.7,1834.4,486.2,693.5,1073.2 +1.728969776459703,0.4708613143996365,1.4398966328953218,1430.7,1763.3,1660.2,401.2,1266.2,1208.0 +1.7290514976200522,0.47084302950257473,1.5707963267948966,1399.0,1629.2,1628.9,363.0,1193.2,1193.1 +1.7290528408896102,0.47084324556453616,1.7016960206944713,1473.6,1704.9,1403.9,358.7,1208.8,1244.7 +1.7290559849487335,0.4708440259697979,1.832595714594046,1684.3,1071.2,692.4,393.7,1330.8,1458.7 +1.7291168714258247,0.4708837187389774,1.9634954084936205,2118.0,705.0,486.1,488.8,1622.4,1843.3 +1.729137826782433,0.4709089953352694,2.0943951023931953,1820.7,533.0,405.7,716.5,1729.6,1602.7 +1.7291305460223831,0.47089504618658684,2.2252947962927703,1638.2,439.8,381.0,1229.5,1511.8,1453.2 +1.729136642892342,0.4709232135122312,2.356194490192345,1599.7,393.1,393.7,1162.2,1428.5,1429.2 +1.7291328639331442,0.47095864038402246,2.4870941840919194,1470.0,380.8,440.1,1187.4,1453.8,1512.9 +1.729135039725627,0.47095371384222284,2.6179938779914944,714.2,406.5,534.4,1318.7,1604.2,1732.1 +1.7291192536145947,0.4709734188990411,2.748893571891069,486.5,486.9,707.1,1619.4,1954.0,2173.6 +1.7291252753666597,0.47096904331859824,2.8797932657906435,392.9,693.5,1073.8,1682.7,1961.5,1833.8 +1.7291130030379636,0.47097613311698683,3.010692959690218,358.5,1267.4,1209.0,1474.4,1718.9,1660.0 +1.7291385468072236,0.571255344343411,0.0,462.9,1192.8,1193.0,1299.2,1628.5,1629.0 +1.7290784065714884,0.5706574145332997,0.1308996938995747,505.9,1209.5,1269.2,1328.6,1661.2,1682.3 +1.7291081335149714,0.5706673313515114,0.2617993877991494,601.9,1331.2,1458.4,1475.7,1271.4,892.1 +1.7291458836939928,0.5706920341600874,0.39269908169872414,790.6,1621.8,1838.2,1814.7,846.3,627.2 +1.7291765779460713,0.5707280098466927,0.5235987755982988,1191.1,1615.2,1487.7,1914.7,649.5,522.0 +1.7288074712635764,0.5710254533997097,0.6544984694978736,1187.1,1408.7,1350.0,1681.2,543.4,484.5 +1.728802698032852,0.5710075358608497,0.7853981633974483,1163.1,1329.0,1328.4,1598.8,493.5,493.1 +1.728803945702997,0.5710110171883571,0.916297857297023,1230.3,1350.1,1408.8,1638.4,484.5,543.5 +1.7288143694603688,0.5709813002599802,1.0471975511965976,1410.4,1487.9,1615.4,1190.6,521.6,649.0 +1.728837132678723,0.5709446065473576,1.1780972450961724,1776.4,1808.0,2027.3,790.3,627.9,847.0 +1.72882810610071,0.5709535413553357,1.3089969389957472,1474.9,1961.3,1834.3,576.5,893.1,1272.8 +1.7288356617408385,0.5709504681017257,1.4398966328953218,1327.1,1717.8,1660.0,504.6,1323.9,1208.1 +1.7289017949862688,0.5709358441666299,1.5707963267948966,1298.8,1629.1,1628.8,463.0,1193.2,1193.1 +1.7288885689696456,0.5709353413815514,1.7016960206944713,1369.9,1659.2,1706.9,462.3,1209.1,1267.9 +1.72887894769404,0.5709316606022257,1.832595714594046,1568.9,1270.1,891.3,509.3,1331.1,1459.1 +1.7289295146559145,0.5709639984173827,1.9634954084936205,1976.4,846.1,627.1,630.6,1622.3,1836.7 +1.728943268327556,0.5709802079099378,2.0943951023931953,1820.3,648.3,521.3,916.6,1613.8,1487.0 +1.7289319897224897,0.5709564835686505,2.2252947962927703,1638.0,543.2,484.5,1313.0,1407.9,1349.7 +1.7289369890996114,0.5709749451454085,2.356194490192345,1599.3,492.9,493.6,1162.6,1328.5,1329.2 +1.7289345735509962,0.5710015574990566,2.4870941840919194,1681.8,484.5,543.7,1187.8,1350.4,1409.4 +1.7289400372901742,0.5709892287345266,2.6179938779914944,913.2,522.3,650.1,1319.1,1488.5,1616.4 +1.728928782175112,0.571003141004067,2.748893571891069,627.7,628.4,848.9,1620.1,1812.2,2032.7 +1.7289400564167448,0.5709946377388844,2.8797932657906435,508.4,893.8,1273.7,1567.5,1960.7,1833.2 +1.7289332812058489,0.5709991343320469,3.010692959690218,462.0,1313.5,1209.3,1370.6,1718.3,1660.0 +1.7289650482406236,0.6712829228469308,0.0,563.0,1193.0,1193.2,1199.2,1628.5,1628.8 +1.7289223006877257,0.6712813781818203,0.1308996938995747,609.4,1209.9,1269.2,1225.5,1660.9,1720.6 +1.7288564125819832,0.6712613179994067,0.2617993877991494,717.5,1331.1,1458.8,1360.2,1470.1,1091.1 +1.7287947234216166,0.6712225950862134,0.39269908169872414,932.3,1622.1,1666.4,1673.1,987.5,768.4 +1.7287463309114064,0.6711720176822005,0.5235987755982988,1318.6,1499.5,1372.3,1914.5,764.9,637.5 +1.7287241858744185,0.6711270191903513,0.6544984694978736,1187.4,1305.4,1246.5,1681.1,646.9,587.8 +1.728707501783655,0.6710584078897226,0.7853981633974483,1163.3,1229.1,1228.4,1598.9,593.5,593.0 +1.728709866765849,0.6710271872064844,0.916297857297023,1230.0,1246.4,1305.2,1638.2,588.1,646.9 +1.72872840746441,0.6709707081603795,1.0471975511965976,1410.9,1372.4,1499.6,1390.5,637.1,764.6 +1.7287641232956739,0.6709131776558717,1.1780972450961724,1672.1,1666.7,1886.1,931.8,769.0,988.4 +1.728771119304208,0.6709070367044148,1.3089969389957472,1359.5,1962.1,1834.1,717.4,1092.6,1331.3 +1.7287965799824332,0.670894374513431,1.4398966328953218,1223.6,1718.0,1794.8,608.1,1266.4,1208.2 +1.7288812300949823,0.6708754522109528,1.5707963267948966,1198.9,1628.7,1628.6,563.1,1193.3,1193.2 +1.7288852902297187,0.6708754950281652,1.7016960206944713,1266.6,1659.5,1717.8,565.8,1209.3,1267.4 +1.7288910045263564,0.670876471832881,1.832595714594046,1453.2,1469.4,1090.6,625.1,1331.2,1458.9 +1.7289543308988773,0.6709168001784485,1.9634954084936205,1834.8,987.3,768.2,772.4,1622.4,1664.9 +1.7289775139914374,0.6709431253174467,2.0943951023931953,1820.6,763.9,636.8,1116.5,1498.5,1371.5 +1.728972188461256,0.6709305989632388,2.2252947962927703,1638.2,646.6,588.1,1229.6,1304.7,1246.1 +1.7289798303876243,0.6709606122056546,2.356194490192345,1599.4,593.1,593.6,1162.5,1228.3,1229.0 +1.7289770063294725,0.6709982091366498,2.4870941840919194,1770.1,588.1,647.2,1187.7,1246.8,1306.0 +1.7289794898328579,0.6709955288223144,2.6179938779914944,1112.7,637.9,765.6,1318.9,1372.8,1500.6 +1.7289632449732748,0.6710173889125179,2.748893571891069,769.1,770.1,990.3,1620.0,1671.2,1891.1 +1.728968196617744,0.6710147668862778,2.8797932657906435,624.0,1093.1,1330.5,1452.3,1961.1,1833.5 +1.7289543696601464,0.6710230174398419,3.010692959690218,565.5,1268.0,1209.2,1267.4,1718.6,1660.1 +1.7289776182634766,0.7713003534326675,0.0,663.0,1193.2,1193.3,1099.1,1629.0,1629.2 +1.7289591675319727,0.7706889024082748,0.1308996938995747,712.8,1209.5,1268.8,1121.2,1660.9,1719.9 +1.728995570909438,0.7707006663917337,0.2617993877991494,832.8,1330.4,1457.8,1244.1,1672.4,1292.3 +1.7290320607341514,0.7707240661500763,0.39269908169872414,1073.1,1620.9,1526.4,1530.0,1129.7,910.4 +1.7290600838410541,0.7707564301608218,0.5235987755982988,1319.0,1384.9,1257.1,1915.5,881.1,753.5 +1.7290873700352127,0.770804583211093,0.6544984694978736,1187.4,1202.1,1143.0,1681.7,750.8,691.5 +1.7290925218908577,0.7708324583577486,0.7853981633974483,1163.1,1129.1,1128.4,1599.0,693.5,692.9 +1.729091859773518,0.7708926965886196,0.916297857297023,1230.2,1142.7,1201.6,1637.8,691.4,750.1 +1.7290855242778138,0.7709179855983688,1.0471975511965976,1409.9,1256.3,1383.6,1591.9,752.2,879.4 +1.7290792201706289,0.7709273233678124,1.1780972450961724,1531.8,1524.7,1743.5,1074.4,909.4,1128.4 +1.7290336282108438,0.770970914233793,1.3089969389957472,1244.8,1962.6,1835.1,833.3,1289.7,1426.1 +1.7289999767782667,0.770990792556584,1.4398966328953218,1120.5,1718.5,1660.0,711.6,1266.9,1208.4 +1.7290231271590406,0.7709862156319625,1.5707963267948966,1099.0,1628.6,1628.6,662.9,1193.4,1193.3 +1.7289696474019682,0.770984969853604,1.7016960206944713,1163.1,1659.1,1717.5,669.0,1209.0,1267.3 +1.7288825018633558,0.7709556883397615,1.832595714594046,1337.2,1670.7,1291.1,740.2,1330.3,1458.2 +1.7291054851620797,0.7710988416590323,1.9634954084936205,1691.4,1129.1,909.7,913.3,1621.2,1525.7 +1.7290038684017968,0.7709918415520871,2.0943951023931953,1821.5,879.8,752.5,1314.0,1384.2,1256.6 +1.7289627898160946,0.7709139142456587,2.2252947962927703,1638.3,750.3,691.4,1229.8,1202.0,1142.8 +1.7289609930191243,0.7709058904751365,2.356194490192345,1599.6,693.0,693.6,1162.8,1128.5,1128.8 +1.7289589731939632,0.7709165642551947,2.4870941840919194,1681.4,691.5,750.5,1187.2,1143.0,1202.2 +1.728967317570285,0.7708933854940059,2.6179938779914944,1313.1,753.3,880.7,1317.9,1256.7,1384.2 +1.7289615162666103,0.770898930725024,2.748893571891069,911.1,910.5,1130.4,1618.5,1528.3,1748.2 +1.7289790605678077,0.7708847117752489,2.8797932657906435,739.8,1290.7,1427.2,1337.1,1962.1,1834.6 +1.7289793405010416,0.7708858183693166,3.010692959690218,669.1,1268.2,1209.2,1164.3,1719.3,1660.3 +1.7290194739546598,0.8711760202530872,0.0,763.0,1193.0,1193.1,999.1,1629.3,1628.9 +1.7289824982510857,0.8711754012759041,0.1308996938995747,816.2,1209.6,1268.6,1017.9,1660.8,1720.2 +1.7289206637272176,0.8711573734874003,0.2617993877991494,948.3,1330.7,1457.9,1128.5,1827.5,1491.6 +1.7288617430124014,0.8711213068266983,0.39269908169872414,1214.5,1620.7,1385.1,1388.8,1270.7,1051.2 +1.7288148398089973,0.871073546364614,0.5235987755982988,1319.0,1269.2,1141.7,1915.7,996.7,868.9 +1.7287936429272461,0.8710315321081903,0.6544984694978736,1187.3,1098.8,1039.8,1682.0,854.1,794.8 +1.7287767654404835,0.8709654185025419,0.7853981633974483,1163.2,1029.2,1028.3,1599.1,793.6,792.9 +1.7287787585835723,0.8709366289955525,0.916297857297023,1229.9,1039.2,1098.0,1638.0,794.9,853.6 +1.7287964967083576,0.870882236007857,1.0471975511965976,1409.8,1140.8,1267.8,1791.8,867.6,994.9 +1.7288309663614156,0.8708260013398097,1.1780972450961724,1389.8,1383.2,1602.3,1216.2,1050.5,1269.4 +1.7288107035733042,0.8708500044821876,1.3089969389957472,1128.9,1959.4,1834.9,949.0,1459.3,1331.8 +1.7288578421515568,0.8708264960899297,1.4398966328953218,1017.2,1718.7,1659.9,815.2,1266.9,1208.4 +1.728946123162519,0.8708068421750532,1.5707963267948966,999.1,1629.0,1628.7,762.9,1193.3,1193.0 +1.7289474868039905,0.8708072784756486,1.7016960206944713,1059.4,1658.9,1717.5,772.6,1209.0,1267.3 +1.728948584945325,0.8708079608659307,1.832595714594046,1221.1,1825.9,1490.8,855.9,1330.6,1458.0 +1.7290073332297884,0.870846152837607,1.9634954084936205,1549.8,1270.3,1051.1,1054.9,1620.9,1384.1 +1.7290268533417323,0.8708691011465266,2.0943951023931953,1821.6,995.5,867.9,1410.6,1268.6,1141.0 +1.7290187005953113,0.8708529666319145,2.2252947962927703,1638.5,854.1,794.9,1229.8,1098.0,1039.2 +1.7290247504597986,0.8708789124103036,2.356194490192345,1599.4,793.0,793.5,1162.5,1028.4,1028.9 +1.7290219186902147,0.8709121532361779,2.4870941840919194,1681.4,795.0,854.0,1187.3,1039.4,1098.7 +1.7290251300501367,0.8709058038306292,2.6179938779914944,1512.6,868.8,996.4,1318.3,1141.2,1268.8 +1.729011159552268,0.870924382214399,2.748893571891069,1052.6,1051.9,1272.0,1547.7,1386.8,1606.9 +1.7290186208026626,0.8709195772434803,2.8797932657906435,855.4,1458.4,1330.8,1221.5,1961.9,1834.4 +1.729007724707663,0.8709266436214154,3.010692959690218,772.5,1268.2,1209.2,1060.5,1719.3,1660.6 +2.829060887576355,0.17089771314193714,0.0,63.0,93.1,93.0,1699.0,2728.3,2729.4 +2.829094953187069,0.1714189307417211,0.1308996938995747,91.6,119.2,129.6,1742.6,963.9,233.3 +2.829000520298327,0.1713889572651679,0.2617993877991494,116.7,59.3,186.8,1937.8,474.7,95.2 +2.82894302656649,0.1713519802785144,0.39269908169872414,62.7,63.0,283.8,2380.7,282.2,63.0 +2.828904841523059,0.17131184414393097,0.5235987755982988,150.3,95.3,474.6,3186.4,187.4,59.8 +2.8288906947963506,0.17128171195994368,0.6544984694978736,48.3,234.6,1054.8,2820.4,129.5,70.5 +2.828877401622831,0.1712295900157319,0.7853981633974483,63.1,1728.8,1728.3,2698.7,93.7,93.3 +2.8288785912487,0.1712142654532769,0.916297857297023,91.3,1763.5,1822.7,917.0,70.6,129.5 +2.828891850060046,0.17117179258471382,1.0471975511965976,139.2,1949.8,2077.4,393.6,59.5,94.9 +2.8289191802454354,0.17112518911950092,1.1780972450961724,222.6,2371.7,2591.1,224.2,63.3,110.3 +2.828916152615242,0.17112659161562815,1.3089969389957472,393.4,3233.6,3106.5,139.8,95.6,200.7 +2.8289308624096297,0.17111821661271853,1.4398966328953218,837.0,2856.0,2797.2,91.0,128.5,70.1 +2.829004877467542,0.17110022755006216,1.5707963267948966,1698.8,2729.2,2728.8,63.3,93.2,93.0 +2.828999509211308,0.17109871910472862,1.7016960206944713,1783.7,1065.7,238.0,48.6,122.5,129.3 +2.828997219021363,0.1710963765802871,1.832595714594046,2030.9,474.5,95.5,47.1,58.8,186.6 +2.8290541603384534,0.17113186713773,1.9634954084936205,2542.4,282.3,63.3,63.7,62.5,283.5 +2.8290727232612785,0.17115257973917153,2.0943951023931953,3091.3,186.7,59.5,117.4,95.5,475.9 +2.829064264850906,0.17113432727195366,2.2252947962927703,2776.8,129.5,70.7,91.0,235.6,1059.5 +2.8290701416286925,0.1711585222267169,2.356194490192345,2699.2,93.2,93.8,62.4,1728.0,1728.9 +2.829066886006946,0.1711903690412666,2.4870941840919194,316.5,70.5,129.6,48.3,1764.3,1823.4 +2.829069895542841,0.1711824048095747,2.6179938779914944,117.6,59.9,94.5,46.5,1950.8,2078.1 +2.8290553943491505,0.1711993421933211,2.748893571891069,62.7,62.7,110.3,63.2,2377.3,2598.0 +2.829062852698841,0.17139113423671248,2.8797932657906435,46.6,95.0,200.4,117.2,3233.1,3105.4 +2.8288970833671985,0.1709027149964526,3.010692959690218,48.1,129.3,70.4,318.0,2857.9,2799.1 +2.8289197330482785,0.17089931104718792,0.0,63.1,93.1,93.0,1699.1,2728.7,2728.8 +2.828984108458107,0.1709043995769275,0.1308996938995747,91.4,119.8,129.6,1742.5,965.6,233.6 +2.8289736204978886,0.17090110205968667,0.2617993877991494,117.1,59.4,186.8,1937.2,475.0,95.2 +2.8289841304067647,0.17090752580259405,0.39269908169872414,62.9,63.1,283.7,2379.9,282.2,62.9 +2.8289962097427663,0.17092201130274054,0.5235987755982988,149.9,95.4,474.3,3187.5,187.4,59.7 +2.829014170497188,0.17095195003219965,0.6544984694978736,48.4,234.7,1053.4,2820.5,129.4,70.3 +2.829015379647139,0.17096168618359964,0.7853981633974483,63.2,1728.9,1728.1,2698.6,93.6,93.1 +2.829015310211368,0.1710050006334578,0.916297857297023,91.4,1763.9,1822.4,917.9,70.5,129.2 +2.8290134454481866,0.17101520128119319,1.0471975511965976,139.2,1949.6,2076.6,393.7,59.2,95.3 +2.829014646203069,0.17101209235683124,1.1780972450961724,222.6,2370.9,2590.2,224.1,63.0,109.9 +2.8289784807902336,0.17104625565256315,1.3089969389957472,393.2,3234.7,3106.9,139.7,95.1,200.9 +2.8289555193189475,0.17105973170527977,1.4398966328953218,921.6,2909.0,2797.9,90.9,128.7,70.2 +2.828989941822207,0.17105196265142708,1.5707963267948966,1698.8,2729.1,2728.1,63.1,93.4,93.1 +2.828947195674598,0.17105039451065962,1.7016960206944713,1783.5,1066.6,237.6,48.4,123.9,129.3 +2.82891126589967,0.17103920359646674,1.832595714594046,2030.7,474.6,95.1,46.8,58.9,186.5 +2.828939964075067,0.17105792970924028,1.9634954084936205,2542.0,282.2,63.0,63.3,62.6,283.4 +2.8289375827937957,0.17105670994229483,2.0943951023931953,3092.2,186.6,59.2,116.9,95.5,475.6 +2.8289157495132984,0.17101411883349282,2.2252947962927703,2777.3,129.3,70.5,91.1,235.2,1057.9 +2.8289157968151972,0.1710129676936727,2.356194490192345,2699.5,93.1,93.6,62.5,1728.4,1729.1 +2.8289139471193914,0.17102052878699414,2.4870941840919194,316.5,70.3,129.3,48.4,1764.4,1823.2 +2.8289239905999137,0.17099160048843243,2.6179938779914944,117.3,59.7,94.7,46.5,1950.6,2077.9 +2.828921424693808,0.17099145803870353,2.748893571891069,62.5,62.5,109.9,63.2,2376.7,2596.6 +2.828943374291192,0.17097258649958524,2.8797932657906435,46.4,94.6,200.5,117.1,3233.1,3105.5 +2.828948743094004,0.17097038054447378,3.010692959690218,48.1,129.3,70.4,318.1,2857.7,2799.3 +2.8289506317077633,0.17097207377989831,0.0,63.1,93.1,93.0,1698.9,2728.8,2728.8 +2.828993119362331,0.17097627737335208,0.1308996938995747,91.4,119.9,129.6,1742.6,965.3,233.5 +2.828965807058611,0.1709678459751922,0.2617993877991494,117.1,59.4,186.8,1937.2,475.0,95.1 +2.8289617881303926,0.17096521223614625,0.39269908169872414,62.9,63.1,283.8,2379.9,282.2,62.9 +2.828962853194825,0.17096792537199845,0.5235987755982988,149.9,95.4,474.4,3187.0,187.4,59.7 +2.828973761320767,0.17098476812915164,0.6544984694978736,48.4,234.6,1053.3,2820.6,129.4,70.3 +2.828971775505182,0.17098090931459886,0.7853981633974483,63.2,1729.3,1728.5,2699.0,93.6,93.1 +2.828972077428113,0.17101135752601548,0.916297857297023,91.4,1763.3,1822.4,918.0,70.5,129.2 +2.828973679112102,0.17101004366230188,1.0471975511965976,139.2,1949.3,2076.5,393.6,59.2,95.3 +2.8289807631304713,0.1709974614394798,1.1780972450961724,222.6,2370.9,2590.3,224.1,63.0,109.9 +2.8289520218282287,0.17102461871418018,1.3089969389957472,393.2,3234.2,3106.6,139.7,95.1,200.9 +2.8289374215559357,0.17103358625265797,1.4398966328953218,921.7,2856.7,2797.8,90.9,128.6,70.2 +2.8289805225676234,0.17102380513751414,1.5707963267948966,1699.0,2728.7,2728.0,63.1,93.4,93.1 +2.828945885368924,0.1710224860389855,1.7016960206944713,1783.7,1066.9,237.7,48.4,123.8,129.3 +2.8289171588292605,0.17101345661210465,1.832595714594046,2030.7,474.5,95.2,46.8,58.9,186.5 +2.828951850717036,0.17103592951127933,1.9634954084936205,2542.1,282.2,63.0,63.3,62.6,283.4 +2.828953896069744,0.17103946488004484,2.0943951023931953,3091.9,186.6,59.2,116.9,95.5,475.6 +2.828934867769425,0.1710021223849323,2.2252947962927703,2776.6,129.3,70.5,91.0,235.3,1058.1 +2.8289361647177893,0.17100639034332366,2.356194490192345,2699.6,93.1,93.6,62.5,1728.8,1729.0 +2.8289341187014077,0.17101911701454697,2.4870941840919194,316.4,70.3,129.3,48.4,1764.4,1823.1 +2.828942773526978,0.17099471669929978,2.6179938779914944,117.3,59.7,94.7,46.5,1950.2,2078.5 +2.828937852075314,0.17099831464230153,2.748893571891069,62.5,62.5,109.9,63.2,2376.6,2596.4 +2.8289568358699673,0.17098220590581614,2.8797932657906435,46.4,94.6,200.5,117.1,3233.3,3105.3 +2.8289588925462823,0.17098176387546515,3.010692959690218,48.0,129.3,70.5,318.1,2858.0,2798.5 +2.8289573692541103,0.17098424397284528,0.0,63.1,93.0,93.0,1698.7,2729.2,2729.5 +2.8289961861802118,0.17098828787501064,0.1308996938995747,91.4,119.9,129.6,1742.5,965.1,233.5 +2.828966295179913,0.17097906883654934,0.2617993877991494,117.1,59.4,186.8,1937.2,474.8,95.1 +2.828959985851759,0.1709750099906031,0.39269908169872414,62.9,63.1,283.7,2379.6,282.2,62.8 +2.8289592984748753,0.17097585676456162,0.5235987755982988,149.8,95.4,474.3,3187.6,187.4,59.7 +2.828969073013759,0.1709906141031139,0.6544984694978736,48.4,234.6,1053.4,2821.1,129.4,70.3 +2.828966569759537,0.17098458909984338,0.7853981633974483,63.2,1728.7,1728.3,2698.8,93.6,93.0 +2.82896691807882,0.17101297990426834,0.916297857297023,91.4,1763.4,1822.2,917.8,70.5,129.2 +2.8289690617981487,0.17100981980504648,1.0471975511965976,139.2,1949.1,2076.8,393.6,59.2,95.2 +2.8289770790499538,0.17099571846928985,1.1780972450961724,222.6,2371.1,2590.1,224.1,63.0,109.9 +2.8289495189394147,0.17102174564612915,1.3089969389957472,393.1,3234.1,3106.6,139.6,95.1,200.9 +2.82893625385813,0.1710299781396558,1.4398966328953218,921.6,2856.7,2798.1,90.8,128.6,70.2 +2.828980746239442,0.17101987152823317,1.5707963267948966,1698.5,2728.4,2728.3,63.1,93.4,93.1 +2.828947410757264,0.17101858929973313,1.7016960206944713,1783.9,1066.8,237.7,48.4,123.8,129.2 +2.828919842542146,0.17100990165522467,1.832595714594046,2031.0,474.5,95.2,46.8,58.9,186.5 +2.828955496431114,0.17103297909341708,1.9634954084936205,2541.9,282.1,63.0,63.3,62.6,283.4 +2.828958247997061,0.1710372849453945,2.0943951023931953,3092.6,186.6,59.2,116.9,95.5,475.5 +2.8289396650521583,0.1710007873138959,2.2252947962927703,2776.6,129.3,70.5,91.0,235.3,1058.1 +2.8289411545252916,0.17100592615908194,2.356194490192345,2699.4,93.1,93.6,62.5,1728.6,1728.9 +2.8289390638623013,0.17101948269392886,2.4870941840919194,316.4,70.3,129.3,48.4,1764.3,1823.0 +2.828947487616044,0.17099580290012573,2.6179938779914944,117.3,59.7,94.7,46.5,1950.2,2078.0 +2.82894217618788,0.17098327019888537,2.748893571891069,62.5,62.5,109.9,63.2,2376.8,2596.7 +2.8289676265374575,0.17097781126064793,2.8797932657906435,46.4,94.6,200.5,117.1,3233.2,3105.9 +2.8289634257335416,0.1709806631347892,3.010692959690218,48.0,129.3,70.5,318.1,2857.5,2799.1 +1.6288829316445625,0.5710032919936556,0.0,463.1,1293.1,1293.0,1299.0,1528.9,1528.9 +1.6289546072910093,0.5715033308114488,0.1308996938995747,505.9,1313.1,1372.5,1328.3,1557.2,1616.7 +1.6289150507398713,0.5714901344350964,0.2617993877991494,601.9,1446.2,1573.8,1475.2,1272.6,892.9 +1.6288600595613663,0.5714544698551152,0.39269908169872414,790.5,1762.6,1807.6,1814.1,846.8,627.7 +1.6288127647188446,0.5714041675087735,0.5235987755982988,1190.3,1615.2,1487.7,1799.8,650.0,522.3 +1.628790615917717,0.5713583992156916,0.6544984694978736,1290.7,1409.0,1349.9,1578.2,543.7,484.6 +1.6287734290475246,0.5712884701732999,0.7853981633974483,1263.2,1328.6,1328.4,1498.9,493.8,493.3 +1.6287754342132,0.5712559501299876,0.916297857297023,1333.6,1349.4,1408.5,1535.0,484.7,543.6 +1.6287936024237475,0.5711980249607111,1.0471975511965976,1525.5,1487.1,1614.7,1192.4,521.7,649.0 +1.628828971098579,0.5711386117686867,1.1780972450961724,1814.2,1806.6,2025.5,791.0,627.9,847.0 +1.6288360306641436,0.5711305806352918,1.3089969389957472,1474.9,1846.5,1719.1,602.4,892.8,1272.0 +1.6288620410568624,0.5711161744222055,1.4398966328953218,1326.9,1614.9,1556.6,504.9,1370.3,1311.8 +1.6289477423237007,0.5710952541314682,1.5707963267948966,1298.7,1528.8,1528.6,463.3,1293.4,1293.2 +1.6289533545150288,0.5710938548419384,1.7016960206944713,1369.6,1556.2,1614.2,462.6,1312.4,1370.8 +1.6289608819187011,0.5710942798187422,1.832595714594046,1568.1,1271.9,892.6,509.5,1420.9,1574.0 +1.629026136940015,0.5711345739404652,1.9634954084936205,1975.3,846.9,627.8,630.7,1763.3,1806.6 +1.6290510215526603,0.5711614695222724,2.0943951023931953,1705.2,648.9,521.6,916.2,1614.1,1487.1 +1.6290466790989788,0.5711502849449002,2.2252947962927703,1534.9,543.5,484.8,1396.6,1408.0,1349.7 +1.6290545642651593,0.5711818960277615,2.356194490192345,1499.7,493.3,493.8,1262.5,1328.2,1328.6 +1.6290513664325763,0.5712208613550482,2.4870941840919194,1577.8,484.7,543.9,1291.0,1350.0,1409.1 +1.6290525980811499,0.5712192883606368,2.6179938779914944,914.4,522.4,650.1,1433.7,1487.7,1615.6 +1.629035006773035,0.571241490703327,2.748893571891069,628.5,628.5,848.5,1760.5,1811.3,2031.2 +1.6290383211088795,0.5712386070147393,2.8797932657906435,508.8,893.1,1272.7,1567.8,1846.3,1718.9 +1.6290231458155517,0.5712459775198817,3.010692959690218,462.4,1371.4,1312.6,1370.8,1615.3,1556.8 +1.629045647992211,0.6715226324087729,0.0,563.2,1293.1,1293.0,1198.8,1529.1,1528.8 +1.6289966736862105,0.6707296779120282,0.1308996938995747,609.3,1313.1,1372.7,1225.0,1557.6,1662.6 +1.6290208331803515,0.6707375586944444,0.2617993877991494,717.3,1446.2,1573.5,1359.6,1472.1,1092.4 +1.6290512336667167,0.6707571453878078,0.39269908169872414,931.5,1762.6,1667.0,1672.4,988.3,768.8 +1.6290757671633953,0.6707858167710947,0.5235987755982988,1388.8,1500.3,1372.4,1799.8,765.5,637.8 +1.6291009287156812,0.6708302753148019,0.6544984694978736,1290.9,1305.8,1246.7,1578.2,647.0,588.0 +1.629105129708409,0.6708545235986856,0.7853981633974483,1263.4,1229.1,1228.5,1498.9,593.5,593.0 +1.629104369499878,0.6709112738654688,0.916297857297023,1333.6,1246.1,1304.9,1534.4,587.9,646.7 +1.6290987688004204,0.6709333837608018,1.0471975511965976,1525.4,1372.0,1498.9,1391.9,636.9,763.8 +1.6290939193407663,0.6709401239108546,1.1780972450961724,1673.1,1665.8,1884.8,932.5,768.5,987.6 +1.6290502012633614,0.6709816664870365,1.3089969389957472,1360.2,1846.8,1719.2,717.7,1090.9,1447.3 +1.629018738543648,0.6710000635414275,1.4398966328953218,1224.0,1614.8,1556.5,608.1,1370.2,1311.7 +1.629044263714046,0.6709948609223686,1.5707963267948966,1199.0,1529.1,1528.8,563.0,1293.3,1293.2 +1.6289930408295286,0.6709935866784766,1.7016960206944713,1266.4,1555.7,1659.8,565.5,1312.4,1370.5 +1.6289493803776,0.670980660532094,1.832595714594046,1452.8,1470.9,1091.4,624.7,1445.9,1573.8 +1.628971402440093,0.6709959396787148,1.9634954084936205,1833.6,987.7,768.6,771.7,1762.7,1666.1 +1.628963845337945,0.6709900514559533,2.0943951023931953,1705.5,764.2,636.8,1115.0,1499.4,1372.0 +1.628938538269345,0.6709420079366692,2.2252947962927703,1534.9,646.7,587.9,1333.0,1305.1,1246.2 +1.6289368327060898,0.6709350104124794,2.356194490192345,1499.7,593.0,593.6,1262.2,1228.5,1229.0 +1.6289349060293672,0.6709368711760268,2.4870941840919194,1689.1,587.8,647.0,1290.7,1246.6,1305.9 +1.6289463958623471,0.6709028545963358,2.6179938779914944,1113.3,637.6,765.3,1434.0,1372.5,1500.2 +1.6289464628228079,0.6708985563536451,2.748893571891069,769.6,769.5,989.4,1760.1,1670.2,1889.7 +1.628971874355691,0.6708767205916824,2.8797932657906435,624.1,1092.0,1446.1,1452.6,1846.5,1718.9 +1.6289811053922443,0.6708728289549926,3.010692959690218,565.6,1371.2,1312.6,1267.7,1615.3,1556.6 +1.6290322564515978,0.7711714006662349,0.0,662.8,1293.0,1292.9,1099.2,1529.2,1528.9 +1.629002994698221,0.7711708818781118,0.1308996938995747,712.5,1312.9,1372.5,1121.5,1557.4,1616.8 +1.6289469689335814,0.7711545405337286,0.2617993877991494,832.6,1446.3,1573.8,1244.3,1671.5,1291.8 +1.6288924860790779,0.7711212054998497,0.39269908169872414,1073.1,1762.8,1526.2,1531.1,1129.3,909.7 +1.6288488213981038,0.7710769145899703,0.5235987755982988,1434.4,1384.8,1257.1,1799.9,880.9,753.4 +1.6288295474362846,0.7710386704808676,0.6544984694978736,1291.0,1202.1,1143.2,1578.0,750.6,691.6 +1.628813520447013,0.7709764993506698,0.7853981633974483,1263.0,1129.1,1128.5,1499.2,693.4,693.0 +1.6288152327165903,0.7709513341989236,0.916297857297023,1333.4,1142.7,1201.5,1534.4,691.6,750.2 +1.628831815510189,0.7709001152399151,1.0471975511965976,1525.1,1256.5,1383.7,1591.6,752.3,879.5 +1.6288645159852466,0.7708465082308202,1.1780972450961724,1531.4,1524.9,1743.8,1074.4,909.7,1128.6 +1.6288681585218532,0.7708434599355645,1.3089969389957472,1244.4,1847.1,1719.3,833.3,1290.4,1447.0 +1.6289038594734162,0.7708255244980158,1.4398966328953218,1120.4,1615.1,1556.7,711.6,1370.4,1311.7 +1.628974174441414,0.7708098913785051,1.5707963267948966,1098.9,1529.1,1528.7,663.1,1293.3,1293.0 +1.628972260789528,0.7708101163289991,1.7016960206944713,1162.9,1556.0,1614.3,669.1,1312.4,1370.6 +1.628974796551356,0.770811069331776,1.832595714594046,1337.2,1670.2,1290.8,740.5,1446.1,1573.8 +1.6290359800966825,0.770850778982999,1.9634954084936205,1691.7,1128.9,909.9,913.6,1762.9,1525.1 +1.6290575608703268,0.7708760729768673,2.0943951023931953,1705.9,879.6,727.0,1314.7,1383.9,1256.4 +1.6290507763905697,0.770862574935947,2.2252947962927703,1535.1,750.4,691.5,1333.0,1201.4,1142.7 +1.6290573759277558,0.7708912889981427,2.356194490192345,1499.3,693.0,693.5,1262.4,1128.4,1129.1 +1.6290542565368082,0.7709272033815093,2.4870941840919194,1578.1,691.5,750.6,1290.9,1143.0,1202.0 +1.6290566445646157,0.7709230926659645,2.6179938779914944,1312.5,753.1,880.8,1433.9,1256.7,1384.4 +1.6290412593330466,0.770943505268342,2.748893571891069,910.9,910.9,1130.9,1689.0,1528.4,1748.5 +1.6290471261620385,0.7709399558105154,2.8797932657906435,739.8,1291.0,1446.4,1336.9,1846.3,1719.0 +1.6290345050263484,0.770947753413251,3.010692959690218,669.0,1371.4,1312.8,1163.9,1615.8,1556.7 +1.6290592172288247,0.871226303847209,0.0,762.7,1292.8,1293.2,999.2,1529.0,1529.4 +1.6290000355985212,0.8706505755918905,0.1308996938995747,816.5,1312.9,1372.5,1017.8,1557.5,1616.7 +1.6290309019546885,0.8706607114907219,0.2617993877991494,948.4,1446.3,1573.6,1128.4,1718.6,1491.3 +1.6290697299833197,0.8706857698264603,0.39269908169872414,1214.8,1604.2,1384.8,1388.7,1270.5,1051.4 +1.6291012637086557,0.8707221579869142,0.5235987755982988,1543.9,1269.1,1141.2,1799.6,996.7,869.0 +1.6287886784488836,0.8710239388659309,0.6544984694978736,1290.9,1098.5,1039.4,1577.6,853.9,795.1 +1.6287850280457268,0.8710108362905999,0.7853981633974483,1263.2,1029.0,1028.4,1498.9,793.4,793.0 +1.6287863318159788,0.8710137076460611,0.916297857297023,1333.9,1039.2,1098.1,1534.8,795.2,854.0 +1.6287974484913246,0.8709818322279328,1.0471975511965976,1526.1,1141.1,1268.4,1706.4,868.3,995.7 +1.6288531346057304,0.8708922296935662,1.1780972450961724,1388.5,1384.3,1603.7,1215.3,1051.6,1270.8 +1.6286642604092993,0.8710665701979949,1.3089969389957472,1128.3,1846.1,1718.8,948.3,1491.3,1447.3 +1.628791306605866,0.8710005107755561,1.4398966328953218,1016.9,1614.6,1556.4,814.9,1370.1,1311.5 +1.6288910633232603,0.8709782872027885,1.5707963267948966,999.0,1528.7,1528.6,763.2,1293.1,1293.1 +1.6288810824483382,0.8709779250005543,1.7016960206944713,1059.7,1555.9,1614.3,772.7,1312.6,1371.0 +1.6288653988694373,0.8709724282957936,1.832595714594046,1221.7,1720.3,1488.5,856.4,1446.4,1574.2 +1.6289083340524526,0.870999954091574,1.9634954084936205,1551.0,1269.4,1050.4,1056.2,1602.0,1383.0 +1.6289158172309675,0.871009359393625,2.0943951023931953,1704.8,994.9,867.7,1516.1,1267.7,1140.7 +1.6289004287071023,0.8709778818557916,2.2252947962927703,1534.9,853.6,794.9,1333.0,1097.6,1039.0 +1.628903590262587,0.870988250535808,2.356194490192345,1499.1,792.9,793.6,1262.4,1028.3,1029.1 +1.6289015018624096,0.8710071180384478,2.4870941840919194,1578.5,795.3,854.4,1291.0,1039.6,1098.7 +1.628909060400687,0.8709880062012145,2.6179938779914944,1510.4,869.2,997.0,1434.5,1141.7,1269.1 +1.6289293352362968,0.8709519234924743,2.748893571891069,1051.9,1053.2,1273.3,1546.1,1387.5,1607.9 +1.6289186640378068,0.8709636503739786,2.8797932657906435,855.1,1492.4,1448.4,1221.0,1845.1,1718.4 +1.6289097793760907,0.8709692224854109,3.010692959690218,772.5,1371.2,1312.7,1060.2,1615.4,1556.6 diff --git a/tools/localisation_machine_learning/data/sector4.csv b/tools/localisation_machine_learning/data/sector4.csv new file mode 100644 index 00000000..06be3000 --- /dev/null +++ b/tools/localisation_machine_learning/data/sector4.csv @@ -0,0 +1,2496 @@ +2.828952192164696,1.8289997058496303,0.0,1721.1,93.1,93.2,40.9,2729.1,2729.0 +2.829015094059926,1.8294389817312315,0.1308996938995747,698.7,70.3,129.8,25.4,2800.7,2860.6 +2.8289192700815335,1.8294082950824215,0.2617993877991494,116.7,59.4,50.9,21.2,3107.6,3234.9 +2.828859993699072,1.8293697736577774,0.39269908169872414,62.7,63.1,31.6,31.9,2620.6,2401.5 +2.828820621621919,1.8293276339744853,0.5235987755982988,46.9,95.6,33.4,72.2,2077.4,1975.9 +2.8288056827914927,1.8292951628703578,0.6544984694978736,48.4,106.3,47.4,232.0,1845.8,1787.0 +2.828792588675131,1.829240985909381,0.7853981633974483,63.2,70.7,70.3,2699.0,1751.9,1751.7 +2.8287942515514723,1.8292236735681497,0.916297857297023,91.5,47.2,106.3,2776.9,1055.9,235.6 +2.828808424034774,1.8291795731956533,1.0471975511965976,114.0,33.7,161.3,3093.9,717.5,94.9 +2.8288370510726875,1.829132095278746,1.1780972450961724,31.4,31.3,250.8,2571.0,284.1,63.6 +2.8288352082357617,1.829132787038054,1.3089969389957472,20.9,50.7,430.8,2055.5,187.2,59.8 +2.8288510395251256,1.8291237112507983,1.4398966328953218,25.6,152.2,983.6,1806.0,128.4,70.2 +2.8289261934162053,1.8291058232327666,1.5707963267948966,40.8,2728.6,2728.9,1721.5,93.2,93.2 +2.8289670279632237,1.8291036781863728,1.7016960206944713,68.1,2798.0,2856.6,921.3,70.8,129.4 +2.8289364315400825,1.8290921763199808,1.832595714594046,114.0,3108.4,3237.0,391.0,58.9,50.4 +2.828988971680752,1.8291245728169572,1.9634954084936205,192.5,2619.9,2401.3,221.3,62.7,31.3 +2.8290091005937783,1.8291467100577197,2.0943951023931953,350.2,2101.3,1973.7,139.3,95.8,33.8 +2.829003083334592,1.8291317662658721,2.2252947962927703,833.7,1845.2,1786.7,91.0,105.9,47.3 +2.8290105593613437,1.8291603071070228,2.356194490192345,2699.8,1750.7,1751.8,62.5,70.1,70.8 +2.8290074505179486,1.8291969249828044,2.4870941840919194,2821.6,1050.0,233.9,48.4,47.3,106.6 +2.829009766831573,1.829193188750614,2.6179938779914944,3189.3,715.7,94.6,46.6,33.3,161.2 +2.828993102378388,1.8292139735026314,2.748893571891069,2405.0,282.8,63.2,63.3,32.1,252.4 +2.828997973206131,1.8292100065832695,2.8797932657906435,1936.0,186.7,59.5,117.5,51.6,432.1 +2.8289843366190586,1.8292167788106193,3.010692959690218,1764.3,129.2,70.6,68.4,151.9,977.8 +2.8289204393595107,1.7289132325379315,0.0,1621.0,93.0,93.2,140.6,2728.8,2729.1 +2.8289408915567456,1.7293328430035246,0.1308996938995747,595.1,70.3,129.7,129.0,2800.3,2860.7 +2.8289033697155617,1.7293205096068853,0.2617993877991494,116.8,59.4,187.0,136.8,3106.9,3199.8 +2.8288652113396098,1.7292955710522266,0.39269908169872414,62.8,63.1,172.8,173.6,2480.8,2230.5 +2.828834498297621,1.7292630917662273,0.5235987755982988,47.0,95.5,149.0,271.6,1988.3,1860.6 +2.8288236404596527,1.7292384347376486,0.6544984694978736,48.4,232.7,150.9,617.9,1742.3,1683.3 +2.8288119780756187,1.7291910917503204,0.7853981633974483,63.2,170.8,170.3,2699.0,1651.7,1651.2 +2.828813509357292,1.7291800022581931,0.916297857297023,91.4,150.8,209.7,2776.9,1057.5,632.7 +2.8288261366276513,1.7291413902631863,1.0471975511965976,139.3,149.3,276.8,3214.0,621.0,95.0 +2.8288520459030573,1.7290982645093549,1.1780972450961724,191.8,172.6,391.9,2430.7,284.3,63.6 +2.828846877856957,1.7291023555523175,1.3089969389957472,136.5,250.2,629.7,1940.3,187.3,59.8 +2.8288589341231436,1.7290957572369692,1.4398966328953218,129.1,542.5,1372.7,1703.1,128.5,70.2 +2.8289300419626984,1.7290788863452267,1.5707963267948966,140.8,2728.8,2728.6,1621.6,93.3,93.1 +2.8289218191111636,1.729077515180447,1.7016960206944713,171.6,2797.8,2855.8,922.8,70.8,129.4 +2.828916982218583,1.7290743379526503,1.832595714594046,229.5,3108.3,3197.6,609.1,58.9,186.7 +2.8289718191935815,1.7291084407910997,1.9634954084936205,334.3,2479.3,2260.6,221.4,62.7,172.4 +2.8289889101548944,1.7291273918804058,2.0943951023931953,549.8,1985.8,1858.8,139.3,95.7,149.3 +2.828979785176669,1.7291070664769759,2.2252947962927703,1220.1,1742.0,1683.0,91.0,232.3,150.9 +2.8289856737379067,1.7291292330581791,2.356194490192345,2699.0,1651.3,1651.7,62.5,170.2,170.8 +2.8289829114032448,1.7291593864257055,2.4870941840919194,2821.4,1051.8,632.9,48.4,150.9,210.1 +2.828986947539617,1.7291500430671773,2.6179938779914944,3174.9,622.0,94.6,46.6,149.0,276.8 +2.8289735231913054,1.7291661199015314,2.748893571891069,2265.2,283.0,63.2,63.3,173.6,393.8 +2.8289822273589103,1.7291588228601147,2.8797932657906435,1846.4,186.8,59.5,117.4,251.3,631.5 +2.8289728636695965,1.7291635903791207,3.010692959690218,1660.7,129.2,70.5,172.0,539.6,1363.9 +2.8289137496476044,1.62886388474961,0.0,1521.5,93.0,93.1,240.6,2729.1,2728.7 +2.8289498062922864,1.6293255261276305,0.1308996938995747,491.4,70.3,129.7,232.6,2800.2,2859.9 +2.8289162358366378,1.6293144694388453,0.2617993877991494,116.8,59.4,187.0,252.4,3106.4,3001.3 +2.8288794250758245,1.6292904620766626,0.39269908169872414,62.8,63.1,283.9,315.3,2340.0,2121.0 +2.828849160856535,1.629258608629623,0.5235987755982988,46.9,95.5,264.6,470.8,1873.0,1745.1 +2.828838490572868,1.6292344556804297,0.6544984694978736,48.4,235.0,254.5,1003.7,1638.6,1579.8 +2.8288267840078607,1.6291874773637638,0.7853981633974483,63.2,270.8,270.3,2698.7,1551.6,1551.3 +2.8288282378341516,1.6291767249289844,0.916297857297023,91.4,254.4,313.3,2777.2,1360.0,529.1 +2.828840716767151,1.6291383820331198,1.0471975511965976,139.3,264.9,392.4,3093.1,474.9,95.0 +2.828866409705926,1.6290953805288506,1.1780972450961724,222.8,313.7,533.0,2289.6,284.3,63.6 +2.828861057265401,1.6290995863975883,1.3089969389957472,252.2,449.6,829.1,1825.0,187.3,59.8 +2.828872942560013,1.6290931244193372,1.4398966328953218,232.5,932.4,1761.9,1599.6,128.5,70.2 +2.8289438695984064,1.6290762278558308,1.5707963267948966,240.8,2728.6,2728.8,1521.3,93.3,93.1 +2.8289354921916647,1.629074856948092,1.7016960206944713,275.0,2797.6,2856.4,923.4,70.8,129.3 +2.8289304877663253,1.6290717478815921,1.832595714594046,345.2,3107.7,2998.9,493.3,58.9,186.6 +2.8289851742678285,1.6291058162595826,1.9634954084936205,475.9,2339.7,2120.2,221.4,62.6,283.8 +2.829002142091084,1.629124672016772,2.0943951023931953,749.6,1870.5,1743.6,139.3,95.7,264.9 +2.8289928592718767,1.6291042984302986,2.2252947962927703,1607.4,1638.6,1579.5,91.0,236.0,254.3 +2.8289986142616037,1.6291263739826998,2.356194490192345,2700.2,1551.1,1552.0,62.5,270.2,270.9 +2.8289958095562935,1.6291563595925376,2.4870941840919194,2820.8,1360.3,529.4,48.4,254.4,313.7 +2.828999776588738,1.6291468851385917,2.6179938779914944,3020.2,473.4,94.6,46.6,264.6,392.4 +2.828986434162281,1.6291627875432724,2.748893571891069,2123.8,283.0,63.2,63.3,315.1,535.3 +2.8289951945564393,1.629155372791712,2.8797932657906435,1731.2,186.8,59.5,117.3,450.9,831.1 +2.8289859376691466,1.6291600631350396,3.010692959690218,1557.3,129.2,70.5,298.3,927.1,1750.9 +2.8289268943205395,1.5288605035076095,0.0,1421.5,93.0,93.1,340.6,2729.1,2729.1 +2.8289621962444595,1.5293248289429244,0.1308996938995747,314.3,70.3,129.6,336.1,2800.4,2860.5 +2.8289285045883195,1.5293137607192484,0.2617993877991494,116.8,59.3,186.9,368.0,3106.5,2802.2 +2.828891695095093,1.529289808179112,0.39269908169872414,62.7,63.1,283.9,457.0,2198.7,1980.0 +2.828861413751039,1.5292580377856428,0.5235987755982988,46.9,95.4,380.3,670.2,1757.2,1629.6 +2.8288507380584558,1.5292339983193404,0.6544984694978736,48.4,234.9,358.0,1389.3,1535.7,1476.3 +2.8288389467470036,1.5291870854269658,0.7853981633974483,63.2,370.8,370.3,2699.2,1451.8,1451.1 +2.8288403355051592,1.5291764011884421,0.916297857297023,91.3,357.8,416.7,2776.7,1256.2,425.6 +2.828852737121434,1.5291380960645307,1.0471975511965976,139.2,380.5,507.8,3060.4,474.9,95.0 +2.8288783381549503,1.5290950558199237,1.1780972450961724,222.7,454.9,674.1,2148.1,457.2,63.6 +2.8288729375070214,1.529099239705825,1.3089969389957472,393.3,648.7,1028.3,1709.6,187.3,59.8 +2.8288848017649344,1.5290927960876088,1.4398966328953218,336.0,1322.1,2151.5,1496.2,128.5,70.2 +2.828955713056238,1.5290758438615657,1.5707963267948966,340.8,2729.3,2729.1,1421.4,93.3,93.1 +2.828947335709628,1.5290744655507877,1.7016960206944713,378.5,2797.8,2856.3,1233.8,70.8,129.3 +2.8289423145865613,1.529071422493316,1.832595714594046,460.8,3107.5,2800.4,391.5,58.9,186.6 +2.828996979497023,1.5291055165080876,1.9634954084936205,617.6,2198.2,1979.4,221.5,62.6,283.6 +2.8290139195534345,1.5291243753917274,2.0943951023931953,949.1,1755.6,1628.2,139.4,95.6,380.3 +2.8290045602767253,1.5291040425921723,2.2252947962927703,1994.6,1535.0,1476.7,91.0,235.8,357.8 +2.82901022916488,1.529126130800816,2.356194490192345,2699.8,1450.7,1451.8,62.5,370.2,370.8 +2.829007375454266,1.5291560705749294,2.4870941840919194,2821.0,1256.8,425.7,48.4,358.1,417.2 +2.829011261045814,1.529146558822195,2.6179938779914944,2821.6,473.6,94.6,46.6,380.3,508.0 +2.828997926366784,1.529162379222034,2.748893571891069,1982.5,455.5,63.2,63.2,456.5,676.6 +2.8290066769948075,1.529154902671746,2.8797932657906435,1615.6,186.8,59.5,117.3,650.5,1030.6 +2.8289974470206842,1.529159544367005,3.010692959690218,1453.6,129.2,70.5,318.8,1314.4,2137.9 +2.8289384133718616,1.428860053033536,0.0,1321.1,93.0,93.0,440.6,2729.0,2729.0 +2.8289720746639406,1.429324821300059,0.1308996938995747,314.4,70.2,129.6,439.8,2800.4,2859.7 +2.828938018345829,1.429313658813514,0.2617993877991494,354.6,59.3,186.9,483.6,2982.2,2603.4 +2.8289011110160702,1.4292896848689824,0.39269908169872414,62.7,63.1,283.8,598.6,2057.9,1838.9 +2.8288707756483276,1.4292579327519055,0.5235987755982988,46.9,95.4,474.7,869.2,1641.8,1514.0 +2.8288600765306278,1.4292339435349386,0.6544984694978736,48.4,234.8,461.6,1775.0,1432.0,1372.9 +2.8288482131355526,1.4291870483918014,0.7853981633974483,63.1,470.8,470.3,2698.6,1351.7,1351.3 +2.8288495524680695,1.4291763870015697,0.916297857297023,91.3,461.4,520.3,2776.2,1130.0,322.0 +2.828861901910093,1.4291380847932311,1.0471975511965976,139.2,496.0,623.4,2904.2,475.0,95.0 +2.82888744503841,1.4290949938262467,1.1780972450961724,222.6,596.1,815.1,2006.6,284.4,63.6 +2.828882023077893,1.4290991444664551,1.3089969389957472,393.5,848.1,1227.6,1593.9,187.3,59.8 +2.8288938891207582,1.4290927031117198,1.4398966328953218,439.4,1711.8,2541.1,1392.5,128.5,70.2 +2.8289648075788247,1.4290757028889973,1.5707963267948966,440.8,2728.9,2728.7,1321.3,93.3,93.1 +2.828956448638681,1.4290743182170673,1.7016960206944713,482.0,2797.5,2856.1,1130.3,70.8,129.3 +2.8289514316753452,1.429071328861383,1.832595714594046,576.3,2980.7,2601.4,391.5,58.9,186.6 +2.829006094427289,1.4292295923084062,1.9634954084936205,759.2,2057.3,1838.2,221.5,62.6,283.6 +2.8290286352385414,1.4291281344270153,2.0943951023931953,1148.7,1639.9,1512.7,139.4,95.6,476.0 +2.8290171236133417,1.4291039568311832,2.2252947962927703,2381.8,1431.6,1373.0,91.0,235.7,461.4 +2.8290225677677845,1.42912535649626,2.356194490192345,2699.7,1351.2,1351.7,62.5,470.2,470.8 +2.829019663993696,1.4291556739191906,2.4870941840919194,2821.3,1130.0,322.2,48.4,461.6,520.7 +2.8290232779228437,1.429146821426245,2.6179938779914944,2622.9,473.5,94.6,46.5,495.8,623.6 +2.829009533219573,1.4291632433469474,2.748893571891069,1841.7,283.1,63.2,63.2,597.8,818.1 +2.829017724904979,1.4291562353549137,2.8797932657906435,1500.1,186.8,59.5,117.2,849.9,1229.8 +2.8290078887637584,1.429161175209594,3.010692959690218,1350.4,129.2,70.5,318.6,1701.1,2524.6 +2.8289481020881686,1.3288611634266516,0.0,1221.4,93.0,93.0,540.6,2728.3,2729.3 +2.8289799174988564,1.3293242608616986,0.1308996938995747,314.4,70.2,129.6,543.3,2800.4,2859.8 +2.828945513248929,1.3293130058653477,0.2617993877991494,239.0,59.3,186.9,599.2,2783.6,2404.3 +2.8289085698099683,1.3292890412496483,0.39269908169872414,62.7,63.0,283.8,740.3,1916.6,1698.1 +2.8288782464225015,1.3292573621161043,0.5235987755982988,46.9,95.4,474.6,1068.5,1526.4,1398.5 +2.8288675681481603,1.3292334861142188,0.6544984694978736,48.3,234.7,565.1,2160.5,1328.5,1269.4 +2.8288556676404277,1.329186685355151,0.7853981633974483,63.1,570.8,570.3,2698.9,1251.7,1251.1 +2.828856966185149,1.3291761185754498,0.916297857297023,91.3,564.9,623.7,2777.1,1058.9,236.3 +2.8288692545153906,1.3291378877949338,1.0471975511965976,139.2,611.5,738.9,2705.0,475.1,286.1 +2.8288947180454396,1.3290948153197908,1.1780972450961724,222.6,737.1,956.3,1864.9,284.4,63.6 +2.828889235326101,1.3290989831277653,1.3089969389957472,393.3,1047.6,1426.5,1478.5,187.3,59.7 +2.828901052645857,1.3290925712635602,1.4398966328953218,542.9,2101.2,2798.3,1289.1,128.5,70.2 +2.8289719244300904,1.329075547760013,1.5707963267948966,540.8,2728.6,2728.5,1221.3,93.3,93.1 +2.8289635304107765,1.3290741581039185,1.7016960206944713,585.4,2797.3,2855.9,1004.0,70.8,129.3 +2.828958472493986,1.3290711979123861,1.832595714594046,691.9,2781.3,2402.4,391.6,58.9,186.6 +2.829013096259006,1.3291053189015236,1.9634954084936205,900.9,1916.4,1697.4,221.5,62.6,283.6 +2.8290299894102433,1.329124173329657,2.0943951023931953,1348.1,1524.4,1397.3,280.3,95.5,475.9 +2.8290205211192805,1.329103884874868,2.2252947962927703,2768.8,1327.9,1269.2,91.0,235.5,564.8 +2.829026070603792,1.3291259791946426,2.356194490192345,2699.4,1251.2,1251.7,62.5,570.3,570.8 +2.829023149211964,1.3291558470938705,2.4870941840919194,2820.7,1143.2,234.4,48.4,565.1,624.2 +2.8290269268015873,1.3291462749665666,2.6179938779914944,2423.9,473.6,287.0,46.5,611.5,739.1 +2.8290136050325794,1.3291619764292784,2.748893571891069,1700.0,283.1,63.2,63.2,739.3,959.3 +2.829022347789432,1.3291544092664744,2.8797932657906435,1384.9,186.8,59.4,117.2,1049.4,1429.5 +2.829013160542431,1.329158979971655,3.010692959690218,1246.9,129.2,70.5,318.5,2088.4,2799.0 +2.8289541503846087,1.2288595873785404,0.0,1121.4,93.0,93.0,640.7,2728.9,2729.0 +2.8289854831013477,1.2293248618877017,0.1308996938995747,314.5,70.2,129.6,646.9,2800.3,2860.0 +2.828950905407344,1.2293135632324383,0.2617993877991494,116.8,59.3,186.8,714.7,2584.5,2205.0 +2.828913855507463,1.2292895538511068,0.39269908169872414,204.0,63.0,283.8,881.8,1776.0,1556.5 +2.8288834428142655,1.2292578218114143,0.5235987755982988,46.9,95.3,474.5,1267.6,1410.5,1282.8 +2.8288727099945774,1.229233896808486,0.6544984694978736,48.3,234.6,668.6,2545.8,1224.9,1165.7 +2.8288607483126924,1.2291870223496766,0.7853981633974483,63.1,670.8,670.4,2698.8,1151.8,1150.9 +2.828862020793181,1.2291763888357792,0.916297857297023,91.3,668.4,727.2,2777.3,1058.9,236.3 +2.8288743003500625,1.2291380878749967,1.0471975511965976,139.2,727.1,854.3,2505.5,475.0,95.0 +2.828899766409303,1.229094926095641,1.1780972450961724,222.6,878.4,1097.4,1723.1,284.4,236.4 +2.82889431722277,1.2290990300394662,1.3089969389957472,393.3,1246.4,1626.2,1362.8,187.3,59.7 +2.82890618753682,1.2290925905024417,1.4398966328953218,646.3,2491.2,2797.8,1185.4,128.5,70.1 +2.8289771176910072,1.2290755247765865,1.5707963267948966,640.7,2729.0,2728.9,1121.1,93.3,93.1 +2.8289687855756642,1.229074131426211,1.7016960206944713,688.9,2797.3,2856.0,1017.0,70.8,129.3 +2.8289637760209447,1.2290712150577796,1.832595714594046,807.6,2582.3,2203.4,391.6,58.9,186.6 +2.8290184373574823,1.2291053745997012,1.9634954084936205,1042.6,1775.4,1556.5,221.5,62.6,283.5 +2.8290353535821504,1.2291242660771315,2.0943951023931953,1548.0,1408.7,1281.7,139.4,95.5,475.9 +2.829025874069988,1.229104036034023,2.2252947962927703,2776.6,1224.4,1165.7,91.0,235.5,668.4 +2.8290313955594875,1.2291261781524736,2.356194490192345,2699.7,1151.3,1151.8,62.5,670.2,670.8 +2.8290284508259864,1.2291560660743652,2.4870941840919194,2820.6,1053.3,234.5,48.4,668.7,727.8 +2.829032180701847,1.2291465126712762,2.6179938779914944,2225.2,473.6,94.6,46.5,727.1,854.9 +2.829018842971533,1.229162206315571,2.748893571891069,1558.7,283.2,235.7,63.2,880.8,1100.8 +2.829027557099396,1.2291546320503857,2.8797932657906435,1269.2,186.8,59.4,117.2,1248.7,1628.9 +2.8290183551512804,1.2291591930658496,3.010692959690218,1143.1,129.3,70.5,318.5,2474.9,2799.2 +2.828959318329021,1.1288598073222493,0.0,1021.3,93.0,93.0,740.7,2729.0,2728.7 +2.8289898971670473,1.1293249340882547,0.1308996938995747,314.5,70.2,129.6,750.6,2800.5,2859.7 +2.8289551428622137,1.1293135889558088,0.2617993877991494,116.9,59.3,186.8,830.3,2385.1,2005.6 +2.8289180396781846,1.1292895638091152,0.39269908169872414,62.7,63.0,283.7,1023.5,1635.0,1415.6 +2.828887596231405,1.1292578325680833,0.5235987755982988,46.9,95.3,474.4,1467.0,1295.1,1167.1 +2.8288768488479215,1.1292339220937753,0.6544984694978736,48.3,234.6,772.3,2820.7,1121.3,1062.4 +2.828864853218942,1.129187047537433,0.7853981633974483,63.1,770.8,770.3,2698.3,1051.6,1051.1 +2.828866103882427,1.1291764166626153,0.916297857297023,91.3,772.0,830.8,2776.8,1059.1,236.3 +2.828878362156172,1.129138110246044,1.0471975511965976,139.2,842.6,969.8,2306.3,475.1,95.0 +2.8289038057643063,1.1290949202781193,1.1780972450961724,222.6,1019.4,1238.5,1581.6,284.4,63.5 +2.8288983513265,1.1290990051928502,1.3089969389957472,393.3,1445.7,1825.0,1247.2,187.3,59.7 +2.828910227259813,1.129092563839837,1.4398966328953218,749.8,2856.7,2798.0,1082.1,128.5,70.1 +2.8289811656793686,1.129075475356148,1.5707963267948966,740.8,2728.6,2728.8,1021.3,93.3,93.1 +2.8289728465797697,1.129074079118554,1.7016960206944713,792.4,2797.5,2856.4,924.3,70.8,129.3 +2.8289678432359393,1.129071187767524,1.832595714594046,923.2,2383.0,2004.3,391.6,58.9,186.5 +2.8290225072974167,1.1291053616640436,1.9634954084936205,1184.2,1603.2,1415.1,221.5,62.5,283.5 +2.829039421565072,1.1291242618806245,2.0943951023931953,1747.7,1293.5,1165.9,139.4,95.5,475.9 +2.8290299209329497,1.1291040541979949,2.2252947962927703,2777.2,1121.0,1062.1,91.0,235.5,771.9 +2.8290354152573842,1.129126209566075,2.356194490192345,2699.7,1051.3,1051.8,62.5,770.2,770.8 +2.829032453174156,1.1291560905858846,2.4870941840919194,2820.4,1053.5,234.5,48.4,772.0,831.3 +2.8290361527321988,1.129146531844026,2.6179938779914944,2025.9,473.7,94.6,46.5,842.8,970.4 +2.8290228130174007,1.1291622035521218,2.748893571891069,1417.1,283.1,63.2,63.2,1022.2,1242.3 +2.829031518477022,1.1291546122502187,2.8797932657906435,1153.8,186.8,59.4,117.2,1448.3,1828.4 +2.829022319909326,1.1291591588440926,3.010692959690218,1039.8,129.3,70.4,318.4,2857.8,2799.1 +2.729015886142992,1.8292519979902422,0.0,1721.2,193.0,193.0,40.8,2629.4,2629.1 +2.729002613517055,1.828947465734458,0.1308996938995747,698.7,173.8,233.1,25.5,2696.9,2756.0 +2.729002643913587,1.8289474928336698,0.2617993877991494,316.3,174.9,51.2,21.3,2990.2,3117.5 +2.7289528937447063,1.8289217280251089,0.39269908169872414,203.9,204.6,31.8,32.0,2623.6,2403.8 +2.728987829724162,1.8289612736291865,0.5235987755982988,162.6,161.2,33.5,72.2,2104.2,1976.5 +2.7290038002907364,1.8289883748344746,0.6544984694978736,151.9,106.6,47.5,231.4,1846.4,1787.1 +2.7290013597560647,1.8289839380673505,0.7853981633974483,163.2,70.9,70.4,2598.6,1751.5,1750.8 +2.7290014249473193,1.8290100717379556,0.916297857297023,194.8,47.5,106.3,2673.7,1566.7,735.8 +2.7290042226985274,1.8290036404273147,1.0471975511965976,73.3,34.0,161.3,2977.2,675.0,294.7 +2.7290138840605564,1.8289865063881987,1.1780972450961724,31.8,31.6,250.7,2574.1,426.3,205.3 +2.7289885997015175,1.8290100993169502,1.3089969389957472,21.2,51.0,430.2,2056.7,303.0,175.4 +2.7289780442854794,1.8290166388525018,1.4398966328953218,25.8,152.3,980.9,1806.2,232.0,173.6 +2.729025459407898,1.8290058655461958,1.5707963267948966,40.9,2629.1,2628.6,1721.0,193.3,193.0 +2.7289948676017968,1.829004706776638,1.7016960206944713,68.3,2694.0,2752.5,1544.0,174.3,232.7 +2.7289697326330806,1.8289967751627063,1.832595714594046,114.0,2991.4,3119.3,724.3,174.5,51.0 +2.729007326353805,1.8290212815303073,1.9634954084936205,192.5,2622.2,2402.6,362.6,204.2,31.6 +2.729011374857718,1.8290273975153002,2.0943951023931953,349.8,2102.3,1974.7,254.9,161.3,34.0 +2.728993508858559,1.828992747780927,2.2252947962927703,831.2,1845.4,1786.3,194.5,106.3,47.5 +2.7289951392379406,1.8289997128156545,2.356194490192345,2599.4,1751.1,1751.9,162.4,70.4,71.0 +2.7289926463375163,1.829014955035798,2.4870941840919194,2716.8,1566.9,736.3,151.9,47.5,106.6 +2.7290004000585775,1.828992599616121,2.6179938779914944,3133.8,737.2,293.8,162.1,33.5,161.2 +2.728994089995956,1.8289978393079334,2.748893571891069,2407.0,424.6,204.5,204.5,32.3,252.3 +2.7290115848544416,1.8289828459301865,2.8797932657906435,1962.6,302.4,175.0,114.3,51.8,431.6 +2.729012077063184,1.8289830771070255,3.010692959690218,1764.5,232.7,173.9,68.8,151.9,974.7 +2.728964265101849,1.7286923117731048,0.0,1621.3,193.1,193.0,140.8,2629.3,2629.2 +2.728999739886674,1.72929333674033,0.1308996938995747,698.7,173.8,233.1,129.1,2696.5,2756.2 +2.728969554014504,1.7292835088000906,0.2617993877991494,316.3,174.9,294.4,136.8,2990.3,3117.6 +2.7289361049463126,1.729261905182195,0.39269908169872414,203.9,204.6,172.9,173.5,2481.9,2262.8 +2.7289082981180495,1.729233185541247,0.5235987755982988,162.5,294.5,149.0,271.3,1989.0,1860.9 +2.7288992139411112,1.7292125802648814,0.6544984694978736,151.8,210.0,151.0,616.4,1742.6,1683.4 +2.7288878742054035,1.7291690435963463,0.7853981633974483,163.1,170.8,170.3,2598.9,1652.1,1651.4 +2.7288889684576287,1.7291615675003196,0.916297857297023,194.8,150.9,209.7,2673.3,1463.3,623.7 +2.7289171459732784,1.729071475042868,1.0471975511965976,254.7,149.4,276.7,2976.8,674.9,294.7 +2.7289204508482587,1.729063646815025,1.1780972450961724,173.3,172.5,391.5,2432.0,426.2,205.3 +2.7289067828264923,1.729075406635375,1.3089969389957472,136.6,250.0,629.1,1941.0,303.0,175.3 +2.728917344355859,1.7290697468737748,1.4398966328953218,129.1,541.4,1369.7,1703.0,232.0,173.6 +2.7289897512733345,1.7290523310374253,1.5707963267948966,140.8,2628.4,2628.3,1621.3,193.3,193.0 +2.7289836941736105,1.7290510784521074,1.7016960206944713,171.5,2693.3,2752.3,1440.7,174.3,232.7 +2.728980937014095,1.7290490249272343,1.832595714594046,229.4,2991.9,3119.6,591.0,174.4,293.8 +2.7290375203702255,1.7290845197232803,1.9634954084936205,333.9,2480.6,2262.3,362.7,204.3,172.5 +2.7290558446155093,1.7291050411656448,2.0943951023931953,549.2,1986.9,1859.6,254.9,295.1,149.3 +2.7290471678922494,1.7290866478586493,2.2252947962927703,1217.9,1742.1,1683.5,194.5,209.7,150.8 +2.729052973846691,1.7291106281419792,2.356194490192345,2599.6,1651.3,1652.1,162.5,170.2,170.8 +2.7290499069703817,1.7291421786278431,2.4870941840919194,2716.9,1463.5,620.0,151.9,150.9,210.0 +2.7290691754186254,1.7290823496672023,2.6179938779914944,3072.3,673.0,293.9,162.2,149.0,276.6 +2.729035458134129,1.7291307473781252,2.748893571891069,2235.1,424.5,204.6,204.6,173.5,393.5 +2.7290680028987797,1.7291023462178159,2.8797932657906435,1821.8,302.5,175.0,229.7,251.0,630.9 +2.7290333129477884,1.7291204617430853,3.010692959690218,1660.7,232.7,173.9,172.1,538.5,1361.4 +2.72897169799283,1.6288324651430404,0.0,1521.4,193.0,193.0,240.7,2629.4,2629.3 +2.7290027427146053,1.6293258074093486,0.1308996938995747,698.7,173.8,233.1,232.6,2697.1,2756.5 +2.7289678160927395,1.6293144368359425,0.2617993877991494,316.3,174.9,302.3,252.4,3095.4,3002.9 +2.7289305460865556,1.6292903611787395,0.39269908169872414,203.9,204.6,314.1,315.2,2341.1,2121.7 +2.7288999254685975,1.629258543302738,0.5235987755982988,162.5,294.4,264.6,470.4,1873.3,1745.5 +2.7288890647028534,1.6292345475665961,0.6544984694978736,151.9,313.6,254.5,1002.2,1639.2,1580.3 +2.728876929802629,1.6291875251179049,0.7853981633974483,163.1,270.8,270.2,2599.2,1551.6,1551.3 +2.728878118397943,1.6291767603141267,0.916297857297023,194.8,254.4,313.2,2673.5,1446.9,623.7 +2.7288903502632382,1.629138309056125,1.0471975511965976,254.7,264.8,392.3,3061.7,674.9,294.7 +2.728915789803313,1.6290949248301454,1.1780972450961724,332.6,313.6,532.7,2290.1,599.1,205.2 +2.728910402315693,1.6290988721982198,1.3089969389957472,252.2,449.2,828.4,1825.2,303.0,175.3 +2.7289223893694374,1.6290923755718336,1.4398966328953218,232.5,931.1,1759.2,1599.4,232.0,173.6 +2.7289934503037423,1.6291501392461898,1.5707963267948966,240.7,2628.7,2628.7,1521.1,193.3,193.0 +2.728983735387362,1.6290730026480555,1.7016960206944713,275.0,2693.4,2752.6,1337.3,174.3,232.7 +2.7289798643547094,1.629070563281545,1.832595714594046,345.0,3092.8,3000.6,591.0,174.5,302.1 +2.7290349207705726,1.629105024361953,1.9634954084936205,475.7,2339.7,2120.6,362.6,204.2,313.7 +2.7290519419218455,1.629124070997908,2.0943951023931953,748.8,1870.9,1743.7,254.9,295.1,264.8 +2.729042409020431,1.6291039950011035,2.2252947962927703,1605.0,1638.8,1579.8,194.5,313.2,254.3 +2.7290478285415065,1.6291262305275753,2.356194490192345,2599.5,1551.0,1551.8,162.5,270.2,270.8 +2.729044813215352,1.629156118457358,2.4870941840919194,2717.2,1439.3,620.1,151.9,254.5,313.6 +2.729048412025337,1.629146566684864,2.6179938779914944,3022.1,673.0,293.8,162.1,264.6,392.2 +2.7290350566527652,1.6291621886052663,2.748893571891069,2124.6,597.2,204.6,204.6,314.9,534.9 +2.729043721272228,1.6291545585584952,2.8797932657906435,1731.5,302.4,175.0,316.6,450.6,830.3 +2.729034517556432,1.6291590696611982,3.010692959690218,1557.5,232.8,174.0,275.6,925.6,1748.7 +2.7289754481501785,1.5288597447231218,0.0,1421.0,193.0,193.0,340.7,2629.3,2629.0 +2.72900372164695,1.5293250128836267,0.1308996938995747,698.6,173.8,233.1,336.2,2696.7,2755.9 +2.7289684418333606,1.5293135312902384,0.2617993877991494,470.0,174.9,302.4,367.9,2990.8,2803.2 +2.728931189448076,1.5292894683760967,0.39269908169872414,203.9,204.6,425.3,456.8,2200.1,1980.6 +2.72890066139493,1.5292577528048945,0.5235987755982988,162.5,294.5,380.2,669.6,1757.6,1629.9 +2.7288898755417224,1.529233901753412,0.6544984694978736,151.9,417.1,358.0,1387.7,1535.8,1476.6 +2.728877776558651,1.5291870408860635,0.7853981633974483,163.1,370.8,370.2,2599.2,1451.6,1451.3 +2.7288789584029467,1.5291764314294358,0.916297857297023,194.8,357.9,416.8,2696.1,1446.9,623.7 +2.728891146473581,1.529138119667738,1.0471975511965976,254.7,380.4,507.7,2976.8,675.0,517.2 +2.728916513794892,1.5290948509834288,1.1780972450961724,363.7,454.8,673.8,2148.7,426.1,205.3 +2.728911035525274,1.5290988835250823,1.3089969389957472,367.8,648.6,1027.7,1709.8,303.0,175.3 +2.7289229207289245,1.529092441420001,1.4398966328953218,336.0,1320.6,2149.1,1496.2,232.0,173.6 +2.7289938762374173,1.529075283934595,1.5707963267948966,340.7,2629.4,2629.1,1421.3,193.3,193.0 +2.7289855896297346,1.5290738787657745,1.7016960206944713,378.5,2694.4,2752.5,1314.3,174.3,232.7 +2.7289805982147293,1.5290710640835596,1.832595714594046,460.6,2991.3,2801.5,590.9,174.5,302.2 +2.7290352643827065,1.5291052793831483,1.9634954084936205,617.3,2198.8,1979.7,362.6,204.2,425.1 +2.72905216768147,1.5291242021874165,2.0943951023931953,948.5,1755.8,1628.6,254.9,295.1,380.5 +2.729042597658673,1.5291040592606677,2.2252947962927703,1992.4,1535.2,1476.4,194.5,416.6,357.8 +2.7290480053223125,1.5291262504959657,2.356194490192345,2599.4,1451.2,1451.7,162.5,370.2,370.7 +2.7290449890416038,1.5291561043434947,2.4870941840919194,2716.9,1439.5,620.0,151.9,358.0,417.1 +2.7290485950306507,1.5291465240893918,2.6179938779914944,2822.6,672.9,518.2,162.1,380.2,507.8 +2.729035251806209,1.5291621230808523,2.748893571891069,1983.1,424.5,204.6,204.6,456.4,676.4 +2.729043933388497,1.5291544756160038,2.8797932657906435,1616.0,302.4,175.0,316.7,650.0,1029.8 +2.7290347490784446,1.5293216906936287,3.010692959690218,1453.9,232.8,173.9,379.2,1312.6,2136.0 +2.72896730540172,1.4288485890810771,0.0,1321.4,193.0,193.0,440.6,2628.9,2629.2 +2.7290009515095512,1.4293169213470462,0.1308996938995747,698.8,173.8,233.2,439.8,2697.0,2755.9 +2.7289679221906367,1.429306151503189,0.2617993877991494,316.4,174.9,302.4,483.5,2984.1,2604.2 +2.728931857348604,1.4292828506644142,0.39269908169872414,203.9,204.6,425.4,598.5,2058.4,1838.9 +2.7289020390587964,1.4292519138620268,0.5235987755982988,162.5,294.5,495.8,868.9,1642.0,1514.4 +2.7288916679375763,1.429228848529429,0.6544984694978736,151.8,535.1,461.6,1773.2,1432.3,1372.9 +2.728879748378931,1.4291827690146648,0.7853981633974483,163.1,470.9,470.2,2598.7,1351.8,1351.3 +2.728880912792532,1.4291728911847783,0.916297857297023,194.8,461.4,520.3,2673.4,1361.7,623.7 +2.728892912898644,1.4291352337072225,1.0471975511965976,254.6,495.9,623.1,2905.6,674.9,401.5 +2.7289179572219933,1.4290925046842924,1.1780972450961724,363.6,595.8,814.9,2007.0,426.1,205.3 +2.728912070282255,1.429096945438134,1.3089969389957472,483.4,847.7,1226.9,1594.6,422.3,175.3 +2.7289234905564794,1.4290907784734292,1.4398966328953218,439.5,1710.4,2538.8,1392.7,232.0,173.6 +2.728993955999287,1.4290737523913697,1.5707963267948966,440.7,2629.0,2628.3,1321.3,193.3,193.1 +2.728985205014892,1.429072352205117,1.7016960206944713,481.9,2694.1,2753.0,1314.4,174.3,232.7 +2.728979793349491,1.4290694337776957,1.832595714594046,576.3,2981.6,2602.3,591.1,174.4,302.1 +2.729034104558886,1.429103445066948,1.9634954084936205,759.2,2058.1,1838.9,362.7,204.2,425.2 +2.7290507427910806,1.429122097333348,2.0943951023931953,1148.3,1640.2,1513.1,254.9,295.1,495.9 +2.729041001585625,1.4291016522734425,2.2252947962927703,2380.1,1431.5,1372.9,194.5,537.5,461.3 +2.72904633312298,1.4291235267912192,2.356194490192345,2599.6,1351.2,1351.7,162.5,470.3,470.8 +2.729043333142111,1.4291530756398014,2.4870941840919194,2717.4,1373.0,620.1,151.9,461.6,520.6 +2.729047027150802,1.4291432321545168,2.6179938779914944,2624.0,672.9,402.5,162.1,495.8,623.5 +2.729033835609913,1.429158617060505,2.748893571891069,1841.8,424.5,204.6,204.6,597.7,817.7 +2.729042701190449,1.4291508201072853,2.8797932657906435,1500.3,302.4,175.0,316.7,849.4,1229.3 +2.7290337180925945,1.4291552341513563,3.010692959690218,1350.5,232.8,173.9,482.6,1700.3,2522.6 +2.7289749011003566,1.328856104018465,0.0,1221.3,193.0,193.0,540.7,2628.6,2629.0 +2.7290035674645443,1.3293243333715727,0.1308996938995747,1070.8,173.8,233.2,543.3,2696.7,2756.5 +2.728968441616675,1.3293129011751437,0.2617993877991494,316.3,174.9,302.3,599.1,2784.1,2405.1 +2.728931278263984,1.3292888958337485,0.39269908169872414,345.5,204.6,425.3,740.0,1917.6,1698.1 +2.7289008064335656,1.3292572424134912,0.5235987755982988,162.5,294.5,629.7,1068.2,1526.3,1398.6 +2.728890054175938,1.3292334556026297,0.6544984694978736,151.9,620.0,565.1,2159.2,1328.6,1269.6 +2.7288779697212497,1.3291866591448211,0.7853981633974483,163.1,570.8,570.3,2598.9,1251.7,1251.3 +2.7288791499213136,1.3291761101310007,0.916297857297023,194.8,564.9,623.6,2673.4,1269.3,623.7 +2.7288913223019975,1.329137852425171,1.0471975511965976,254.6,611.5,738.9,2706.1,674.8,294.7 +2.7289166628382193,1.3290946283030132,1.1780972450961724,363.7,737.0,956.1,1865.2,426.2,378.2 +2.728911150780273,1.3290986945725025,1.3089969389957472,592.4,1047.0,1426.3,1478.6,303.0,175.3 +2.7289229975856313,1.3290922752576237,1.4398966328953218,543.0,2100.0,2694.5,1289.1,232.0,173.6 +2.7290220364620845,1.3290649524950555,1.5707963267948966,540.7,2628.8,2628.4,1221.1,193.3,193.0 +2.7289939762471898,1.3290628751506652,1.7016960206944713,585.4,2693.9,2752.5,1246.7,174.3,232.7 +2.7289853318306676,1.3290589384147011,1.832595714594046,691.8,2782.4,2403.2,591.0,174.4,302.1 +2.729041020759808,1.32909378578889,1.9634954084936205,900.7,1916.4,1697.3,362.6,204.3,425.0 +2.7290596974123575,1.3291146071730626,2.0943951023931953,1347.8,1524.4,1397.2,255.0,295.1,631.5 +2.7290514774808186,1.3290969868815736,2.2252947962927703,2673.8,1328.0,1269.3,194.5,622.7,565.0 +2.7290575255607554,1.3291219379258403,2.356194490192345,2600.0,1251.0,1252.0,162.5,570.1,570.8 +2.729054415732369,1.3291544728015605,2.4870941840919194,2717.5,1269.2,620.1,151.9,565.1,624.2 +2.729057301547529,1.3291472630949568,2.6179938779914944,2424.6,672.9,293.9,162.1,611.5,739.1 +2.729042733839357,1.329164826003198,2.748893571891069,1700.4,424.6,377.0,204.6,739.2,959.2 +2.7290498641934633,1.3291586352019567,2.8797932657906435,1384.5,302.4,175.0,316.6,1049.1,1428.8 +2.729038944107494,1.329164068876068,3.010692959690218,1246.8,232.8,173.9,586.3,2087.2,2695.4 +2.7289778009216623,1.2288631902369789,0.0,1121.2,193.0,193.0,640.7,2629.3,2628.8 +2.72900452234543,1.22932336266737,0.1308996938995747,967.4,173.8,233.1,646.9,2696.5,2756.0 +2.7289690781422693,1.2293118331903754,0.2617993877991494,316.3,174.9,302.4,714.7,2585.1,2205.5 +2.7289319472379736,1.2292878508332907,0.39269908169872414,203.9,204.6,425.3,881.7,1776.3,1556.7 +2.728901575163076,1.2292563082365429,0.5235987755982988,162.5,294.5,673.6,1267.3,1410.6,1283.0 +2.7288909015231315,1.2292326739637809,0.6544984694978736,151.9,620.0,668.6,2544.5,1225.0,1165.9 +2.7288788542959868,1.2291860463117257,0.7853981633974483,163.1,670.8,670.3,2599.0,1151.7,1151.1 +2.728880027494269,1.2291756593068528,0.916297857297023,194.8,668.4,727.2,2673.4,1165.7,1004.5 +2.7288921544339706,1.229137547018396,1.0471975511965976,254.6,727.2,854.3,2506.4,674.8,294.7 +2.728917419956732,1.2290944432564093,1.1780972450961724,363.6,878.2,1097.2,1723.6,426.2,205.3 +2.728911813686264,1.2290985985811829,1.3089969389957472,592.5,1246.4,1625.5,1363.1,302.9,175.3 +2.728923554689044,1.2290922367676254,1.4398966328953218,646.4,2489.6,2694.8,1185.8,232.0,173.6 +2.728994359951089,1.2290751179835444,1.5707963267948966,640.8,2628.9,2628.6,1121.2,171.3,193.0 +2.7289859317073986,1.2290737126730251,1.7016960206944713,688.9,2693.7,2752.5,1143.1,174.3,232.7 +2.728980812980323,1.2290708641205508,1.832595714594046,807.5,2582.7,2203.8,590.9,174.5,302.1 +2.729035371383744,1.2291050174870295,1.9634954084936205,1042.6,1775.6,1556.4,362.6,204.2,425.2 +2.7290521932528606,1.2291238595163563,2.0943951023931953,1547.6,1409.2,1281.7,254.9,295.1,675.3 +2.7290425702414516,1.229103625124636,2.2252947962927703,2673.3,1224.6,1165.9,194.5,622.6,668.5 +2.7290479528280596,1.2291257203173123,2.356194490192345,2599.5,1151.2,1152.0,162.5,670.3,670.9 +2.7290449379304995,1.2291554817280665,2.4870941840919194,2717.7,1165.9,1004.9,151.9,668.7,727.7 +2.729048568256097,1.2291458197596716,2.6179938779914944,2225.3,673.0,293.8,162.1,727.0,854.7 +2.729035267487035,1.2291613516939153,2.748893571891069,1558.8,424.6,204.6,204.6,880.7,1100.8 +2.7290440036338586,1.2291536555086322,2.8797932657906435,1269.2,302.4,175.0,316.6,1248.5,1628.4 +2.7288843670151386,1.2288833027906945,3.010692959690218,1143.3,232.8,173.9,704.6,2472.1,2695.8 +2.7288714575521067,1.128653609379723,0.0,1021.2,193.1,193.0,740.8,2628.9,2629.2 +2.728954109666052,1.1292944385338692,0.1308996938995747,863.9,173.8,233.2,750.6,2697.3,2755.9 +2.7289341652609918,1.1292877324209876,0.2617993877991494,316.3,174.9,302.5,830.4,2384.8,2005.6 +2.7289026081813916,1.1292672044668672,0.39269908169872414,203.9,204.7,425.5,1023.6,1634.9,1415.2 +2.728874607382843,1.1292380564217184,0.5235987755982988,162.5,294.6,673.9,1467.2,1295.1,1167.4 +2.7288650581190805,1.1292162728092072,0.6544984694978736,151.9,620.5,772.0,2717.6,1121.3,1062.4 +2.7288536197234765,1.129171364964995,0.7853981633974483,163.1,770.9,770.3,2598.7,1051.7,1051.1 +2.7288549210906945,1.1291625253878728,0.916297857297023,194.9,771.9,830.9,2673.3,1062.5,901.0 +2.7288668190712477,1.1291258370264359,1.0471975511965976,254.7,842.7,970.0,2305.9,674.8,294.7 +2.7288915712242865,1.1290840424750077,1.1780972450961724,363.8,1019.6,1238.5,1581.5,426.1,205.3 +2.7288851713421725,1.1290892019827914,1.3089969389957472,592.7,1446.2,1825.1,1247.4,302.9,175.3 +2.7288959233659975,1.1290834874418816,1.4398966328953218,749.8,2752.9,2694.7,1082.1,232.0,173.6 +2.7289656485396527,1.1290668065892222,1.5707963267948966,740.8,2629.4,2628.6,1021.3,193.3,193.1 +2.728956154618927,1.129065459195667,1.7016960206944713,792.4,2694.5,2752.6,1039.9,174.3,232.7 +2.7289500895757532,1.1290622808434143,1.832595714594046,923.2,2382.8,2003.9,590.8,174.5,302.3 +2.729003862521717,1.129095919198216,1.9634954084936205,1184.4,1634.3,1415.1,362.6,204.3,425.3 +2.729020129677825,1.129114115855577,2.0943951023931953,1747.4,1293.4,1166.2,255.0,295.2,675.4 +2.7290102665077014,1.1290930988166008,2.2252947962927703,2673.2,1120.9,1062.3,194.5,623.0,772.0 +2.729015662504275,1.1291144315390234,2.356194490192345,2599.9,1051.2,1051.7,162.5,770.3,771.0 +2.729012825921259,1.1291435707087016,2.4870941840919194,2717.5,1062.3,901.5,129.2,772.2,831.4 +2.729016853372083,1.1291333918836375,2.6179938779914944,2025.6,672.8,293.8,162.2,842.7,970.5 +2.7290039400158137,1.1291486147126313,2.748893571891069,1417.2,424.5,204.6,204.6,1022.3,1242.1 +2.729013145018306,1.1291407390782604,2.8797932657906435,1153.5,302.4,175.0,316.7,1448.4,1828.5 +2.729004443949584,1.1291451573072462,3.010692959690218,1039.9,232.8,174.0,706.0,2754.1,2695.4 +2.6289985224190713,1.82923911742401,0.0,1721.0,293.1,293.0,40.8,2529.0,2529.2 +2.6289832887850992,1.8285359621470738,0.1308996938995747,1083.0,277.4,149.2,25.6,2592.9,2652.0 +2.629034933996544,1.8285527233514651,0.2617993877991494,515.9,290.5,51.4,21.4,2875.1,3114.4 +2.629088720300264,1.8285873985750671,0.39269908169872414,345.3,251.3,31.9,32.1,2623.2,2404.1 +2.629130825493993,1.8286353704430132,0.5235987755982988,278.3,161.3,33.6,72.4,2103.7,1976.9 +2.6287790498649626,1.828991312264698,0.6544984694978736,255.5,106.5,47.6,232.4,1845.3,1786.9 +2.6287769649779076,1.8289847458138253,0.7853981633974483,263.3,70.9,70.5,2498.7,1751.8,1751.2 +2.6287780245658126,1.8290361130450035,0.916297857297023,298.5,47.5,106.5,2570.0,1786.8,1008.7 +2.6287981890431324,1.8289749074468578,1.0471975511965976,73.2,34.0,161.5,2862.5,873.6,494.0 +2.6288259563586007,1.8289306291604643,1.1780972450961724,31.8,31.6,251.1,2571.9,567.5,346.9 +2.628818126446064,1.8289386697235788,1.3089969389957472,21.2,51.1,430.9,2055.7,418.4,291.0 +2.6288249741960206,1.8289361070054884,1.4398966328953218,25.8,152.9,983.8,1806.1,335.5,277.2 +2.6288896092819853,1.82892202702881,1.5707963267948966,41.0,2528.5,2528.8,1721.0,293.3,293.2 +2.6288746955089684,1.8289216089313696,1.7016960206944713,68.3,2590.4,2649.4,1699.7,277.8,151.8 +2.6288634763595775,1.8289174955730834,1.832595714594046,114.2,2876.9,3108.4,789.4,290.3,50.9 +2.628912661024554,1.8289490510907607,1.9634954084936205,192.7,2619.9,2401.5,503.5,250.4,31.6 +2.6289253722411647,1.8289642285680028,2.0943951023931953,350.5,2100.9,1974.2,370.3,161.2,34.1 +2.628913481583206,1.8289392738870005,2.2252947962927703,833.8,1845.0,1786.4,298.0,106.2,47.6 +2.628918262254424,1.828956465950168,2.356194490192345,2499.3,1750.9,1751.5,262.5,70.3,71.0 +2.628915768293526,1.8290275559303069,2.4870941840919194,2614.0,1787.3,1003.6,255.5,47.5,106.8 +2.6289307756892364,1.828984587482638,2.6179938779914944,2957.8,871.2,492.8,278.0,33.5,161.4 +2.6289236552863375,1.828992220293119,2.748893571891069,2405.7,565.5,345.9,192.1,32.4,252.6 +2.6289349848053454,1.8289838960042413,2.8797932657906435,1961.5,417.9,290.6,114.2,52.0,432.4 +2.6289261709165936,1.8289896589347243,3.010692959690218,1764.1,336.3,277.6,68.7,152.6,977.5 +2.628828643952814,1.7286795699974216,0.0,1621.2,293.0,293.2,140.8,2528.6,2528.7 +2.628894678003749,1.7292679127385013,0.1308996938995747,1080.4,277.4,337.0,129.0,2593.4,2652.6 +2.6288753804009493,1.7292613378871278,0.2617993877991494,701.5,290.6,250.2,136.8,2875.7,3003.7 +2.628846622206186,1.7292423571087039,0.39269908169872414,345.0,346.7,172.8,173.7,2480.3,2261.3 +2.6288215131793784,1.7292158623152059,0.5235987755982988,278.1,276.5,149.0,271.7,1988.4,1860.1 +2.6288139130253603,1.7291971636041794,0.6544984694978736,255.5,209.9,151.0,618.3,1741.9,1683.4 +2.6288038051713802,1.7291558159640044,0.7853981633974483,263.3,170.8,170.3,2499.0,1651.4,1651.2 +2.6288053240172613,1.7291503281054412,0.916297857297023,298.5,150.9,209.8,2570.5,1683.4,1008.8 +2.6288166301936733,1.7291167700620038,1.0471975511965976,272.4,149.4,276.9,2862.3,873.6,723.0 +2.6288401872131537,1.7290779394244729,1.1780972450961724,173.2,172.6,392.0,2430.8,740.4,346.8 +2.628831918536794,1.729085275316866,1.3089969389957472,136.6,250.3,630.1,1940.3,418.5,291.0 +2.628840380935387,1.7290808157480013,1.4398966328953218,129.1,542.9,1373.6,1702.7,335.4,277.1 +2.628907681231318,1.7290650844371227,1.5707963267948966,140.8,2528.6,2528.8,1621.1,293.4,293.2 +2.628895819003971,1.7290637771794208,1.7016960206944713,171.6,2590.9,2649.2,1660.7,277.8,336.4 +2.628887713488704,1.7290596810171834,1.832595714594046,229.6,2876.7,3005.0,789.5,290.3,249.7 +2.6289398020141967,1.7290921409090187,1.9634954084936205,334.3,2479.6,2260.6,503.5,346.3,172.4 +2.6289548637857005,1.7291089607746555,2.0943951023931953,550.1,1986.1,1858.8,370.3,276.5,149.4 +2.628944534958856,1.729086190393342,2.2252947962927703,1221.1,1741.7,1682.9,298.0,209.6,150.9 +2.628949988186857,1.729105847253362,2.356194490192345,2499.8,1651.3,1651.7,262.5,170.2,170.9 +2.628947457129837,1.7291336879148596,2.4870941840919194,2614.1,1683.9,1003.5,255.5,150.9,210.1 +2.6289523436863904,1.7291223526575656,2.6179938779914944,2956.8,871.2,724.3,277.9,149.0,276.8 +2.628940114403865,1.729136907145717,2.748893571891069,2264.2,738.1,345.8,346.4,173.7,394.0 +2.628950290327192,1.729128565807677,2.8797932657906435,1846.6,417.9,290.5,229.5,251.4,631.9 +2.628942461984002,1.7291327686709665,3.010692959690218,1660.5,336.3,277.5,172.0,539.9,1364.9 +2.628885099699252,1.6288343232934306,0.0,1521.3,293.1,293.2,240.6,2528.6,2528.7 +2.6289256121593603,1.6293194681270546,0.1308996938995747,1381.8,277.4,336.9,232.6,2593.8,2652.4 +2.628893662370786,1.6293088850526576,0.2617993877991494,515.4,290.6,418.2,252.4,2875.5,3000.7 +2.628857765700772,1.6292853704472883,0.39269908169872414,345.0,346.5,314.0,315.3,2339.3,2120.5 +2.628828150533558,1.6292540465503962,0.5235987755982988,278.1,392.1,264.6,470.9,1872.9,1744.9 +2.6288178704859333,1.6292304096577208,0.6544984694978736,255.5,313.4,254.5,1004.3,1639.0,1579.7 +2.6288064856358067,1.6291840447813366,0.7853981633974483,263.2,270.8,270.3,2498.8,1551.6,1551.4 +2.62880804110101,1.6291738588757998,0.916297857297023,298.5,254.3,313.3,2570.3,1579.9,1009.0 +2.62882048267958,1.6291360663884291,1.0471975511965976,370.4,264.9,392.5,3015.0,873.7,633.1 +2.6288460368475017,1.6290936463592625,1.1780972450961724,314.8,313.8,533.1,2289.2,567.6,346.9 +2.6288403851222144,1.6290982789924113,1.3089969389957472,252.1,449.7,829.4,1824.9,418.5,290.9 +2.628851868324925,1.629092044578295,1.4398966328953218,232.5,933.0,1763.5,1599.3,335.4,277.1 +2.628922359595734,1.6290753738633168,1.5707963267948966,240.8,2528.9,2528.8,1521.4,293.3,293.2 +2.628913542085867,1.6290740213766794,1.7016960206944713,275.1,2590.9,2649.9,1557.2,277.8,336.3 +2.6289081697548036,1.6290706942445767,1.832595714594046,345.2,2876.8,2998.6,789.5,290.2,418.0 +2.62896255902279,1.6291045226077094,1.9634954084936205,476.0,2339.1,2119.6,503.7,346.2,313.4 +2.628979326150975,1.6291231161303925,2.0943951023931953,749.7,1870.7,1743.6,370.4,391.9,264.9 +2.6289700202522854,1.6291023820377133,2.2252947962927703,1608.4,1638.3,1579.4,298.0,313.1,254.3 +2.6289758599747666,1.6291241343175658,2.356194490192345,2499.5,1551.1,1552.0,262.5,270.2,270.8 +2.628973160400453,1.6291539141148432,2.4870941840919194,2614.2,1580.4,1003.7,255.6,254.4,313.7 +2.6289773594332986,1.6291442582594542,2.6179938779914944,2957.2,871.5,633.9,277.9,264.6,392.5 +2.628964147402442,1.6291601072553354,2.748893571891069,2123.3,565.7,345.9,346.3,315.1,535.4 +2.6289731003464203,1.629152663873677,2.8797932657906435,1730.8,417.8,290.6,345.0,451.0,831.2 +2.6289639854681193,1.6291573622255622,3.010692959690218,1557.4,336.3,277.5,275.6,927.6,1751.9 +2.6289051399260033,1.5288578478445778,0.0,1421.3,293.0,293.2,340.6,2528.2,2529.2 +2.6289428286428045,1.5293241496579426,0.1308996938995747,1278.2,277.4,336.9,336.2,2593.5,2652.5 +2.628909733712004,1.5293132314033906,0.2617993877991494,515.4,290.5,418.1,368.0,2926.4,2801.7 +2.6288731491839816,1.5292893424581195,0.39269908169872414,345.0,346.5,455.1,457.0,2198.9,1979.8 +2.6288430326372705,1.5292575994017437,0.5235987755982988,278.1,494.3,380.2,670.1,1757.1,1629.3 +2.6288324475515514,1.529233544259259,0.6544984694978736,255.4,417.1,358.1,1390.3,1535.2,1476.4 +2.628820820352326,1.5291866879429343,0.7853981633974483,263.1,370.7,370.4,2498.9,1451.8,1451.0 +2.628822304723399,1.5291760466664215,0.916297857297023,298.4,357.9,416.8,2569.8,1476.4,1315.4 +2.628834786501528,1.5291378154649988,1.0471975511965976,370.4,380.5,508.0,2861.9,873.9,494.0 +2.6288604626394383,1.529094942050338,1.1780972450961724,474.2,455.0,674.3,2147.8,567.6,346.9 +2.6288550539021824,1.5290992415764755,1.3089969389957472,367.8,648.9,1028.5,1709.6,418.4,290.9 +2.628866857379958,1.5290928263805725,1.4398966328953218,336.0,1323.1,2152.8,1495.8,335.4,277.1 +2.628937694306765,1.5290759853179328,1.5707963267948966,340.8,2529.2,2529.1,1421.0,293.3,293.2 +2.628929223704364,1.5290746199236969,1.7016960206944713,378.6,2590.8,2649.4,1453.8,277.8,336.3 +2.6289241432513824,1.5290714569579413,1.832595714594046,460.8,2928.4,2799.7,789.8,290.2,418.0 +2.628978769244249,1.529105471278197,1.9634954084936205,617.8,2198.0,1978.6,503.6,346.2,454.6 +2.6289956980122007,1.5291242708018005,2.0943951023931953,949.1,1755.0,1628.3,370.3,495.3,380.3 +2.6289864200846442,1.529103815546112,2.2252947962927703,1995.5,1535.1,1475.9,298.0,416.6,357.9 +2.628992204353717,1.529125820793276,2.356194490192345,2499.6,1451.2,1451.6,262.5,370.2,370.9 +2.6289894289839246,1.5291557684021122,2.4870941840919194,2614.1,1476.5,1315.7,255.5,358.1,417.2 +2.6289934561946464,1.529146260543521,2.6179938779914944,2821.1,871.5,492.8,277.9,380.2,508.1 +2.628980141440449,1.5291621625047367,2.748893571891069,1982.2,565.8,345.9,346.2,456.6,676.8 +2.6289889443887158,1.529154750392169,2.8797932657906435,1615.7,417.9,290.6,472.8,650.6,1030.6 +2.6289797144343092,1.5291594496105692,3.010692959690218,1453.5,336.2,277.5,379.1,1315.0,2139.1 +2.62892071147941,1.4288598924157232,0.0,1321.2,293.0,293.1,440.7,2528.9,2528.8 +2.628957023827625,1.4293246359180152,0.1308996938995747,1174.5,277.4,336.9,439.7,2593.5,2652.5 +2.6289235526854697,1.4293136271789428,0.2617993877991494,515.4,290.5,418.2,483.6,2875.4,2602.6 +2.6288868096831406,1.4292896965230986,0.39269908169872414,487.5,346.5,567.2,598.6,2057.7,1838.6 +2.628856565334385,1.4292579271683998,0.5235987755982988,278.1,494.1,495.8,869.4,1641.6,1513.9 +2.6288459068049317,1.4292338719016233,0.6544984694978736,255.5,520.5,461.5,1775.3,1432.0,1373.0 +2.628834154978685,1.4291869597948197,0.7853981633974483,263.2,470.7,470.4,2499.1,1351.9,1351.5 +2.628835569095868,1.4291762728973474,0.916297857297023,298.4,461.4,520.4,2569.6,1373.1,1211.8 +2.6288479954760158,1.4291379745068347,1.0471975511965976,370.4,496.1,623.3,2860.2,873.9,494.2 +2.6288736226979212,1.429094967493619,1.1780972450961724,505.1,596.0,815.3,2006.1,567.6,519.8 +2.6288682282906235,1.4290991739651422,1.3089969389957472,483.3,848.4,1227.8,1593.7,418.5,291.0 +2.628880086005235,1.4290927329613683,1.4398966328953218,439.4,1712.7,2542.1,1392.6,335.4,277.1 +2.628950987426594,1.4290758077734012,1.5707963267948966,440.8,2529.0,2528.4,1321.2,293.3,293.1 +2.628942594674248,1.4290744333798306,1.7016960206944713,482.1,2590.7,2649.2,1350.3,277.7,336.3 +2.6289375659380347,1.4290713616087949,1.832595714594046,576.4,2876.5,2600.8,789.8,290.2,418.0 +2.6289922271040482,1.4291054390243594,1.9634954084936205,759.4,2056.8,1838.2,503.6,346.2,567.2 +2.6290091689060895,1.4291242876919545,2.0943951023931953,1148.9,1639.9,1512.6,370.4,495.1,496.0 +2.6289998338408,1.42910392872921,2.2252947962927703,2382.9,1431.5,1372.9,298.0,520.1,461.4 +2.62900553419984,1.4291260011524365,2.356194490192345,2499.7,1351.5,1351.7,262.4,470.1,470.8 +2.6290027007999592,1.429155948538247,2.4870941840919194,2614.2,1373.1,1212.3,255.5,461.6,520.7 +2.6290066219510053,1.4291464427618479,2.6179938779914944,2622.7,871.8,492.9,277.9,495.9,623.7 +2.628993290112833,1.4291622886148443,2.748893571891069,1841.2,565.8,518.5,346.1,598.0,818.2 +2.629002051312138,1.4291548320904295,2.8797932657906435,1500.0,417.9,290.6,516.6,850.0,1230.2 +2.6289928178523745,1.4291594910014505,3.010692959690218,1350.6,336.3,277.5,482.5,1701.8,2525.8 +2.628933788203352,1.3288599808743142,0.0,1221.3,293.0,293.1,540.6,2528.9,2529.3 +2.6289681534080143,1.3293247417849772,0.1308996938995747,1081.6,277.4,336.8,543.3,2593.1,2652.5 +2.6289342392235433,1.3293136164688983,0.2617993877991494,515.6,290.5,418.1,599.2,2783.5,2404.1 +2.6288973697737155,1.3292896510667853,0.39269908169872414,345.1,346.4,567.2,740.4,1916.9,1697.5 +2.6288670553355145,1.3292578918023041,0.5235987755982988,278.2,494.0,611.4,1068.8,1526.3,1398.5 +2.6288563651008716,1.3292338826575756,0.6544984694978736,255.4,624.1,565.0,2160.9,1328.5,1269.4 +2.6288445300729455,1.3291869803761824,0.7853981633974483,263.2,570.6,570.4,2498.9,1251.7,1251.0 +2.6288458889275206,1.32917630968374,0.916297857297023,298.4,564.9,623.8,2570.2,1269.3,1085.3 +2.6288582591512473,1.3291380061264744,1.0471975511965976,370.4,611.6,738.9,2704.5,874.2,494.2 +2.62888382553305,1.3290949352440395,1.1780972450961724,505.0,737.2,956.3,1865.0,567.7,347.0 +2.6288784124427527,1.3290990991212794,1.3089969389957472,599.0,1047.5,1426.9,1478.7,418.5,291.0 +2.628890278126814,1.3290926570521915,1.4398966328953218,542.8,2102.1,2590.7,1289.1,335.5,277.1 +2.6289611939051,1.3290756762857865,1.5707963267948966,540.8,2528.9,2528.8,1221.2,293.3,293.1 +2.628952827801893,1.3290742946514218,1.7016960206944713,585.4,2590.6,2649.0,1246.7,277.8,336.2 +2.6289478091779803,1.329071284424321,1.832595714594046,692.0,2780.7,2401.8,790.2,290.2,417.8 +2.6290024725294012,1.3291053953099605,1.9634954084936205,901.2,1916.0,1696.9,503.6,346.1,567.1 +2.6290194058782705,1.329124262467392,2.0943951023931953,1348.7,1498.9,1397.3,370.3,495.1,611.4 +2.6290100153549854,1.3291039558063296,2.2252947962927703,2570.0,1327.9,1269.2,298.0,623.6,564.7 +2.6290156462628866,1.3291260574022359,2.356194490192345,2499.7,1251.1,1252.1,262.5,570.3,570.8 +2.6290127692898166,1.3291559833987079,2.4870941840919194,2613.5,1269.4,1085.7,255.5,565.1,624.3 +2.629016615223287,1.329146460645478,2.6179938779914944,2423.7,871.9,492.9,277.8,611.5,739.1 +2.6290032802764234,1.329162248400693,2.748893571891069,1699.7,565.8,346.0,346.1,739.4,959.5 +2.6290120220518776,1.3291547469210314,2.8797932657906435,1384.6,417.8,290.6,516.4,1049.5,1429.3 +2.6290027997462295,1.3291593683016436,3.010692959690218,1246.9,336.2,277.5,586.1,2089.1,2591.7 +2.6289437660460555,1.2288599065463979,0.0,1121.4,293.0,293.0,640.6,2529.0,2529.4 +2.6289766557684966,1.2293248041372968,0.1308996938995747,1082.2,277.4,336.8,647.0,2593.6,2652.5 +2.6289424074534105,1.2293135912460413,0.2617993877991494,515.6,290.5,418.1,714.7,2584.7,2204.6 +2.6289054437319463,1.229289600851255,0.39269908169872414,345.1,346.4,567.2,882.0,1775.7,1556.5 +2.628875077140696,1.2292578508804675,0.5235987755982988,278.2,493.9,727.2,1267.8,1410.5,1282.8 +2.6288643635027404,1.2294206259218305,0.6544984694978736,255.4,727.7,668.6,2546.2,1224.9,1165.8 +2.628845609119256,1.2291648371094768,0.7853981633974483,263.1,670.9,670.3,2499.2,1151.8,1151.3 +2.628846348723017,1.2291696008574682,0.916297857297023,298.3,668.4,727.3,2570.0,1165.7,1098.3 +2.6288577670383164,1.229134209899714,1.0471975511965976,370.2,727.2,854.4,2505.2,1036.4,494.2 +2.6288836905258,1.2290904320911635,1.1780972450961724,505.0,878.4,1097.6,1723.5,567.8,346.9 +2.62887960527173,1.2290932999878454,1.3089969389957472,714.6,1246.6,1626.0,1362.9,418.5,432.0 +2.628893319359017,1.2290858701781708,1.4398966328953218,646.4,2491.4,2591.0,1185.6,335.4,277.0 +2.6289662756421626,1.22906837915856,1.5707963267948966,640.8,2528.7,2528.7,1121.1,293.2,293.0 +2.6289598631201883,1.2290670546584197,1.7016960206944713,688.8,2590.4,2649.6,1143.3,277.7,336.2 +2.628956579957889,1.2290646147948192,1.832595714594046,807.7,2582.3,2203.1,790.1,290.1,417.8 +2.6290126858536897,1.229099653661407,1.9634954084936205,1042.7,1775.3,1525.3,503.7,346.1,567.1 +2.6290306785037636,1.2291196786930945,2.0943951023931953,1548.0,1408.8,1281.8,370.4,495.0,727.0 +2.629021920839612,1.2291006762545473,2.2252947962927703,2570.3,1224.5,1165.8,298.0,727.0,668.4 +2.6290278005645336,1.229124105172589,2.356194490192345,2499.6,1151.1,1151.8,262.4,670.2,670.8 +2.6290248463695587,1.2291552580552003,2.4870941840919194,2614.2,1165.9,1005.0,255.5,668.6,727.7 +2.6290283022273635,1.2291468144159161,2.6179938779914944,2224.6,871.8,493.0,277.8,727.1,854.7 +2.6290144018784876,1.2291634600380839,2.748893571891069,1558.8,566.0,345.9,346.1,880.9,1101.1 +2.6290224160025892,1.229156592838501,2.8797932657906435,1269.2,417.9,431.5,516.4,1249.0,1628.9 +2.629012405140795,1.229161613935815,3.010692959690218,1143.3,336.3,277.5,689.6,2475.9,2591.3 +2.628952404732023,1.1288614672435937,0.0,1021.2,293.0,293.1,740.7,2529.0,2528.7 +2.628983503317603,1.1293240909290974,0.1308996938995747,1082.3,277.3,336.8,750.5,2593.3,2652.9 +2.628948935616925,1.1293127926488864,0.2617993877991494,515.7,290.5,418.0,830.4,2385.1,2005.5 +2.6289119585786542,1.1292888219976258,0.39269908169872414,345.1,346.4,567.2,1023.5,1634.8,1415.4 +2.628881624272767,1.129257159130692,0.5235987755982988,278.1,493.9,868.3,1467.2,1294.7,1167.2 +2.6288709442771157,1.1292333145066868,0.6544984694978736,255.4,831.3,772.3,2613.0,1121.2,1062.4 +2.628859021349583,1.1291865350511014,0.7853981633974483,263.1,770.8,770.2,2498.5,1051.7,1051.2 +2.6288603016611196,1.1291759906328755,0.916297857297023,298.2,772.0,830.9,2570.0,1062.4,1010.5 +2.6288725675090228,1.1291377737136823,1.0471975511965976,370.3,842.6,969.9,2306.2,920.9,494.3 +2.6288980040868606,1.1290946940322049,1.1780972450961724,505.0,1019.4,1238.8,1581.6,567.7,346.9 +2.6288925057801937,1.129098858078089,1.3089969389957472,791.9,1445.9,1825.2,1247.2,418.5,290.9 +2.6289043145932505,1.1290924523059545,1.4398966328953218,749.8,2649.4,2591.0,1082.1,335.4,277.1 +2.6289751792509115,1.129075414700878,1.5707963267948966,740.8,2528.7,2529.0,1021.3,293.2,293.0 +2.628966782653836,1.129074023222712,1.7016960206944713,792.5,2590.6,2648.8,1039.8,277.7,336.2 +2.628961717945234,1.129071080156212,1.832595714594046,923.4,2383.0,2004.1,909.0,290.1,417.9 +2.629016333709944,1.1291052071088212,1.9634954084936205,1184.4,1634.2,1414.8,503.7,346.0,566.9 +2.629033217508708,1.1292284540096882,2.0943951023931953,1747.6,1293.6,1166.2,370.4,495.1,867.9 +2.6290191556364846,1.1290952748598198,2.2252947962927703,2570.0,1120.9,1062.3,298.1,830.5,771.9 +2.6290260937164818,1.129123664991252,2.356194490192345,2500.0,1051.4,1051.8,262.5,770.2,770.9 +2.629023108143288,1.129154911892377,2.4870941840919194,2614.2,1062.5,1005.4,255.4,772.2,831.4 +2.629026915602259,1.1291451477252763,2.6179938779914944,2025.4,896.4,493.0,277.8,842.7,970.5 +2.629013942754622,1.1291602715357199,2.748893571891069,1417.1,565.9,345.9,346.0,1022.2,1242.3 +2.6290232328443603,1.1291521733618524,2.8797932657906435,1153.4,418.0,290.5,516.3,1448.4,1828.6 +2.6290147113578732,1.1291563793735024,3.010692959690218,1039.8,336.3,277.5,793.1,2650.3,2592.0 +2.529009139132053,1.82925119915318,0.0,1721.3,393.1,393.0,40.8,2428.6,2429.1 +2.528990670480472,1.8285393705058797,0.1308996938995747,1588.5,380.9,149.2,25.6,2489.6,2548.9 +2.5290413016203743,1.8285558241421607,0.2617993877991494,816.6,406.1,51.4,21.4,2759.3,2886.5 +2.529094566275873,1.8285901923852281,0.39269908169872414,486.4,251.2,31.9,32.1,2623.1,2404.0 +2.529136363094642,1.828637867323513,0.5235987755982988,393.9,161.3,33.6,72.4,2104.7,1976.5 +2.528715567104176,1.829026552394663,0.6544984694978736,359.1,106.5,47.6,232.5,1845.7,1786.7 +2.5287114178286094,1.8290102235311116,0.7853981633974483,363.3,70.9,70.5,2398.7,1751.7,1750.9 +2.528713151676047,1.8290051799938536,0.916297857297023,231.8,47.5,106.4,2466.7,1786.6,1625.9 +2.5287271006731165,1.8289647347883469,1.0471975511965976,73.2,34.0,161.5,2746.7,1072.8,864.1 +2.5287561988056084,1.8289184887875678,1.1780972450961724,31.8,31.6,251.0,2571.8,881.8,488.6 +2.5287552115980185,1.8289201885847277,1.3089969389957472,21.2,51.1,431.0,2055.3,534.0,406.6 +2.5287717840662824,1.8289124212893166,1.4398966328953218,25.8,152.9,983.8,1805.7,438.9,380.6 +2.5288472320335136,1.8288958496277112,1.5707963267948966,41.0,2428.5,2428.8,1721.3,393.4,393.2 +2.528842656489133,1.828895701263885,1.7016960206944713,68.3,2487.3,2545.8,1764.2,381.4,151.7 +2.528840730093661,1.828894255440287,1.832595714594046,114.2,2761.0,2888.7,988.3,406.0,50.9 +2.5288977229123653,1.8289305290327535,1.9634954084936205,192.8,2620.5,2401.4,644.6,250.4,31.6 +2.5289162804326564,1.8289517529816854,2.0943951023931953,350.5,2101.0,1974.1,485.8,161.1,34.0 +2.5289081993243294,1.828933511834709,2.2252947962927703,833.8,1845.3,1786.5,401.5,106.2,47.5 +2.5289147975455184,1.8289577076554484,2.356194490192345,2399.4,1751.1,1751.7,362.6,70.3,71.0 +2.5289124085413617,1.8289899219678438,2.4870941840919194,2510.8,1787.3,1626.4,359.1,47.5,106.7 +2.5289166693709957,1.8289825622481426,2.6179938779914944,2842.2,1070.2,865.4,391.1,33.5,161.4 +2.528903010482642,1.829000722254591,2.748893571891069,2405.3,879.4,487.3,192.1,32.4,252.6 +2.5289111958237895,1.828995421661647,2.8797932657906435,1961.6,533.4,406.2,114.2,52.0,432.3 +2.5289008391209773,1.8290020315812896,3.010692959690218,1764.2,439.7,381.1,68.7,152.6,977.6 +2.5288398986181826,1.7287009286169543,0.0,1621.1,393.1,393.2,140.8,2428.8,2428.7 +2.528885820294992,1.7292784002421127,0.1308996938995747,1485.5,381.1,440.6,129.1,2490.2,2549.2 +2.5288594956505666,1.729269584218567,0.2617993877991494,714.2,406.4,250.2,136.9,2760.0,2938.8 +2.5288285026325417,1.7294709266118766,0.39269908169872414,486.1,391.7,172.8,173.7,2479.6,2261.1 +2.5291130635632513,1.7289115344377233,0.5235987755982988,393.6,276.7,149.1,271.5,1988.4,1860.6 +2.5291547885056054,1.7289907307085848,0.6544984694978736,359.0,210.1,151.1,617.8,1742.5,1683.3 +2.5291485729064163,1.728970229374697,0.7853981633974483,363.2,170.9,170.4,2398.9,1651.5,1650.7 +2.52914789129081,1.7290076175635156,0.916297857297023,401.9,151.0,209.8,2466.0,1683.3,1522.0 +2.529144737890204,1.7290194276586355,1.0471975511965976,272.8,149.6,276.9,2746.5,1073.6,693.7 +2.5291432899404396,1.7290196831188571,1.1780972450961724,173.5,172.8,392.0,2430.9,749.2,488.6 +2.5291034623708764,1.7290565369975095,1.3089969389957472,136.8,250.5,629.8,1940.5,533.9,406.4 +2.5290764302350075,1.729071512060696,1.4398966328953218,129.3,542.8,1372.4,1702.7,438.8,380.5 +2.5291068207463185,1.729064681479946,1.5707963267948966,141.0,2429.0,2429.0,1621.0,393.2,393.1 +2.5290603174688044,1.729063024068573,1.7016960206944713,171.8,2487.4,2545.3,1660.4,381.2,439.7 +2.5290210741682517,1.7290507512765574,1.832595714594046,229.7,2761.0,2954.8,988.8,405.6,250.2 +2.5290468256068097,1.7290680735826325,1.9634954084936205,334.4,2480.1,2261.2,644.6,391.7,172.7 +2.5290419473325945,1.7290651345683423,2.0943951023931953,549.9,1986.2,1859.1,485.8,276.8,149.6 +2.5290400079518554,1.72906251550014,2.2252947962927703,1220.6,1741.6,1683.3,401.3,209.8,151.0 +2.5290316394578234,1.7290270252282336,2.356194490192345,2399.2,1651.1,1651.6,362.3,170.4,171.0 +2.5290293846472442,1.7290247953057125,2.4870941840919194,2510.2,1683.4,1522.8,358.9,151.0,210.3 +2.5290394705884904,1.7289938150818114,2.6179938779914944,2933.0,1070.6,691.9,393.4,149.1,276.9 +2.5290358894277,1.728993934853233,2.748893571891069,2265.3,707.1,487.1,333.6,173.8,393.8 +2.5290566601712894,1.7289755201897807,2.8797932657906435,1846.5,533.4,405.9,229.7,251.5,631.5 +2.5290607075344496,1.7289736139271126,3.010692959690218,1660.8,439.6,380.9,172.2,539.6,1363.6 +2.529017472137234,1.6286861207951124,0.0,1521.3,392.9,393.0,240.7,2429.7,2429.4 +2.529062202892697,1.6292776822139885,0.1308996938995747,1467.4,380.9,440.2,232.6,2489.7,2549.3 +2.5290127295778757,1.6292619693663637,0.2617993877991494,715.2,405.9,450.1,252.4,2759.1,2886.9 +2.528977060569943,1.629239103282495,0.39269908169872414,486.3,487.9,314.1,315.1,2341.0,2121.6 +2.5289510584306303,1.6292125525236916,0.5235987755982988,393.8,392.3,264.6,470.4,1873.2,1745.8 +2.528943832017556,1.6291957771716599,0.6544984694978736,359.0,313.5,254.5,1001.9,1638.9,1580.1 +2.5289333115342507,1.6291566567718365,0.7853981633974483,363.0,270.8,270.3,2399.3,1551.8,1551.4 +2.5289340947208765,1.6291534801020573,0.916297857297023,401.8,254.4,313.2,2466.2,1579.9,1418.5 +2.528944129026231,1.629121810594202,1.0471975511965976,485.6,264.9,392.2,2745.8,1074.5,693.9 +2.5289659849128303,1.6290839527910481,1.1780972450961724,315.0,313.6,532.7,2290.8,709.6,488.6 +2.528956180870674,1.6290920026394513,1.3089969389957472,252.3,449.2,828.4,1825.5,534.2,406.5 +2.5289632474373755,1.629088203104343,1.4398966328953218,232.5,931.0,1759.1,1599.7,438.9,380.5 +2.529029206905272,1.6290722457209226,1.5707963267948966,240.8,2429.1,2428.8,1521.0,393.3,393.0 +2.5290602824482455,1.6290700719759035,1.7016960206944713,275.0,2487.3,2545.5,1557.2,381.2,439.6 +2.52902253614946,1.6290575122045512,1.832595714594046,345.0,2760.3,2888.0,989.6,405.7,449.3 +2.529068462784067,1.6290864509948038,1.9634954084936205,475.8,2339.7,2121.0,644.8,487.6,313.6 +2.5290834441697676,1.6291035760858168,2.0943951023931953,748.8,1871.4,1743.8,486.0,392.2,264.9 +2.5290735616504936,1.6290833366956752,2.2252947962927703,1605.0,1638.8,1579.7,401.5,313.2,254.4 +2.5290788687791954,1.6291060457114794,2.356194490192345,2399.7,1550.9,1552.0,362.4,270.3,270.8 +2.52907566988513,1.6291365252983478,2.4870941840919194,2510.4,1580.1,1419.2,359.0,254.5,313.5 +2.5290789367968123,1.6291275304359505,2.6179938779914944,2840.6,1071.6,692.3,393.4,264.6,392.3 +2.5290652260228166,1.6291435805850905,2.748893571891069,2124.2,707.3,487.4,487.3,314.9,535.0 +2.5290734759069795,1.6291362832023046,2.8797932657906435,1731.5,533.6,406.2,345.3,450.5,830.3 +2.5290638597474464,1.6291410384429452,3.010692959690218,1557.2,439.7,380.9,275.6,925.6,1748.0 +2.5290042785063735,1.5288414096748544,0.0,1421.4,392.9,393.0,340.7,2429.1,2429.1 +2.529024238474316,1.5293195186654018,0.1308996938995747,1467.3,381.0,440.2,336.2,2489.8,2549.3 +2.528987812621659,1.5293077309560084,0.2617993877991494,715.4,406.1,533.5,368.0,2925.4,2804.2 +2.528950780888429,1.529283894673576,0.39269908169872414,628.8,487.8,455.3,456.8,2199.5,1980.2 +2.52892065410768,1.529252767460624,0.5235987755982988,393.8,508.0,380.3,669.5,1758.0,1630.0 +2.5289101832778234,1.5292297002500994,0.6544984694978736,358.9,417.2,358.1,1387.0,1535.8,1476.7 +2.528898117691376,1.529183615297222,0.7853981633974483,363.1,370.8,370.2,2399.0,1451.7,1451.1 +2.5288991818772075,1.5291737562323013,0.916297857297023,401.8,357.9,416.7,2465.9,1476.0,1398.6 +2.5289110803541623,1.529136085300501,1.0471975511965976,485.6,380.4,507.7,2818.3,1074.4,694.0 +2.5289360183220952,1.529093249888868,1.1780972450961724,456.8,454.7,673.9,2149.3,709.6,661.5 +2.528930094001029,1.529097613489575,1.3089969389957472,367.9,648.4,1027.4,1710.0,665.2,406.6 +2.528941523523543,1.5290914320452602,1.4398966328953218,336.0,1320.3,2148.2,1496.2,438.9,380.5 +2.529012013556047,1.5290743115222605,1.5707963267948966,340.7,2429.2,2429.2,1421.0,393.3,393.0 +2.529003309121938,1.5290728954565045,1.7016960206944713,378.4,2487.6,2544.8,1453.3,381.2,439.6 +2.5289979192193965,1.5290700716927215,1.832595714594046,460.5,2926.8,2802.6,989.6,405.7,533.2 +2.5290522372563102,1.5291041404954022,1.9634954084936205,617.4,2198.9,1979.9,645.0,487.7,454.8 +2.5290688608421497,1.5291228306664006,2.0943951023931953,948.3,1756.1,1628.7,486.0,507.8,380.4 +2.5290590275284335,1.5291024749062634,2.2252947962927703,1991.5,1535.2,1476.5,401.5,416.7,357.9 +2.5290642403567305,1.529124400473162,2.356194490192345,2399.6,1451.0,1451.6,362.5,370.3,370.8 +2.529061157892535,1.529153918112728,2.4870941840919194,2510.3,1476.5,1391.9,359.0,358.0,417.1 +2.5290647213977673,1.5291440439716175,2.6179938779914944,2823.5,1071.6,692.4,393.3,380.2,507.9 +2.5290515121731887,1.5291593302544844,2.748893571891069,1983.3,707.4,660.1,487.4,456.3,676.2 +2.529060340685593,1.5291514516243303,2.8797932657906435,1616.1,533.6,406.2,460.8,649.9,1029.5 +2.5290513733152595,1.5291557952707195,3.010692959690218,1453.9,439.8,381.0,379.2,1312.3,2134.6 +2.528992559706395,1.4288567483755865,0.0,1321.3,393.0,392.9,440.6,2429.1,2429.2 +2.529018158985521,1.4293246383097444,0.1308996938995747,1382.9,380.9,440.2,439.7,2489.4,2548.7 +2.5289823180394486,1.4293130119039676,0.2617993877991494,715.4,406.0,533.4,483.5,2758.7,2604.7 +2.5289449427910746,1.4292889312807553,0.39269908169872414,486.4,487.8,596.5,598.5,2058.7,1839.2 +2.5289143622618147,1.4292572712999632,0.5235987755982988,393.8,649.0,495.9,868.7,1642.0,1514.4 +2.5289035610391717,1.429233529543623,0.6544984694978736,358.9,520.7,461.5,1773.0,1432.2,1372.9 +2.528891366306883,1.4291867337469597,0.7853981633974483,363.1,470.9,470.2,2399.1,1351.8,1351.0 +2.528892475049307,1.4291761947580888,0.916297857297023,401.8,461.4,520.2,2466.1,1372.6,1398.6 +2.528904577313988,1.4291379207697164,1.0471975511965976,485.7,495.9,623.2,2745.6,1074.3,694.1 +2.5289298438540038,1.429094606583754,1.1780972450961724,629.6,595.9,815.0,2007.1,709.7,488.6 +2.528924313435389,1.42909861178812,1.3089969389957472,483.4,847.7,1226.7,1594.3,534.3,406.6 +2.5289361771411474,1.4290921865971966,1.4398966328953218,439.4,1709.4,2487.7,1392.7,439.0,380.5 +2.529007117774905,1.42907496658342,1.5707963267948966,440.7,2428.9,2428.1,1321.2,393.3,393.0 +2.52899883402859,1.429073552618899,1.7016960206944713,481.9,2487.4,2545.8,1350.1,381.2,439.6 +2.528993827196986,1.42907081023946,1.832595714594046,576.2,2760.5,2602.4,989.8,405.6,533.2 +2.52904847186473,1.4291050551448605,1.9634954084936205,759.1,2058.2,1838.9,644.9,487.6,596.0 +2.529065345828038,1.4291239839124006,2.0943951023931953,1148.1,1639.9,1512.8,486.0,623.4,496.1 +2.529055692327103,1.429103888116189,2.2252947962927703,2378.9,1431.7,1372.9,401.6,520.1,461.4 +2.5290610048502224,1.4291260954613743,2.356194490192345,2400.0,1351.4,1351.8,362.4,470.3,470.7 +2.529057932892381,1.4291559009867048,2.4870941840919194,2510.1,1372.7,1391.6,358.9,461.5,520.6 +2.52906144761166,1.4291462806901745,2.6179938779914944,2624.3,1071.4,692.4,393.3,495.8,623.5 +2.529048110305988,1.4291617900088893,2.748893571891069,1842.2,707.5,487.4,487.3,597.7,817.7 +2.529056779361226,1.4291540741556923,2.8797932657906435,1500.2,533.5,406.1,576.5,849.5,1229.1 +2.529047623263442,1.4291585195844532,3.010692959690218,1350.7,439.8,380.9,482.7,1699.4,2488.5 +2.5289885903755294,1.328859289648587,0.0,1221.4,393.0,393.0,540.6,2429.4,2429.5 +2.529014862371841,1.3293250241762333,0.1308996938995747,1290.9,380.9,440.2,543.2,2489.6,2549.1 +2.5289791204341645,1.3293134211625581,0.2617993877991494,715.4,406.0,533.5,599.0,2741.1,2404.9 +2.5289417386794146,1.3292893223587445,0.39269908169872414,486.4,487.9,708.5,740.0,1917.9,1698.3 +2.5289111416945156,1.3292576186144904,0.5235987755982988,534.7,692.8,611.5,1068.0,1526.6,1398.7 +2.5289003253849667,1.329233816651584,0.6544984694978736,359.0,624.3,565.1,2158.3,1328.5,1269.6 +2.528888144007152,1.3291869691971334,0.7853981633974483,363.1,570.9,570.3,2398.8,1251.7,1251.1 +2.5288892704345654,1.3291763792561198,0.916297857297023,401.7,564.9,623.7,2466.0,1269.3,1328.0 +2.528901401487609,1.3291380653697664,1.0471975511965976,485.6,611.4,738.7,2706.3,1126.2,694.1 +2.528926706662161,1.3290947356274125,1.1780972450961724,645.8,737.1,956.0,1865.7,709.7,488.7 +2.528921207992331,1.3290987276349817,1.3089969389957472,599.1,1046.8,1426.1,1478.6,534.2,406.5 +2.5289330990936647,1.3290922857687018,1.4398966328953218,542.8,2099.5,2487.6,1289.0,438.9,380.5 +2.5290040666500753,1.3290750737982164,1.5707963267948966,540.8,2429.2,2428.5,1221.0,393.2,393.1 +2.5289958045268417,1.32907366179708,1.7016960206944713,585.4,2487.2,2546.0,1246.4,381.2,439.5 +2.5289908212595593,1.3290709082398617,1.832595714594046,691.9,2738.8,2403.6,1139.9,405.7,533.3 +2.5290454877399036,1.3291051561938083,1.9634954084936205,900.8,1916.7,1697.5,644.9,487.6,708.5 +2.5290623810820634,1.3291240964333746,2.0943951023931953,1347.7,1524.7,1397.3,486.0,694.4,611.5 +2.529052754771458,1.3291040043917963,2.2252947962927703,2466.1,1327.9,1269.3,401.6,623.6,564.9 +2.529058092693902,1.3291262232034173,2.356194490192345,2399.5,1251.1,1251.7,362.4,570.3,570.8 +2.529055032936273,1.3291560542353236,2.4870941840919194,2509.9,1269.6,1328.4,359.0,565.1,624.1 +2.5290585643907533,1.3291464557799726,2.6179938779914944,2424.6,1153.0,692.3,393.3,611.5,739.0 +2.5290452188821657,1.3291619958864542,2.748893571891069,1700.1,707.5,487.4,487.3,739.3,959.1 +2.5290538821374158,1.3291543030538784,2.8797932657906435,1384.8,533.6,406.1,715.5,1049.0,1428.5 +2.5290447100751794,1.3291587653134762,3.010692959690218,1246.9,439.8,381.0,586.2,2086.7,2488.7 +2.5289856635226333,1.2288595100689315,0.0,1121.3,393.0,392.9,640.8,2428.9,2429.0 +2.529012365414244,1.2293250403252367,0.1308996938995747,1187.4,380.9,440.2,646.9,2489.6,2548.7 +2.5289767151167637,1.2293134608682457,0.2617993877991494,715.2,406.0,533.4,714.7,2585.2,2205.0 +2.5289393562082205,1.229289366283675,0.39269908169872414,486.4,487.9,708.7,881.6,1776.2,1556.9 +2.528908771078394,1.2292576560145425,0.5235987755982988,393.8,692.8,727.1,1267.4,1410.7,1283.0 +2.5288979594586274,1.229233839098812,0.6544984694978736,359.0,727.7,668.6,2510.1,1225.0,1166.0 +2.5288857957041087,1.2291869847452377,0.7853981633974483,363.1,670.8,670.3,2398.9,1151.8,1151.0 +2.528886934672996,1.2291763867313685,0.916297857297023,401.7,668.4,727.3,2466.1,1165.9,1224.8 +2.528899079515727,1.2291380700388217,1.0471975511965976,485.7,727.0,854.3,2506.7,1140.9,694.1 +2.5289244003645943,1.2290947513884622,1.1780972450961724,645.7,878.3,1097.1,1723.4,709.6,488.7 +2.528918908414241,1.2290987505236637,1.3089969389957472,714.7,1246.1,1625.2,1363.1,534.2,406.5 +2.528930800569491,1.2290923072732922,1.4398966328953218,646.4,2489.7,2487.2,1185.6,438.9,380.5 +2.5290017678780603,1.229075107045119,1.5707963267948966,640.7,2429.3,2428.7,1121.1,393.3,393.0 +2.5289935025704766,1.2290736966920326,1.7016960206944713,688.8,2487.6,2545.6,1143.2,381.2,439.5 +2.5289885195494834,1.2290709299674991,1.832595714594046,807.5,2583.3,2203.9,1024.5,405.7,533.3 +2.5290431876557133,1.229105171643711,1.9634954084936205,1042.3,1775.7,1525.4,645.0,487.7,708.6 +2.529060084474053,1.2291241093577412,2.0943951023931953,1547.4,1409.1,1281.5,486.0,694.2,727.0 +2.529050471646269,1.229104007370765,2.2252947962927703,2466.2,1224.6,1166.0,401.5,727.3,668.3 +2.5290558256466475,1.2291262215120384,2.356194490192345,2399.7,1151.3,1151.9,362.4,670.2,670.8 +2.5290527756175334,1.2291560591703954,2.4870941840919194,2510.0,1166.0,1225.0,359.0,668.6,727.6 +2.5290563234869947,1.229146466114584,2.6179938779914944,2225.5,1141.8,692.2,393.4,727.1,854.8 +2.529042977818389,1.2291620205902332,2.748893571891069,1558.8,707.5,487.4,487.4,880.8,1100.6 +2.5290516443709326,1.2291543388039665,2.8797932657906435,1269.1,533.5,406.1,715.6,1248.3,1628.4 +2.5290424686142035,1.2291588100755497,3.010692959690218,1143.5,439.7,380.9,689.7,2473.6,2488.3 +2.528983421608618,1.1288595430580548,0.0,1021.4,393.0,393.0,740.5,2429.3,2429.1 +2.529010455200048,1.1293250279421043,0.1308996938995747,1083.7,381.0,440.4,750.6,2489.5,2548.4 +2.5289748781092234,1.1293134675392174,0.2617993877991494,715.2,406.1,533.5,830.3,2386.0,2006.1 +2.5289375393746423,1.1292893779452187,0.39269908169872414,486.3,488.0,708.5,1023.5,1634.8,1415.7 +2.528906965344996,1.1292576649430046,0.5235987755982988,393.8,692.9,842.8,1466.7,1295.3,1167.4 +2.528896158603756,1.1292338390795018,0.6544984694978736,359.0,831.2,772.3,2510.0,1121.5,1062.3 +2.52888400889939,1.1291869820086884,0.7853981633974483,363.1,770.8,770.3,2399.1,1051.9,1051.2 +2.5288851573826157,1.1291763802353585,0.916297857297023,401.8,771.9,830.6,2466.4,1062.3,1121.0 +2.5288973121312903,1.1291380635582264,1.0471975511965976,485.6,842.7,969.8,2306.7,1074.5,694.1 +2.528922643887043,1.1290947551768766,1.1780972450961724,645.9,1019.3,1238.3,1582.1,709.7,488.7 +2.528917155714006,1.1290987611075005,1.3089969389957472,830.2,1445.4,1824.5,1247.4,534.1,406.7 +2.528929047131697,1.1290923176968404,1.4398966328953218,749.8,2545.7,2487.8,1082.3,439.0,380.4 +2.529000012629276,1.1290751268859092,1.5707963267948966,740.6,2428.9,2428.6,1021.3,393.3,393.1 +2.5289917433512605,1.1290737178134287,1.7016960206944713,792.2,2487.0,2545.4,1039.8,381.2,439.6 +2.528986759129889,1.1290709406758945,1.832595714594046,922.9,2383.4,2004.8,989.6,405.6,533.4 +2.5290414273010566,1.1291051768855054,1.9634954084936205,1184.1,1634.3,1415.3,644.9,487.6,708.5 +2.5290583258894594,1.129124111786743,2.0943951023931953,1746.9,1293.5,1166.1,485.9,694.5,842.6 +2.5290487227946454,1.1291040011994886,2.2252947962927703,2466.9,1121.1,1062.3,401.5,830.8,771.9 +2.5290540888247843,1.1291262107215094,2.356194490192345,2399.6,1051.2,1051.9,362.5,770.2,770.9 +2.529051046270792,1.129156052436987,2.4870941840919194,2510.0,1062.4,1121.5,359.0,772.1,831.2 +2.529054606974887,1.1291464626294143,2.6179938779914944,2026.2,1071.3,692.3,393.3,842.7,970.2 +2.5290412616736058,1.1291620273764285,2.748893571891069,1417.7,707.4,487.4,487.4,1022.1,1241.9 +2.5290499313561505,1.1291543535314643,2.8797932657906435,1153.7,533.6,406.1,715.5,1448.0,1827.8 +2.529040753444053,1.1291588314029224,3.010692959690218,1039.8,439.8,381.0,793.1,2547.5,2488.5 +2.4290344015891185,1.829251930837567,0.0,1721.1,493.0,493.0,40.8,2328.8,2329.1 +2.4290025429483184,1.8285393205632368,0.1308996938995747,1808.6,484.6,149.2,25.6,2385.9,2445.6 +2.429050488556268,1.828554958681855,0.2617993877991494,914.6,431.1,51.4,21.4,2643.6,2771.2 +2.4291032306235305,1.828589029516488,0.39269908169872414,627.6,251.2,31.9,32.1,2622.8,2404.1 +2.429145068605725,1.82863679864897,0.5235987755982988,509.5,161.3,33.6,72.4,2104.2,1976.5 +2.4287729536707863,1.8289908578488285,0.6544984694978736,462.6,106.5,47.6,232.6,1846.0,1786.5 +2.4287702448401913,1.828981408102837,0.7853981633974483,463.3,70.9,70.5,2298.4,1751.6,1751.0 +2.4287715619661756,1.828985426123352,0.916297857297023,231.8,47.5,106.4,2362.9,1786.6,1780.8 +2.4287826941419968,1.8289538780810117,1.0471975511965976,73.2,34.0,161.5,2631.1,1272.1,892.8 +2.4288070139713662,1.82891516931479,1.1780972450961724,31.8,31.6,251.0,2571.6,890.6,630.2 +2.428799999452422,1.828922489757238,1.3089969389957472,21.2,51.1,431.0,2055.0,649.6,522.1 +2.4288098015640838,1.8289183586594413,1.4398966328953218,25.8,153.0,984.0,1805.6,542.3,484.1 +2.4288782319102733,1.8289034725924889,1.5707963267948966,41.0,2328.5,2329.1,1721.3,493.3,493.3 +2.428864496563236,1.828903770616244,1.7016960206944713,68.3,2384.4,2442.3,1764.2,484.9,151.8 +2.428858360177753,1.8289011964814976,1.832595714594046,114.2,2645.9,2773.8,1187.4,429.6,50.9 +2.4289106797923092,1.8289347301501722,1.9634954084936205,192.8,2620.5,2401.1,785.5,250.4,31.6 +2.4289253889119307,1.8289520769588743,2.0943951023931953,350.6,2101.1,1974.2,601.4,161.1,34.1 +2.428914722411904,1.8289293473958166,2.2252947962927703,833.8,1845.4,1786.7,505.0,106.2,47.6 +2.42892006358484,1.8289487965828068,2.356194490192345,2299.7,1751.1,1751.5,462.5,70.3,71.0 +2.4289176998046127,1.828976418998602,2.4870941840919194,2407.0,1787.1,1772.3,462.7,47.5,106.8 +2.4289230996067066,1.8289649753205295,2.6179938779914944,2725.6,1269.1,890.6,347.4,33.5,161.4 +2.4289114801726925,1.8289797412300326,2.748893571891069,2405.9,848.3,628.5,192.1,32.4,252.7 +2.428922316670689,1.8289719260224597,2.8797932657906435,1961.8,648.9,521.7,114.2,52.0,432.4 +2.428914955829236,1.8289769523589514,3.010692959690218,1764.0,543.3,484.6,68.7,152.7,977.7 +2.4288576578200596,1.728678609504473,0.0,1621.2,493.1,493.3,140.8,2329.0,2328.7 +2.428900687875397,1.7292769267789914,0.1308996938995747,1705.9,484.7,544.1,129.1,2386.1,2445.9 +2.428873960777025,1.729268018322141,0.2617993877991494,913.7,521.9,250.2,136.8,2644.9,2938.4 +2.42884296865141,1.7292475870491215,0.39269908169872414,627.2,391.8,172.8,173.7,2479.9,2261.0 +2.428817227838916,1.7292203451166193,0.5235987755982988,509.3,276.4,149.0,271.7,1987.9,1860.6 +2.428809431212064,1.7292012257798537,0.6544984694978736,462.5,209.9,151.0,618.3,1742.4,1683.5 +2.4287993183409564,1.729159636914405,0.7853981633974483,463.3,170.8,170.3,2298.8,1651.7,1651.2 +2.4288008561842203,1.7291539534783655,0.916297857297023,505.5,150.9,209.8,2363.3,1683.3,1742.4 +2.4288122188939996,1.7291202403983963,1.0471975511965976,272.3,149.4,276.9,2631.3,1272.1,892.9 +2.428835872209102,1.7290813297381418,1.1780972450961724,173.2,172.6,392.0,2430.5,850.8,630.0 +2.4288276880595583,1.7290885842558557,1.3089969389957472,136.6,250.3,630.1,1940.1,649.5,522.0 +2.428836236456286,1.7290840282524624,1.4398966328953218,129.1,543.1,1374.0,1702.6,542.2,484.0 +2.428903637550905,1.7290682938863084,1.5707963267948966,140.8,2328.4,2328.4,1621.2,493.3,493.2 +2.428891867709931,1.7290669752375407,1.7016960206944713,171.7,2384.3,2442.8,1660.9,484.7,543.4 +2.428883864109643,1.7290628378852775,1.832595714594046,229.6,2645.5,2909.5,1187.4,521.6,249.6 +2.4289360423147324,1.7290953227984767,1.9634954084936205,334.4,2479.3,2260.7,785.6,391.2,172.4 +2.4289511715950036,1.7291122074669545,2.0943951023931953,550.1,1986.0,1858.8,601.2,276.5,149.4 +2.428940921259485,1.7290894764244156,2.2252947962927703,1221.4,1741.7,1683.2,504.9,209.5,150.9 +2.428946431248845,1.7291091931422626,2.356194490192345,2299.5,1651.1,1651.7,462.5,170.2,170.9 +2.428943900427333,1.7291371293971358,2.4870941840919194,2406.8,1684.0,1743.0,462.6,150.9,210.1 +2.4289488016093705,1.7291258599686998,2.6179938779914944,2725.7,1269.3,890.5,509.3,149.0,276.9 +2.428936506189275,1.7291404961240926,2.748893571891069,2264.0,848.2,628.6,333.2,173.7,393.9 +2.42894663831513,1.729132199246525,2.8797932657906435,1846.7,649.0,521.6,229.5,251.4,631.8 +2.4289387474521207,1.729136422974426,3.010692959690218,1660.9,543.1,484.5,172.0,540.2,1365.2 +2.428881359872837,1.6288379098770849,0.0,1521.6,493.0,493.2,240.6,2328.9,2328.9 +2.4289203147015668,1.629320347391701,0.1308996938995747,1601.9,484.6,544.1,232.6,2386.9,2445.6 +2.4288879531378527,1.6293096230969997,0.2617993877991494,913.7,521.8,449.6,252.5,2644.7,2772.0 +2.4288113526398614,1.6292643322107203,0.39269908169872414,627.1,533.0,313.9,315.4,2339.5,2120.8 +2.4288026956429376,1.629255533723234,0.5235987755982988,509.3,392.1,264.6,471.0,1872.5,1744.5 +2.4287953328268164,1.629237402713588,0.6544984694978736,462.5,313.4,254.5,1004.5,1639.0,1579.9 +2.4287836508876213,1.6291896090108333,0.7853981633974483,463.3,270.8,270.3,2298.7,1551.6,1551.2 +2.428785345618408,1.6291757708852996,0.916297857297023,505.5,254.3,313.3,2363.0,1580.0,1638.9 +2.4287990250324345,1.6291340005298922,1.0471975511965976,471.7,264.9,392.4,2631.1,1272.6,892.9 +2.4288267817991787,1.6290881385364744,1.1780972450961724,314.9,313.8,533.2,2288.3,850.9,802.9 +2.4288239291775646,1.629090173592033,1.3089969389957472,252.1,449.7,829.3,1824.9,649.5,522.1 +2.4288385673983997,1.6290822441338317,1.4398966328953218,232.5,933.2,1763.7,1599.3,542.3,484.1 +2.428912334953423,1.6290648468991278,1.5707963267948966,240.8,2328.4,2328.7,1521.3,493.3,493.3 +2.4289065728669437,1.6290635956643515,1.7016960206944713,275.1,2383.6,2442.6,1556.9,484.8,543.3 +2.4289039222133733,1.6290610553390916,1.832595714594046,345.2,2645.8,2773.4,1187.7,521.5,448.8 +2.428960580031192,1.6290962839632885,1.9634954084936205,476.0,2338.2,2119.6,785.7,532.3,313.5 +2.428979029451424,1.6291166668129444,2.0943951023931953,749.6,1870.6,1743.5,601.3,391.9,264.9 +2.4289708182886973,1.6290978913533465,2.2252947962927703,1608.8,1638.3,1579.6,504.9,313.0,254.3 +2.4289771722311198,1.6291216800742057,2.356194490192345,2299.2,1551.2,1551.8,462.5,270.1,270.9 +2.4289744257529433,1.6291534286720646,2.4870941840919194,2407.0,1580.3,1639.8,462.7,254.4,313.7 +2.4289781422418555,1.6291454994824992,2.6179938779914944,2725.8,1269.5,891.0,509.2,264.6,392.5 +2.42896404171405,1.629162799479045,2.748893571891069,2123.5,848.3,801.1,474.6,315.1,535.3 +2.428971881616554,1.6291564299104035,2.8797932657906435,1730.6,649.1,521.6,345.1,451.0,831.4 +2.4289615045965873,1.6291618186733021,3.010692959690218,1557.0,543.2,484.5,275.5,927.7,1752.3 +2.4289011493527815,1.5288611418780704,0.0,1421.5,493.0,493.1,340.6,2329.0,2329.0 +2.428937626023434,1.5293231029268006,0.1308996938995747,1498.2,484.6,544.0,336.2,2386.5,2446.1 +2.4289043754012325,1.5293121267229732,0.2617993877991494,913.9,521.8,649.4,368.0,2644.6,2757.6 +2.4288678711914224,1.5292882661475211,0.39269908169872414,627.3,630.0,455.1,457.1,2199.0,1979.5 +2.4288378886109614,1.529256623269834,0.5235987755982988,509.3,507.7,380.2,670.3,1757.0,1629.5 +2.42882739964395,1.5292326944868524,0.6544984694978736,462.5,417.0,358.0,1390.3,1535.0,1476.4 +2.42881585633447,1.5291860026281692,0.7853981633974483,463.2,370.8,370.3,2298.9,1451.7,1451.4 +2.4288173647873017,1.5291755161770761,0.916297857297023,505.5,357.9,416.9,2363.1,1476.8,1535.6 +2.4288467212368707,1.5290826969916123,1.0471975511965976,601.7,380.6,507.9,2630.7,1383.1,893.2 +2.428851583091741,1.5290731774779664,1.1780972450961724,456.5,454.8,674.1,2147.7,850.9,686.4 +2.4288396469726945,1.529083573757958,1.3089969389957472,367.8,649.1,1028.6,1709.2,649.6,522.1 +2.428852029838467,1.529133565291589,1.4398966328953218,336.0,1322.9,2153.2,1495.6,542.4,484.0 +2.4289561494750473,1.5290486387798123,1.5707963267948966,340.8,2329.1,2328.6,1421.3,493.2,493.2 +2.428930950267805,1.5290466841008672,1.7016960206944713,378.6,2384.3,2442.7,1453.6,484.7,543.3 +2.428925982459274,1.5290435008895698,1.832595714594046,460.9,2645.3,2755.1,1187.7,521.5,649.2 +2.428985069660666,1.5290802833925285,1.9634954084936205,617.7,2198.0,1978.9,785.6,629.7,454.6 +2.429006392769775,1.5291037835357453,2.0943951023931953,949.3,1755.4,1628.0,601.4,507.5,380.3 +2.4290001685932046,1.5290889596491657,2.2252947962927703,1996.2,1535.1,1476.5,505.0,416.5,357.9 +2.429007379907559,1.5291169580551665,2.356194490192345,2299.4,1451.1,1451.7,462.5,370.2,370.8 +2.429004420509602,1.5291526975564402,2.4870941840919194,2406.9,1476.7,1535.8,462.6,358.1,417.2 +2.429022871790778,1.5290971431254983,2.6179938779914944,2725.6,1384.8,890.9,509.3,380.3,508.1 +2.428987458903476,1.5291484536258162,2.748893571891069,1982.1,848.5,628.6,629.3,456.5,676.7 +2.4290173073374675,1.5291228989732588,2.8797932657906435,1615.5,648.9,521.7,460.6,650.5,1030.8 +2.4289803110250836,1.529142328581819,3.010692959690218,1454.0,543.2,484.6,379.0,1314.8,2139.2 +2.4289156200508937,1.4288514772694525,0.0,1321.4,493.0,493.0,440.7,2329.0,2328.8 +2.428952857258837,1.4293264109323505,0.1308996938995747,1394.7,484.6,544.1,439.8,2386.1,2445.6 +2.4289192115272398,1.4293153380995007,0.2617993877991494,914.0,521.8,649.3,483.6,2738.2,2602.5 +2.428882275901847,1.4292912651270955,0.39269908169872414,627.3,629.7,596.3,598.7,2058.1,1838.4 +2.428851890866288,1.429259306545958,0.5235987755982988,509.4,623.4,495.8,869.4,1641.7,1514.1 +2.4288411404244137,1.4292350341807893,0.6544984694978736,462.5,520.6,461.6,1775.9,1431.9,1372.8 +2.42882937556777,1.4291879154622769,0.7853981633974483,463.2,470.8,470.3,2298.7,1351.9,1351.2 +2.4288308171556814,1.4291770310691196,0.916297857297023,505.5,461.5,520.3,2362.8,1372.6,1431.9 +2.4288433161447043,1.429138563761092,1.0471975511965976,601.5,496.0,623.5,2631.1,1372.2,893.2 +2.4288690531071135,1.429095441124924,1.1780972450961724,598.2,596.1,815.3,2006.2,851.1,630.2 +2.428863774172629,1.4290995584856816,1.3089969389957472,483.3,848.3,1228.0,1593.8,649.6,522.1 +2.428875751112939,1.4290930472512993,1.4398966328953218,439.5,1712.7,2384.0,1392.7,542.3,484.0 +2.428946775162985,1.4290761106065808,1.5707963267948966,440.8,2328.7,2328.7,1321.1,493.3,493.1 +2.4289384932108598,1.429074738722751,1.7016960206944713,481.9,2383.9,2442.5,1350.4,484.7,543.2 +2.4289335699545367,1.4290716705938482,1.832595714594046,576.5,2696.2,2600.8,1230.6,521.4,649.3 +2.4289883225819757,1.4291057881624645,1.9634954084936205,759.4,2056.8,1838.0,785.9,629.7,595.8 +2.4290053368402624,1.4291246998575597,2.0943951023931953,1149.0,1639.5,1487.1,601.4,623.0,495.8 +2.428996068514329,1.4291043989435603,2.2252947962927703,2362.8,1431.6,1372.6,505.0,520.0,461.4 +2.429001816751219,1.429126542261161,2.356194490192345,2299.5,1351.2,1351.7,462.5,470.2,470.8 +2.4289989974051545,1.429156577507184,2.4870941840919194,2406.7,1372.9,1432.2,462.6,461.5,520.7 +2.4290029262523176,1.4291471475674298,2.6179938779914944,2622.3,1373.3,891.0,509.2,495.9,623.7 +2.4289895573384945,1.429163072946011,2.748893571891069,1841.1,848.5,628.6,629.1,598.0,818.1 +2.428998278860167,1.4293169644778811,2.8797932657906435,1500.2,649.0,521.6,576.1,850.0,1230.2 +2.4288672687123354,1.4288882889059398,3.010692959690218,1350.3,543.5,484.5,482.8,1698.1,2385.1 +2.4288597526596654,1.3286572825456398,0.0,1221.3,493.1,493.0,540.9,2329.5,2329.5 +2.4289483279057307,1.3292958491599172,0.1308996938995747,1290.8,484.5,543.8,543.3,2386.1,2446.0 +2.4289295125655097,1.329289483733101,0.2617993877991494,914.5,521.7,649.2,599.1,2643.6,2404.2 +2.4288980401209472,1.3292689921187908,0.39269908169872414,627.4,629.7,737.6,740.3,1917.2,1697.6 +2.428869895624748,1.3292396588397983,0.5235987755982988,509.3,739.1,611.4,1068.6,1526.3,1398.6 +2.4288602110319752,1.3292175802114883,0.6544984694978736,462.5,624.1,565.1,2160.3,1328.6,1269.4 +2.4288487261363576,1.329172348132405,0.7853981633974483,463.1,570.9,570.3,2298.6,1251.9,1251.0 +2.428850058175683,1.3291631934076735,0.916297857297023,505.5,564.9,623.8,2362.9,1269.3,1328.1 +2.4288620610853,1.3291262275569928,1.0471975511965976,601.3,611.5,738.9,2630.3,1273.5,893.5 +2.4288869760863943,1.329084220106584,1.1780972450961724,771.3,737.2,956.2,1864.7,851.2,630.4 +2.428880764081137,1.3290892216809649,1.3089969389957472,599.0,1047.6,1426.8,1478.5,649.8,646.3 +2.428891718124644,1.3290833988924042,1.4398966328953218,542.9,2101.0,2384.1,1289.1,542.3,483.9 +2.4289616501930005,1.3290666813713197,1.5707963267948966,540.7,2329.0,2328.5,1221.1,493.4,493.0 +2.4289523469515792,1.3290653384353284,1.7016960206944713,585.4,2383.7,2441.7,1246.8,484.8,543.1 +2.428946456218876,1.3290621927818478,1.832595714594046,692.0,2645.5,2402.1,1244.7,521.4,649.0 +2.429000378423001,1.3290959083401381,1.9634954084936205,901.0,1915.8,1697.5,785.9,629.5,736.9 +2.429016761987701,1.329114211314458,2.0943951023931953,1348.4,1524.6,1397.2,601.6,738.8,611.5 +2.429006988980613,1.329093306954537,2.2252947962927703,2362.8,1327.8,1269.2,504.9,623.7,564.9 +2.4290124412630907,1.3291147651142678,2.356194490192345,2299.7,1251.0,1251.7,462.5,570.3,570.8 +2.4290096185473296,1.3291440388054032,2.4870941840919194,2407.2,1269.4,1328.9,462.5,565.1,624.2 +2.429013635754324,1.3291339803705857,2.6179938779914944,2423.9,1270.3,891.5,509.1,611.5,739.3 +2.429000668025479,1.3291493151485252,2.748893571891069,1700.2,848.7,628.8,629.0,739.4,959.3 +2.4290098040630155,1.3291415236932593,2.8797932657906435,1384.3,649.1,521.7,691.9,1049.4,1429.3 +2.4290010155922945,1.3291459975915783,3.010692959690218,1246.8,543.2,484.5,586.1,2088.4,2384.6 +2.4289424048858175,1.2288469174864638,0.0,1121.0,493.0,493.1,640.6,2328.9,2328.8 +2.4289781963076456,1.2293218176523506,0.1308996938995747,1187.6,484.6,543.9,647.1,2386.2,2445.1 +2.4289448293040787,1.2293108904583745,0.2617993877991494,914.5,521.6,649.3,714.8,2584.5,2204.8 +2.4289082852655786,1.229287182579847,0.39269908169872414,627.5,629.7,850.4,881.9,1775.6,1556.8 +2.428878140892491,1.2292557008906888,0.5235987755982988,509.3,880.1,727.0,1267.7,1410.5,1282.8 +2.428867551908834,1.2292319934885234,0.6544984694978736,462.5,727.7,668.6,2406.3,1225.1,1166.0 +2.428855687455409,1.2291853472691092,0.7853981633974483,463.2,670.9,670.3,2298.8,1151.8,1151.1 +2.428856984864906,1.2291749219953965,0.916297857297023,505.4,668.5,727.4,2362.5,1165.6,1224.7 +2.4288692399529443,1.229136817467177,1.0471975511965976,601.4,727.0,854.3,2505.3,1273.6,893.5 +2.428894644227068,1.2290938491077286,1.1780972450961724,787.3,878.4,1097.5,1723.3,851.2,630.4 +2.4288890861015586,1.2290980975731294,1.3089969389957472,714.7,1246.7,1626.1,1362.6,649.7,522.1 +2.4289101363962926,1.2290855894422688,1.4398966328953218,646.3,2443.2,2384.5,1185.5,542.3,483.9 +2.4289737755520497,1.2290702497876969,1.5707963267948966,640.8,2328.7,2328.9,1121.3,493.3,493.1 +2.428963785897816,1.2290688115698365,1.7016960206944713,688.9,2384.1,2442.1,1143.2,484.7,543.2 +2.4289589771482847,1.2290659333185507,1.832595714594046,807.5,2582.1,2203.1,1188.2,521.4,649.1 +2.4290142941853192,1.2291004931243625,1.9634954084936205,1042.7,1775.2,1556.0,785.9,629.3,850.5 +2.429031821386841,1.2291200308137342,2.0943951023931953,1547.5,1408.8,1281.8,601.5,879.8,727.0 +2.4290227812483787,1.2291005479784056,2.2252947962927703,2363.0,1224.4,1165.9,505.0,727.3,668.4 +2.4290285275502366,1.2291234909493953,2.356194490192345,2299.1,1151.3,1151.8,462.4,670.4,670.8 +2.4290255811630694,1.229154172537154,2.4870941840919194,2406.6,1165.9,1224.9,462.5,668.6,727.8 +2.429029144061567,1.2291453195593438,2.6179938779914944,2224.6,1270.4,891.4,509.1,727.3,854.9 +2.4290154586976715,1.2291616173062518,2.748893571891069,1558.5,848.7,628.8,629.0,880.8,1100.7 +2.4290237367827734,1.2291544960682412,2.8797932657906435,1269.2,649.1,521.6,807.5,1249.1,1628.5 +2.4290140277217946,1.2291593565139824,3.010692959690218,1143.1,543.2,484.5,689.7,2444.0,2384.5 +2.4289543805987464,1.128859492655279,0.0,1021.3,493.0,493.0,740.6,2328.9,2329.1 +2.428984849929241,1.1293250355725242,0.1308996938995747,1083.8,484.7,543.8,750.5,2386.2,2445.8 +2.428950024790566,1.1293136584899388,0.2617993877991494,1001.3,521.6,649.0,830.3,2384.8,2005.5 +2.4289128985026083,1.1292895972911408,0.39269908169872414,627.4,629.8,850.5,1023.6,1634.6,1415.4 +2.42888246544502,1.1292578357236347,0.5235987755982988,509.3,892.4,842.6,1467.1,1294.9,1167.4 +2.4288717262944086,1.1292338902512702,0.6544984694978736,462.6,831.1,772.2,2406.1,1121.3,1062.2 +2.4288597698359107,1.1291870042879237,0.7853981633974483,463.0,770.8,770.3,2299.3,1051.7,1051.3 +2.4288610471947765,1.1291763604497234,0.916297857297023,505.3,771.9,830.8,2362.6,1062.3,1121.0 +2.4288733337301838,1.1291380525501675,1.0471975511965976,601.4,842.6,970.0,2306.1,1166.3,1048.1 +2.4288988091190493,1.1290948913620902,1.1780972450961724,787.1,1019.4,1238.5,1582.0,851.3,630.3 +2.428893366159081,1.1290989948449335,1.3089969389957472,830.1,1445.8,1825.1,1247.5,649.8,522.2 +2.428905240723495,1.1290925518944017,1.4398966328953218,749.7,2442.6,2384.3,1082.3,542.3,484.0 +2.4289761748002907,1.1290754906564824,1.5707963267948966,740.7,2329.3,2328.6,1021.2,493.3,493.1 +2.428967845288225,1.1290740983969156,1.7016960206944713,792.3,2383.5,2441.6,1039.7,484.7,543.1 +2.428962839499745,1.129071177121558,1.832595714594046,923.2,2383.4,2003.9,1154.8,521.4,649.2 +2.4290175042042526,1.1291053359706813,1.9634954084936205,1184.5,1634.1,1384.0,785.9,629.5,850.5 +2.4290344235884516,1.129124229230262,2.0943951023931953,1747.3,1293.5,1166.1,601.5,894.3,842.4 +2.4290249510565056,1.129103997574153,2.2252947962927703,2363.2,1120.9,1062.2,505.1,830.6,771.8 +2.4290304798575524,1.1291261402043116,2.356194490192345,2299.4,1051.2,1051.7,462.5,770.3,770.8 +2.4290275386748204,1.1291560335322186,2.4870941840919194,2406.5,1062.3,1121.5,462.6,772.3,831.2 +2.4290312749006997,1.129146484402681,2.6179938779914944,2025.8,1167.5,1049.7,509.1,842.9,970.5 +2.4290179355437482,1.1291621860485022,2.748893571891069,1417.4,848.7,628.8,628.8,1021.9,1242.4 +2.4290266497317003,1.1291546177714624,2.8797932657906435,1153.7,649.1,521.6,915.5,1448.9,1828.8 +2.429017444729854,1.1291591835519768,3.010692959690218,1039.8,543.3,484.5,793.1,2443.7,2384.5 +2.3290109878312886,1.8292519492977033,0.0,1721.4,593.0,593.0,40.8,2229.3,2228.8 +2.328991428626562,1.8285391668701747,0.1308996938995747,1808.4,588.1,149.2,25.6,2282.5,2364.4 +2.3290418366793606,1.8285555524607437,0.2617993877991494,1114.1,431.0,51.4,21.4,2528.4,2655.1 +2.329095075342149,1.8285899061202404,0.39269908169872414,768.8,251.2,31.9,32.1,2622.6,2403.7 +2.3291368930392076,1.8286376062624632,0.5235987755982988,625.1,161.3,33.6,72.4,2104.2,1976.5 +2.329173000161072,1.8287030414725758,0.6544984694978736,566.2,106.7,47.6,231.9,1846.2,1786.9 +2.3291821304901554,1.8287489721816765,0.7853981633974483,563.1,71.1,70.5,2198.4,1751.6,1750.9 +2.329180701701657,1.8288261397816212,0.916297857297023,233.2,47.7,106.5,2258.9,1786.4,1845.3 +2.3291696541332496,1.8288665226604681,1.0471975511965976,73.7,34.2,161.5,2514.2,1473.7,1093.5 +2.3291556479014317,1.8288884279609041,1.1780972450961724,32.1,31.9,250.9,2573.6,993.2,772.2 +2.3291003353296054,1.8289413062658804,1.3089969389957472,21.4,51.4,430.5,2056.0,765.5,638.0 +2.3290557422801,1.8289671579272178,1.4398966328953218,26.0,153.1,981.7,1783.3,646.0,587.5 +2.3290675304237833,1.8289656341448384,1.5707963267948966,41.1,2228.8,2228.5,1720.8,593.4,593.1 +2.3290033116309643,1.828964436381773,1.7016960206944713,68.5,2280.0,2338.8,1763.9,588.2,153.2 +2.3289479502854062,1.8289484273881005,1.832595714594046,114.3,2528.9,2657.1,1388.0,430.6,51.4 +2.328960064120864,1.8289580221146127,1.9634954084936205,192.8,2621.9,2402.8,927.2,251.1,31.9 +2.32894504060221,1.8289446941105418,2.0943951023931953,350.3,2102.0,1974.9,716.9,161.5,34.2 +2.328914934354487,1.828888198413029,2.2252947962927703,831.7,1845.5,1786.4,608.6,106.5,47.7 +2.3289110359224363,1.8288723460386676,2.356194490192345,2199.2,1750.6,1751.4,562.5,70.6,71.1 +2.3289093624934574,1.8288657354191769,2.4870941840919194,2303.1,1786.8,1846.0,565.9,47.7,106.8 +2.328923238846445,1.8288242721696857,2.6179938779914944,2609.4,1469.9,1090.7,348.2,33.7,161.3 +2.3289273067391507,1.8288139355966604,2.748893571891069,2407.0,990.3,770.2,192.5,32.5,252.5 +2.3289578042716874,1.8287877723763595,2.8797932657906435,1962.6,764.7,637.2,114.4,52.1,431.9 +2.3289726344525272,1.8287813255624847,3.010692959690218,1764.2,646.8,588.0,68.9,152.4,975.1 +2.3289416157872576,1.7285032732774697,0.0,1620.9,592.9,592.9,141.0,2229.0,2229.1 +2.3289909063455605,1.7292627637662865,0.1308996938995747,1705.1,588.1,532.8,129.1,2282.7,2341.8 +2.328967053684881,1.729254968447735,0.2617993877991494,1114.1,637.2,250.6,136.8,2528.2,2655.2 +2.3289375209342214,1.7292358843685516,0.39269908169872414,768.7,392.2,172.9,173.6,2482.3,2262.5 +2.328912292183033,1.7292099865453645,0.5235987755982988,625.1,276.7,149.0,271.2,1988.8,1861.1 +2.3289047710709823,1.7291923384968833,0.6544984694978736,566.1,210.1,151.0,616.7,1742.8,1683.4 +2.3288941341276974,1.7291518003382644,0.7853981633974483,563.2,170.8,170.3,2198.6,1651.9,1651.3 +2.3288951658636434,1.7291471407904715,0.916297857297023,608.8,150.9,209.7,2258.7,1683.5,1742.0 +2.328905815549181,1.7291141624334927,1.0471975511965976,272.7,149.4,276.7,2514.7,1614.0,1093.3 +2.3289285533833284,1.7290753209188565,1.1780972450961724,173.3,172.5,391.5,2432.1,993.1,945.0 +2.3289197327932576,1.7290826904415946,1.3089969389957472,136.7,250.0,629.2,1940.8,765.5,637.8 +2.3289278132928977,1.7290784759494966,1.4398966328953218,129.1,541.5,1370.0,1702.9,645.8,587.4 +2.3289947649967826,1.7290624157065109,1.5707963267948966,140.8,2229.0,2228.6,1621.1,593.4,593.1 +2.3289826797202036,1.7290610585273853,1.7016960206944713,171.6,2280.2,2339.1,1660.2,588.2,623.8 +2.328974255997666,1.729057374038701,1.832595714594046,229.5,2529.8,2657.1,1388.0,636.9,250.0 +2.329026017360026,1.729089926825632,1.9634954084936205,334.1,2481.0,2261.9,927.2,391.5,172.5 +2.32904074266,1.729106654793258,2.0943951023931953,549.2,1986.9,1859.1,717.0,276.7,149.4 +2.3290297775592665,1.7290840323458,2.2252947962927703,1218.1,1742.1,1683.5,608.6,209.6,150.9 +2.329034566638837,1.7291036271469364,2.356194490192345,2199.4,1651.2,1651.7,562.5,170.3,170.8 +2.3290316693427693,1.7291309964326609,2.4870941840919194,2302.8,1683.9,1742.6,566.1,151.0,210.1 +2.3290360059691086,1.7291192563622508,2.6179938779914944,2609.6,1615.6,1090.7,546.8,149.0,276.6 +2.3290238816986744,1.7291331130178635,2.748893571891069,2266.1,990.0,942.9,333.6,173.6,393.5 +2.329034071689668,1.729124241112154,2.8797932657906435,1846.9,764.6,637.3,229.7,251.1,630.9 +2.32902653220461,1.7291280385580376,3.010692959690218,1661.0,646.8,588.0,172.1,538.5,1361.3 +2.3289693767434847,1.6288301733371227,0.0,1521.6,593.0,593.0,240.7,2229.3,2229.1 +2.3290004305209715,1.6293192858378858,0.1308996938995747,1601.8,588.0,647.4,232.7,2282.8,2341.9 +2.3289663342427747,1.629308181013141,0.2617993877991494,1114.0,637.2,450.0,252.3,2528.2,2716.1 +2.328929812171129,1.6292845815361139,0.39269908169872414,768.6,533.4,314.1,315.2,2340.9,2121.5 +2.3288997701705796,1.6292533851348112,0.5235987755982988,625.0,392.4,264.6,470.5,1873.4,1745.8 +2.328889278818772,1.6292300757253244,0.6544984694978736,566.1,313.6,254.5,1002.3,1639.1,1580.0 +2.3288773233422275,1.6291837711271364,0.7853981633974483,563.2,270.8,270.3,2199.0,1551.7,1551.2 +2.3288782397583896,1.6292200575827245,0.916297857297023,608.8,254.4,313.1,2259.7,1579.9,1638.6 +2.328899515271314,1.6291521429176503,1.0471975511965976,472.3,264.9,392.2,2514.6,1498.5,1093.2 +2.328928283903736,1.629103563217753,1.1780972450961724,315.0,313.6,532.7,2290.4,993.0,827.2 +2.3289218246297154,1.6291085669616465,1.3089969389957472,252.2,449.2,828.5,1825.6,864.6,637.8 +2.3289305132379967,1.6291038622232596,1.4398966328953218,232.5,930.9,1759.6,1599.5,645.7,587.3 +2.328997396283434,1.6290876724868397,1.5707963267948966,240.8,2228.1,2228.7,1521.1,593.1,593.1 +2.3289850595485015,1.6290861573937756,1.7016960206944713,275.0,2280.1,2338.7,1557.1,588.2,646.5 +2.3289763933115246,1.6290822404743501,1.832595714594046,345.0,2529.5,2714.0,1487.0,637.0,449.2 +2.3290279755523087,1.6291145372707474,1.9634954084936205,475.7,2339.7,2121.0,927.1,532.7,313.6 +2.329042592286922,1.6291310179945149,2.0943951023931953,748.8,1845.5,1744.1,858.1,392.2,264.9 +2.3290315786591567,1.6291081635291067,2.2252947962927703,1605.4,1638.7,1579.7,608.5,313.1,254.4 +2.3290363482575964,1.6291275546840764,2.356194490192345,2199.4,1551.4,1551.5,562.3,270.2,270.8 +2.3290331693897537,1.6292015136377902,2.4870941840919194,2303.4,1580.1,1639.1,566.1,254.5,313.6 +2.3290468305997067,1.6291592323001691,2.6179938779914944,2735.5,1499.8,1090.8,624.7,264.5,392.3 +2.3290383416749756,1.6291672143204408,2.748893571891069,2124.6,990.1,770.3,475.0,315.0,534.9 +2.329047851066823,1.6291588385998885,2.8797932657906435,1731.4,764.6,637.3,345.3,450.6,830.4 +2.329037498829904,1.629163992387825,3.010692959690218,1557.3,646.9,588.0,275.6,925.7,1748.7 +2.3289387992869344,1.528853246891066,0.0,1421.3,592.9,593.1,340.6,2229.1,2229.3 +2.3289880725979564,1.5292114917531139,0.1308996938995747,1497.9,588.0,647.5,336.2,2282.2,2341.8 +2.328971866545565,1.529206101205431,0.2617993877991494,1114.0,637.3,649.6,367.9,2527.9,2655.1 +2.3289489532685796,1.529191266289375,0.39269908169872414,768.8,674.6,455.4,456.8,2199.6,1980.3 +2.328928723636464,1.5291708454332502,0.5235987755982988,625.0,508.0,380.3,669.7,1757.6,1629.7 +2.328924390055948,1.529159251245649,0.6544984694978736,566.0,417.2,358.1,1387.6,1535.5,1476.6 +2.328915180090305,1.5291249628135586,0.7853981633974483,563.2,370.8,370.3,2198.7,1451.8,1451.2 +2.328916034498995,1.5291262077888246,0.916297857297023,608.8,357.9,416.7,2259.1,1476.3,1535.0 +2.3289251161914124,1.5290985170381888,1.0471975511965976,716.0,380.5,507.8,2514.5,1473.5,1093.6 +2.328945196790847,1.5290640419231676,1.1780972450961724,456.8,454.8,673.9,2148.4,993.0,772.2 +2.3289330208702412,1.5290746810062508,1.3089969389957472,367.9,648.6,1027.8,1709.6,765.6,637.9 +2.3289373041243113,1.529072626488181,1.4398966328953218,336.0,1320.9,2149.7,1496.0,645.9,587.6 +2.3290002818017204,1.5290575928738908,1.5707963267948966,340.8,2229.1,2228.9,1421.4,593.3,593.1 +2.328984446759287,1.5290562320992391,1.7016960206944713,378.5,2280.2,2338.6,1453.4,588.3,646.5 +2.3289726499753227,1.529051656135518,1.832595714594046,460.7,2529.3,2656.6,1476.0,636.9,648.7 +2.3290215675578123,1.5290825487515889,1.9634954084936205,617.4,2198.6,1979.6,927.2,673.9,454.8 +2.3290341639185543,1.5290971073406445,2.0943951023931953,948.6,1755.8,1628.2,717.0,507.7,380.5 +2.329021826581933,1.5290720525967674,2.2252947962927703,1992.4,1535.4,1476.1,608.6,416.7,357.9 +2.329025991797348,1.5290891040489671,2.356194490192345,2199.9,1450.9,1451.8,562.4,370.3,370.8 +2.3290231841260685,1.5291140313203098,2.4870941840919194,2303.0,1476.6,1535.4,566.0,358.1,417.1 +2.3290281972054783,1.5291001579918215,2.6179938779914944,2609.5,1469.7,1090.7,624.7,380.3,508.0 +2.329017234609354,1.529112270942615,2.748893571891069,1983.2,990.5,770.1,616.5,456.4,676.5 +2.329028874912586,1.5291021499537318,2.8797932657906435,1615.8,764.7,637.2,460.8,650.2,1030.0 +2.329022937503641,1.5291052008865953,3.010692959690218,1453.6,646.8,587.9,379.3,1313.0,2135.4 +2.3289676524647205,1.4288087615252025,0.0,1321.3,593.0,593.0,440.8,2228.9,2228.8 +2.329000267568222,1.4293157903762264,0.1308996938995747,1394.4,588.0,647.4,439.8,2282.4,2341.8 +2.3289668902743115,1.4293049181740576,0.2617993877991494,1114.3,637.2,764.6,483.4,2527.5,2604.0 +2.328930813368732,1.4292816087289986,0.39269908169872414,768.7,771.2,596.5,598.4,2058.4,1839.4 +2.328901061569112,1.4292507369168477,0.5235987755982988,763.8,623.5,495.8,868.8,1641.9,1514.5 +2.3288907461777697,1.4292277688056434,0.6544984694978736,566.0,520.7,461.6,1773.4,1432.3,1373.1 +2.328878864054428,1.4291818065444386,0.7853981633974483,563.1,470.9,470.3,2198.8,1351.9,1351.1 +2.328880031115122,1.4291720405978745,0.916297857297023,608.8,461.5,520.2,2259.4,1372.6,1431.5 +2.328892007659667,1.4291344868661064,1.0471975511965976,716.8,495.9,623.3,2617.9,1473.3,1093.3 +2.3289170091154245,1.4290918537213915,1.1780972450961724,598.6,595.9,814.9,2007.4,992.9,772.2 +2.3289110595225937,1.4290963653974567,1.3089969389957472,483.5,847.9,1226.9,1594.4,765.4,637.8 +2.328922404550253,1.4290902411943929,1.4398966328953218,439.5,1710.5,2280.9,1392.7,645.8,587.4 +2.328992790202647,1.4290732464577633,1.5707963267948966,440.7,2229.4,2228.8,1321.0,593.3,593.1 +2.3289839613324137,1.4290718501438713,1.7016960206944713,481.9,2280.0,2338.5,1350.1,588.2,646.6 +2.3289784809686647,1.4290689067294522,1.832595714594046,576.3,2554.8,2602.7,1387.9,636.9,764.6 +2.3290327337033148,1.4291028826797612,1.9634954084936205,759.1,2057.7,1838.4,927.1,771.2,595.9 +2.329049328161863,1.4291214915714474,2.0943951023931953,1148.5,1640.2,1512.9,717.0,623.3,496.0 +2.329039565653681,1.4291009908794565,2.2252947962927703,2259.1,1431.5,1372.7,608.6,520.2,461.4 +2.3290448931382426,1.4291228098937894,2.356194490192345,2199.5,1351.3,1351.8,562.5,470.3,470.7 +2.3290418994763935,1.4291523126511718,2.4870941840919194,2303.0,1373.0,1432.1,565.9,461.6,520.7 +2.329045618185086,1.4291424277324383,2.6179938779914944,2579.8,1469.7,1090.6,624.7,495.9,623.5 +2.329032450100305,1.4291577860130755,2.748893571891069,1841.7,990.3,770.1,770.2,597.8,817.7 +2.3290413489480617,1.4291499707335258,2.8797932657906435,1500.4,764.8,637.3,576.4,849.5,1229.6 +2.3290323976846437,1.4291543764635652,3.010692959690218,1350.4,646.9,588.0,482.7,1700.1,2281.6 +2.328973622032314,1.3288552730606478,0.0,1221.4,592.9,593.0,540.7,2229.2,2228.9 +2.3290023509296485,1.3293267108328446,0.1308996938995747,1290.8,588.1,647.5,543.4,2282.4,2342.1 +2.3289669325139024,1.3293151814940138,0.2617993877991494,1232.3,637.2,764.6,599.0,2527.7,2404.7 +2.328929479333972,1.3292909846000784,0.39269908169872414,768.7,771.2,737.7,740.2,1917.0,1697.9 +2.3288987841269226,1.3292590764500054,0.5235987755982988,625.0,739.2,611.5,1068.0,1526.3,1398.6 +2.328887887516378,1.329235003147987,0.6544984694978736,566.0,624.2,565.2,2158.8,1328.7,1269.5 +2.328875746500554,1.3291879151774686,0.7853981633974483,563.1,570.9,570.2,2198.6,1251.8,1251.1 +2.3288769413267705,1.3291770896808437,0.916297857297023,608.8,564.9,623.8,2259.1,1269.3,1328.0 +2.3288891930572064,1.3291385866505276,1.0471975511965976,716.8,611.4,739.0,2514.6,1397.4,1093.4 +2.3289146642556386,1.3290951669586122,1.1780972450961724,740.0,736.9,956.1,1865.0,993.0,772.1 +2.3289093105065923,1.3290990859585297,1.3089969389957472,599.0,1046.9,1426.3,1478.7,765.4,637.7 +2.328921333017201,1.32909256596372,1.4398966328953218,542.9,2100.5,2281.1,1289.3,645.9,587.5 +2.3289924311815295,1.3290753780332043,1.5707963267948966,540.7,2229.1,2228.7,1221.3,593.3,593.0 +2.3289842777581486,1.3290739743562963,1.7016960206944713,585.4,2280.0,2338.5,1246.7,588.1,646.6 +2.3289794076374495,1.3290711853661357,1.832595714594046,691.8,2529.6,2403.0,1385.7,636.9,764.6 +2.3290341765918225,1.3291054571200616,1.9634954084936205,900.9,1916.4,1697.5,927.3,771.2,737.1 +2.329051158042382,1.3291244565333455,2.0943951023931953,1347.7,1524.4,1397.5,717.0,738.9,611.5 +2.3290416442823516,1.3291043959769568,2.2252947962927703,2259.0,1328.0,1269.4,608.7,623.8,564.9 +2.329047082885779,1.3291266760978333,2.356194490192345,2199.8,1251.0,1251.7,562.4,570.3,570.8 +2.3290440689067156,1.3291566209879502,2.4870941840919194,2303.0,1269.5,1328.5,566.0,565.1,624.2 +2.3290476594665765,1.3291471204240097,2.6179938779914944,2424.4,1398.9,1090.6,624.7,611.4,739.1 +2.3290342751300654,1.3291627898760416,2.748893571891069,1700.2,990.3,770.2,770.1,739.2,959.2 +2.3290429066492813,1.3291551936989747,2.8797932657906435,1384.6,764.7,637.2,691.9,1049.0,1429.0 +2.329033663072493,1.3291597258395527,3.010692959690218,1246.8,646.8,588.1,586.2,2087.2,2281.3 +2.32897455186059,1.2288603660972959,0.0,1121.4,593.1,593.0,640.7,2228.7,2229.1 +2.32900279730015,1.2293283942862414,0.1308996938995747,1187.5,588.1,647.3,647.0,2282.3,2342.0 +2.32896708732346,1.2293167713351982,0.2617993877991494,1116.6,637.2,764.8,714.7,2528.4,2205.6 +2.3289294238394826,1.229292439650511,0.39269908169872414,768.6,771.3,878.9,881.7,1776.0,1557.1 +2.3288985794787496,1.2292603692581425,0.5235987755982988,625.1,854.8,727.0,1267.2,1410.7,1283.0 +2.3288875899960004,1.2292361211940273,0.6544984694978736,566.1,727.7,668.6,2303.1,1225.1,1165.9 +2.328875406210486,1.2291888536066904,0.7853981633974483,563.1,670.9,670.2,2199.4,1151.8,1151.1 +2.3288766046651768,1.229177858945937,0.916297857297023,608.7,668.4,727.3,2259.4,1165.6,1224.6 +2.3288888996461443,1.2291392039846176,1.0471975511965976,716.7,727.0,854.4,2506.1,1281.7,1138.1 +2.328914445138388,1.2290956573685645,1.1780972450961724,913.1,878.1,1097.0,1723.8,992.9,772.2 +2.3289091866101863,1.229099480971954,1.3089969389957472,714.7,1246.4,1625.8,1362.6,765.5,637.8 +2.328921317802893,1.2290928979381461,1.4398966328953218,646.4,2338.5,2281.5,1185.7,646.1,587.4 +2.3289925302437857,1.2290756783308032,1.5707963267948966,640.8,2229.2,2228.9,1121.3,593.3,593.1 +2.328984485302118,1.2290742735760318,1.7016960206944713,688.8,2280.0,2338.4,1143.1,588.2,646.6 +2.328979712852878,1.2290715106026118,1.832595714594046,807.7,2529.5,2203.5,1270.2,636.9,764.4 +2.3290345642832406,1.2291058303196274,1.9634954084936205,1042.5,1775.6,1556.3,927.1,771.2,878.2 +2.3290516073984753,1.2291248924602516,2.0943951023931953,1547.2,1409.1,1281.6,717.2,854.3,727.1 +2.3290421323936443,1.2291049031671353,2.2252947962927703,2259.2,1224.7,1165.8,608.6,727.0,668.3 +2.32904758759185,1.2291272574638237,2.356194490192345,2199.6,1151.2,1151.7,562.5,670.2,670.8 +2.329044569783136,1.2291572725909221,2.4870941840919194,2303.1,1165.8,1224.9,566.0,668.7,727.7 +2.3290481387047515,1.2291478332217898,2.6179938779914944,2225.6,1283.0,1165.2,624.6,727.1,854.6 +2.3290347200162906,1.2291635514971373,2.748893571891069,1558.8,990.4,770.3,770.2,880.7,1100.6 +2.329043308622522,1.2291559897723863,2.8797932657906435,1269.4,764.7,637.3,807.4,1248.7,1628.7 +2.3290340186089726,1.2291605417365106,3.010692959690218,1143.6,646.7,587.9,689.6,2340.2,2280.8 +2.3289748535556862,1.1288611419390184,0.0,1021.2,593.1,592.9,740.6,2229.1,2229.0 +2.329003018313051,1.1293290453745501,0.1308996938995747,1083.7,588.0,647.5,750.6,2282.3,2341.8 +2.328967215817883,1.1293173927746176,0.2617993877991494,1114.1,637.2,764.7,830.1,2385.5,2005.8 +2.328929473260939,1.1292930108326995,0.39269908169872414,768.8,771.3,991.9,1023.3,1634.6,1415.6 +2.3288985688228965,1.12926087591708,0.5235987755982988,624.9,970.4,842.8,1466.6,1295.0,1167.3 +2.328887541139997,1.1292365568695897,0.6544984694978736,566.1,831.3,772.3,2302.7,1121.5,1062.2 +2.328875339010926,1.1291892152752803,0.7853981633974483,563.1,770.8,770.2,2199.0,1051.8,1050.9 +2.3288765385973424,1.129178150807733,0.916297857297023,608.8,771.9,830.9,2259.4,1062.2,1121.0 +2.328888851133716,1.1291394329585698,1.0471975511965976,716.7,842.6,969.8,2306.5,1166.5,1152.8 +2.328914426982264,1.1290958332825036,1.1780972450961724,928.2,1019.2,1238.2,1581.9,993.0,772.1 +2.328909207849138,1.129099617156972,1.3089969389957472,830.2,1445.7,1825.1,1247.2,765.4,637.9 +2.3289213841929652,1.1290930082410933,1.4398966328953218,750.0,2339.3,2280.8,1082.3,645.9,587.4 +2.328992644069699,1.1290757751772875,1.5707963267948966,740.7,2229.1,2229.0,1021.3,593.3,593.0 +2.3289846442187354,1.1290743700671086,1.7016960206944713,792.3,2280.0,2338.5,1039.7,588.2,646.5 +2.3289799121807326,1.129071618559396,1.832595714594046,922.9,2383.9,2004.2,1154.5,636.9,764.7 +2.3290347976581107,1.129105958447735,1.9634954084936205,1184.3,1634.3,1415.2,927.2,771.2,992.0 +2.3290518661531983,1.129125046648793,2.0943951023931953,1747.0,1293.7,1166.4,717.1,969.8,842.4 +2.3290424066573987,1.12910508725415,2.2252947962927703,2259.7,1121.3,1062.4,608.6,830.7,772.0 +2.3290478681446882,1.1291274724281517,2.356194490192345,2199.8,1051.3,1051.8,562.5,770.4,770.7 +2.3290448485063258,1.1291575163478893,2.4870941840919194,2303.0,1062.3,1121.6,566.1,772.1,831.2 +2.32904840794442,1.129148102158953,2.6179938779914944,2025.7,1167.5,1154.2,624.8,842.6,970.4 +2.3290349752272963,1.1291638401734623,2.748893571891069,1417.4,990.1,770.3,770.3,1022.1,1242.2 +2.3290435460408903,1.1291562924464102,2.8797932657906435,1153.9,764.6,637.3,923.1,1448.3,1827.6 +2.329034236999501,1.1291608524670576,3.010692959690218,1040.0,646.9,588.0,793.2,2340.1,2281.0 +2.2290277031889936,1.8292535108097572,0.0,1721.6,693.0,693.0,40.8,2129.4,2129.2 +2.2289993337209304,1.82853960978697,0.1308996938995747,1808.6,691.8,149.1,25.6,2178.9,2238.4 +2.2290479434519286,1.8285554484353215,0.2617993877991494,1313.8,431.1,51.4,21.4,2412.5,2539.8 +2.2291007872497075,1.8285895739490532,0.39269908169872414,1053.7,251.2,31.9,32.1,2622.8,2403.5 +2.2291425876720727,1.8286372881496822,0.5235987755982988,740.7,161.3,33.6,72.4,2104.4,1976.6 +2.2291787203852014,1.8287028425710443,0.6544984694978736,669.8,106.7,47.6,231.9,1845.8,1786.8 +2.229187859977129,1.828748938612085,0.7853981633974483,663.1,71.1,70.5,2099.2,1751.7,1750.9 +2.2291863870597095,1.8288262557529997,0.916297857297023,233.2,47.7,106.5,2155.5,1786.7,1845.2 +2.2291752626605574,1.828866762848072,1.0471975511965976,73.7,34.2,161.5,2398.5,1703.5,1293.4 +2.2291611653599075,1.8288887723115885,1.1780972450961724,32.1,31.9,250.9,2573.4,1134.9,1086.9 +2.2291057482270893,1.828941711833091,1.3089969389957472,21.4,51.4,430.6,2056.0,881.0,753.5 +2.229061050302705,1.828967584662345,1.4398966328953218,26.0,153.1,981.6,1806.1,749.3,691.0 +2.229072743025373,1.8289660825888134,1.5707963267948966,41.2,2129.1,2128.6,1720.7,693.4,693.1 +2.229008437052491,1.828964881814243,1.7016960206944713,68.5,2177.0,2235.3,1763.7,691.7,153.2 +2.2289530007213534,1.828948842880839,1.832595714594046,114.3,2413.3,2541.5,1717.5,430.7,51.4 +2.2289650439260527,1.8289584117043844,1.9634954084936205,192.8,2622.0,2402.5,1068.3,251.0,31.9 +2.228949953682525,1.8289450553382278,2.0943951023931953,350.2,2101.9,1974.6,832.6,161.5,34.2 +2.2289197973242483,1.8288885091711258,2.2252947962927703,832.0,1845.1,1786.7,711.9,106.5,47.7 +2.2289158589351366,1.8288725980435485,2.356194490192345,2099.3,1750.5,1751.4,662.5,70.6,71.1 +2.2289141502420615,1.8286887216297711,2.4870941840919194,2199.8,1787.0,1846.0,669.6,47.7,106.8 +2.228932577742946,1.828804621690298,2.6179938779914944,2494.1,1705.6,1290.1,348.2,33.7,161.4 +2.228929344370627,1.8288059553135239,2.748893571891069,2407.2,1131.5,1084.3,192.5,32.5,252.5 +2.2289578195634423,1.8287816211501786,2.8797932657906435,1962.4,880.1,752.8,114.4,52.1,431.9 +2.2289732471088013,1.8287748250672031,3.010692959690218,1764.1,750.3,691.4,68.9,152.4,975.2 +2.2289442787515323,1.7284988390574403,0.0,1621.1,693.0,693.0,140.9,2128.8,2129.1 +2.2289929362307843,1.729264751695407,0.1308996938995747,1705.1,691.6,532.8,129.1,2179.1,2238.5 +2.228968749529302,1.7292568534669397,0.2617993877991494,1313.5,630.3,250.6,136.8,2412.4,2539.9 +2.228938959730801,1.7292376115438544,0.39269908169872414,909.9,392.2,172.9,173.5,2482.1,2263.0 +2.2289135384004837,1.7292115170853999,0.5235987755982988,740.7,276.7,149.0,271.3,1988.9,1861.3 +2.228905896194581,1.7291936568218491,0.6544984694978736,669.7,210.1,151.0,616.6,1742.8,1683.6 +2.228895192942221,1.7291528927588256,0.7853981633974483,663.0,170.9,170.3,2098.9,1651.9,1651.3 +2.2288962214570742,1.7291480208732628,0.916297857297023,704.7,150.9,209.7,2155.8,1683.1,1742.1 +2.228906918258272,1.7291148488250823,1.0471975511965976,272.7,149.4,276.7,2398.9,1718.5,1293.0 +2.228929742018773,1.7290758368045163,1.1780972450961724,173.3,172.5,391.6,2432.3,1134.6,968.0 +2.2289210401835176,1.7290830792776826,1.3089969389957472,136.6,250.0,629.3,1941.2,1022.1,753.3 +2.2289292603062942,1.7290787852134881,1.4398966328953218,129.1,541.4,1370.1,1703.2,749.2,691.0 +2.2289963594021,1.729062677162615,1.5707963267948966,140.8,2129.1,2128.6,1621.4,693.3,693.1 +2.2289844157666185,1.7290613182198007,1.7016960206944713,171.5,2176.8,2235.3,1660.5,691.7,541.4 +2.2289761172900233,1.7290576764561645,1.832595714594046,229.4,2414.0,2541.2,1602.2,629.3,250.0 +2.229027983309012,1.7290902953602623,1.9634954084936205,334.0,2481.0,2262.0,1068.1,391.7,172.5 +2.2290427853002184,1.7291071057273288,2.0943951023931953,549.1,1987.0,1859.3,832.7,276.6,149.4 +2.2290318609538478,1.7290845814057922,2.2252947962927703,1217.9,1742.4,1683.4,712.1,209.7,150.9 +2.2290366608125,1.7291042744699405,2.356194490192345,2099.4,1651.5,1651.7,662.6,170.3,170.8 +2.229033752475293,1.7291317295123336,2.4870941840919194,2199.2,1683.7,1742.7,669.6,150.9,210.0 +2.2290380508755216,1.7291200645686882,2.6179938779914944,2493.6,1720.1,1290.0,546.9,149.0,276.7 +2.229025883105277,1.7291339747384793,2.748893571891069,2265.8,1131.5,911.7,333.6,173.6,393.5 +2.22903601619468,1.7291251403081178,2.8797932657906435,1847.0,1021.3,752.8,229.7,251.1,630.9 +2.2290284197319363,1.7291289579471782,3.010692959690218,1660.9,750.4,691.5,172.2,538.6,1361.4 +2.2289711954443545,1.6288310497971812,0.0,1521.1,693.0,692.9,240.7,2129.0,2128.9 +2.2290019051960996,1.6293228340074948,0.1308996938995747,1601.6,691.6,750.9,232.6,2178.6,2238.5 +2.2289673196553275,1.6293115732200905,0.2617993877991494,1313.7,752.7,450.0,252.4,2412.4,2539.9 +2.2289303650887087,1.6292877003564241,0.39269908169872414,909.8,533.4,314.1,315.1,2341.1,2121.8 +2.22889998975871,1.6292561486286956,0.5235987755982988,740.6,392.3,264.6,470.5,1873.2,1745.4 +2.2288892857436324,1.6292324471306066,0.6544984694978736,669.6,313.6,254.5,1002.2,1639.0,1579.9 +2.228877225988575,1.629361656202915,0.7853981633974483,663.0,270.8,270.3,2099.0,1551.7,1551.1 +2.228878701522014,1.6291653643647377,0.916297857297023,712.4,254.4,313.2,2155.4,1579.6,1638.5 +2.228888895539024,1.6291335095472679,1.0471975511965976,472.3,264.9,392.1,2399.2,1673.2,1293.0 +2.2289134531587913,1.6290915600546492,1.1780972450961724,315.0,313.6,532.6,2290.5,1134.9,913.7 +2.2289080126021066,1.6290955677001595,1.3089969389957472,252.2,449.2,828.6,1825.2,881.1,753.5 +2.2289203653935425,1.629088883349123,1.4398966328953218,232.5,931.1,1759.5,1599.3,749.3,691.0 +2.228991956908195,1.629071590020005,1.5707963267948966,240.7,2128.9,2128.8,1521.3,693.2,693.0 +2.2289843099217577,1.6290702136170534,1.7016960206944713,275.0,2176.3,2235.4,1557.0,691.7,750.0 +2.228979899862741,1.629067578811929,1.832595714594046,345.0,2413.4,2541.2,1587.4,752.6,449.3 +2.2290350525352154,1.629102102920767,1.9634954084936205,475.6,2340.0,2120.9,1068.6,532.8,313.7 +2.229052316244227,1.629121415717525,2.0943951023931953,748.7,1870.9,1743.7,832.6,392.2,264.9 +2.2290429776657916,1.6291017004729313,2.2252947962927703,1605.0,1638.3,1580.0,712.1,313.2,254.4 +2.229048492651412,1.629124333320752,2.356194490192345,2099.7,1551.1,1551.8,662.4,270.2,270.8 +2.2290454670613467,1.6291546106893358,2.4870941840919194,2199.5,1580.2,1639.0,669.6,254.5,313.6 +2.2290489687562167,1.6291454041359472,2.6179938779914944,2493.5,1669.2,1289.9,740.3,264.6,392.3 +2.22903543993292,1.6291613168314534,2.748893571891069,2124.4,1131.7,911.7,474.9,315.0,535.0 +2.229043884757994,1.6291539055357704,2.8797932657906435,1731.6,880.2,752.8,345.2,450.5,830.3 +2.2290344313464074,1.629158561318319,3.010692959690218,1557.8,750.4,691.4,275.6,925.5,1748.4 +2.2289750581743872,1.528859010773415,0.0,1421.5,693.1,693.0,340.6,2129.0,2129.1 +2.229003198534312,1.5293296699437824,0.1308996938995747,1497.7,691.7,750.9,336.2,2179.0,2238.4 +2.228967307940483,1.5293179892313093,0.2617993877991494,1463.4,752.7,649.5,368.0,2412.2,2540.3 +2.2289294858034228,1.529293556831863,0.39269908169872414,909.9,674.6,455.3,456.9,2200.0,1980.2 +2.228898519887811,1.5292613559240114,0.5235987755982988,740.7,508.0,380.2,669.7,1757.6,1629.7 +2.228909741348812,1.529281584094345,0.6544984694978736,669.6,417.0,358.0,1387.6,1535.7,1476.4 +2.2288899290889157,1.5292006839441024,0.7853981633974483,663.1,370.8,370.2,2099.1,1451.6,1450.9 +2.2288914055860394,1.5291817155009808,0.916297857297023,712.4,357.9,416.7,2155.4,1476.5,1535.0 +2.228903613061861,1.5291433888396262,1.0471975511965976,672.0,380.4,507.7,2399.3,1628.2,1292.9 +2.2289276733179704,1.5291022284334734,1.1780972450961724,456.7,454.7,673.8,2148.5,1134.6,913.8 +2.2289199632455645,1.5291083550523932,1.3089969389957472,367.7,648.5,1027.6,1709.8,880.9,753.3 +2.2289291062547543,1.529103372771825,1.4398966328953218,336.0,1320.8,2149.4,1496.1,749.3,690.9 +2.2289971379187037,1.5290868840254384,1.5707963267948966,340.7,2128.9,2128.6,1421.3,693.4,693.0 +2.228986096847451,1.5290853817866015,1.7016960206944713,378.4,2176.6,2235.0,1453.9,691.6,750.0 +2.228978656465325,1.5290818131633754,1.832595714594046,460.7,2413.9,2541.0,1587.3,752.6,648.5 +2.229031285700871,1.5291147423647575,1.9634954084936205,617.3,2198.9,1979.6,1068.3,673.9,454.6 +2.229046685533962,1.529132041978008,2.0943951023931953,948.5,1755.6,1628.1,832.5,507.8,380.4 +2.2290591933023043,1.5291554029962224,2.2252947962927703,1992.5,1535.3,1476.3,712.0,416.6,357.9 +2.2290563963002272,1.5291417319088787,2.356194490192345,2099.4,1451.4,1451.7,662.5,370.3,370.8 +2.2290537801148975,1.5291619533089433,2.4870941840919194,2199.5,1476.3,1535.4,669.7,358.0,417.0 +2.229057717797609,1.5291513392105334,2.6179938779914944,2579.8,1630.3,1290.3,740.2,380.2,507.8 +2.229043547407203,1.5291682651046525,2.748893571891069,1983.1,1131.7,911.6,616.5,456.4,676.4 +2.229050588216731,1.5291621506822715,2.8797932657906435,1615.9,880.4,752.8,460.7,650.1,1030.0 +2.229039334370532,1.529167752002119,3.010692959690218,1453.9,750.2,691.5,379.2,1313.2,2135.9 +2.2289776926498237,1.4288664546283598,0.0,1321.3,692.9,692.9,440.6,2128.7,2128.9 +2.2290542165870777,1.428864017389774,0.1308996938995747,1394.7,691.5,751.0,439.7,2179.0,2238.4 +2.2290657449097306,1.428866524001867,0.2617993877991494,1347.9,752.8,880.3,483.4,2412.7,2539.8 +2.2291103628354807,1.4288934638426007,0.39269908169872414,909.8,815.5,596.4,598.3,2058.8,1839.0 +2.2291521161794097,1.4289390849546442,0.5235987755982988,740.6,623.5,495.7,868.8,1642.4,1514.3 +2.2291897540725336,1.4290053732525112,0.6544984694978736,669.7,520.6,461.5,1773.0,1431.9,1373.1 +2.2291999000746787,1.4290535928716666,0.7853981633974483,663.2,470.8,470.3,2098.8,1351.8,1351.3 +2.229198340788151,1.4291333913624875,0.916297857297023,712.6,461.4,520.2,2155.8,1372.6,1431.5 +2.229186005714393,1.4291760956018207,1.0471975511965976,832.5,495.9,623.3,2398.9,1512.9,1394.5 +2.229169855408798,1.4291995216239115,1.1780972450961724,598.5,595.9,815.0,2007.1,1134.8,914.1 +2.229112012809423,1.429252835952681,1.3089969389957472,483.5,847.8,1227.3,1594.4,881.2,845.2 +2.2290649634981543,1.4292780470512878,1.4398966328953218,439.5,1710.7,2177.2,1392.4,749.4,691.0 +2.2290747917048246,1.429275041886088,1.5707963267948966,440.9,2128.7,2128.5,1321.2,693.3,693.1 +2.229009400503051,1.4292718642462816,1.7016960206944713,482.0,2176.6,2235.1,1349.9,691.6,750.1 +2.228953695835085,1.4292537903916573,1.832595714594046,576.3,2413.9,2541.4,1501.2,752.4,880.2 +2.2289661457550096,1.429261649588415,1.9634954084936205,759.1,2057.2,1838.5,1068.5,815.1,596.0 +2.2289518327296673,1.4292471456698606,2.0943951023931953,1148.5,1640.0,1512.9,832.6,623.3,495.9 +2.228922465171538,1.4291900550202532,2.2252947962927703,2155.9,1431.8,1372.5,711.9,520.3,461.4 +2.228919007576879,1.429174084608999,2.356194490192345,2099.8,1351.1,1351.9,662.4,470.2,470.9 +2.2289172727650084,1.4291675610823567,2.4870941840919194,2199.5,1373.3,1432.2,669.6,461.6,520.7 +2.2289306047784936,1.4291260382490445,2.6179938779914944,2493.5,1514.2,1396.4,740.1,495.8,623.4 +2.2289337684737287,1.4291152457164633,2.748893571891069,1841.5,1131.7,911.6,757.9,597.7,818.0 +2.2289633250690146,1.4290880666727719,2.8797932657906435,1500.5,880.0,752.8,576.4,849.6,1229.3 +2.228977479767549,1.4290800803062171,3.010692959690218,1350.5,750.3,691.4,482.7,1699.5,2177.8 +2.2289466140148555,1.3288019008289087,0.0,1221.6,692.9,693.0,540.6,2128.7,2129.0 +2.2289949046068425,1.3293444224699242,0.1308996938995747,1290.6,691.7,750.8,543.3,2179.0,2238.1 +2.2289618595902967,1.3293336039998422,0.2617993877991494,1313.5,752.8,880.2,599.1,2497.1,2404.8 +2.2289231902152125,1.3293086091912518,0.39269908169872414,910.0,912.7,737.7,740.1,1917.5,1698.1 +2.228890770001104,1.329274810125949,0.5235987755982988,740.7,739.0,611.5,1068.1,1526.5,1398.7 +2.2288706341721802,1.3292341439950026,0.6544984694978736,669.6,624.1,565.1,2158.3,1328.4,1269.5 +2.228860385019584,1.3291950516774964,0.7853981633974483,663.1,570.8,570.2,2098.8,1251.8,1251.2 +2.2288615744761864,1.3291840838228133,0.916297857297023,712.3,564.9,623.6,2155.7,1269.3,1328.0 +2.22887459736364,1.3291430063732292,1.0471975511965976,832.4,611.5,738.9,2449.8,1397.2,1383.4 +2.228901796837724,1.3290967580354567,1.1780972450961724,740.1,737.1,956.0,1865.3,1134.6,913.8 +2.228898819705384,1.3290984051470414,1.3089969389957472,599.1,1047.1,1426.1,1478.4,881.0,753.3 +2.2289135988693127,1.3290903797840898,1.4398966328953218,542.9,2099.6,2177.4,1289.2,749.3,690.9 +2.2289875900990404,1.3290724691362579,1.5707963267948966,540.8,2129.0,2128.7,1221.5,693.3,693.1 +2.228982164210699,1.3290711048264239,1.7016960206944713,585.3,2176.5,2235.0,1246.9,691.6,750.1 +2.228979731133581,1.3290690188968886,1.832595714594046,691.8,2495.6,2403.0,1385.6,752.6,880.1 +2.2290365471335316,1.3291045196973257,1.9634954084936205,900.9,1916.4,1697.7,1068.4,912.8,737.1 +2.2290550594114182,1.32912509468788,2.0943951023931953,1347.8,1524.7,1397.2,832.6,738.7,611.4 +2.2290465190019675,1.3291068080702373,2.2252947962927703,2156.0,1328.1,1269.3,712.2,623.6,564.9 +2.2290523985626,1.3291309310262238,2.356194490192345,2099.9,1251.4,1251.7,662.4,570.2,570.8 +2.2290493356747394,1.329162629872834,2.4870941840919194,2199.5,1269.5,1328.3,669.6,565.0,624.1 +2.229052443988021,1.3291546778309595,2.6179938779914944,2425.2,1398.7,1385.6,740.3,611.5,739.2 +2.2290382591647937,1.329171611789571,2.748893571891069,1700.4,1131.9,911.6,911.7,739.3,959.3 +2.2290458616700186,1.3291649433979456,2.8797932657906435,1384.8,880.3,752.7,692.1,1049.0,1428.9 +2.229035476041353,1.3291700507588327,3.010692959690218,1247.3,750.4,691.6,586.2,2087.1,2177.9 +2.228974986365113,1.2288696669068035,0.0,1121.3,693.0,693.0,640.6,2128.9,2129.1 +2.2290033026660345,1.2293324432572739,0.1308996938995747,1187.2,691.7,750.9,646.9,2179.2,2238.4 +2.228967115048724,1.2293206640665701,0.2617993877991494,1313.8,752.7,880.2,714.6,2412.3,2205.2 +2.228928983006191,1.2292960312891863,0.39269908169872414,909.9,912.8,878.9,881.9,1776.1,1556.9 +2.228897769956328,1.2292635591635326,0.5235987755982988,740.7,854.8,727.0,1267.4,1410.9,1283.0 +2.2288865431212708,1.2292388625762176,0.6544984694978736,669.6,727.7,668.6,2199.3,1225.0,1165.8 +2.2288742494483205,1.2291911281842651,0.7853981633974483,663.1,670.8,670.3,2099.2,1151.8,1151.2 +2.22887545901809,1.2291796924574383,0.916297857297023,712.4,668.4,727.2,2155.5,1165.7,1224.6 +2.228887868700067,1.2291406413965942,1.0471975511965976,832.2,727.0,854.0,2399.2,1282.1,1292.9 +2.228913609797325,1.2290967643645585,1.1780972450961724,881.7,878.1,1097.5,1723.5,1134.8,913.9 +2.2289086011121237,1.2291003403992748,1.3089969389957472,714.8,1246.2,1625.6,1363.0,880.9,753.4 +2.228921016608398,1.229093594541307,1.4398966328953218,646.4,2236.3,2177.6,1185.7,749.3,690.9 +2.2289925272199373,1.2290762936667048,1.5707963267948966,640.8,2128.6,2129.1,1121.3,693.3,693.2 +2.228984764841926,1.2290748871385535,1.7016960206944713,688.8,2176.9,2235.1,1143.4,691.6,750.1 +2.2289802465000523,1.2290721925316168,1.832595714594046,807.4,2413.8,2203.5,1270.2,752.5,880.2 +2.2290353125395566,1.2291066370822228,1.9634954084936205,1042.6,1775.5,1556.4,1068.3,912.8,878.2 +2.229052516444292,1.2291258620734107,2.0943951023931953,1547.3,1408.9,1281.9,832.6,854.2,727.0 +2.229043143042364,1.2291060578281199,2.2252947962927703,2156.0,1224.6,1166.0,712.1,727.2,668.5 +2.2290486427112244,1.2291286049159051,2.356194490192345,2099.5,1151.0,1151.7,662.5,670.3,670.8 +2.2290456166372423,1.2291588029927163,2.4870941840919194,2199.2,1166.1,1225.0,669.6,668.7,727.7 +2.229049130880507,1.2291495237273389,2.6179938779914944,2225.1,1283.2,1290.1,740.2,727.1,854.6 +2.2290356242877514,1.2291653704681398,2.748893571891069,1558.8,1131.6,911.6,911.7,880.4,1100.6 +2.2290441020215,1.2291579002424187,2.8797932657906435,1269.4,880.2,752.8,807.4,1248.6,1628.3 +2.2290346912563774,1.2291625057295081,3.010692959690218,1143.3,750.4,691.6,689.7,2236.5,2177.9 +2.228975384957117,1.128863001517404,0.0,1021.4,692.9,693.0,740.5,2128.8,2129.2 +2.229003446687025,1.129331775953782,0.1308996938995747,1083.6,691.7,751.1,750.6,2179.2,2238.2 +2.2289673000269032,1.1293200118729743,0.2617993877991494,1246.7,752.8,880.2,830.2,2385.9,2005.9 +2.2289292338625817,1.129295422507754,0.39269908169872414,910.0,912.9,1020.0,1023.5,1634.9,1415.6 +2.2288980776257494,1.1292630138512583,0.5235987755982988,740.6,970.4,842.7,1466.6,1295.2,1167.5 +2.228886888334323,1.1292383902917575,0.6544984694978736,669.6,831.5,772.2,2199.9,1121.4,1062.3 +2.2288746111632536,1.12919073195992,0.7853981633974483,663.0,770.8,770.3,2099.1,1051.8,1051.2 +2.2288758179304975,1.129179368271854,0.916297857297023,712.3,771.9,830.8,2155.3,1062.3,1121.3 +2.228888207977035,1.1291403816229193,1.0471975511965976,832.3,842.5,969.8,2306.5,1166.2,1293.0 +2.228913916299647,1.1290965575426974,1.1780972450961724,1054.7,1019.1,1238.3,1581.6,1243.1,913.8 +2.228908866626378,1.1291001732978956,1.3089969389957472,830.2,1445.4,1825.1,1247.6,881.1,753.4 +2.228921235924753,1.1290934539115067,1.4398966328953218,749.7,2235.6,2177.2,1082.2,749.3,691.0 +2.228992698195578,1.1290761656482045,1.5707963267948966,740.6,2129.1,2128.9,1021.3,693.2,693.0 +2.228984890152916,1.1290747594805164,1.7016960206944713,792.3,2177.1,2234.8,1039.8,691.6,750.0 +2.2289803305084313,1.1290720547115942,1.832595714594046,923.1,2383.8,2004.8,1154.5,752.6,880.2 +2.229035361477554,1.1291064795718495,1.9634954084936205,1184.3,1634.1,1415.4,1089.1,913.0,1019.2 +2.2290525388406404,1.1291256784667096,2.0943951023931953,1747.3,1293.5,1166.2,832.6,970.0,842.5 +2.229043147892357,1.1291058448371216,2.2252947962927703,2155.8,1121.1,1062.3,712.0,830.9,771.9 +2.229048639141751,1.129128360868589,2.356194490192345,2099.4,1051.2,1051.6,662.4,770.2,770.9 +2.2290456136030334,1.1291585287558368,2.4870941840919194,2199.3,1062.6,1121.4,669.7,772.2,831.3 +2.2290491356452313,1.1291492230017748,2.6179938779914944,2026.2,1167.6,1289.9,740.2,842.7,970.4 +2.2290356432871636,1.1291650478832331,2.748893571891069,1417.5,1245.1,911.6,911.7,1022.2,1242.1 +2.229044138910914,1.1291575620247836,2.8797932657906435,1153.6,880.3,752.8,923.0,1448.1,1827.8 +2.229034748110017,1.1291621582586933,3.010692959690218,1039.9,750.4,691.5,793.2,2236.6,2177.8 +2.1290281150717925,1.8292545925963617,0.0,1721.2,793.1,793.0,40.8,2029.0,2029.0 +2.128999510331458,1.828539841434495,0.1308996938995747,1808.6,795.3,149.2,25.6,2075.6,2135.0 +2.1290480510302037,1.8285556583822336,0.2617993877991494,1513.0,431.0,51.4,21.4,2296.9,2424.9 +2.129100858723943,1.8285897611112065,0.39269908169872414,1051.4,251.2,31.9,32.1,2622.5,2403.4 +2.1291426376151996,1.8286374522756057,0.5235987755982988,856.3,161.3,33.6,72.4,2104.1,1976.6 +2.129178757406958,1.8287029834300743,0.6544984694978736,773.3,106.7,47.6,231.9,1846.2,1786.9 +2.129187891155943,1.828749056309132,0.7853981633974483,763.3,71.1,70.5,1998.9,1751.5,1751.0 +2.1291864181324454,1.8288263514965186,0.916297857297023,233.2,47.7,106.5,2052.0,1786.6,1845.7 +2.1291752988080166,1.8288668387482945,1.0471975511965976,73.7,34.2,161.5,2283.1,1873.1,1493.0 +2.1291612108833955,1.8288888318161813,1.1780972450961724,32.1,31.9,250.9,2573.2,1276.4,1108.9 +2.1291058058331296,1.8289417587524701,1.3089969389957472,21.4,51.4,430.6,2056.3,996.6,869.0 +2.1290611218339204,1.8289676228969802,1.4398966328953218,26.0,153.2,981.8,1806.1,852.8,794.5 +2.1290728294090626,1.8289661168559155,1.5707963267948966,41.1,2029.0,2028.6,1720.8,793.2,793.2 +2.1290085375285352,1.8289649160541606,1.7016960206944713,68.4,2073.5,2132.0,1763.7,795.0,153.2 +2.1289531139255913,1.8289488803441352,1.832595714594046,114.2,2298.1,2426.1,1786.4,430.6,51.4 +2.128965167705946,1.8289584556521779,1.9634954084936205,192.8,2622.0,2402.3,1209.5,251.0,31.9 +2.1289500850674736,1.8289451078795211,2.0943951023931953,350.2,2101.8,1974.7,948.1,161.5,34.2 +2.1289199333909696,1.8288885710182554,2.2252947962927703,831.8,1845.1,1786.8,815.4,106.5,47.7 +2.1289159967442712,1.8288726694418955,2.356194490192345,1999.7,1750.8,1751.2,762.4,70.6,71.1 +2.128914286916005,1.8288660098274714,2.4870941840919194,2096.0,1786.8,1845.7,773.1,47.7,106.8 +2.1289281551403962,1.8288244840497137,2.6179938779914944,2377.9,1868.3,1489.2,348.2,33.7,161.4 +2.1289322158313984,1.828814092876532,2.748893571891069,2406.7,1273.1,1053.1,192.5,32.5,252.5 +2.128962736949951,1.828787876397414,2.8797932657906435,1962.2,995.9,868.4,114.4,52.1,431.9 +2.128977603423634,1.8287813898257044,3.010692959690218,1764.2,853.9,795.0,68.9,152.4,975.2 +2.1289466619841577,1.7285033874234284,0.0,1621.3,792.9,793.1,140.9,2029.3,2029.2 +2.128993689603528,1.7292629724686863,0.1308996938995747,1705.4,795.2,532.8,129.1,2075.5,2134.5 +2.128969334989121,1.7292550252843482,0.2617993877991494,1513.2,630.3,250.6,136.8,2297.4,2424.6 +2.1289396783158234,1.7292358712044984,0.39269908169872414,1051.0,392.2,172.9,173.6,2482.5,2262.8 +2.128914425645908,1.7292099630508582,0.5235987755982988,856.2,276.7,149.0,271.3,1989.1,1861.1 +2.128906904417486,1.7291923356159835,0.6544984694978736,773.1,210.1,151.0,616.6,1742.5,1684.1 +2.1288962575251986,1.7291518222563118,0.7853981633974483,763.2,170.9,170.3,1998.7,1651.8,1651.2 +2.128897277203922,1.7291471893955912,0.916297857297023,619.5,150.9,209.7,2052.2,1683.3,1742.2 +2.128907908745267,1.729114231827193,1.0471975511965976,272.8,149.4,276.6,2283.5,1859.4,1492.5 +2.128930623594047,1.7290753976452526,1.1780972450961724,173.4,172.5,391.6,2432.0,1276.5,1055.7 +2.128921784325451,1.7290827724678974,1.3089969389957472,136.7,250.0,629.2,1941.1,1064.0,869.1 +2.128929849363236,1.729078564688665,1.4398966328953218,129.1,541.4,1369.8,1703.2,852.8,794.4 +2.1289967868374067,1.729062498694702,1.5707963267948966,140.8,2029.0,2028.8,1621.1,793.4,793.0 +2.1289846907413765,1.7290611396662685,1.7016960206944713,171.5,2072.9,2131.3,1660.6,795.0,541.5 +2.1289762553543574,1.7290574609454654,1.832595714594046,229.5,2297.7,2426.0,1786.6,629.2,249.9 +2.1290280055540465,1.7290900129709408,1.9634954084936205,333.9,2481.3,2262.3,1209.5,391.6,172.6 +2.1290427201078734,1.7291067363689534,2.0943951023931953,549.3,1986.6,1859.4,1087.5,276.7,149.4 +2.1290317392964684,1.7290841133006336,2.2252947962927703,1217.9,1742.1,1683.1,815.6,209.7,150.9 +2.129036512833217,1.7291037028918397,2.356194490192345,1999.4,1651.4,1651.8,762.5,170.3,170.8 +2.1290336063857827,1.729131058781227,2.4870941840919194,2096.0,1683.4,1742.6,773.2,150.9,210.0 +2.129037931601572,1.7291193061744117,2.6179938779914944,2377.8,1861.4,1489.5,546.9,149.0,276.7 +2.129025809513801,1.72913314480512,2.748893571891069,2266.3,1273.2,1053.0,333.6,173.6,393.6 +2.129036001422354,1.7291242584274915,2.8797932657906435,1847.2,995.8,868.4,229.7,251.1,630.8 +2.129028470265976,1.7291280447243278,3.010692959690218,1660.9,853.7,795.0,172.2,538.5,1361.3 +2.12897132436723,1.628830196336692,0.0,1521.4,792.9,793.0,240.7,2029.3,2029.3 +2.1290019998363103,1.6293251083525537,0.1308996938995747,1601.5,795.3,854.5,232.6,2075.6,2134.6 +2.128967137714643,1.6293137576279668,0.2617993877991494,1553.8,868.2,450.0,252.3,2296.9,2424.5 +2.1289299139368683,1.62928971128427,0.39269908169872414,1051.2,533.3,314.0,315.1,2340.7,2121.5 +2.12889932789908,1.6292579286323932,0.5235987755982988,856.2,392.3,264.6,470.4,1873.4,1745.4 +2.1288884882065604,1.6292339691793793,0.6544984694978736,773.3,313.6,254.4,1002.1,1639.4,1580.0 +2.1288763670164648,1.6291869862332107,0.7853981633974483,763.0,270.8,270.3,1998.6,1551.9,1551.1 +2.1288775577717045,1.6291762578638527,0.916297857297023,816.0,254.4,313.1,2052.0,1579.6,1638.5 +2.128889783563081,1.629137840556856,1.0471975511965976,472.3,264.9,392.2,2284.0,1744.0,1625.7 +2.12891521103419,1.6290944887061687,1.1780972450961724,315.0,313.7,532.7,2290.3,1276.6,1055.7 +2.128909804606333,1.6290984605114442,1.3089969389957472,252.3,449.1,828.6,1825.7,996.5,869.0 +2.128921767869015,1.629091979022659,1.4398966328953218,232.5,931.0,1759.7,1599.6,852.8,794.6 +2.128992802823343,1.6290748074830392,1.5707963267948966,240.8,2029.0,2028.6,1521.4,793.2,792.9 +2.1289845894415387,1.629073406279878,1.7016960206944713,275.0,2073.6,2131.7,1557.4,795.0,853.5 +2.128979663504826,1.6290706089097098,1.832595714594046,345.0,2298.0,2425.8,1732.6,868.0,449.2 +2.129034384556333,1.6291048562853878,1.9634954084936205,475.7,2339.7,2120.6,1209.4,532.6,313.6 +2.129056850197154,1.6291277192441544,2.0943951023931953,748.9,1871.1,1743.7,948.1,392.2,264.9 +2.1290451941714856,1.6291036987024536,2.2252947962927703,1605.2,1638.5,1579.7,815.6,313.1,254.4 +2.129050452275123,1.629125201859386,2.356194490192345,1999.7,1551.3,1551.8,762.5,270.3,270.8 +2.1290474291890056,1.6291554853297594,2.4870941840919194,2095.8,1580.2,1639.3,773.2,254.5,313.5 +2.129050828733831,1.6291466109023185,2.6179938779914944,2378.0,1745.7,1627.6,746.0,264.6,392.2 +2.1290370657230033,1.6291628932006257,2.748893571891069,2124.6,1273.1,1053.1,474.9,314.9,534.9 +2.1290451885966397,1.6291557780528008,2.8797932657906435,1731.2,995.8,868.3,345.2,450.6,830.5 +2.1290353659273253,1.6291606262887302,3.010692959690218,1557.4,853.8,795.0,275.7,925.6,1748.7 +2.128975545248375,1.5288607385206643,0.0,1421.5,792.9,793.1,340.7,2029.2,2029.4 +2.128992902379039,1.5288593103309012,0.1308996938995747,1498.2,795.1,854.6,336.0,2075.8,2135.0 +2.129044402348417,1.5288741093946603,0.2617993877991494,1568.2,868.3,649.1,367.7,2297.0,2516.7 +2.1290969377801443,1.5289060547156406,0.39269908169872414,1051.2,674.5,455.1,456.6,2200.0,1980.8 +2.1291381220561054,1.5289511049192472,0.5235987755982988,963.1,507.8,380.2,669.3,1758.0,1630.0 +2.1291739741550284,1.5290140896718376,0.6544984694978736,773.3,417.1,357.9,1387.5,1535.7,1476.7 +2.1291830858187772,1.5290579044063042,0.7853981633974483,763.2,370.8,370.2,1999.0,1451.8,1451.2 +2.129181664502894,1.529133224337855,0.916297857297023,815.9,357.9,416.7,2052.0,1476.2,1535.2 +2.129170577655871,1.529171825991519,1.0471975511965976,672.1,380.5,507.8,2283.4,1628.3,1510.1 +2.1291565541667006,1.5291918516339176,1.1780972450961724,456.8,454.8,673.9,2149.0,1276.8,1055.6 +2.1291013992053887,1.5292426531354975,1.3089969389957472,367.9,648.5,1027.7,1709.7,996.8,1010.2 +2.12905737390275,1.5292662568699569,1.4398966328953218,336.1,1321.1,2073.9,1496.1,853.0,794.4 +2.129070334572623,1.5292625406761067,1.5707963267948966,340.8,2029.1,2029.0,1421.2,793.2,792.9 +2.1290078649281274,1.5292594682194354,1.7016960206944713,378.5,2072.9,2131.8,1453.4,795.0,853.5 +2.1289547495101506,1.529242188761944,1.832595714594046,460.7,2297.6,2514.8,1616.7,868.1,648.5 +2.128969350782699,1.5292514045793493,1.9634954084936205,617.4,2199.0,1979.7,1209.3,673.8,454.7 +2.1289566259143777,1.5292386132265927,2.0943951023931953,948.6,1755.3,1628.2,948.2,507.8,380.5 +2.128928263674392,1.5291834115365694,2.2252947962927703,1992.5,1534.9,1476.1,815.6,416.7,357.9 +2.128925256344004,1.5291693887558029,2.356194490192345,1999.6,1451.1,1451.7,762.4,370.3,370.8 +2.128923458714782,1.5291647202426744,2.4870941840919194,2095.7,1476.7,1535.4,773.1,358.0,417.1 +2.128936299573087,1.5291248284203274,2.6179938779914944,2536.6,1629.9,1511.8,855.8,380.2,508.0 +2.1289386296642805,1.5291153865197606,2.748893571891069,1983.2,1273.1,1053.0,616.4,456.3,676.5 +2.128967128554784,1.5290892128156481,2.8797932657906435,1615.6,995.9,1009.3,460.7,650.1,1029.8 +2.12898009744073,1.5290818760825888,3.010692959690218,1454.0,854.1,795.0,379.1,1312.7,2074.2 +2.128947790899579,1.4288026199292698,0.0,1321.3,793.0,793.0,440.6,2029.2,2028.9 +2.128995211304516,1.4293428313661454,0.1308996938995747,1394.2,795.2,854.5,439.7,2075.4,2134.9 +2.128962135334173,1.4293320061013683,0.2617993877991494,1512.9,868.3,848.9,483.5,2296.8,2424.4 +2.1288824410365828,1.4292850562657393,0.39269908169872414,1050.9,815.7,596.5,598.4,2058.4,1839.1 +2.128871540610162,1.4292743716634875,0.5235987755982988,856.2,623.5,495.8,868.8,1641.9,1514.1 +2.1288624800907,1.4292537764966884,0.6544984694978736,773.2,520.6,461.5,1772.9,1432.1,1372.8 +2.1288494521505275,1.429202907552595,0.7853981633974483,763.2,470.8,470.3,1999.1,1351.9,1351.3 +2.128850831677281,1.4291861501384129,0.916297857297023,815.7,461.3,520.2,2052.1,1372.6,1431.3 +2.128864911488754,1.4291415962574603,1.0471975511965976,871.6,496.0,623.2,2283.6,1512.9,1492.9 +2.128893595933968,1.4290929682767042,1.1780972450961724,598.5,595.9,815.0,2007.1,1276.4,1055.8 +2.1288923602109744,1.4290929802106669,1.3089969389957472,483.4,847.7,1227.0,1594.1,996.7,868.9 +2.1289090463009828,1.4290839334539813,1.4398966328953218,439.4,1710.1,2073.9,1392.8,852.6,794.4 +2.1289849956521505,1.429065573299171,1.5707963267948966,440.7,2029.2,2029.1,1321.2,793.3,793.0 +2.1289813919540577,1.429064269022652,1.7016960206944713,481.8,2073.3,2131.4,1350.1,795.0,853.3 +2.1289840367638666,1.4290626583934496,1.832595714594046,576.2,2298.2,2425.6,1501.3,868.2,847.7 +2.1290403582015642,1.4290978577599738,1.9634954084936205,759.1,2057.8,1838.9,1209.3,814.9,595.9 +2.129059631318579,1.4291192461620157,2.0943951023931953,1148.2,1640.2,1512.8,948.2,623.3,495.9 +2.129051823730435,1.4291023308014905,2.2252947962927703,2052.7,1431.6,1373.0,815.7,520.1,461.4 +2.129058072946233,1.4291280479434316,2.356194490192345,1999.5,1351.3,1351.8,762.5,470.2,470.8 +2.1290549545464605,1.4291613249700839,2.4870941840919194,2095.9,1373.1,1431.9,773.2,461.6,520.6 +2.1290576372658223,1.4291547765731893,2.6179938779914944,2378.0,1514.5,1489.4,855.7,495.7,623.4 +2.1290427258987297,1.4291728768695942,2.748893571891069,1842.1,1273.2,1053.3,757.7,597.7,817.7 +2.129049408204359,1.4291670746351475,2.8797932657906435,1500.4,995.7,868.5,576.4,849.6,1229.3 +2.1290379920914275,1.4291727384321669,3.010692959690218,1350.2,853.9,795.0,482.7,1700.0,2074.0 +2.1289762565215216,1.3288714213841704,0.0,1221.3,792.9,793.0,540.6,2028.7,2029.1 +2.128992277369138,1.3288699027659985,0.1308996938995747,1291.2,795.3,854.4,543.1,2074.9,2134.3 +2.1290427941477303,1.3288843524959604,0.2617993877991494,1477.7,868.3,995.9,599.0,2296.8,2405.5 +2.1290945961002805,1.3289157880734543,0.39269908169872414,1051.3,956.9,737.4,739.8,1917.5,1698.1 +2.1291352584870893,1.3289602257458193,0.5235987755982988,856.4,739.1,611.5,1067.8,1526.5,1398.5 +2.129170800532347,1.3290225632658919,0.6544984694978736,773.2,624.1,565.0,2095.9,1328.5,1269.5 +2.129179774521237,1.32906571746441,0.7853981633974483,763.2,570.9,570.2,1998.7,1251.7,1251.2 +2.1291783841470027,1.3291404280877712,0.916297857297023,816.0,564.9,623.7,2052.3,1269.4,1328.4 +2.129181446482392,1.3291330742841359,1.0471975511965976,947.9,611.5,738.7,2449.7,1397.2,1492.8 +2.129150458092142,1.3291801788172186,1.1780972450961724,740.4,737.0,956.2,1865.4,1276.9,1055.8 +2.1290903004414474,1.3292355938063576,1.3089969389957472,599.1,1047.0,1426.2,1478.5,996.9,869.1 +2.1290472350924063,1.3292586379831317,1.4398966328953218,542.9,2100.1,2074.0,1289.1,853.0,794.4 +2.129063571245624,1.3292540884814712,1.5707963267948966,540.9,2028.9,2028.8,1221.2,793.2,793.0 +2.1290050199103714,1.3292510933683532,1.7016960206944713,585.3,2073.2,2131.6,1246.6,795.1,853.6 +2.1289556345610725,1.329234902691648,1.832595714594046,692.0,2297.8,2403.2,1385.9,868.2,995.9 +2.128973426903549,1.3292460632394536,1.9634954084936205,900.8,1916.2,1697.3,1209.4,956.3,737.2 +2.1289630947336695,1.3292357748087746,2.0943951023931953,1347.7,1524.5,1397.3,948.2,738.9,611.5 +2.128936258507796,1.3291833743649635,2.2252947962927703,2052.4,1328.2,1269.1,815.5,623.7,565.0 +2.1289339410491346,1.3291722588555004,2.356194490192345,1999.7,1251.3,1251.9,762.5,570.4,570.9 +2.1289320571546653,1.3291703627953058,2.4870941840919194,2096.2,1269.4,1328.7,773.1,565.1,624.2 +2.1289613613974825,1.329077508196851,2.6179938779914944,2378.4,1398.5,1489.0,855.9,611.3,739.2 +2.128941411925753,1.329103846245457,2.748893571891069,1700.2,1273.0,1053.1,899.2,739.2,959.2 +2.128994997196923,1.329055744485514,2.8797932657906435,1384.9,995.7,868.4,692.0,1049.0,1428.8 +2.1289798804357947,1.3290632908010642,3.010692959690218,1246.8,853.8,795.0,586.1,2086.3,2074.5 +2.128944056922855,1.2287956228125736,0.0,1121.3,793.0,792.9,640.6,2029.3,2029.2 +2.1289944386970663,1.2293488238663186,0.1308996938995747,1187.4,795.2,854.6,646.9,2075.5,2134.7 +2.128961154352996,1.2293379242590248,0.2617993877991494,1362.2,868.3,995.8,714.8,2296.7,2205.6 +2.1289220305971295,1.2293126347091854,0.39269908169872414,1051.1,1054.5,879.0,881.8,1776.1,1556.8 +2.1288892067419747,1.2292783914558938,0.5235987755982988,856.0,854.9,727.1,1267.2,1410.7,1283.0 +2.1288767821645553,1.2292513979732824,0.6544984694978736,773.1,727.9,668.7,2095.8,1225.0,1165.9 +2.1288639175663593,1.2292011564858938,0.7853981633974483,763.0,670.8,670.1,1998.8,1151.8,1151.2 +2.1288652140638034,1.2291873241571267,0.916297857297023,815.9,668.4,727.2,2052.1,1165.9,1224.6 +2.1288782780166304,1.2291461193706499,1.0471975511965976,947.9,726.9,854.4,2283.9,1281.6,1409.0 +2.1289051112990616,1.2291004500909257,1.1780972450961724,882.0,878.0,1097.2,1723.0,1384.2,1055.5 +2.1289014859584117,1.229102695810032,1.3089969389957472,714.7,1246.3,1625.5,1337.7,996.6,868.9 +2.1289154632015355,1.2290950889604844,1.4398966328953218,646.4,2132.6,2073.8,1185.7,852.9,794.5 +2.1289885994599427,1.2290773631026526,1.5707963267948966,640.8,2028.9,2028.8,1121.2,793.2,792.9 +2.1289823707341826,1.2290759606464796,1.7016960206944713,688.8,2096.1,2131.7,1143.1,795.1,853.6 +2.128979226687308,1.22907364756117,1.832595714594046,807.5,2298.1,2203.9,1270.3,868.2,995.8 +2.1290354546033607,1.2291087673089338,1.9634954084936205,1042.6,1775.6,1556.4,1230.5,1054.5,878.1 +2.129053535406113,1.2291288657333022,2.0943951023931953,1547.4,1409.2,1281.9,948.2,854.2,727.0 +2.1290447235429077,1.229110057623529,2.2252947962927703,2052.7,1224.6,1166.0,815.6,727.0,668.4 +2.1290504829090877,1.2291336455258286,2.356194490192345,1999.7,1151.1,1151.8,762.4,670.3,670.8 +2.129047438758084,1.2291648358050313,2.4870941840919194,2095.6,1165.8,1224.9,773.2,668.7,727.8 +2.129050680221751,1.2291564368512935,2.6179938779914944,2226.0,1282.9,1411.0,855.9,727.0,854.7 +2.129036721220817,1.2291729989509437,2.748893571891069,1558.9,1386.3,1053.0,1053.0,880.7,1100.6 +2.12904460969318,1.2291660511398357,2.8797932657906435,1269.2,996.0,868.4,807.5,1248.5,1628.2 +2.129034546013083,1.2291709740356067,3.010692959690218,1143.4,853.7,795.1,689.9,2133.3,2074.5 +2.128974450877364,1.1288708853856493,0.0,1021.4,793.2,793.0,740.7,2029.0,2028.6 +2.1289916346857183,1.128869379114221,0.1308996938995747,1084.1,795.2,854.6,750.4,2075.5,2134.7 +2.12904302491387,1.1288840773356266,0.2617993877991494,1246.9,868.3,995.8,830.1,2296.6,2006.4 +2.1290954998098863,1.1289159151859884,0.39269908169872414,1051.3,1054.5,1020.0,1023.1,1635.0,1415.8 +2.12913665475033,1.1289608619628817,0.5235987755982988,856.4,970.3,842.5,1466.6,1295.2,1167.5 +2.1291725106701795,1.1290237638447165,0.6544984694978736,773.2,831.3,772.1,2096.2,1121.7,1062.6 +2.129181626989009,1.1290675048004595,0.7853981633974483,763.2,770.9,770.3,1998.6,1051.9,1051.1 +2.1291802210488,1.1291427719605116,0.916297857297023,815.9,772.0,830.8,2052.1,1062.3,1121.0 +2.1291691446184045,1.1291813278264593,1.0471975511965976,948.1,842.5,970.0,2262.6,1166.0,1293.1 +2.1291551229441907,1.1292012963399802,1.1780972450961724,1023.7,1019.3,1238.4,1582.0,1276.6,1055.7 +2.12909997632103,1.1292520429865338,1.3089969389957472,830.2,1445.6,1824.9,1247.3,996.8,869.1 +2.1290559688632036,1.1292755951760285,1.4398966328953218,749.9,2132.3,2074.0,1082.1,852.9,794.5 +2.129068959965135,1.1292718068871919,1.5707963267948966,740.8,2029.1,2028.6,1021.3,793.6,793.0 +2.129006539487468,1.1292686753486756,1.7016960206944713,792.6,2073.0,2132.0,1039.6,795.2,853.5 +2.1289534865771436,1.1292513642877517,1.832595714594046,923.0,2297.8,2004.7,1154.4,868.0,995.7 +2.128968162605071,1.1292605609926998,1.9634954084936205,1184.2,1634.3,1415.3,1248.5,1054.6,1019.4 +2.1289555134964417,1.129247772226484,2.0943951023931953,1747.4,1293.6,1166.1,948.0,970.0,842.6 +2.1289272066040117,1.1291926083629447,2.2252947962927703,2052.4,1121.1,1062.2,815.4,830.6,772.0 +2.128924231346986,1.1291786406223148,2.356194490192345,1999.5,1051.3,1051.8,762.4,770.3,770.9 +2.1289224437902603,1.1291740263651606,2.4870941840919194,2095.8,1062.5,1121.2,773.1,772.1,831.1 +2.1289352552312786,1.1291341877357974,2.6179938779914944,2026.0,1167.3,1295.1,855.8,842.6,970.4 +2.128937546693065,1.1291247736136503,2.748893571891069,1417.6,1273.1,1053.0,1052.9,1022.2,1242.2 +2.1289659851915883,1.1290986053165122,2.8797932657906435,1153.7,995.9,868.4,923.1,1447.8,1827.4 +2.128978897112761,1.1290912459731752,3.010692959690218,1039.9,853.7,795.0,793.2,2133.3,2074.6 +2.0289724819203254,1.8292506991727047,0.0,1721.3,893.0,893.0,40.8,1929.0,1928.8 +2.0289781400175513,1.8285540980958699,0.1308996938995747,1808.5,898.9,149.1,25.6,1971.9,2031.2 +2.0290347162508473,1.8285723694640241,0.2617993877991494,1810.1,431.1,51.4,21.4,2181.3,2309.0 +2.029087699794803,1.8286065393529654,0.39269908169872414,1192.3,251.3,31.9,32.1,2623.2,2403.7 +2.0291279668289137,1.8286525377527938,0.5235987755982988,972.0,161.3,33.6,72.4,2104.3,1976.4 +2.0291627719492427,1.828715521912306,0.6544984694978736,876.8,106.7,47.6,231.9,1846.1,1787.0 +2.029171290173463,1.8287587329634423,0.7853981633974483,863.3,71.1,70.5,1898.9,1751.4,1750.9 +2.0291699366401117,1.8288332508062373,0.916297857297023,233.1,47.7,106.5,1948.6,1786.4,1845.4 +2.0291596002641996,1.82887124013211,1.0471975511965976,73.7,34.2,161.5,2167.5,1974.7,1856.4 +2.0291468144259373,1.8288911888729662,1.1780972450961724,32.1,31.8,250.9,2573.3,1418.5,1197.2 +2.029093027801754,1.8289425944711182,1.3089969389957472,21.4,51.4,430.6,2056.3,1253.5,984.7 +2.029050156122245,1.8289674584249893,1.4398966328953218,26.0,153.1,981.8,1806.2,956.3,897.6 +2.0290637474486166,1.8289655012790362,1.5707963267948966,41.1,1928.8,1928.6,1720.8,893.2,893.0 +2.029001221541983,1.8289643206919657,1.7016960206944713,68.4,1969.9,2028.1,1763.6,898.6,153.1 +2.0289473850055812,1.8289487004780751,1.832595714594046,114.3,2182.4,2310.1,1963.4,430.6,51.4 +2.028960778339668,1.8289590516831884,1.9634954084936205,192.8,2622.0,2402.5,1350.4,250.9,31.9 +2.028946705824155,1.8289467169742344,2.0943951023931953,350.3,2102.1,1974.9,1063.6,161.5,34.2 +2.0289172265986117,1.82889130694959,2.2252947962927703,832.1,1845.1,1786.3,918.9,106.5,47.7 +2.028913621415046,1.8288765929284903,2.356194490192345,1899.6,1751.1,1751.7,862.4,70.5,71.1 +2.028911906556585,1.828871092638075,2.4870941840919194,1992.7,1786.6,1846.1,876.5,47.7,106.8 +2.0289255016390904,1.8288305897079637,2.6179938779914944,2262.3,1976.6,1688.3,348.1,33.7,161.4 +2.0289290390139296,1.8288210577641,2.748893571891069,2407.4,1414.3,1194.7,192.5,32.5,252.5 +2.0289588953220417,1.8287954710454377,2.8797932657906435,1962.3,1111.6,984.0,114.4,52.1,431.9 +2.0289730061609568,1.828789377463879,3.010692959690218,1764.0,957.3,898.4,68.9,152.5,975.3 +2.0289411635734367,1.7285106803313017,0.0,1621.2,892.9,892.9,140.9,1928.9,1929.2 +2.0289891449007995,1.729263843158677,0.1308996938995747,1705.1,898.9,532.8,129.1,1971.7,2031.2 +2.028964873516823,1.7292559115765695,0.2617993877991494,1799.5,630.3,250.6,136.8,2181.3,2309.0 +2.028935168502507,1.729236707377851,0.39269908169872414,1192.5,392.2,172.9,173.5,2482.1,2263.0 +2.0289098649021726,1.7292107080279067,0.5235987755982988,971.8,276.7,149.0,271.3,1988.8,1861.1 +2.0289023050711297,1.7291929639231873,0.6544984694978736,876.6,210.0,150.9,616.6,1742.5,1683.4 +2.0288916686920175,1.7291523448535853,0.7853981633974483,863.1,170.8,170.3,1898.8,1651.5,1651.3 +2.0288927135665826,1.7291476091516977,0.916297857297023,619.3,150.9,209.7,1949.0,1683.2,1742.0 +2.028903393217345,1.7291145673242776,1.0471975511965976,272.7,149.4,276.7,2168.1,1859.5,1741.3 +2.0289261758020984,1.729075687540319,1.1780972450961724,173.3,172.5,391.6,2432.1,1418.3,1197.1 +2.028917398569325,1.7290830258912702,1.3089969389957472,136.7,250.0,629.2,1941.1,1112.0,984.8 +2.0289255221166926,1.7290787826990826,1.4398966328953218,129.1,541.4,1369.9,1703.2,956.2,897.8 +2.02899251861998,1.7290627217131498,1.5707963267948966,140.8,1929.0,1928.8,1621.3,893.3,893.0 +2.0289804731319934,1.729061364946276,1.7016960206944713,171.5,1969.7,2028.1,1660.7,898.5,541.4 +2.0289720891586827,1.7290576751476754,1.832595714594046,229.5,2182.6,2310.3,1848.5,629.1,250.0 +2.0290238856018723,1.729090240194396,1.9634954084936205,334.1,2480.7,2261.7,1350.4,391.6,172.5 +2.0290386391029895,1.7291069913035209,2.0943951023931953,549.2,1986.8,1859.5,1063.5,276.7,149.4 +2.029027703874435,1.7290843868234211,2.2252947962927703,1218.2,1742.1,1683.3,919.1,209.7,150.9 +2.0290325163459295,1.7291040064419412,2.356194490192345,1899.7,1651.3,1651.7,862.4,170.3,170.8 +2.029029626453975,1.7291314113589946,2.4870941840919194,1992.4,1683.7,1742.5,876.7,151.0,210.0 +2.0290339711341008,1.7291197009702461,2.6179938779914944,2262.6,1861.6,1717.7,546.9,149.0,276.7 +2.029021831150641,1.7291335920526214,2.748893571891069,2265.8,1414.5,1194.4,333.5,173.6,393.5 +2.0290320068417422,1.7291247445046305,2.8797932657906435,1846.9,1111.3,983.9,229.7,251.1,630.9 +2.029024444529417,1.729128558192846,3.010692959690218,1660.9,957.4,898.5,172.1,538.7,1361.5 +2.028967269459654,1.6288306677990545,0.0,1521.2,892.9,892.9,240.7,1929.1,1929.2 +2.028997959254802,1.6293260957979392,0.1308996938995747,1601.5,898.7,958.0,232.6,1971.9,2031.4 +2.0289629877184185,1.629314701068449,0.2617993877991494,1712.2,829.6,450.0,252.3,2181.5,2309.0 +2.0289256628534686,1.6292905716987474,0.39269908169872414,1192.3,533.4,314.1,315.2,2341.3,2121.5 +2.02889501352919,1.6292586856447357,0.5235987755982988,971.9,392.3,264.6,470.4,1873.0,1745.4 +2.028884133403284,1.6292346077151225,0.6544984694978736,876.7,313.6,254.5,1002.2,1639.2,1580.2 +2.0288720216518565,1.6291875206391269,0.7853981633974483,863.1,270.8,270.3,1899.0,1551.9,1551.1 +2.028873236498413,1.6291766922890907,0.916297857297023,919.4,254.4,313.1,1948.7,1579.7,1638.9 +2.0288855085118476,1.6291381932993025,1.0471975511965976,472.3,264.9,392.3,2167.8,1744.1,1692.3 +2.0289110011547415,1.6290947970462253,1.1780972450961724,315.0,313.6,532.7,2290.4,1418.3,1197.4 +2.028907172379225,1.6290969040381609,1.3089969389957472,252.2,449.2,828.3,1825.7,1112.3,984.6 +2.0289178318673713,1.6290911011502887,1.4398966328953218,232.5,931.1,1759.3,1599.5,956.2,897.9 +2.0289886748039394,1.6290739965611027,1.5707963267948966,240.8,1928.8,1928.4,1521.0,893.3,892.9 +2.0289805789260424,1.629072601070098,1.7016960206944713,275.0,1969.8,2027.7,1556.9,898.4,956.8 +2.0289758633722554,1.629069843047565,1.832595714594046,345.0,2182.6,2310.4,1732.6,828.5,449.1 +2.029030791802244,1.6291042064039694,1.9634954084936205,475.7,2340.0,2121.0,1350.5,532.7,313.6 +2.0290479016113143,1.6291233358310038,2.0943951023931953,748.9,1871.0,1743.7,1063.6,392.3,264.9 +2.0290384873865994,1.6291034109621547,2.2252947962927703,1605.3,1638.7,1579.9,919.2,313.1,254.3 +2.029043986421656,1.629125839928839,2.356194490192345,1899.9,1551.1,1551.9,862.5,270.2,270.8 +2.0290409836552943,1.629155943202494,2.4870941840919194,1992.0,1580.1,1639.4,876.7,254.5,313.6 +2.0290445608895595,1.6291465824292968,2.6179938779914944,2262.2,1745.9,1732.1,745.9,264.6,392.2 +2.029031112117816,1.6291623831338848,2.748893571891069,2124.1,1414.2,1194.4,474.9,315.0,534.9 +2.0290396652526455,1.6291548867351118,2.8797932657906435,1706.0,1111.3,984.0,345.2,450.5,830.3 +2.0290303218535652,1.6291594877600644,3.010692959690218,1557.1,957.4,898.5,275.6,925.8,1748.9 +2.028971093207002,1.5288600262489018,0.0,1421.6,893.0,893.0,340.7,1928.9,1929.0 +2.0289888622051735,1.5288586071420391,0.1308996938995747,1498.2,898.7,958.2,335.9,1971.6,2031.6 +2.029040670331396,1.528873492824752,0.2617993877991494,1709.0,983.8,649.1,367.8,2181.5,2308.8 +2.0290934469060695,1.5289055744147437,0.39269908169872414,1192.4,674.4,455.1,456.6,2199.6,1980.3 +2.029134821518597,1.5289508005874612,0.5235987755982988,972.0,507.8,380.1,669.4,1757.6,1630.6 +2.0291707932700276,1.5290139751862977,0.6544984694978736,876.8,417.1,358.0,1387.4,1535.6,1476.8 +2.0291799830048354,1.5290580029322451,0.7853981633974483,863.3,370.7,370.2,1898.6,1451.8,1451.3 +2.029178572367678,1.5291335219337319,0.916297857297023,919.4,357.8,416.7,1948.6,1476.2,1535.3 +2.0291674469129277,1.5291723080002573,1.0471975511965976,672.0,380.4,507.8,2168.0,1628.6,1692.3 +2.029153348207941,1.5291925057375324,1.1780972450961724,456.8,454.8,673.9,2148.7,1418.3,1197.4 +2.0290980787212467,1.5292434310173828,1.3089969389957472,367.9,648.6,1027.8,1709.7,1112.1,1044.5 +2.0290539153607394,1.529267102504262,1.4398966328953218,336.0,1321.2,1970.3,1495.9,956.2,897.9 +2.029066732163651,1.529263433729464,1.5707963267948966,340.9,1929.0,1928.7,1421.1,893.4,893.1 +2.029004124792593,1.529260355267175,1.7016960206944713,378.6,1969.9,2028.1,1453.5,898.6,957.1 +2.0289508935465737,1.5292430149374168,1.832595714594046,460.7,2182.6,2310.0,1617.2,983.6,648.6 +2.0289654022013695,1.5292521562193062,1.9634954084936205,617.4,2199.0,1979.8,1350.5,674.0,454.8 +2.028952613819117,1.5292392813729898,2.0943951023931953,948.8,1755.8,1628.3,1063.5,507.7,380.5 +2.0289242306916244,1.529183977434139,2.2252947962927703,1949.2,1535.3,1476.3,919.0,416.7,357.9 +2.0289212314985647,1.529169859346528,2.356194490192345,1899.8,1451.2,1451.9,862.3,370.2,370.8 +2.028919454275011,1.5291651187164996,2.4870941840919194,1992.6,1476.5,1535.4,876.8,358.0,417.1 +2.028932344745029,1.5291251632742822,2.6179938779914944,2262.2,1630.0,1688.6,971.5,380.2,507.9 +2.0289347123618384,1.529115684843587,2.748893571891069,1982.9,1414.2,1194.4,616.2,456.4,676.5 +2.028963263785081,1.5290894844108074,2.8797932657906435,1590.3,1111.3,984.0,460.8,650.1,1029.9 +2.0289762793601374,1.5290821331448572,3.010692959690218,1454.0,957.3,898.4,379.1,1312.9,1970.9 +2.0289440352594705,1.4288029078189715,0.0,1321.5,892.9,893.1,440.6,1928.5,1929.1 +2.0289920756653856,1.4293429861763505,0.1308996938995747,1394.6,898.8,958.2,439.8,1971.4,2031.1 +2.0289591066190797,1.4293321880086198,0.2617993877991494,1593.4,984.0,849.0,483.5,2180.9,2360.0 +2.0289205914269224,1.4293072804361002,0.39269908169872414,1192.1,815.8,596.5,598.6,2058.9,1839.3 +2.02888832009534,1.4292736203564118,0.5235987755982988,971.8,623.5,495.9,868.9,1642.0,1514.2 +2.028876263590688,1.4292473003390915,0.6544984694978736,876.6,520.7,461.6,1773.0,1432.0,1372.9 +2.028863587575584,1.4291977802433142,0.7853981633974483,863.0,470.9,470.2,1899.0,1351.6,1351.4 +2.0288646131275425,1.429230704777374,0.916297857297023,919.3,461.4,520.2,1948.6,1372.8,1431.5 +2.028886662993111,1.4291602392727487,1.0471975511965976,871.6,496.0,623.3,2168.1,1513.0,1640.2 +2.0289168030678875,1.4291094228450534,1.1780972450961724,598.4,595.8,815.0,2007.1,1418.3,1197.0 +2.0289121057501407,1.4291127272402007,1.3089969389957472,483.4,847.8,1227.2,1594.2,1112.2,984.6 +2.028922795680985,1.429106901870381,1.4398966328953218,439.4,1710.5,1970.5,1392.6,956.2,897.9 +2.028991771278429,1.4290901695369103,1.5707963267948966,440.7,1929.0,1928.9,1321.1,893.3,893.0 +2.0289814101671335,1.429088655162257,1.7016960206944713,482.0,1969.7,2028.0,1350.1,898.5,956.9 +2.028974520497507,1.429085211238886,1.832595714594046,576.3,2182.6,2309.8,1501.6,984.0,847.8 +2.0290276056093735,1.429118374364879,1.9634954084936205,759.0,2057.4,1838.8,1350.2,814.9,595.9 +2.0290433556680663,1.429135985486472,2.0943951023931953,1148.1,1640.1,1512.8,1063.7,623.3,495.9 +2.029033076453998,1.4291144101233875,2.2252947962927703,1949.2,1431.6,1373.1,919.0,520.1,461.3 +2.029038189579437,1.4291351424430339,2.356194490192345,1899.6,1351.0,1351.8,862.3,470.3,470.7 +2.0290349769640517,1.429210616470559,2.4870941840919194,1991.9,1373.0,1432.2,876.6,461.6,520.6 +2.029048336046569,1.42916932451352,2.6179938779914944,2336.6,1514.3,1642.0,971.4,495.9,623.4 +2.0290392693099566,1.42917820691869,2.748893571891069,1841.6,1414.6,1194.4,757.9,597.8,817.9 +2.029048013658754,1.4291705067277918,2.8797932657906435,1500.3,1111.2,983.8,576.3,849.5,1229.4 +2.029036800970391,1.4291760735535128,3.010692959690218,1350.3,957.3,898.4,482.7,1700.0,1970.9 +2.028936877402162,1.3288645064844034,0.0,1221.4,893.0,893.0,540.7,1929.1,1929.0 +2.028978541086331,1.3288639854665774,0.1308996938995747,1291.1,898.7,958.2,543.2,1971.6,2030.9 +2.029037217566125,1.3288809554625842,0.2617993877991494,1477.7,983.9,1086.1,598.9,2181.5,2308.8 +2.0290915478870155,1.3289139701628927,0.39269908169872414,1192.3,956.8,737.3,739.9,1917.3,1698.3 +2.029133021975446,1.3289592603821925,0.5235987755982988,972.0,739.0,611.3,1067.8,1526.7,1398.9 +2.029168840968415,1.329022091440659,0.6544984694978736,876.9,624.1,565.0,1992.4,1328.8,1269.5 +2.0291779194449058,1.3290656053051093,0.7853981633974483,863.3,570.8,570.3,1899.1,1251.7,1251.2 +2.0291765324961877,1.3293205735396443,0.916297857297023,919.6,564.9,623.7,1948.3,1269.1,1328.2 +2.0288023767390824,1.3290712155762838,1.0471975511965976,1063.2,611.4,738.6,2167.5,1396.9,1524.0 +2.0288278823377675,1.3290290152086794,1.1780972450961724,740.6,736.8,955.6,1866.1,1524.6,1198.0 +2.0288225346157955,1.3290339008929584,1.3089969389957472,599.3,1046.3,1425.3,1479.0,1112.6,984.8 +2.0288345131202052,1.3290283792745776,1.4398966328953218,543.0,2029.3,1970.5,1289.1,956.5,897.9 +2.0289053053940975,1.3290116063324113,1.5707963267948966,540.8,1929.3,1928.7,1221.3,893.4,893.1 +2.0288967336686685,1.3290105553201124,1.7016960206944713,585.2,1969.6,2028.2,1246.5,898.7,956.9 +2.028891318124259,1.3290081208961033,1.832595714594046,691.6,2181.8,2309.2,1385.4,983.7,1085.9 +2.028945660699809,1.3290421770853227,1.9634954084936205,900.4,1917.7,1698.3,1371.6,956.6,737.5 +2.028962495665992,1.3290606214682492,2.0943951023931953,1346.8,1525.0,1397.5,1064.1,739.2,611.7 +2.028952960871292,1.3290401639209202,2.2252947962927703,1949.2,1328.3,1269.4,919.3,623.9,565.0 +2.028958676621456,1.3290620492552854,2.356194490192345,1899.6,1251.2,1251.6,862.7,570.3,570.9 +2.028956357413115,1.3290916034851974,2.4870941840919194,1992.1,1269.3,1328.1,876.7,565.1,624.1 +2.0289605150228005,1.3290821332401173,2.6179938779914944,2261.8,1398.2,1526.2,971.3,611.5,738.9 +2.0289480047051613,1.329097951205044,2.748893571891069,1701.2,1527.1,1195.0,900.0,738.8,958.9 +2.028957116072486,1.3290908294839634,2.8797932657906435,1384.9,1111.8,984.2,692.3,1048.4,1427.5 +2.0289481672208907,1.329095947091143,3.010692959690218,1246.9,957.5,898.5,586.4,2029.6,1971.0 +2.0288886345685095,1.2287965223578232,0.0,1121.4,893.1,893.0,640.9,1929.1,1928.9 +2.0289065000172286,1.22879557701543,0.1308996938995747,1187.3,898.9,958.1,646.8,1971.4,2030.4 +2.02895820678709,1.2288106629648978,0.2617993877991494,1362.2,983.7,1111.0,714.5,2299.9,2207.5 +2.029010914341142,1.2288427503150676,0.39269908169872414,1193.2,1098.6,879.1,881.2,1777.3,1557.8 +2.029052232153452,1.228887778445043,0.5235987755982988,972.2,855.1,727.2,1266.4,1411.3,1283.7 +2.0290885499403304,1.228950823951156,0.6544984694978736,877.0,728.0,668.7,1992.3,1225.1,1166.1 +2.029098042028726,1.2289946128732319,0.7853981633974483,863.2,670.8,670.3,1898.5,1151.9,1151.1 +2.0290972765196913,1.2290702190968141,0.916297857297023,919.4,668.4,727.0,1948.6,1165.6,1224.3 +2.0290867962408132,1.2291093296443452,1.0471975511965976,1063.3,726.9,854.1,2264.1,1281.5,1408.6 +2.029073129971713,1.2291298310660617,1.1780972450961724,882.6,878.0,1096.9,1724.3,1419.0,1198.3 +2.029018223655267,1.2291813884988887,1.3089969389957472,715.0,1245.5,1624.4,1363.6,1112.9,984.9 +2.0289741897688205,1.2292059668739097,1.4398966328953218,646.5,2029.2,1970.4,1185.6,956.6,898.1 +2.028986803124516,1.229202702877976,1.5707963267948966,640.9,1928.8,1928.5,1121.0,893.4,893.1 +2.0289238511190675,1.2291999966305536,1.7016960206944713,688.9,1969.6,2027.8,1142.9,898.5,956.8 +2.0288701283047903,1.2291830500790266,1.832595714594046,807.3,2297.6,2205.3,1269.5,983.7,1111.2 +2.0288842390953588,1.2291920384379975,1.9634954084936205,1042.2,1776.1,1557.1,1389.3,1098.1,878.7 +2.0288713024663645,1.2291786803753828,2.0943951023931953,1546.3,1409.5,1282.1,1064.1,854.9,727.4 +2.028842870517377,1.2291230424573887,2.2252947962927703,1949.3,1224.8,1165.8,919.1,727.4,668.4 +2.0288400953153265,1.2292128447881203,2.356194490192345,1899.6,1151.1,1151.7,862.6,670.3,670.8 +2.02916669291472,1.2290692473717186,2.4870941840919194,1992.5,1165.7,1224.9,876.9,668.8,727.9 +2.029169257398418,1.2290622107074043,2.6179938779914944,2225.0,1283.0,1410.7,971.5,727.4,854.9 +2.029149845582578,1.2290875658463039,2.748893571891069,1559.1,1414.5,1194.5,1040.8,880.9,1100.9 +2.02914892982899,1.2290891254038443,2.8797932657906435,1269.3,1111.4,983.9,807.7,1248.8,1628.9 +2.029128241846911,1.229100174571884,3.010692959690218,1143.1,957.3,898.4,689.9,2029.9,1971.0 +2.0290548466118756,1.1287901268788003,0.0,1021.0,893.1,892.9,740.7,1928.7,1929.3 +2.029062357994944,1.1287891457959947,0.1308996938995747,1083.7,898.7,958.2,750.4,1972.0,2030.8 +2.029106295804219,1.1288023928697173,0.2617993877991494,1246.8,984.1,1111.4,830.1,2181.3,2006.1 +2.029152743676258,1.1288314133676387,0.39269908169872414,1192.3,1196.1,1020.0,1023.1,1635.2,1415.6 +2.0291892027642304,1.1288724678631978,0.5235987755982988,972.1,970.3,842.9,1466.6,1295.1,1167.6 +2.0292217865760676,1.1289307691093662,0.6544984694978736,876.5,831.3,772.3,1992.5,1121.6,1062.3 +2.0292291340039537,1.1289694695610661,0.7853981633974483,863.2,770.8,770.3,1899.0,1051.7,1051.2 +2.0292274549419083,1.1290397555685927,0.916297857297023,919.3,772.0,831.0,1948.4,1062.0,1121.1 +2.0292175186105688,1.1290737411736176,1.0471975511965976,1063.4,842.7,970.0,2168.0,1166.2,1293.3 +2.0292058081520707,1.12908996903177,1.1780972450961724,1023.8,1019.4,1238.6,1582.0,1415.3,1197.6 +2.0291537280039638,1.1291380725827032,1.3089969389957472,830.4,1445.9,1825.0,1247.0,1112.3,984.7 +2.0291132056386805,1.1291601584415263,1.4398966328953218,750.1,2028.7,1970.7,1082.0,956.2,897.8 +2.0291297306311105,1.1291561161839758,1.5707963267948966,740.8,1929.4,1928.9,1021.0,893.3,892.8 +2.0290704253093947,1.1291537486864716,1.7016960206944713,792.4,1969.7,2028.2,1039.6,898.4,956.9 +2.0290198822857524,1.1291379585354435,1.832595714594046,923.3,2182.5,2004.2,1154.4,983.6,1111.2 +2.029036343422102,1.1291491892373466,1.9634954084936205,1184.7,1634.0,1415.2,1350.4,1196.3,1019.3 +2.029024702691751,1.1291386013790274,2.0943951023931953,1747.5,1293.4,1166.2,1063.6,970.0,842.8 +2.0289967491780607,1.1290855305473926,2.2252947962927703,1949.1,1121.0,1062.3,919.0,830.8,772.1 +2.0289936356972866,1.1290734353356071,2.356194490192345,1899.6,1051.1,1051.7,862.3,770.3,770.9 +2.028991381858958,1.1290704031985004,2.4870941840919194,1992.4,1062.3,1121.2,876.6,772.2,831.4 +2.029003580865794,1.129031838793396,2.6179938779914944,2025.9,1167.4,1295.1,971.4,843.0,970.5 +2.029005173331426,1.129023491329365,2.748893571891069,1417.3,1414.3,1194.6,1194.4,1022.1,1242.2 +2.0290329003680707,1.1289982343323581,2.8797932657906435,1153.7,1111.3,983.7,923.2,1448.2,1828.1 +2.029045046584361,1.128991697426077,3.010692959690218,1039.9,957.2,898.4,793.1,2029.5,1970.9 +1.9290386198648062,1.8291484155137452,0.0,1721.1,993.0,992.9,40.9,1829.3,1828.9 +1.929021594038537,1.828526179860308,0.1308996938995747,1809.0,1002.3,149.0,25.6,1868.8,1927.8 +1.9290765174921802,1.8285440877348844,0.2617993877991494,1910.7,430.8,51.4,21.4,2066.2,2193.7 +1.929131598570564,1.828579800307029,0.39269908169872414,1333.1,251.1,31.9,32.1,2522.3,2403.0 +1.9291742996439418,1.8286287263251122,0.5235987755982988,1087.5,161.2,33.6,72.5,2103.6,1976.2 +1.929210630983354,1.828435820304747,0.6544984694978736,980.2,106.7,47.7,232.2,1845.3,1786.9 +1.9288117606519837,1.8289243921970944,0.7853981633974483,963.3,70.9,70.6,1798.6,1751.6,1751.2 +1.9288033008026666,1.829138800482467,0.916297857297023,232.1,47.6,106.6,1845.5,1786.8,1845.8 +1.9288538457663211,1.8289804517202608,1.0471975511965976,73.3,34.1,161.7,2053.4,1975.7,1961.9 +1.9288926253762995,1.828918997090058,1.1780972450961724,31.9,31.7,251.2,2514.1,1558.6,1338.2 +1.9288815726903827,1.8289302919935524,1.3089969389957472,21.3,51.3,431.3,2054.8,1264.6,1099.8 +1.9288779365566568,1.828933471294851,1.4398966328953218,25.9,153.4,984.8,1805.6,1059.6,1001.3 +1.9289292156982372,1.8289228307355225,1.5707963267948966,41.1,1829.3,1828.5,1721.3,993.4,993.2 +1.9289009422389611,1.8289223042233171,1.7016960206944713,68.4,1866.5,1925.3,1764.6,1002.3,151.9 +1.9288775303480346,1.828914728883096,1.832595714594046,114.3,2067.8,2195.8,1964.5,429.5,51.0 +1.9289163537224199,1.8289401957164486,1.9634954084936205,193.0,2526.0,2400.6,1490.7,250.4,31.7 +1.9289212363395842,1.8289475211972313,2.0943951023931953,350.7,2100.7,1974.0,1178.5,161.2,34.1 +1.9289043311850431,1.828913627977292,2.2252947962927703,834.8,1844.7,1786.2,1022.3,106.2,47.6 +1.9289067856851145,1.828921490923925,2.356194490192345,1799.3,1751.0,1751.6,962.4,70.4,71.1 +1.9289046217190502,1.8289380546683607,2.4870941840919194,1889.1,1787.3,1846.8,824.5,47.6,106.8 +1.92891295400796,1.8289168172807362,2.6179938779914944,2148.6,1977.4,1964.4,347.3,33.6,161.5 +1.928906315741419,1.828923544532993,2.748893571891069,2404.8,1554.6,1335.0,192.1,32.4,252.8 +1.9289236053923298,1.828909808442712,2.8797932657906435,1961.5,1226.4,1099.0,114.2,52.1,432.7 +1.9289234522098833,1.8289111491287975,3.010692959690218,1763.8,1060.9,1002.0,68.7,152.9,978.4 +1.9288748917569558,1.7286193486334045,0.0,1621.3,992.9,993.3,140.8,1828.5,1829.3 +1.9289117006329317,1.7292741357789334,0.1308996938995747,1705.6,1002.7,531.3,129.0,1868.5,1928.1 +1.9288840854778675,1.7292649820223294,0.2617993877991494,1910.0,629.4,250.3,136.9,2066.4,2194.8 +1.9288531122879629,1.7292446085892759,0.39269908169872414,1332.7,391.8,172.8,173.7,2480.8,2261.8 +1.9288275485555715,1.7292176366359242,0.5235987755982988,1087.2,276.5,149.0,271.6,1988.0,1860.2 +1.9288198976108777,1.7291988960707223,0.6544984694978736,980.2,209.9,151.0,618.3,1742.2,1683.1 +1.9288098009318468,1.7291576913277487,0.7853981633974483,963.2,170.7,170.4,1799.1,1651.8,1651.3 +1.9288112758955103,1.729152376304634,0.916297857297023,617.6,150.9,209.8,1845.4,1683.4,1742.4 +1.9288224923903674,1.7291189768429236,1.0471975511965976,272.3,149.4,276.9,2053.2,1860.5,1889.8 +1.9288459348077742,1.7290802831725536,1.1780972450961724,173.2,172.6,392.0,2430.1,1559.1,1338.3 +1.9288375295654514,1.7290877001515264,1.3089969389957472,136.6,250.3,630.1,1940.6,1227.5,1100.1 +1.9288458523034175,1.7290832668657057,1.4398966328953218,129.1,542.8,1373.7,1702.7,1059.5,1001.3 +1.9289130250190345,1.7290675564856797,1.5707963267948966,140.8,1828.7,1828.6,1621.1,993.2,993.2 +1.9289010489357448,1.7290662354054434,1.7016960206944713,171.6,1866.4,1925.5,1660.9,1002.2,540.0 +1.9288928494323245,1.729062089996826,1.832595714594046,229.6,2067.3,2195.3,1848.9,628.3,249.7 +1.9289448543045657,1.7290945058528924,1.9634954084936205,334.3,2479.2,2260.5,1490.5,391.2,172.5 +1.9289598410204682,1.7292004942831576,2.0943951023931953,550.1,1986.0,1858.6,1178.8,276.5,149.4 +1.9289445591147556,1.7290788742618757,2.2252947962927703,1221.1,1741.5,1682.7,1022.4,209.5,150.9 +1.928951551308258,1.7291055591376991,2.356194490192345,1799.7,1651.2,1651.8,962.6,170.2,170.9 +1.9289489199743253,1.7291349272873437,2.4870941840919194,1889.1,1683.7,1743.6,980.5,150.9,210.1 +1.9289538494984768,1.7291233348728907,2.6179938779914944,2147.6,1861.9,1885.4,546.2,149.0,276.9 +1.9289419895835347,1.729137216494613,2.748893571891069,2264.6,1555.1,1335.3,333.2,173.7,393.9 +1.9289527945104994,1.7291282432252637,2.8797932657906435,1846.5,1226.4,1099.1,229.5,251.3,631.7 +1.9289457306111446,1.7291320050460155,3.010692959690218,1660.4,1060.4,1002.0,172.1,540.0,1365.0 +1.9288893556100963,1.6288343030419108,0.0,1521.2,993.1,993.2,240.6,1829.0,1828.7 +1.9289089779769613,1.6288331085248435,0.1308996938995747,1602.3,1002.5,914.0,232.5,1868.8,1927.7 +1.9289621185499892,1.6288484446176206,0.2617993877991494,1825.5,828.2,449.2,252.3,2066.4,2194.0 +1.9290159677889231,1.6288810955405735,0.39269908169872414,1332.9,532.8,313.7,315.2,2339.4,2120.4 +1.9290583882078334,1.628927065636213,0.5235987755982988,1163.6,392.0,264.5,470.8,1872.3,1744.9 +1.9290949822103018,1.6289909248610397,0.6544984694978736,980.4,313.4,254.4,1004.2,1638.9,1579.6 +1.9291049367432682,1.629035960903156,0.7853981633974483,963.4,270.7,270.3,1798.5,1551.5,1551.2 +1.9291038385592114,1.6291123682318984,0.916297857297023,1023.5,254.4,313.3,1845.0,1579.9,1638.6 +1.9290928299272305,1.6291520898108458,1.0471975511965976,471.9,265.1,392.4,2053.2,1744.5,1872.1 +1.9290787285820636,1.6291735156368403,1.1780972450961724,314.9,313.9,533.3,2288.7,1558.8,1338.5 +1.9290230365741488,1.62922533955394,1.3089969389957472,252.2,449.9,829.6,1824.3,1227.5,1240.9 +1.9289781757541058,1.6292494285441326,1.4398966328953218,232.6,933.6,1764.2,1599.1,1059.5,1001.4 +1.9289902029359491,1.6292464125170432,1.5707963267948966,240.9,1828.8,1828.8,1520.8,993.4,993.2 +1.9289267293962715,1.6292434504654676,1.7016960206944713,275.2,1866.3,1924.9,1557.3,1002.5,929.2 +1.9288727987207643,1.6292255433978196,1.832595714594046,345.4,2067.4,2195.1,1733.1,827.5,448.9 +1.9288867439914683,1.6292341722303518,1.9634954084936205,476.2,2338.3,2119.6,1490.6,532.4,313.5 +1.928873597085823,1.6292207802969534,2.0943951023931953,749.9,1870.1,1743.3,1178.6,392.1,264.8 +1.9288453593651165,1.6291646312495258,2.2252947962927703,1609.3,1637.9,1579.6,1022.7,313.1,254.4 +1.928842772547153,1.6291498060669338,2.356194490192345,1799.8,1551.2,1551.7,962.3,270.3,270.9 +1.9288413737360979,1.6291447592201234,2.4870941840919194,1888.8,1580.4,1639.2,980.3,254.5,313.7 +1.9288550173642365,1.6291045388333378,2.6179938779914944,2147.6,1746.1,1873.9,745.2,264.6,392.5 +1.9288576980966066,1.6290952094834439,2.748893571891069,2123.3,1554.8,1335.1,474.6,315.2,535.4 +1.9288867372444332,1.629069187333952,2.8797932657906435,1731.0,1226.4,1099.2,345.0,451.0,831.4 +1.9289000159122363,1.6290620844833554,3.010692959690218,1557.4,1060.6,1002.1,275.5,927.8,1752.5 +1.9288681245489456,1.5287827985354079,0.0,1421.2,992.9,993.1,340.6,1828.7,1829.1 +1.9289267609896374,1.5293373325351145,0.1308996938995747,1498.4,1002.4,1062.0,336.2,1868.2,1927.9 +1.9288967616554542,1.5293273478761602,0.2617993877991494,1709.7,1028.2,649.0,368.0,2066.2,2194.1 +1.9288595129902106,1.5293029840181864,0.39269908169872414,1333.0,674.2,455.0,457.0,2198.4,1979.4 +1.9288280982804198,1.529269752062589,0.5235987755982988,1087.4,507.7,380.1,670.2,1757.0,1629.7 +1.928816521958051,1.5292437184482202,0.6544984694978736,980.3,417.0,358.0,1390.2,1535.3,1476.5 +1.9288044696901774,1.529194723515198,0.7853981633974483,963.1,370.7,370.3,1798.7,1451.7,1451.1 +1.9288060695526537,1.5291820313559241,0.916297857297023,1023.0,357.9,416.8,1845.3,1476.4,1535.5 +1.9288191508524717,1.529141971249048,1.0471975511965976,671.5,380.6,507.9,2052.8,1628.8,1756.1 +1.928845802766249,1.5290976188364913,1.1780972450961724,456.5,454.9,674.2,2147.8,1559.1,1338.5 +1.928841587669881,1.5291008188102573,1.3089969389957472,367.7,649.0,1028.5,1709.3,1227.4,1099.8 +1.9288547167236323,1.529093675202338,1.4398966328953218,336.0,1322.9,1866.8,1495.9,1059.7,1001.4 +1.9289269276277587,1.5290765153413355,1.5707963267948966,340.9,1829.1,1828.4,1421.5,993.2,993.1 +1.9289197429153506,1.529075162295083,1.7016960206944713,378.5,1866.5,1925.0,1453.5,1002.1,1060.8 +1.9289158232773869,1.5290722836386688,1.832595714594046,460.8,2066.9,2195.3,1617.0,1026.8,647.9 +1.928971434270654,1.5291068503744896,1.9634954084936205,617.7,2197.3,1978.5,1491.0,673.6,454.5 +1.9289891131052916,1.5291263803802493,2.0943951023931953,949.2,1755.1,1627.9,1178.8,507.6,380.3 +1.9289803505992524,1.529106735454465,2.2252947962927703,1845.3,1535.1,1476.1,1022.4,416.6,357.8 +1.9289864045351106,1.5291296045691403,2.356194490192345,1799.7,1451.1,1451.7,962.5,370.2,370.8 +1.928983645581519,1.5291604101959935,2.4870941840919194,1888.9,1476.7,1536.0,980.3,358.0,417.2 +1.9289874953666162,1.5291516629017656,2.6179938779914944,2147.8,1630.1,1758.3,944.4,380.3,508.1 +1.9289738005211219,1.5291682149754802,2.748893571891069,1982.1,1554.9,1335.6,616.0,456.6,676.8 +1.9289821179177389,1.529161280739033,2.8797932657906435,1615.6,1226.7,1099.4,460.6,650.6,1030.7 +1.928972326138597,1.5291662791306342,3.010692959690218,1453.9,1060.8,1002.1,379.1,1315.3,1867.2 +1.9289126565723693,1.4288661969643173,0.0,1321.6,993.1,993.1,440.6,1828.8,1829.1 +1.9289300206631985,1.428864738790121,0.1308996938995747,1395.0,1002.8,1061.9,439.6,1868.4,1927.7 +1.9289815314787309,1.428879428789609,0.2617993877991494,1594.1,1099.8,847.9,483.5,2066.1,2359.3 +1.9290341664194213,1.4289112101619281,0.39269908169872414,1333.1,815.1,596.0,598.6,2057.9,1838.8 +1.929075663638253,1.4289561526195536,0.5235987755982988,1087.3,623.2,495.7,869.5,1641.4,1513.9 +1.9291117213711986,1.4290189784638399,0.6544984694978736,980.3,520.5,461.4,1776.2,1431.8,1372.9 +1.929121309375486,1.4290628932873934,0.7853981633974483,963.4,470.7,470.3,1799.0,1351.6,1351.4 +1.929120165653888,1.4291382852925647,0.916297857297023,1023.4,461.4,520.2,1845.5,1372.9,1431.7 +1.9291093158023396,1.4291770594011237,1.0471975511965976,871.1,496.0,623.4,2052.9,1513.2,1640.7 +1.929095518992444,1.4291975460087376,1.1780972450961724,598.3,596.2,815.4,2006.2,1667.3,1338.8 +1.9290403373271576,1.4292486450349264,1.3089969389957472,483.4,848.5,1227.9,1593.5,1227.7,1100.2 +1.9289961319113682,1.4292722682410055,1.4398966328953218,439.5,1713.5,1866.5,1392.1,1059.8,1001.2 +1.929008886812223,1.429268825373601,1.5707963267948966,440.9,1828.7,1828.8,1321.2,993.4,993.2 +1.9289461707198237,1.4292657228912964,1.7016960206944713,482.0,1866.3,1924.5,1350.0,1002.1,1060.6 +1.9288929348599397,1.4292480095274027,1.832595714594046,576.5,2067.2,2313.5,1502.0,1099.7,847.2 +1.9289074974360942,1.4292569364535201,1.9634954084936205,759.6,2056.7,1837.6,1514.5,814.5,595.7 +1.9288948282720064,1.4292439457877018,2.0943951023931953,1149.0,1639.7,1512.4,1178.8,622.9,495.8 +1.9288668080465656,1.4291883762828037,2.2252947962927703,1845.5,1431.3,1372.6,1022.5,520.1,461.4 +1.92886423544649,1.4291741368711155,2.356194490192345,1799.4,1351.3,1351.7,962.6,470.2,470.8 +1.92886273285167,1.4291695552258152,2.4870941840919194,1889.1,1373.1,1432.5,980.2,461.6,520.8 +1.928876036601925,1.4291297454718985,2.6179938779914944,2147.3,1514.9,1642.7,1087.5,495.9,623.7 +1.9288784187936607,1.4291206243107362,2.748893571891069,1841.0,1670.3,1335.6,757.5,598.0,818.4 +1.9289070464559928,1.4290947013023492,2.8797932657906435,1500.1,1226.6,1099.3,576.2,850.0,1230.3 +1.928919965018002,1.4290875697732766,3.010692959690218,1350.5,1060.7,1002.0,482.5,1702.4,1867.2 +1.9288876699954682,1.3288080664389255,0.0,1221.4,993.0,993.3,540.6,1828.7,1829.1 +1.928944973724187,1.3293439025729326,0.1308996938995747,1290.8,1002.6,1061.8,543.4,1868.1,1927.8 +1.9289139124900276,1.329333607442891,0.2617993877991494,1478.1,1099.7,1047.7,599.2,2066.1,2193.6 +1.9288758130543575,1.3293087699412836,0.39269908169872414,1333.1,956.6,737.4,740.4,1916.6,1697.2 +1.9288437100571614,1.3292749273464186,0.5235987755982988,1087.2,738.9,611.2,1068.7,1526.0,1398.3 +1.9288538242957494,1.329292562315374,0.6544984694978736,980.0,624.1,565.1,1888.4,1328.5,1269.4 +1.9288339225457176,1.3292095658812846,0.7853981633974483,963.1,570.8,570.3,1798.8,1251.7,1251.4 +1.9288357276073507,1.3291883987245472,0.916297857297023,1022.9,564.9,623.8,1845.1,1269.4,1328.1 +1.9288487841195106,1.329148131756745,1.0471975511965976,1070.9,611.6,739.0,2052.8,1397.5,1525.1 +1.9288741218682506,1.3291056074254377,1.1780972450961724,740.0,737.2,956.5,1864.9,1559.4,1338.6 +1.9288677727672074,1.329110696636709,1.3089969389957472,598.9,1047.6,1427.2,1478.3,1227.8,1100.2 +1.92887832376739,1.3291049240278738,1.4398966328953218,542.9,1925.4,1866.9,1289.0,1059.6,1001.3 +1.9289477943544726,1.329088290949378,1.5707963267948966,540.8,1829.0,1828.7,1221.4,993.1,993.1 +1.9289380521913408,1.3290868253419255,1.7016960206944713,585.4,1866.3,1924.9,1247.1,1002.2,1060.7 +1.9289318370851962,1.3290833350110685,1.832595714594046,692.1,2067.1,2194.8,1386.0,1099.7,1046.4 +1.928985530734214,1.329116738915309,1.9634954084936205,901.2,1916.1,1697.1,1532.5,955.8,736.7 +1.9290017791405552,1.329134763178051,2.0943951023931953,1348.5,1524.3,1371.6,1179.1,738.6,611.4 +1.9290150878759846,1.3291589154704355,2.2252947962927703,1845.2,1327.9,1269.1,1022.5,623.5,564.8 +1.9290128276672056,1.3291460024225947,2.356194490192345,1799.8,1251.2,1252.1,962.6,570.2,570.9 +1.9290103935002072,1.3291672191942503,2.4870941840919194,1888.9,1269.5,1328.7,980.1,565.0,624.3 +1.9290144160289362,1.3291574943702957,2.6179938779914944,2147.2,1399.0,1526.7,1087.2,611.6,739.2 +1.9289998393415044,1.3291753449298342,2.748893571891069,1699.5,1555.4,1335.7,898.9,739.4,959.7 +1.9290064179278315,1.3291699182266736,2.8797932657906435,1384.6,1226.9,1099.2,691.7,1049.7,1429.8 +1.9289945054789537,1.329175983553693,3.010692959690218,1246.8,1060.9,1001.9,586.1,1926.2,1867.1 +1.9289321480052408,1.2288739263203352,0.0,1121.5,993.0,993.2,640.6,1828.9,1828.9 +1.9290079625395329,1.2288714730815833,0.1308996938995747,1187.8,1002.6,1061.8,646.8,1868.4,1927.5 +1.929019150744938,1.2288737645906411,0.2617993877991494,1362.6,1099.8,1227.2,714.6,2065.7,2160.9 +1.929063538000721,1.2289003761601176,0.39269908169872414,1333.7,1097.6,878.3,881.8,1775.6,1556.4 +1.9291052844404295,1.2289456514319967,0.5235987755982988,1087.4,854.4,726.8,1267.7,1410.7,1282.6 +1.9291429263066182,1.2290115320507002,0.6544984694978736,980.4,727.5,668.7,1888.6,1225.2,1166.0 +1.9291533521403037,1.2290595212566138,0.7853981633974483,963.3,670.8,670.2,1798.8,1151.8,1151.4 +1.9291520076462982,1.229139090225623,0.916297857297023,1023.0,668.4,727.3,1845.5,1166.1,1224.8 +1.929139921851646,1.2291816684613759,1.0471975511965976,1179.4,727.1,854.5,2078.5,1282.1,1409.3 +1.929124061190373,1.229205217313936,1.1780972450961724,881.6,878.5,1097.7,1723.3,1556.8,1338.9 +1.9290663583357535,1.2292585899824622,1.3089969389957472,714.5,1247.0,1626.5,1362.6,1227.7,1100.0 +1.929019358445506,1.2292837124194298,1.4398966328953218,646.4,1924.9,1867.4,1185.4,1059.6,1001.3 +1.9290292256130535,1.2292808473001657,1.5707963267948966,640.8,1828.9,1828.8,1121.1,993.5,993.2 +1.928963835824945,1.2292776402901815,1.7016960206944713,688.9,1866.7,1925.0,1143.1,1002.0,1060.6 +1.9289082074976036,1.229259291081223,1.832595714594046,807.8,2067.1,2158.3,1270.4,1099.6,1227.3 +1.9289207713303245,1.229267013350916,1.9634954084936205,1043.1,1774.9,1555.7,1491.3,1097.0,877.9 +1.9289066095130054,1.229252462166495,2.0943951023931953,1548.5,1408.6,1281.5,1179.0,854.1,726.9 +1.9288775624871095,1.2291952218687099,2.2252947962927703,1845.4,1224.7,1165.5,1022.4,727.1,668.4 +1.9288744561206421,1.229179219246767,2.356194490192345,1799.7,1151.1,1151.6,962.4,670.3,670.8 +1.928872937896793,1.2291728782147335,2.4870941840919194,1888.7,1165.9,1225.1,980.4,668.7,727.9 +1.9288865729236642,1.2291315231856355,2.6179938779914944,2147.3,1283.2,1411.0,1087.3,727.2,854.9 +1.928889720934191,1.2291210497096512,2.748893571891069,1558.8,1555.5,1335.6,1040.2,880.8,1101.0 +1.9289192970904716,1.2290941149329666,2.8797932657906435,1269.0,1226.8,1099.3,807.3,1249.3,1629.4 +1.9289333338529537,1.22908631288951,3.010692959690218,1143.3,1060.8,1002.1,689.6,1926.1,1867.2 +1.9289023765503317,1.1288078838101114,0.0,1021.4,993.1,993.1,740.7,1829.0,1828.8 +1.9289582266348653,1.1293456717097943,0.1308996938995747,1083.8,1002.6,1061.8,750.6,1868.2,1927.6 +1.928926646925535,1.129335237654315,0.2617993877991494,1246.8,1099.7,1227.3,830.4,2141.6,2005.3 +1.9288882454324627,1.1293102617304385,0.39269908169872414,1408.3,1239.0,1019.8,1024.0,1634.5,1415.5 +1.9288559043295768,1.1292762643798455,0.5235987755982988,1087.4,970.0,842.7,1467.2,1294.8,1167.4 +1.9288437493369173,1.1292494362245815,0.6544984694978736,980.2,831.2,772.1,1888.6,1121.2,1062.1 +1.9288312315599874,1.129199491473324,0.7853981633974483,963.2,770.8,770.2,1799.0,1051.8,1051.1 +1.9288326993620557,1.1291859176967463,0.916297857297023,1023.1,771.7,830.7,1845.3,1062.3,1121.2 +1.9288458643559738,1.1291450089902375,1.0471975511965976,1179.2,842.6,970.2,2052.7,1166.4,1293.7 +1.928872756809139,1.1290997792581376,1.1780972450961724,1023.3,1019.5,1238.6,1581.5,1415.5,1462.6 +1.9288690161051107,1.1291023375228488,1.3089969389957472,830.3,1446.0,1825.6,1247.3,1227.7,1100.2 +1.9288827674138465,1.1290948492695732,1.4398966328953218,749.7,1925.6,1867.0,1082.1,1059.5,1001.3 +1.9289847554636994,1.1290668978353757,1.5707963267948966,740.7,1829.1,1828.7,1021.2,993.3,993.2 +1.9289578590859824,1.1290648192910984,1.7016960206944713,792.4,1866.6,1924.8,1039.9,1002.0,1060.6 +1.9289507613499581,1.1290611071747705,1.832595714594046,923.2,2139.9,2003.7,1154.6,1099.5,1227.3 +1.9290079087714738,1.1290966966384346,1.9634954084936205,1184.6,1634.0,1414.8,1421.5,1238.1,1019.2 +1.9290277493441719,1.1291185977136928,2.0943951023931953,1748.0,1293.3,1166.0,1179.1,969.7,842.4 +1.9290204474779464,1.1291021131343402,2.2252947962927703,1845.4,1120.9,1062.2,1022.6,830.5,771.8 +1.929027063859147,1.1291283389696334,2.356194490192345,1799.4,1051.3,1051.9,962.4,770.2,770.9 +1.929024067134301,1.1291622548150455,2.4870941840919194,1888.9,1062.5,1121.7,980.4,772.2,831.3 +1.9290268397546395,1.1291562597886111,2.6179938779914944,2025.3,1167.7,1295.3,1087.2,842.7,970.6 +1.929011678623542,1.1291749578097585,2.748893571891069,1417.6,1417.8,1337.2,1181.8,1022.4,1242.4 +1.9290180949139721,1.1291696017475776,2.8797932657906435,1153.5,1226.8,1099.4,922.8,1448.6,1828.6 +1.9290062763079,1.1291755756982989,3.010692959690218,1039.7,1060.8,1001.9,793.2,1926.0,1867.4 +1.828996464059831,1.8292605841583935,0.0,1721.1,1093.0,1093.1,40.8,1729.1,1729.0 +1.8289831609973932,1.8285398770074506,0.1308996938995747,1808.4,965.3,149.2,25.6,1764.8,1823.6 +1.8290346407929696,1.8285565778313229,0.2617993877991494,2055.3,431.1,51.4,21.4,1950.6,2077.5 +1.8290880307312396,1.8285909968382055,0.39269908169872414,1474.8,251.3,31.9,32.1,2442.8,2404.1 +1.8291297754607463,1.8286385735901867,0.5235987755982988,1203.3,161.3,33.6,72.4,2104.5,1976.8 +1.8291658302192102,1.8287038133964888,0.6544984694978736,1084.0,106.7,47.6,231.8,1845.8,1787.1 +1.8291749430793431,1.8287495119531367,0.7853981633974483,1063.3,71.1,70.5,1698.7,1751.6,1750.7 +1.8291735722623728,1.82882648008433,0.916297857297023,233.3,47.7,106.5,1741.5,1786.4,1845.3 +1.8291626243292707,1.828866699492166,1.0471975511965976,73.7,34.2,161.5,1936.7,1974.6,2091.9 +1.8291487341578216,1.8288884640065644,1.1780972450961724,32.1,31.9,250.9,2371.2,1701.6,1480.9 +1.8290935573562177,1.8289412597407941,1.3089969389957472,21.4,51.4,430.5,2056.4,1343.7,1215.8 +1.8290491014843249,1.8289670838795173,1.4398966328953218,26.0,153.1,981.5,1806.2,1163.3,1105.0 +1.829061014601887,1.828965525435563,1.5707963267948966,41.1,1729.2,1728.9,1720.8,1093.5,1093.1 +1.8289969116858578,1.8289643286397668,1.7016960206944713,68.4,1762.6,1821.3,1763.7,982.0,153.2 +1.828941649943672,1.8289483610519517,1.832595714594046,114.3,1950.9,2078.5,1963.1,430.7,51.4 +1.8289538585039895,1.8289579891354604,1.9634954084936205,192.8,2444.2,2402.6,1633.1,251.0,31.9 +1.8289389248203403,1.8289446972858079,2.0943951023931953,350.2,2101.9,1974.7,1295.0,161.5,34.2 +1.8289088830937228,1.828888271148132,2.2252947962927703,831.6,1845.5,1786.5,1126.1,106.5,47.7 +1.8289050347978817,1.8288724985839646,2.356194490192345,1699.7,1751.0,1751.4,1062.4,70.6,71.1 +1.8289034068731016,1.828865963651171,2.4870941840919194,1785.0,1786.8,1845.7,828.2,47.7,106.8 +1.828917284641789,1.8288245929940041,2.6179938779914944,2031.4,1976.3,2087.1,348.3,33.7,161.3 +1.8289213554468389,1.8288143329697366,2.748893571891069,2407.2,1697.4,1477.6,192.5,32.5,252.5 +1.8289518116360086,1.8287882421793995,2.8797932657906435,1962.3,1342.4,1215.2,114.4,52.1,431.8 +1.8289725125194845,1.828779564382779,3.010692959690218,1764.2,1164.7,1105.6,68.9,152.4,974.8 +1.8289387256465703,1.7285136698840589,0.0,1621.3,1093.0,1092.9,140.9,1728.9,1729.1 +1.8289887344739035,1.7292580099928272,0.1308996938995747,1705.2,1106.1,532.7,129.0,1764.6,1824.1 +1.8289655148625663,1.7292504147538135,0.2617993877991494,1939.9,630.3,250.6,136.8,1950.3,2077.7 +1.8289365478298067,1.7292316885418395,0.39269908169872414,1474.4,392.3,172.9,173.5,2380.1,2263.0 +1.8289117571084248,1.729206257436661,0.5235987755982988,1344.4,276.7,149.0,271.3,1988.9,1861.2 +1.8289045154658985,1.7291891242109367,0.6544984694978736,1083.7,210.1,151.0,616.6,1742.6,1683.5 +1.828894016754291,1.7291491262167014,0.7853981633974483,1063.3,170.9,170.3,1698.9,1651.6,1651.2 +1.8288950427394435,1.7291449758465667,0.916297857297023,619.4,150.9,209.7,1741.7,1683.3,1742.2 +1.828905566709815,1.7291124571520897,1.0471975511965976,272.7,149.4,276.7,1936.8,1859.7,1986.6 +1.828928085960435,1.7290740068777104,1.1780972450961724,173.3,172.5,391.6,2371.3,1701.6,1480.9 +1.8289189784655944,1.7290816688244117,1.3089969389957472,136.7,250.1,629.2,1941.2,1343.4,1215.9 +1.8289267285370268,1.7290776428194796,1.4398966328953218,129.1,541.5,1369.9,1703.1,1163.1,1104.8 +1.8289933330725743,1.7290616837888728,1.5707963267948966,140.8,1729.1,1729.1,1621.1,1093.3,1093.2 +1.8289809171991744,1.7290603296029534,1.7016960206944713,171.6,1763.0,1821.7,1660.9,1105.6,541.4 +1.8289721981675164,1.729056557538755,1.832595714594046,229.5,1951.0,2078.7,1848.2,629.2,250.0 +1.8290237112164003,1.7290889610313611,1.9634954084936205,334.1,2381.6,2262.1,1632.6,391.6,172.5 +1.829038251874151,1.7291054979823945,2.0943951023931953,549.2,1986.6,1859.3,1294.7,276.7,149.4 +1.8290271769283082,1.7290826544729758,2.2252947962927703,1217.9,1742.0,1683.2,1126.0,209.7,150.9 +1.829031924444956,1.7291020223798101,2.356194490192345,1699.6,1651.5,1651.6,1062.5,170.3,170.8 +1.8290290431985539,1.7291291830691162,2.4870941840919194,1785.5,1684.0,1743.1,1083.9,150.9,210.0 +1.8290334535301074,1.7291172604686413,2.6179938779914944,2031.3,1861.1,1988.8,546.9,149.0,276.7 +1.8290214319389535,1.7291309769391177,2.748893571891069,2266.0,1697.3,1477.3,333.6,173.6,393.5 +1.8290317529570321,1.7291220059466192,2.8797932657906435,1846.8,1342.4,1215.1,229.7,251.1,630.9 +1.8290243516447635,1.7291257474159403,3.010692959690218,1661.1,1164.4,1105.5,172.2,538.8,1361.5 +1.8289673612853015,1.6288280032370142,0.0,1521.2,1092.9,1092.9,240.7,1728.9,1729.1 +1.8289867032466616,1.628826837205927,0.1308996938995747,1601.9,1105.9,916.2,232.5,1764.8,1824.0 +1.8290396253063799,1.6288422393222737,0.2617993877991494,1824.7,829.4,449.8,252.2,1950.0,2077.6 +1.829093197281756,1.6288749879374527,0.39269908169872414,1474.8,533.2,313.9,315.0,2341.1,2122.3 +1.8291351028415874,1.6289209522373158,0.5235987755982988,1203.0,392.2,264.5,470.3,1873.2,1745.6 +1.8291713965236462,1.6289848793363189,0.6544984694978736,1084.0,313.5,254.5,1002.0,1639.1,1580.0 +1.8291807171795866,1.6290296329675424,0.7853981633974483,1063.1,270.8,270.2,1699.0,1551.8,1551.2 +1.8291793027649812,1.62910583183344,0.916297857297023,1006.6,254.4,313.2,1741.7,1580.0,1638.3 +1.8291680522429468,1.6291452403730475,1.0471975511965976,472.5,264.9,392.3,1936.7,1744.1,1871.2 +1.829153722695991,1.6293860730010246,1.1780972450961724,315.1,313.7,532.8,2290.4,1701.8,1480.8 +1.8288085326224857,1.6289603601502733,1.3089969389957472,252.4,449.3,828.5,1825.5,1343.7,1216.0 +1.8288289885462743,1.6289503713134987,1.4398966328953218,232.7,931.0,1759.1,1599.4,1163.4,1105.0 +1.8289047041624233,1.6289330634495423,1.5707963267948966,240.9,1728.8,1728.5,1521.1,1093.4,1093.1 +1.8288990413044415,1.6289325913287116,1.7016960206944713,275.1,1762.6,1821.2,1556.9,1105.5,932.0 +1.8288956287103098,1.6289310523560179,1.832595714594046,345.1,1951.0,2078.3,1732.7,829.0,449.5 +1.8289513247731672,1.6289664503506296,1.9634954084936205,475.8,2340.1,2121.0,1633.2,533.0,313.9 +1.828968956332003,1.628986396410561,2.0943951023931953,748.9,1871.2,1744.1,1295.1,392.4,265.0 +1.8289599221182482,1.6289672311958308,2.2252947962927703,1604.7,1638.5,1579.6,1126.3,313.3,254.5 +1.8289658362471315,1.6289903480098218,2.356194490192345,1699.2,1551.2,1551.6,1062.3,270.4,270.9 +1.828963372747181,1.6290211298357393,2.4870941840919194,1785.0,1579.8,1638.8,1084.0,254.6,313.7 +1.828967392914842,1.6290126536463576,2.6179938779914944,2031.0,1745.2,1872.6,746.6,264.7,392.4 +1.8289543919529252,1.6290294755121941,2.748893571891069,2124.8,1697.7,1477.4,475.3,315.1,535.0 +1.8289630571848148,1.629023187924665,2.8797932657906435,1731.6,1343.0,1215.2,345.4,450.7,830.4 +1.828953499842545,1.6290290366131708,3.010692959690218,1557.5,1164.6,1105.5,275.8,925.5,1747.9 +1.8288932331149683,1.5287289511285298,0.0,1421.1,1093.2,1093.0,340.8,1728.9,1728.9 +1.8289103678932337,1.528728514842771,0.1308996938995747,1497.9,1106.1,1165.3,336.2,1764.5,1823.8 +1.8289613934980282,1.5287438789420693,0.2617993877991494,1709.0,1029.5,649.5,367.9,1949.9,2077.4 +1.829013417890993,1.5287760337568579,0.39269908169872414,1474.9,674.6,455.3,456.7,2200.4,1980.6 +1.8290541804419587,1.528820946876083,0.5235987755982988,1203.4,508.1,380.2,669.5,1757.9,1630.3 +1.8290899413230883,1.528883610152854,0.6544984694978736,1084.0,417.2,358.0,1387.3,1535.7,1476.5 +1.8290992340769436,1.5289269807512742,0.7853981633974483,1063.2,370.9,370.3,1698.9,1451.6,1451.0 +1.8290983834969003,1.529002026736686,0.916297857297023,1126.5,358.0,416.8,1741.6,1475.9,1534.8 +1.8290880846266024,1.5290406284131417,1.0471975511965976,672.5,380.6,507.8,1936.4,1628.0,1755.4 +1.82907486852427,1.5290609340399322,1.1780972450961724,457.1,454.9,673.9,2148.6,1807.4,1481.3 +1.8290204269788866,1.529112401335123,1.3089969389957472,368.1,648.8,1027.8,1709.3,1343.9,1216.2 +1.8289768396962658,1.5291369674491837,1.4398966328953218,336.2,1320.8,1763.6,1496.0,1163.4,1105.0 +1.8289898478972089,1.5291341449714222,1.5707963267948966,340.9,1729.1,1728.5,1421.2,1093.5,1093.0 +1.8289271021476714,1.529131884856177,1.7016960206944713,378.6,1763.0,1821.4,1453.2,1105.5,1163.9 +1.8288734523877412,1.5291152202826814,1.832595714594046,460.9,1950.8,2078.7,1616.6,1028.4,649.1 +1.828887457966131,1.5291245934237387,1.9634954084936205,617.6,2198.8,1979.6,1655.4,674.2,455.1 +1.828874287991458,1.529111575219161,2.0943951023931953,948.5,1755.5,1627.9,1294.9,507.9,380.6 +1.828845715811238,1.5290559858301243,2.2252947962927703,1742.2,1535.0,1476.3,1126.1,416.8,357.9 +1.8288428627164337,1.5290414828347976,2.356194490192345,1699.8,1451.2,1451.6,1062.4,370.5,371.0 +1.8288416267213141,1.5290363975824868,2.4870941840919194,1785.2,1476.5,1535.4,1083.8,358.1,417.3 +1.8288552008536239,1.5289964131664546,2.6179938779914944,2031.4,1629.7,1757.1,945.7,380.3,508.0 +1.8288584400442016,1.5289871870469245,2.748893571891069,1983.2,1810.3,1477.8,616.6,456.5,676.4 +1.8288876659051316,1.5289616047160661,2.8797932657906435,1615.7,1342.7,1215.1,461.0,650.2,1029.9 +1.8289011124715215,1.5289551003187585,3.010692959690218,1453.8,1164.4,1105.6,379.2,1312.4,1763.9 +1.8288686393002351,1.4286758388712428,0.0,1321.2,1092.9,1093.1,440.7,1729.2,1729.0 +1.8289457046630502,1.429307914638556,0.1308996938995747,1394.4,1106.1,1165.4,439.8,1764.8,1823.9 +1.8289224529207766,1.429300137036482,0.2617993877991494,1593.8,1215.5,848.6,483.5,1950.6,2078.3 +1.8288890541537115,1.4292783728814071,0.39269908169872414,1474.3,815.5,596.3,598.6,2057.8,1838.6 +1.8288599580885108,1.4292479197999564,0.5235987755982988,1202.9,623.4,495.9,869.2,1641.6,1513.9 +1.828849760448935,1.4292247830012914,0.6544984694978736,1083.9,520.5,461.5,1774.8,1432.0,1372.9 +1.8288381242238405,1.429178574643939,0.7853981633974483,1063.3,470.8,470.3,1699.1,1351.7,1351.1 +1.8288395187295705,1.4291685092328936,0.916297857297023,1126.6,461.5,520.2,1741.9,1373.0,1431.7 +1.8288517917850726,1.4291307476018846,1.0471975511965976,871.3,496.0,623.3,1937.3,1512.8,1640.6 +1.8288771476599834,1.4290881382259286,1.1780972450961724,598.3,596.0,815.2,2006.6,1701.0,1480.6 +1.8288714430744692,1.42909267363288,1.3089969389957472,483.5,848.2,1227.4,1593.9,1343.4,1215.6 +1.828882951935791,1.4290865042953176,1.4398966328953218,439.4,1711.9,1763.6,1369.8,1162.9,1104.7 +1.8289534686471474,1.429069670977949,1.5707963267948966,440.8,1729.1,1728.5,1321.4,1093.3,1093.1 +1.8289447101188903,1.4290683227124803,1.7016960206944713,481.9,1763.1,1821.3,1350.1,1105.7,1164.0 +1.8289393279133794,1.4290652411741442,1.832595714594046,576.4,1951.4,2079.0,1501.8,1215.6,847.5 +1.828993685462648,1.4290991759956266,1.9634954084936205,759.3,2057.5,1838.1,1673.9,814.7,595.7 +1.8290104010966775,1.4291177978366107,2.0943951023931953,1148.8,1639.9,1512.7,1295.0,623.2,495.9 +1.829000886997809,1.4290972183064776,2.2252947962927703,1741.8,1431.6,1372.5,1126.3,520.1,461.4 +1.829006491424348,1.4291190401561025,2.356194490192345,1699.6,1351.1,1351.6,1062.6,470.2,470.8 +1.8290036791758593,1.4291487092451882,2.4870941840919194,1785.2,1373.0,1432.5,1083.9,461.6,520.7 +1.829007649699348,1.4291389857354688,2.6179938779914944,2031.7,1514.1,1642.0,1177.5,495.9,623.7 +1.8289944884330174,1.4291546313650647,2.748893571891069,1841.4,1697.0,1477.1,757.6,598.0,817.9 +1.8290034115763385,1.4291470556700447,2.8797932657906435,1500.2,1342.2,1214.9,576.4,849.9,1229.8 +1.8289943641791109,1.4291516595686793,3.010692959690218,1350.3,1164.4,1105.6,482.6,1701.4,1763.4 +1.8289354883744728,1.328852328963415,0.0,1221.3,1093.1,1093.0,540.7,1728.7,1729.0 +1.8289534658078146,1.3288509750720627,0.1308996938995747,1291.1,1105.8,1165.6,543.2,1764.9,1824.3 +1.8290054089791423,1.3288659018193476,0.2617993877991494,1478.4,1215.3,1047.6,599.0,1950.3,2160.8 +1.8290583200754407,1.3288980011213198,0.39269908169872414,1474.4,956.5,737.3,739.9,1917.1,1697.8 +1.8290999009340851,1.3289432651319706,0.5235987755982988,1203.1,739.1,611.4,1068.4,1526.0,1398.6 +1.829136018507166,1.3290064490633116,0.6544984694978736,1210.1,624.1,565.0,1785.5,1328.3,1269.5 +1.829145469235258,1.3290506016951902,0.7853981633974483,1063.2,570.7,570.3,1698.8,1251.8,1251.3 +1.829144225832642,1.3291262381351896,0.916297857297023,1126.5,565.0,623.8,1741.7,1269.3,1328.1 +1.8291332397317595,1.3293515053869256,1.0471975511965976,1070.9,611.7,738.9,1937.0,1397.4,1524.9 +1.829113733622459,1.3291964410210622,1.1780972450961724,740.1,737.3,956.5,1864.7,1698.0,1480.6 +1.82906442845255,1.3292420218384917,1.3089969389957472,599.1,1047.6,1426.9,1478.3,1343.2,1215.9 +1.8290215934899277,1.3292650410751807,1.4398966328953218,543.1,1821.8,1763.3,1289.2,1163.3,1104.9 +1.8290338371859831,1.3292616814961769,1.5707963267948966,540.9,1728.8,1728.7,1221.1,1093.3,1093.2 +1.828970029125581,1.3292586171923308,1.7016960206944713,585.5,1763.0,1821.6,1246.5,1105.3,1164.1 +1.8289155616570392,1.3292407766764773,1.832595714594046,692.0,1951.5,2158.6,1385.9,1215.3,1046.8 +1.8289290019214264,1.3292491671434106,1.9634954084936205,901.1,1916.0,1697.2,1632.7,956.0,736.9 +1.8289154477496474,1.329235371386055,2.0943951023931953,1348.6,1524.3,1397.1,1294.2,738.8,611.6 +1.8288867239505933,1.3291789639818696,2.2252947962927703,1742.0,1305.5,1269.4,1126.1,623.6,565.0 +1.828883720889621,1.3291637740386872,2.356194490192345,1699.2,1251.3,1251.7,1062.3,570.3,570.8 +1.8288821530804076,1.329158150812689,2.4870941840919194,1785.4,1269.4,1328.7,1084.0,565.1,624.3 +1.8288955517641352,1.3291174424218752,2.6179938779914944,2136.9,1398.8,1526.7,1203.2,611.5,739.4 +1.8288984151473784,1.329107481444108,2.748893571891069,1699.9,1697.0,1477.0,899.1,739.4,959.5 +1.8289275926812134,1.329080961678774,2.8797932657906435,1384.7,1342.2,1215.0,691.8,1049.4,1429.5 +1.8289411931311872,1.3290734608344996,3.010692959690218,1247.0,1164.4,1105.5,586.1,1822.4,1763.6 +1.828909634992967,1.228794640398451,0.0,1121.4,1093.0,1093.2,640.6,1728.9,1729.1 +1.8289648901620406,1.2293414113187637,0.1308996938995747,1187.3,1106.0,1165.3,646.9,1764.5,1824.0 +1.8289336128056983,1.2293310930600394,0.2617993877991494,1362.5,1215.0,1247.4,714.6,1950.2,2077.7 +1.8288547085864757,1.2292845247320356,0.39269908169872414,1550.0,1097.9,878.8,881.8,1775.7,1556.7 +1.828843928546873,1.229273769782005,0.5235987755982988,1202.9,854.6,727.1,1268.0,1410.3,1282.8 +1.8288349635131718,1.229253081398084,0.6544984694978736,1083.9,727.8,668.7,1785.0,1224.7,1165.9 +1.8288221678681718,1.229202242463721,0.7853981633974483,1063.0,670.9,670.2,1698.7,1151.8,1151.2 +1.8288236939974039,1.2291855058554795,0.916297857297023,1126.6,668.4,727.2,1741.7,1165.8,1224.5 +1.8288379072336107,1.2291410263372549,1.0471975511965976,1294.6,727.1,854.4,1937.3,1282.1,1409.1 +1.8288667238774894,1.229092617322078,1.1780972450961724,881.7,878.4,1097.3,1723.2,1556.6,1603.8 +1.8288655011913872,1.2290927819042636,1.3089969389957472,714.5,1246.9,1626.3,1363.0,1343.6,1215.6 +1.8288821239807969,1.229083767509025,1.4398966328953218,646.3,1821.6,1763.2,1185.8,1163.2,1104.8 +1.8289579896553143,1.2290655676858606,1.5707963267948966,640.8,1728.9,1728.9,1121.3,1093.4,1093.1 +1.8289542715972205,1.2290642852743179,1.7016960206944713,688.9,1762.9,1821.1,1143.3,1105.5,1163.9 +1.8289533861884963,1.2290625193239055,1.832595714594046,807.6,1951.5,2079.0,1270.4,1215.2,1245.9 +1.829011504494047,1.2290987553905008,1.9634954084936205,1042.5,1775.0,1556.1,1563.4,1097.0,878.1 +1.829031004837739,1.229120321789384,2.0943951023931953,1547.9,1409.0,1281.7,1294.8,854.3,727.0 +1.8290232216086737,1.2291030455801997,2.2252947962927703,1741.8,1224.3,1165.6,1126.3,727.2,668.3 +1.8290295576427797,1.2291282757022945,2.356194490192345,1699.9,1151.2,1151.8,1062.5,670.3,670.8 +1.8290265710072715,1.229161158358516,2.4870941840919194,1785.5,1165.9,1225.0,1084.0,668.7,727.8 +1.8290295775344338,1.229154242331993,2.6179938779914944,2031.6,1283.3,1411.0,1203.0,727.1,854.8 +1.829014893342059,1.2291721494636199,2.748893571891069,1558.5,1559.5,1478.9,1040.3,880.8,1100.8 +1.8290219027250865,1.2291662092344038,2.8797932657906435,1243.7,1342.3,1214.8,807.3,1249.2,1628.8 +1.8290107660783328,1.2291718085248666,3.010692959690218,1143.2,1164.4,1105.5,689.6,1822.5,1763.4 +1.8289494129050585,1.1288706470139465,0.0,1021.5,1093.1,1093.0,740.9,1729.0,1729.2 +1.8289656543074668,1.1288691405423554,0.1308996938995747,1084.1,1105.8,1165.4,750.2,1765.0,1824.0 +1.8290163330404023,1.1288836088247836,0.2617993877991494,1247.1,1215.0,1342.8,830.1,2098.2,2005.6 +1.8290682916185206,1.1289150632855935,0.39269908169872414,1474.7,1238.9,1019.6,1023.4,1635.0,1415.6 +1.8291091667735697,1.1289595577596025,0.5235987755982988,1203.1,970.2,842.6,1466.7,1294.8,1167.4 +1.8291448408627098,1.129021932326404,0.6544984694978736,1083.8,831.2,772.1,1785.3,1121.4,1062.3 +1.8291540375726498,1.1290652345573138,0.7853981633974483,1063.3,770.7,770.3,1698.5,1051.7,1051.3 +1.8291527596414265,1.1291400711875066,0.916297857297023,1126.6,772.0,830.7,1741.7,1062.3,1121.2 +1.8291558896492102,1.1291329500016953,1.0471975511965976,1294.8,842.6,969.9,2018.4,1166.3,1293.8 +1.8291249715228501,1.1291802775599389,1.1780972450961724,1023.4,1019.6,1238.5,1581.8,1415.5,1480.6 +1.8290647612256514,1.1292358670579956,1.3089969389957472,830.3,1446.2,1825.1,1247.3,1343.5,1216.0 +1.8290215625841695,1.129258961055697,1.4398966328953218,749.8,1821.9,1763.4,1082.0,1163.2,1104.7 +1.829037745569461,1.1292545612296148,1.5707963267948966,740.8,1729.1,1728.7,1021.0,1093.4,1093.3 +1.828979020972754,1.1292515681161657,1.7016960206944713,792.5,1763.0,1821.0,1039.8,1105.5,1164.0 +1.8289295181006702,1.1292351865367432,1.832595714594046,923.2,2096.0,2003.7,1154.6,1215.1,1342.8 +1.828947232645673,1.1292462036581035,1.9634954084936205,1184.6,1633.9,1414.8,1421.4,1238.1,1019.2 +1.8289368732225606,1.1292357972105482,2.0943951023931953,1747.9,1293.3,1166.1,1294.7,969.6,842.4 +1.8289101483481551,1.1291831938909778,2.2252947962927703,1742.1,1120.9,1062.2,1126.0,830.6,771.9 +1.8289079987713837,1.1291719340913873,2.356194490192345,1699.5,1051.3,1052.0,1062.5,770.3,770.9 +1.8289062389645416,1.1291700250361605,2.4870941840919194,1785.5,1062.5,1121.4,1083.8,772.3,831.3 +1.8289357601887528,1.129077204079361,2.6179938779914944,2025.4,1167.7,1295.4,1202.9,842.6,970.5 +1.828915855516486,1.1291036142133948,2.748893571891069,1417.2,1417.8,1477.1,1181.8,1022.1,1242.2 +1.8289694785115556,1.129055667332541,2.8797932657906435,1128.3,1342.4,1215.1,922.9,1448.5,1828.2 +1.8289544269728224,1.1290632543868133,3.010692959690218,1039.8,1164.2,1105.6,793.2,1822.7,1763.9 +1.7289471862640815,1.8292453575967995,0.0,1721.2,1193.0,1192.9,40.8,1629.0,1628.9 +1.7289659957808643,1.8285581755849283,0.1308996938995747,1808.7,965.0,149.2,25.6,1660.9,1720.7 +1.7290246940897984,1.8285770797401213,0.2617993877991494,2055.7,431.0,51.4,21.4,1834.8,1962.4 +1.7290777082477984,1.8286112274095607,0.39269908169872414,1616.2,251.2,31.9,32.1,2291.7,2403.7 +1.7291175612910545,1.8286567190459562,0.5235987755982988,1319.0,161.3,59.0,72.4,2104.1,1976.7 +1.7291520475322657,1.8287189835533368,0.6544984694978736,1187.6,106.7,47.6,231.8,1845.9,1787.1 +1.72916042560731,1.8287613852723925,0.7853981633974483,1163.2,71.1,70.5,1598.8,1751.6,1750.8 +1.7291591576123881,1.8288351505965112,0.916297857297023,233.2,47.7,106.5,1638.1,1786.4,1845.7 +1.7288326323646575,1.8288639558455086,1.0471975511965976,73.3,34.1,161.6,1822.1,1975.5,2102.8 +1.728850498181515,1.8288353540376232,1.1780972450961724,31.9,31.7,251.1,2262.4,1842.0,1621.0 +1.7288447383613335,1.8288414039986307,1.3089969389957472,21.3,51.3,431.0,2055.3,1458.5,1330.9 +1.7288599096824393,1.828834493499125,1.4398966328953218,25.9,153.2,984.4,1805.8,1266.6,1208.2 +1.7289353103559675,1.8288182915206859,1.5707963267948966,41.1,1628.5,1628.8,1720.6,1193.3,1193.1 +1.728931012103025,1.828818640709999,1.7016960206944713,68.4,1659.7,1718.0,1764.0,977.9,151.9 +1.7289292759766388,1.828817853743125,1.832595714594046,114.3,1836.3,1964.0,1964.6,429.6,51.0 +1.72898618774723,1.8288549028583418,1.9634954084936205,192.9,2289.3,2401.1,1772.7,250.5,31.7 +1.7290043706779048,1.828876835051776,2.0943951023931953,350.7,2101.0,1974.0,1409.6,161.2,34.1 +1.7289957374979885,1.82885905986953,2.2252947962927703,834.2,1844.9,1786.2,1229.1,106.2,47.6 +1.7290017155118853,1.8288834570218588,2.356194490192345,1599.7,1750.9,1751.6,1162.4,70.4,71.1 +1.7289987571495185,1.8289156422160797,2.4870941840919194,1681.9,1787.0,1846.5,825.0,47.6,106.8 +1.7290026679719142,1.8289080659368473,2.6179938779914944,1916.6,1977.3,2105.3,347.4,33.6,161.5 +1.7289888548941479,1.8289259871376393,2.748893571891069,2374.0,1837.3,1617.1,192.1,32.5,252.8 +1.7289971354343252,1.8289205247782168,2.8797932657906435,1961.6,1457.6,1330.1,114.2,52.1,432.7 +1.7289870018965359,1.8289271640207898,3.010692959690218,1763.7,1267.6,1208.9,68.7,152.9,978.3 +1.7289264212314321,1.728626441823602,0.0,1621.4,1192.6,1193.4,140.8,1629.0,1628.6 +1.7289427630855816,1.728626784125149,0.1308996938995747,1705.4,1209.8,531.4,129.1,1661.3,1720.9 +1.7289930140254386,1.7286427224787606,0.2617993877991494,1941.1,629.3,250.3,136.9,1835.2,1962.8 +1.7290441465162822,1.728675207096015,0.39269908169872414,1614.8,391.9,172.9,173.8,2302.7,2260.9 +1.729084198639157,1.7287202592750062,0.5235987755982988,1363.2,276.6,149.1,272.0,1987.8,1860.4 +1.7291189394128283,1.7287825309904932,0.6544984694978736,1187.3,210.1,151.1,619.2,1742.3,1683.4 +1.7291278833299284,1.7288255535273322,0.7853981633974483,1163.5,170.9,170.5,1598.3,1651.5,1651.0 +1.7291266215929955,1.728899804381578,0.916297857297023,618.2,151.1,210.0,1638.2,1683.3,1742.3 +1.729116343377824,1.7289375897779746,1.0471975511965976,272.8,149.7,277.2,1847.1,1860.1,1987.5 +1.7291037034204115,1.7289577032177232,1.1780972450961724,173.5,173.0,392.4,2231.3,1842.3,1621.3 +1.7290498089375839,1.729008939895241,1.3089969389957472,136.9,250.9,630.6,1939.8,1458.5,1444.4 +1.7290067860004459,1.7290331839770108,1.4398966328953218,129.4,544.2,1375.1,1702.2,1266.3,1208.0 +1.7290203964348094,1.7290311367649613,1.5707963267948966,141.1,1628.8,1628.7,1620.8,1193.3,1193.2 +1.728957957914487,1.729029558902904,1.7016960206944713,172.0,1659.5,1718.1,1660.6,1209.2,540.8 +1.7289044720470228,1.7290131207513069,1.832595714594046,230.0,1836.0,1963.9,1848.8,628.9,250.2 +1.7289182994663186,1.7290231586372409,1.9634954084936205,334.8,2304.3,2260.7,1772.5,391.6,172.8 +1.7289046469626141,1.7290108618291211,2.0943951023931953,550.6,1985.3,1858.5,1409.7,276.8,149.7 +1.7288758248007916,1.7289553158667164,2.2252947962927703,1222.4,1741.1,1682.6,1229.4,209.8,151.2 +1.7288727747335197,1.7289407187955093,2.356194490192345,1599.5,1650.6,1651.5,1162.2,170.4,171.2 +1.7288711613206185,1.7289357249242265,2.4870941840919194,1682.2,1683.9,1742.6,1187.5,151.1,210.3 +1.728884999684792,1.7288955226482359,2.6179938779914944,1916.6,1861.7,1989.4,546.5,149.3,277.2 +1.728888069122801,1.728886462895939,2.748893571891069,2264.0,1837.4,1617.8,333.4,174.0,394.2 +1.7289176624552622,1.7288610316220656,2.8797932657906435,1846.1,1457.6,1330.0,229.8,251.8,632.3 +1.7289313686446472,1.7288548891275073,3.010692959690218,1660.6,1267.6,1208.9,172.2,540.9,1365.9 +1.7288995251565493,1.6285757620255898,0.0,1521.0,1192.9,1193.3,240.8,1628.9,1629.0 +1.7289444751814955,1.629281147155995,0.1308996938995747,1602.1,1209.6,915.6,232.6,1661.2,1720.7 +1.7289178673575945,1.6292723687043131,0.2617993877991494,1824.9,828.9,449.7,252.5,1835.1,1962.2 +1.7288863000115224,1.6292517619085403,0.39269908169872414,1615.2,533.1,314.0,315.3,2239.6,2120.7 +1.728859795763695,1.6292240573715153,0.5235987755982988,1318.8,392.1,264.5,470.8,1872.7,1745.2 +1.7288514760936586,1.629204400681719,0.6544984694978736,1187.3,313.5,254.5,1003.7,1639.1,1579.9 +1.7288408166096423,1.629162026557386,0.7853981633974483,1163.2,270.8,270.3,1598.7,1551.4,1551.5 +1.7288421454093545,1.629155612499412,0.916297857297023,1005.2,254.4,313.3,1638.1,1579.7,1638.8 +1.7288534871679704,1.629121155628807,1.0471975511965976,472.0,265.0,392.4,1821.9,1744.1,1871.7 +1.7288772490711608,1.629081372329898,1.1780972450961724,314.9,313.8,533.0,2230.9,1949.4,1622.0 +1.7288694521546326,1.6290880011271383,1.3089969389957472,252.2,449.7,829.2,1825.0,1458.9,1331.4 +1.7288785613684912,1.629083155637315,1.4398966328953218,232.5,932.4,1660.2,1599.6,1266.4,1208.2 +1.7289465710953893,1.62906704889718,1.5707963267948966,240.8,1629.2,1628.6,1521.3,1193.1,1193.2 +1.7289354288828407,1.6290657094422767,1.7016960206944713,275.1,1659.7,1718.1,1557.3,1209.0,929.7 +1.7289279259582104,1.6290619706462834,1.832595714594046,345.2,1835.9,1963.5,1733.0,827.6,448.9 +1.7289804967430553,1.6290948320410914,1.9634954084936205,476.0,2240.7,2120.0,1798.0,532.6,313.5 +1.7289958752171029,1.6291120935367303,2.0943951023931953,749.5,1870.7,1743.8,1410.2,392.0,264.9 +1.728985567469258,1.6290899206742715,2.2252947962927703,1607.7,1638.5,1579.6,1229.6,313.1,254.4 +1.7289908604417499,1.6291101083871253,2.356194490192345,1599.5,1551.1,1551.8,1162.4,270.2,270.9 +1.728988132074207,1.629138281467522,2.4870941840919194,1682.1,1580.1,1639.3,1187.7,254.5,313.7 +1.7289926190983806,1.6291272288042131,2.6179938779914944,1915.8,1746.0,1873.8,745.5,264.7,392.4 +1.7289801599930754,1.6291418521788383,2.748893571891069,2123.7,1952.5,1618.5,474.7,315.2,535.2 +1.7289900159594094,1.629133535859895,2.8797932657906435,1731.3,1457.8,1330.5,345.1,450.8,831.1 +1.7289819592340805,1.629137706441329,3.010692959690218,1557.3,1267.8,1209.1,275.6,927.2,1660.2 +1.7289242988597853,1.5288392159113733,0.0,1421.4,1192.9,1193.1,340.6,1628.7,1629.0 +1.7289430825557879,1.528837970303269,0.1308996938995747,1498.4,1209.6,1269.3,336.1,1661.2,1720.4 +1.7289956045921473,1.5288531376196968,0.2617993877991494,1709.5,1028.1,648.8,367.8,1835.0,1962.3 +1.729048945348029,1.5288855513890092,0.39269908169872414,1615.6,674.2,455.1,456.8,2199.1,1979.6 +1.729090868938275,1.528931189238655,0.5235987755982988,1318.6,507.7,380.1,670.0,1757.2,1629.5 +1.7291271676305509,1.528994731373627,0.6544984694978736,1187.5,416.9,358.0,1389.6,1535.3,1476.6 +1.7291367740233536,1.5290392951130096,0.7853981633974483,1163.3,370.8,370.2,1598.3,1452.1,1451.1 +1.7291355492181806,1.5291152869562115,0.916297857297023,1230.2,357.9,416.8,1638.2,1476.3,1535.1 +1.7291245149599754,1.5291545804480364,1.0471975511965976,671.6,380.5,507.9,1821.7,1628.5,1756.0 +1.72911044758112,1.5291754581204955,1.1780972450961724,456.6,455.0,674.3,2147.9,1843.1,1622.0 +1.7290549785746605,1.5292269001058578,1.3089969389957472,367.8,649.0,1028.7,1709.2,1459.0,1331.1 +1.729010455749569,1.5292508394687596,1.4398966328953218,336.0,1322.9,1659.9,1496.0,1266.7,1208.2 +1.729022847001551,1.5292475704403217,1.5707963267948966,340.9,1628.9,1628.7,1420.9,1193.4,1193.1 +1.7289597563517334,1.5292445976094906,1.7016960206944713,378.6,1659.4,1718.2,1453.9,1209.1,1267.3 +1.728906119093108,1.5292269813382164,1.832595714594046,460.9,1836.0,1963.4,1617.1,1027.2,648.1 +1.7289202893649236,1.529235858486912,1.9634954084936205,617.8,2198.4,1979.1,1815.8,673.7,454.7 +1.7289072769793021,1.5292226993737805,2.0943951023931953,949.3,1755.3,1627.9,1410.1,507.6,380.4 +1.7288789540941496,1.5291669200024514,2.2252947962927703,1638.3,1534.9,1476.0,1229.4,416.6,357.8 +1.7288761766167824,1.5291523939015952,2.356194490192345,1599.5,1451.0,1451.6,1162.6,370.2,370.8 +1.7288746209600616,1.529147464284161,2.4870941840919194,1681.7,1477.0,1535.9,1187.3,358.1,417.1 +1.7288879501049135,1.5291073530575081,2.6179938779914944,1916.3,1630.1,1757.8,944.7,380.2,508.1 +1.728890526010633,1.5290979590192906,2.748893571891069,1982.5,1838.3,1618.1,616.2,456.5,676.6 +1.7289193785729762,1.5290718762878999,2.8797932657906435,1615.4,1457.7,1330.7,460.7,650.4,1030.6 +1.7289325640766238,1.5290646950025646,3.010692959690218,1453.8,1268.0,1209.1,379.1,1314.8,1660.1 +1.7289005160881628,1.428785446808687,0.0,1321.3,1193.0,1193.0,440.7,1629.2,1629.0 +1.7289555636046936,1.429338217394077,0.1308996938995747,1394.8,1209.5,1269.0,439.8,1661.1,1743.2 +1.728924620866978,1.4293279915870005,0.2617993877991494,1593.5,1227.9,848.5,483.5,1834.7,1962.7 +1.7288870249729473,1.4293035262540827,0.39269908169872414,1615.6,815.6,596.3,598.7,2058.1,1838.8 +1.7288553645353364,1.429270254694954,0.5235987755982988,1318.9,623.4,495.8,869.2,1641.7,1514.2 +1.7288436548446406,1.4292442491808983,0.6544984694978736,1187.3,520.7,461.6,1681.6,1431.9,1372.8 +1.7288313589649744,1.4291951758924286,0.7853981633974483,1163.2,470.8,470.3,1598.8,1351.6,1351.1 +1.7288328159701785,1.4291824255701129,0.916297857297023,1229.8,461.4,520.3,1638.4,1372.8,1431.4 +1.7288457761633305,1.4291422606568314,1.0471975511965976,871.2,496.0,623.4,1821.4,1513.3,1640.4 +1.728872313650792,1.4290976642168531,1.1780972450961724,598.2,596.1,815.3,2006.5,1838.9,1622.2 +1.7288681074700627,1.4291006953733287,1.3089969389957472,483.4,848.2,1227.6,1593.7,1459.0,1331.2 +1.7288813233233322,1.4290935116837031,1.4398966328953218,439.4,1711.8,1660.1,1392.4,1266.6,1208.3 +1.7289536409613815,1.4290761873489117,1.5707963267948966,440.8,1628.8,1628.9,1321.3,1193.2,1193.1 +1.7289465914551707,1.4290748152270396,1.7016960206944713,482.0,1659.6,1718.2,1350.2,1209.1,1267.4 +1.7289427569217772,1.4290721141709837,1.832595714594046,576.4,1835.7,1963.6,1501.8,1226.2,847.2 +1.7289984232177849,1.429233026569821,1.9634954084936205,759.3,2057.2,1838.3,1773.6,814.7,595.7 +1.7290221507355266,1.4291305118073894,2.0943951023931953,1148.7,1639.7,1512.8,1410.1,623.1,495.9 +1.7290110129727985,1.4291068751418217,2.2252947962927703,1637.9,1431.6,1372.7,1229.6,520.1,461.3 +1.7290167214438128,1.4291291018934256,2.356194490192345,1599.2,1351.5,1351.9,1162.4,470.2,470.8 +1.7290138346449526,1.429160322900259,2.4870941840919194,1682.1,1372.9,1432.2,1187.4,461.5,520.7 +1.7290172544053906,1.4291522952777416,2.6179938779914944,1915.7,1514.7,1642.2,1143.9,495.9,623.6 +1.7290030930888831,1.4291694288704802,2.748893571891069,1841.4,1838.2,1618.3,757.6,598.0,818.1 +1.729010750929535,1.4291629463778097,2.8797932657906435,1500.0,1458.1,1330.4,576.3,850.0,1230.0 +1.729000297122015,1.4291682167388369,3.010692959690218,1350.4,1267.6,1209.1,482.5,1701.7,1660.3 +1.728939777081057,1.328867632632496,0.0,1221.4,1193.1,1193.1,540.6,1629.0,1628.7 +1.7289565870837156,1.3288661547363452,0.1308996938995747,1291.3,1209.5,1269.0,543.2,1660.9,1720.4 +1.7290076859870664,1.328880750505343,0.2617993877991494,1478.5,1331.0,1047.6,599.0,1834.8,2117.2 +1.7290599731826746,1.328912393529457,0.39269908169872414,1691.9,956.6,737.4,740.2,1917.2,1697.7 +1.7291011184713718,1.328957129600125,0.5235987755982988,1318.5,739.0,611.3,1068.2,1526.3,1398.5 +1.7291369584833747,1.3290197555653551,0.6544984694978736,1187.4,624.1,565.1,1681.7,1328.7,1269.7 +1.7291462850929116,1.3290633531711864,0.7853981633974483,1163.4,570.8,570.3,1598.7,1251.8,1251.3 +1.7291450362588539,1.329138461277219,0.916297857297023,1230.2,564.9,623.7,1638.3,1269.6,1328.2 +1.7291341548948924,1.3291769366152986,1.0471975511965976,1070.9,611.6,738.9,1821.7,1397.4,1524.7 +1.7291203727179607,1.3291970354179812,1.1780972450961724,740.0,737.2,956.3,1864.9,1697.8,1744.7 +1.7290653445097224,1.3292478650183357,1.3089969389957472,599.0,1047.7,1427.0,1478.4,1459.0,1331.5 +1.7290213771816556,1.3292713867903516,1.4398966328953218,542.9,1718.2,1659.9,1288.9,1266.7,1208.3 +1.729034388928588,1.3292677720270252,1.5707963267948966,540.9,1628.8,1628.6,1221.3,1193.2,1193.2 +1.7289719407069228,1.3292646734833862,1.7016960206944713,585.6,1659.4,1717.8,1246.7,1209.0,1267.5 +1.7289189044901863,1.3292471803859565,1.832595714594046,692.0,1835.6,2115.1,1386.0,1330.6,1046.8 +1.7289336128196955,1.329256295406265,1.9634954084936205,901.2,1916.3,1697.1,1704.9,956.1,737.0 +1.7289210209694434,1.3292434772807167,2.0943951023931953,1348.5,1524.6,1396.9,1410.1,738.7,611.5 +1.7288929198616694,1.3291881717512282,2.2252947962927703,1638.6,1327.8,1269.5,1229.5,623.6,564.9 +1.728890192929002,1.329174138864559,2.356194490192345,1599.7,1251.2,1251.8,1162.5,570.3,570.9 +1.7288885653062085,1.329169628226984,2.4870941840919194,1681.7,1269.4,1328.7,1187.3,565.2,624.4 +1.7289016387314415,1.3291298811436527,2.6179938779914944,1916.2,1399.2,1526.8,1318.7,611.5,739.2 +1.728903948459251,1.3291206992532216,2.748893571891069,1699.9,1700.8,1620.1,899.0,739.4,959.5 +1.7289324519332752,1.3290947229825192,2.8797932657906435,1384.6,1457.9,1330.8,691.6,1049.6,1429.5 +1.7289453170807263,1.3290875324520766,3.010692959690218,1246.9,1268.0,1209.1,586.1,1718.8,1660.1 +1.728912927487925,1.2288080726204251,0.0,1121.3,1192.8,1192.9,640.7,1628.8,1629.0 +1.7289663815046106,1.2293440736277774,0.1308996938995747,1187.4,1209.3,1268.8,646.9,1661.2,1720.4 +1.728934428323171,1.2293335410226782,0.2617993877991494,1362.4,1330.8,1247.4,714.6,1834.6,1962.2 +1.7288960797532282,1.2293086333057062,0.39269908169872414,1615.6,1097.9,878.7,881.9,1776.1,1556.6 +1.7288638449069318,1.2292748139745755,0.5235987755982988,1318.5,854.7,727.1,1267.7,1410.8,1282.7 +1.7288517759824475,1.2292482258001822,0.6544984694978736,1187.5,727.7,668.6,1681.6,1224.8,1166.0 +1.7288392507075763,1.229198510059447,0.7853981633974483,1163.1,670.8,670.3,1598.9,1151.8,1151.0 +1.728840400825548,1.2292312430886403,0.916297857297023,1230.2,668.5,727.4,1638.3,1165.6,1224.9 +1.7288626270318312,1.2291606370008834,1.0471975511965976,1270.5,727.2,854.3,1821.4,1282.0,1409.3 +1.728892982781104,1.2291098425282403,1.1780972450961724,881.7,878.2,1097.4,1723.2,1556.4,1622.1 +1.7288884227669192,1.2291131522272756,1.3089969389957472,714.6,1246.7,1626.1,1362.8,1459.0,1331.4 +1.728899200775355,1.2291072687821463,1.4398966328953218,646.4,1718.3,1659.9,1185.8,1266.5,1208.1 +1.728968254734781,1.2290906331347626,1.5707963267948966,640.8,1629.1,1628.8,1121.4,1193.2,1193.1 +1.7289579379022242,1.2290891345016095,1.7016960206944713,688.8,1659.2,1718.1,1143.5,1209.0,1267.8 +1.728951119824297,1.229085574842971,1.832595714594046,807.6,1835.6,1963.6,1270.2,1330.6,1246.0 +1.7290042803499648,1.2291187072392216,1.9634954084936205,1043.0,1774.8,1556.2,1563.4,1097.0,877.9 +1.7290201103349556,1.2291363361293488,2.0943951023931953,1548.1,1408.9,1281.6,1410.3,854.2,726.9 +1.729009996741133,1.2291147096460895,2.2252947962927703,1638.2,1224.5,1165.9,1229.5,727.2,668.4 +1.7290152866527961,1.2291354469332547,2.356194490192345,1599.8,1151.2,1151.7,1162.3,670.2,670.9 +1.729012164479904,1.229211088986635,2.4870941840919194,1681.8,1165.8,1225.1,1187.6,668.7,727.9 +1.7290256880197266,1.2291698651581997,2.6179938779914944,1966.8,1283.2,1410.9,1318.4,727.2,854.8 +1.7290166021376028,1.2291789233781898,2.748893571891069,1558.6,1559.2,1618.5,1040.5,880.7,1100.9 +1.7290253498079367,1.2291713616143092,2.8797932657906435,1269.1,1457.9,1330.8,807.3,1248.8,1628.9 +1.7290140637324505,1.2291770365357986,3.010692959690218,1143.4,1267.8,1209.0,689.6,1718.9,1659.8 +1.7289141943527622,1.1288653444669268,0.0,1021.4,1193.3,1192.8,740.6,1629.2,1628.7 +1.728955709073176,1.1288648248548463,0.1308996938995747,1084.1,1209.7,1269.0,750.3,1661.2,1720.4 +1.7290143026760412,1.1288817405829272,0.2617993877991494,1247.3,1330.9,1458.4,830.1,1834.7,1961.6 +1.7290686083166793,1.128914668025404,0.39269908169872414,1581.1,1239.0,1019.7,1023.5,1635.0,1415.5 +1.7291101540906864,1.1289598829032355,0.5235987755982988,1318.9,970.2,842.4,1466.8,1295.3,1167.4 +1.7291460168432191,1.1290226116359794,0.6544984694978736,1187.5,831.2,772.0,1681.4,1121.3,1062.4 +1.7291552571158721,1.1290661169139131,0.7853981633974483,1163.2,770.7,770.1,1598.7,1052.0,1051.3 +1.729153970448987,1.1291410928542884,0.916297857297023,1230.1,771.9,830.8,1638.2,1062.3,1120.9 +1.7291430858986345,1.1291794161650128,1.0471975511965976,1410.3,842.6,970.3,1821.3,1166.4,1293.8 +1.7291293261974758,1.129199329681953,1.1780972450961724,1023.5,1019.4,1238.5,1581.6,1415.4,1622.2 +1.729074378529496,1.1292500218613488,1.3089969389957472,830.4,1446.1,1825.3,1247.4,1459.2,1331.6 +1.7290305294832906,1.1292734739144987,1.4398966328953218,749.9,1718.5,1660.1,1081.8,1266.5,1208.2 +1.7290436724564426,1.129269771468627,1.5707963267948966,740.9,1628.9,1628.8,1021.3,1193.2,1193.3 +1.7289813625967232,1.1292666594479064,1.7016960206944713,792.4,1659.6,1717.9,1039.7,1208.9,1267.6 +1.7289284410331867,1.1292492433704195,1.832595714594046,923.1,1835.7,1960.0,1154.7,1330.7,1458.3 +1.7289432425688127,1.1292584358176923,1.9634954084936205,1184.8,1633.7,1415.0,1421.3,1238.2,1019.2 +1.728930712502076,1.1292457001420202,2.0943951023931953,1747.8,1293.3,1166.0,1410.0,969.8,842.6 +1.7289026054527843,1.129190518702743,2.2252947962927703,1638.3,1121.1,1062.2,1229.6,830.6,771.9 +1.728899833667648,1.1291765939529086,2.356194490192345,1599.5,1051.3,1051.8,1162.4,770.2,770.7 +1.7288981590107078,1.1291721419409777,2.4870941840919194,1681.9,1062.5,1121.4,1187.3,772.2,831.3 +1.728911135212256,1.1291324455637906,2.6179938779914944,1916.0,1167.5,1295.3,1318.6,842.7,970.6 +1.7289133967259855,1.1291232609666035,2.748893571891069,1417.3,1417.6,1618.6,1182.0,1022.2,1242.1 +1.7289418286159912,1.1290972741718535,2.8797932657906435,1153.6,1458.0,1330.5,923.0,1448.4,1828.3 +1.7289546480580327,1.1290900604297978,3.010692959690218,1039.7,1268.0,1209.0,793.1,1718.8,1660.4 +1.6289483436737064,1.8292489313910312,0.0,1721.5,1293.0,1292.8,40.8,1528.8,1528.7 +1.6289664235680588,1.8285533257786208,0.1308996938995747,1808.8,965.1,149.1,25.6,1557.6,1616.9 +1.6290255714268016,1.8285723780867689,0.2617993877991494,2055.3,431.1,51.4,21.4,1719.0,1846.4 +1.6289894265375873,1.8288531444245117,0.39269908169872414,1756.5,251.4,32.2,32.4,2097.4,2318.7 +1.6290616505414293,1.8278566785062165,0.5235987755982988,1437.3,164.3,35.3,74.4,2108.3,1979.2 +1.6293707512085078,1.8275293452981698,0.6544984694978736,1294.0,109.0,48.0,225.5,1849.7,1789.1 +1.628722991141441,1.8282261396568067,0.7853981633974483,1263.5,71.1,70.9,1498.5,1751.3,1751.1 +1.6287152639284386,1.8284606733818058,0.916297857297023,231.9,47.8,107.0,1534.9,1786.8,1846.6 +1.6287010715817625,1.8285124568520437,1.0471975511965976,73.7,34.4,162.2,1707.6,1976.4,2103.6 +1.628719539883865,1.8284861210239325,1.1780972450961724,63.4,32.2,252.0,2092.2,1981.7,1761.6 +1.6289826227871538,1.8287422997191956,1.3089969389957472,21.7,52.0,431.6,2055.0,1574.2,1446.7 +1.6292025081653856,1.8278109188858676,1.4398966328953218,27.5,158.9,987.7,1804.5,1369.8,1311.4 +1.6293283449836702,1.8283238127768888,1.5707963267948966,41.5,1529.0,1529.4,1720.6,1292.5,1292.9 +1.6293075411766145,1.828325915111732,1.7016960206944713,68.9,1557.1,1616.0,1764.3,972.3,151.6 +1.6293272926053368,1.8283335826508318,1.832595714594046,115.0,1722.9,1850.9,1965.6,428.5,95.0 +1.6293753499027102,1.8287436782430406,1.9634954084936205,194.5,2107.0,2329.6,1907.0,249.5,32.1 +1.6294739918725565,1.8269917679936702,2.0943951023931953,354.5,2098.4,1971.6,1524.0,163.3,36.3 +1.629093049122248,1.8280188953118395,2.2252947962927703,834.3,1844.7,1785.7,1333.2,107.2,48.4 +1.6291431053488397,1.8282491303434574,2.356194490192345,1499.6,1750.1,1750.6,1262.6,71.3,71.9 +1.62914352898606,1.8281782752700866,2.4870941840919194,1578.3,1785.8,1844.9,830.8,48.5,107.5 +1.6291538113829627,1.828152495652291,2.6179938779914944,1800.2,1975.6,2103.1,349.7,34.5,162.2 +1.6291384983281616,1.8281771552250636,2.748893571891069,2253.3,1980.5,1760.4,193.6,33.6,253.5 +1.6290561291942462,1.8282816364991685,2.8797932657906435,1960.6,1572.8,1445.5,115.1,53.7,434.2 +1.6292456802087392,1.8275338395528316,3.010692959690218,1762.1,1371.1,1312.1,70.7,160.0,984.5 +1.6291893310048358,1.7279314778549786,0.0,1620.6,1292.8,1292.9,141.6,1529.2,1529.3 +1.6291956013300846,1.7279371667503045,0.1308996938995747,1704.9,1313.2,534.0,129.9,1558.0,1617.5 +1.6292324002882168,1.7279543523056256,0.2617993877991494,1940.3,630.7,251.8,137.8,1719.9,1847.7 +1.629269800938007,1.727001371636952,0.39269908169872414,1755.4,392.9,174.0,175.0,2148.0,2259.8 +1.6293111213750997,1.728041488045879,0.5235987755982988,1433.5,277.5,150.0,273.6,1986.9,1859.1 +1.6293294003570877,1.7280806927653354,0.6544984694978736,1290.5,210.8,152.0,622.4,1741.0,1682.3 +1.6293321257986935,1.7281086617820574,0.7853981633974483,1262.9,171.6,171.3,1499.0,1650.6,1650.3 +1.6293296703499731,1.7281709878075568,0.916297857297023,620.8,151.8,210.8,1535.0,1682.6,1741.6 +1.6293221045358615,1.7281988425434867,1.0471975511965976,274.1,150.6,278.1,1707.1,1859.0,1986.8 +1.6293152827444548,1.728211637545893,1.1780972450961724,174.5,174.1,393.5,2121.8,2090.5,1762.5 +1.6292690049519236,1.7282587340904572,1.3089969389957472,137.7,252.4,632.4,1938.6,1573.4,1446.2 +1.6292342207483488,1.728282183659301,1.4398966328953218,130.1,547.4,1378.8,1701.3,1369.6,1311.0 +1.6292554280838019,1.7282826497653154,1.5707963267948966,141.9,1529.0,1529.1,1620.1,1292.9,1292.9 +1.6291986555296583,1.7282858975571043,1.7016960206944713,172.7,1556.8,1615.0,1659.8,1312.3,543.4 +1.6291484767402666,1.72827545641778,1.832595714594046,230.8,1721.1,1848.8,1847.7,630.1,251.6 +1.6291632196155712,1.7282916753822808,1.9634954084936205,335.9,2146.6,2258.5,1939.4,392.5,173.8 +1.6291485477577856,1.7282846833737806,2.0943951023931953,552.4,1984.5,1857.5,1524.4,277.5,175.9 +1.6291176950452344,1.7282329097489955,2.2252947962927703,1226.2,1740.5,1682.0,1332.4,210.5,151.9 +1.6291124923248381,1.7282205752099793,2.356194490192345,1499.9,1650.5,1650.8,1262.2,171.1,171.9 +1.6291093201320992,1.7282167733616796,2.4870941840919194,1579.0,1682.9,1742.3,1290.8,151.9,211.1 +1.6291227012024116,1.728177308145115,2.6179938779914944,1801.2,1860.7,1988.9,547.7,150.1,278.0 +1.6291262121985095,1.7281693696429976,2.748893571891069,2231.7,2094.2,1758.0,334.4,175.0,395.4 +1.6291568421438776,1.728145955337226,2.8797932657906435,1845.7,1572.8,1445.2,230.6,253.3,633.8 +1.6291714055770927,1.728142976702293,3.010692959690218,1659.7,1370.7,1312.2,172.9,544.0,1369.7 +1.6291392458125113,1.6278642777016277,0.0,1520.8,1292.7,1292.9,241.5,1529.0,1529.2 +1.6291012922816788,1.6288375521897105,0.1308996938995747,1600.8,1312.9,920.2,233.0,1557.5,1616.6 +1.6290684584483148,1.6288291321246002,0.2617993877991494,1823.5,831.3,451.1,252.7,1718.8,1846.3 +1.6290436414024594,1.6288156819522681,0.39269908169872414,1757.7,534.3,314.7,315.5,2158.5,2121.6 +1.6290243973370924,1.6287992714410229,0.5235987755982988,1434.7,392.9,265.1,470.7,1873.2,1745.5 +1.6290209940597336,1.628792641052695,0.6544984694978736,1290.8,314.1,254.9,1001.5,1639.1,1579.5 +1.629011654186207,1.6287630571992557,0.7853981633974483,1263.1,271.3,270.6,1499.2,1551.4,1550.9 +1.6290119336565851,1.628768661763698,0.916297857297023,1010.2,254.8,313.5,1534.5,1579.3,1638.2 +1.6290199885511263,1.628744869800007,1.0471975511965976,473.6,265.4,392.4,1705.5,1742.8,1870.0 +1.629038628068668,1.6287136838858702,1.1780972450961724,315.8,314.0,532.9,2088.1,1986.2,1764.9 +1.6290248592345105,1.6287275391097706,1.3089969389957472,252.7,449.6,828.4,1825.6,1575.2,1447.3 +1.6290271366771139,1.628728740165978,1.4398966328953218,232.9,930.7,1556.9,1599.3,1370.3,1311.6 +1.6290874382236706,1.6287162072635732,1.5707963267948966,241.1,1529.0,1528.7,1521.0,1293.1,1292.9 +1.6290684384628387,1.6287169475719225,1.7016960206944713,275.3,1555.9,1614.1,1556.6,1312.2,934.5 +1.629052935918112,1.6287139156633843,1.832595714594046,345.3,1719.6,1847.0,1731.7,830.1,450.4 +1.6290979745842291,1.6287449339965607,1.9634954084936205,475.9,2160.5,2121.5,1955.8,533.6,314.4 +1.6291070441260123,1.6287583117986681,2.0943951023931953,748.9,1871.3,1744.0,1526.3,392.9,265.4 +1.6290917564746048,1.6287312883379748,2.2252947962927703,1535.2,1638.7,1579.7,1332.9,313.6,254.8 +1.6290940954064632,1.6287455336508037,2.356194490192345,1499.6,1550.9,1551.4,1262.6,270.7,271.1 +1.6290910208254354,1.6287672023015238,2.4870941840919194,1578.1,1579.4,1638.5,1290.8,254.8,313.8 +1.6290968624275324,1.6287505662183892,2.6179938779914944,1799.8,1744.8,1872.4,747.6,265.0,392.5 +1.629088181724517,1.6287605478879061,2.748893571891069,2125.0,1981.2,1760.9,475.7,315.4,535.1 +1.6291024821113578,1.6287495716821296,2.8797932657906435,1731.6,1574.1,1446.5,345.8,451.0,830.2 +1.6290993499993534,1.6287530217086514,3.010692959690218,1557.1,1371.5,1312.7,276.1,925.4,1556.9 +1.6290463384803653,1.5284589184172674,0.0,1420.8,1292.9,1292.8,341.0,1528.9,1529.0 +1.6290682813137052,1.5284605563615972,0.1308996938995747,1497.4,1312.9,1372.3,336.4,1557.7,1616.2 +1.6291223929241716,1.52847879780139,0.2617993877991494,1708.1,1030.7,650.5,368.2,1718.9,1845.9 +1.6291760019807284,1.5285141617436562,0.39269908169872414,1757.9,675.4,455.9,456.9,2096.6,1980.8 +1.6292170643320747,1.5285621078208513,0.5235987755982988,1434.7,508.5,380.6,669.7,1757.7,1630.0 +1.6292524285700358,1.5286274023285538,0.6544984694978736,1291.0,417.6,358.4,1386.3,1535.7,1476.2 +1.6292607022818837,1.5286726642940316,0.7853981633974483,1263.0,371.2,370.6,1499.0,1451.4,1451.2 +1.6292588981614198,1.5287491101918778,0.916297857297023,1333.2,358.3,417.0,1534.5,1475.7,1534.3 +1.6292478036565854,1.5287887112059542,1.0471975511965976,673.4,380.9,507.9,1705.4,1627.5,1754.6 +1.6292339951987018,1.5288096972225884,1.1780972450961724,457.6,455.2,674.0,2087.8,1978.1,1765.3 +1.6291792771805635,1.5288620729056341,1.3089969389957472,368.5,648.8,1027.6,1710.2,1575.1,1447.7 +1.6291354640614475,1.5288879768265626,1.4398966328953218,336.5,1319.9,1556.8,1495.9,1370.4,1311.7 +1.6291479750565072,1.5288864729695413,1.5707963267948966,341.1,1529.2,1528.6,1420.5,1293.4,1292.9 +1.6290843458352355,1.528885772080329,1.7016960206944713,378.8,1555.9,1614.2,1453.1,1312.0,1370.6 +1.6290292362646983,1.5288707433054811,1.832595714594046,461.0,1719.4,1847.1,1616.0,1029.3,650.0 +1.6290413252836098,1.5288811235137862,1.9634954084936205,617.7,2097.7,1980.0,1916.1,674.9,455.5 +1.62902604583019,1.5288683681464907,2.0943951023931953,948.5,1755.8,1628.4,1526.1,508.5,381.0 +1.628995335563676,1.5288124717723242,2.2252947962927703,1535.3,1535.2,1476.2,1333.1,417.2,358.3 +1.6289907747964076,1.52879691762037,2.356194490192345,1499.6,1451.1,1451.3,1262.5,370.7,371.2 +1.6289886902206714,1.5287901978306209,2.4870941840919194,1577.9,1476.2,1534.9,1290.4,358.3,417.3 +1.6290021052546824,1.5287486220284627,2.6179938779914944,1799.6,1629.0,1756.6,946.9,380.5,508.0 +1.629006255441877,1.5287379857123318,2.748893571891069,1983.4,1981.0,1760.8,617.3,456.7,676.4 +1.6290368060457865,1.5287117157674759,2.8797932657906435,1616.0,1574.0,1446.4,461.4,650.2,1029.6 +1.629051855782847,1.5287053435316635,3.010692959690218,1453.7,1371.6,1312.5,379.5,1311.4,1557.0 +1.6290208649115387,1.4284276549492487,0.0,1320.9,1293.1,1292.8,441.1,1529.4,1528.9 +1.6290545741562936,1.429243253530558,0.1308996938995747,1394.3,1313.0,1372.1,439.7,1557.5,1616.9 +1.6290294389255744,1.429235212298655,0.2617993877991494,1593.1,1229.6,849.6,483.4,1719.0,1846.0 +1.6290012332042534,1.4292172475725244,0.39269908169872414,1831.7,816.3,596.7,598.3,2059.8,1839.9 +1.6289773998300772,1.4291933639441214,0.5235987755982988,1434.7,623.8,496.0,868.3,1642.6,1514.6 +1.6289708899264326,1.429178234949044,0.6544984694978736,1291.2,520.8,484.5,1578.6,1432.4,1373.3 +1.6289603353513085,1.4291401270366637,0.7853981633974483,1263.1,470.8,470.3,1498.7,1351.6,1351.0 +1.6289609919833796,1.4291378095785585,0.916297857297023,1333.3,461.4,520.1,1534.5,1372.7,1431.5 +1.6289707325087013,1.429106823098015,1.0471975511965976,872.5,495.9,623.0,1705.6,1512.4,1639.2 +1.6289921228637616,1.4290693038978874,1.1780972450961724,598.7,595.7,814.6,2007.6,1837.6,1884.7 +1.6289819194599058,1.4290776931121143,1.3089969389957472,483.6,847.2,1226.1,1594.6,1575.0,1447.3 +1.6289885944368894,1.4290743020333565,1.4398966328953218,439.6,1615.6,1556.8,1392.9,1370.2,1311.7 +1.629054107420888,1.4290583414835791,1.5707963267948966,440.8,1529.0,1528.8,1321.2,1293.2,1293.1 +1.6290407332476158,1.4290569557745383,1.7016960206944713,481.8,1555.7,1614.0,1349.8,1312.3,1370.5 +1.6290310706368463,1.429053277486752,1.832595714594046,576.0,1719.6,1847.3,1501.0,1227.9,848.4 +1.6290817467717091,1.4290853901433522,1.9634954084936205,758.8,2058.5,1839.4,1845.6,815.5,596.2 +1.6290955975074424,1.4291013991651695,2.0943951023931953,1147.2,1640.6,1513.2,1526.2,623.4,496.1 +1.629083790043242,1.4290781349122423,2.2252947962927703,1535.3,1431.7,1373.0,1333.2,520.3,461.4 +1.6290879472996433,1.4290969135177403,2.356194490192345,1499.6,1351.1,1351.6,1262.6,470.4,470.8 +1.6290848341318158,1.429123225673624,2.4870941840919194,1577.9,1372.8,1431.6,1290.7,461.5,520.6 +1.6290890133667528,1.429110566914323,2.6179938779914944,1799.4,1514.1,1642.0,1145.6,495.8,623.3 +1.62907731462042,1.4291234303501663,2.748893571891069,1842.6,1841.0,1888.4,758.2,597.6,817.4 +1.6290879581667284,1.4291138281180582,2.8797932657906435,1500.8,1574.1,1446.4,576.5,849.1,1228.5 +1.6290811001990801,1.429117132731791,3.010692959690218,1350.7,1371.5,1312.5,482.7,1615.9,1556.6 +1.6290246552822063,1.3288200950818734,0.0,1221.2,1292.9,1292.7,540.7,1529.2,1529.2 +1.629044476931932,1.3288189797945358,0.1308996938995747,1290.8,1313.1,1372.2,543.1,1557.6,1616.8 +1.6290977499211035,1.3288345993233277,0.2617993877991494,1477.4,1445.9,1048.9,598.8,1718.8,1845.7 +1.629151503618904,1.3288676760109173,0.39269908169872414,1757.8,957.5,737.9,739.6,1918.2,1699.0 +1.6291933139051409,1.3289139540719783,0.5235987755982988,1435.1,739.3,611.5,1067.1,1526.9,1398.9 +1.6292295453279582,1.3289782642966605,0.6544984694978736,1291.1,624.4,565.1,1578.2,1328.7,1269.6 +1.629238478927382,1.329023162852192,0.7853981633974483,1263.1,570.8,570.2,1498.7,1251.7,1250.9 +1.6292368066282312,1.3290995244291297,0.916297857297023,1333.0,564.9,623.6,1534.4,1269.2,1327.8 +1.6292252817936352,1.3291389808282945,1.0471975511965976,1072.2,611.5,738.5,1705.6,1397.0,1524.0 +1.629210641855396,1.32915945898504,1.1780972450961724,740.6,736.6,955.8,1866.1,1696.6,1765.3 +1.629154967811886,1.3292107089982648,1.3089969389957472,599.2,1046.3,1425.4,1479.1,1575.0,1447.7 +1.6291104482225205,1.3292348536653804,1.4398966328953218,543.1,1615.6,1556.6,1289.4,1370.4,1312.0 +1.6291228494623382,1.3292312417754202,1.5707963267948966,540.8,1528.9,1528.9,1221.3,1293.2,1293.0 +1.6290598442726982,1.3292283528011817,1.7016960206944713,585.4,1555.8,1614.1,1246.5,1312.4,1370.6 +1.62900609822176,1.3292114294216666,1.832595714594046,691.7,1720.0,1847.2,1385.3,1445.7,1047.8 +1.6290200670688804,1.329220656573114,1.9634954084936205,900.5,1917.2,1697.9,1703.8,956.8,737.5 +1.6290067655306597,1.3292076310556125,2.0943951023931953,1346.7,1525.0,1397.5,1525.9,739.2,611.6 +1.6289777388619469,1.3291522523707302,2.2252947962927703,1535.5,1328.0,1269.4,1333.2,623.8,587.7 +1.6289741813162442,1.3291378576194643,2.356194490192345,1499.6,1251.0,1251.8,1262.3,570.3,570.8 +1.6289721676316848,1.3291325518816417,2.4870941840919194,1578.1,1269.5,1328.2,1290.7,565.1,624.2 +1.6289848009498997,1.3290921210695035,2.6179938779914944,1799.7,1398.7,1525.8,1344.9,611.4,738.9 +1.6289874370709223,1.3290820441594473,2.748893571891069,1701.3,1699.7,1760.9,899.6,739.0,958.9 +1.6290162249582487,1.329055459456812,2.8797932657906435,1384.9,1574.0,1446.4,692.2,1048.3,1428.1 +1.6290296516964495,1.3290479050331472,3.010692959690218,1246.7,1371.4,1312.4,586.2,1615.6,1556.8 +1.6289977239918236,1.2287692006670792,0.0,1121.1,1292.9,1292.6,640.7,1529.2,1529.2 +1.6290383559147947,1.2293348282320844,0.1308996938995747,1187.0,1312.9,1372.1,646.8,1557.7,1616.4 +1.6290045827947124,1.2293238870672,0.2617993877991494,1362.4,1445.8,1248.4,714.6,1718.8,1919.2 +1.6289665043517236,1.22929946155057,0.39269908169872414,1721.7,1098.5,879.1,881.5,1776.8,1557.5 +1.6289346831663032,1.2292666651013553,0.5235987755982988,1434.8,855.2,727.2,1266.7,1411.2,1283.2 +1.628922969341203,1.2292414501217306,0.6544984694978736,1291.1,727.9,668.9,1578.6,1225.0,1166.0 +1.6289101579554581,1.2291929135455915,0.7853981633974483,1263.2,670.8,670.1,1498.7,1151.7,1151.3 +1.628911188516735,1.2291807212396306,0.916297857297023,1333.1,668.4,727.1,1534.4,1165.9,1224.3 +1.628923613339884,1.229140909403961,1.0471975511965976,1271.7,726.8,854.2,1705.7,1281.5,1408.8 +1.6289495009065362,1.2290961617197644,1.1780972450961724,882.1,878.1,1096.8,1724.3,1555.7,1764.7 +1.628944907018069,1.2290991182640083,1.3089969389957472,714.7,1245.6,1624.6,1363.3,1575.0,1447.4 +1.6289579009004225,1.2290920865269015,1.4398966328953218,646.5,1615.3,1556.8,1185.8,1370.2,1311.6 +1.6290300308837296,1.2290744262670874,1.5707963267948966,640.6,1529.0,1528.9,1121.4,1293.3,1293.2 +1.629022901660494,1.2290730012760358,1.7016960206944713,688.7,1556.0,1614.3,1142.9,1312.2,1370.6 +1.6290188921649202,1.2290706925285078,1.832595714594046,807.2,1719.5,1917.7,1269.9,1446.0,1246.9 +1.6290743629947197,1.2291055027753388,1.9634954084936205,1042.2,1776.3,1557.0,1562.8,1097.7,878.5 +1.6290918349608094,1.2291250963211735,2.0943951023931953,1546.3,1409.6,1281.8,1525.9,854.5,727.1 +1.6290824357863523,1.2291058398782884,2.2252947962927703,1535.0,1224.6,1166.0,1333.1,727.5,668.5 +1.6290877552060208,1.2291288579032105,2.356194490192345,1499.8,1151.4,1151.6,1262.6,670.3,670.7 +1.6290845633005104,1.2291593091976862,2.4870941840919194,1578.1,1166.0,1224.9,1290.9,668.6,727.5 +1.6290876956316962,1.2291502699756434,2.6179938779914944,1939.8,1282.8,1410.6,1433.8,726.9,854.6 +1.629074037158846,1.2291661389962183,2.748893571891069,1559.3,1558.2,1760.6,1041.2,880.3,1100.4 +1.6290822431268535,1.22915868305399,2.8797932657906435,1269.7,1574.2,1446.4,807.6,1247.9,1627.3 +1.6290726559178184,1.2291632639114307,3.010692959690218,1143.4,1371.6,1312.7,689.8,1615.6,1556.6 +1.6290130528029343,1.1288637561703343,0.0,1021.5,1293.1,1293.0,740.7,1529.2,1529.2 +1.6290306484435186,1.128862298992956,0.1308996938995747,1083.7,1312.8,1372.1,750.1,1557.4,1616.4 +1.6290823363063012,1.1288771728125002,0.2617993877991494,1246.5,1445.8,1447.7,829.9,1718.7,1846.6 +1.629134976895333,1.1289092690201254,0.39269908169872414,1580.3,1239.5,1020.1,1023.0,1635.3,1416.2 +1.629176095203575,1.1289544678130228,0.5235987755982988,1434.7,970.6,842.7,1465.5,1295.4,1167.8 +1.6292397728729069,1.1290738072224702,0.6544984694978736,1290.9,831.4,772.1,1578.3,1121.7,1062.5 +1.6292390247379025,1.1290756240204172,0.7853981633974483,1263.4,771.0,770.2,1498.8,1051.7,1051.3 +1.6292377809965986,1.1291411382156675,0.916297857297023,1333.3,771.8,830.7,1534.6,1062.0,1120.9 +1.6292263746863918,1.1291802735553964,1.0471975511965976,1515.6,842.3,969.5,1705.4,1166.0,1293.3 +1.6292102184194048,1.1292031788057302,1.1780972450961724,1024.1,1019.1,1237.7,1582.4,1414.6,1633.6 +1.6291518475845668,1.129256812389254,1.3089969389957472,830.5,1444.9,1719.4,1247.5,1575.1,1447.5 +1.6291040112214183,1.1292824952345588,1.4398966328953218,750.1,1615.1,1556.4,1082.2,1370.2,1311.3 +1.629112930524215,1.1292795202392014,1.5707963267948966,740.8,1529.2,1528.8,1021.3,1293.4,1292.9 +1.6290467025826827,1.1292763006349515,1.7016960206944713,792.4,1555.6,1614.0,1039.7,1312.6,1370.5 +1.6289901886153795,1.1292582211315407,1.832595714594046,922.9,1719.9,1847.1,1154.1,1445.9,1446.5 +1.6290019375629756,1.129265772084556,1.9634954084936205,1184.0,1634.8,1415.6,1420.4,1238.8,1019.7 +1.6289870683131218,1.129250779064539,2.0943951023931953,1705.9,1294.1,1166.3,1526.2,970.1,842.8 +1.6289779065358267,1.1292339524781778,2.2252947962927703,1535.4,1121.2,1062.2,1333.2,830.7,771.9 +1.6289670505445404,1.1291868870277728,2.356194490192345,1499.6,1051.3,1051.7,1262.4,770.3,771.0 +1.6289654714552873,1.1291726098203678,2.4870941840919194,1578.0,1062.2,1121.3,1290.7,772.1,831.1 +1.628978541488249,1.1291309636239109,2.6179938779914944,1799.7,1167.4,1294.9,1433.8,842.6,970.3 +1.6289805028269995,1.1291218567390349,2.748893571891069,1417.8,1417.0,1637.4,1182.5,1021.8,1241.4 +1.6290079375064592,1.1290964141383304,2.8797932657906435,1153.7,1574.1,1446.4,923.3,1447.2,1718.9 +1.629019636043696,1.1290896111476805,3.010692959690218,1039.9,1371.4,1312.8,793.2,1615.9,1557.0 diff --git a/tools/localisation_machine_learning/data/sectors.md b/tools/localisation_machine_learning/data/sectors.md new file mode 100644 index 00000000..f93a7475 --- /dev/null +++ b/tools/localisation_machine_learning/data/sectors.md @@ -0,0 +1,29 @@ +# Why sectors ? + +The main problem of this localisation method is that for a global bach of data, severals positions can be computed with the same datas. To "solve" the problem, splitting the board into sectors is mandatory. + +## Sector 1 + +x in [0.0, 1.5] +y in [1.0, 2.0] + +## Sector 2 + +x in [0.0, 1.5] +y in [0.0, 1.0] + +## Sector 3 + +x in [1.5, 3.0] +y in [0.0, 1.0] + +## Sector 4 + +x in [1.5, 3.0] +y in [1.0, 2.0] + +## Schematic + +| 1 | 4 | +|---------|----------| +| 2 | 3 | From ac909ce01743c1187c5d82239d09e51471d9d5d1 Mon Sep 17 00:00:00 2001 From: PhileasL Date: Thu, 25 Feb 2021 09:31:18 +0100 Subject: [PATCH 61/67] Removing unused method --- .../data/sector1.csv | 2496 ----------------- .../data/sector2.csv | 2496 ----------------- .../data/sector3.csv | 2496 ----------------- .../data/sector4.csv | 2496 ----------------- .../data/sectors.md | 29 - .../data_obtention.py | 268 -- .../data_treatment.py | 31 - 7 files changed, 10312 deletions(-) delete mode 100644 tools/localisation_machine_learning/data/sector1.csv delete mode 100644 tools/localisation_machine_learning/data/sector2.csv delete mode 100644 tools/localisation_machine_learning/data/sector3.csv delete mode 100644 tools/localisation_machine_learning/data/sector4.csv delete mode 100644 tools/localisation_machine_learning/data/sectors.md delete mode 100644 tools/localisation_machine_learning/data_obtention.py delete mode 100644 tools/localisation_machine_learning/data_treatment.py diff --git a/tools/localisation_machine_learning/data/sector1.csv b/tools/localisation_machine_learning/data/sector1.csv deleted file mode 100644 index 51f82f1e..00000000 --- a/tools/localisation_machine_learning/data/sector1.csv +++ /dev/null @@ -1,2496 +0,0 @@ -0.17092194841810554,1.829207465725712,0.0,1720.8,2750.5,2751.0,40.9,71.0,71.0 -0.17096226623644847,1.828944035105113,0.1308996938995747,1808.8,1049.3,148.9,25.5,47.4,106.8 -0.17095143362032808,1.8290935759243316,0.2617993877991494,2055.7,430.7,51.2,21.3,33.9,161.4 -0.17101085015601797,1.8289812912716459,0.39269908169872414,2572.4,251.1,31.8,32.0,31.9,252.5 -0.17099868966830156,1.8289990419772488,0.5235987755982988,3120.1,161.2,33.5,72.2,50.8,711.8 -0.17084437272556974,1.829115506103378,0.6544984694978736,2800.3,106.5,47.5,68.5,149.6,969.0 -0.1710385852631262,1.8290178054394233,0.7853981633974483,2721.6,70.9,70.4,40.9,1751.8,1751.2 -0.17074105016221489,1.8291807519809502,0.916297857297023,232.0,47.5,106.3,25.4,1786.5,1845.7 -0.17101689265651487,1.8291223577750664,1.0471975511965976,73.2,34.0,51.5,21.4,1974.8,2102.1 -0.17099355760776588,1.8290320788711976,1.1780972450961724,31.8,31.6,31.3,31.1,2403.1,2622.0 -0.17067222541365637,1.828965386969519,1.3089969389957472,21.2,51.1,33.4,72.2,3258.5,3132.3 -0.17090033775471775,1.8291231991687675,1.4398966328953218,25.7,106.5,48.0,697.2,2878.3,2820.4 -0.17100750483107735,1.829008742533505,1.5707963267948966,40.9,71.0,70.7,1720.6,2751.2,2750.8 -0.17098345637569926,1.8289999473008447,1.7016960206944713,68.2,47.4,105.8,1764.1,980.7,152.2 -0.1708952404794647,1.8289803300067213,1.832595714594046,73.6,34.3,162.0,1963.7,430.2,51.0 -0.17104254152315035,1.8290026590520727,1.9634954084936205,32.2,32.4,253.3,2413.1,250.7,31.6 -0.17110862087463477,1.8290650605586949,2.0943951023931953,21.2,51.2,710.9,3210.0,161.2,34.0 -0.171009929363068,1.8290361319052317,2.2252947962927703,25.8,151.4,974.5,2842.1,106.3,47.5 -0.17103547426331028,1.829027115045187,2.356194490192345,41.6,1751.1,1751.6,2720.2,70.4,70.9 -0.17128977565664666,1.8291925114005771,2.4870941840919194,68.6,1786.9,1845.7,828.6,47.5,106.5 -0.17092827544161085,1.8290394691854306,2.6179938779914944,114.3,1976.9,2104.6,347.9,33.5,51.5 -0.17111613270017226,1.8291252543682692,2.748893571891069,191.7,2407.8,2627.1,192.2,32.2,31.7 -0.17089797234302156,1.8288907850802376,2.8797932657906435,349.1,3258.4,3130.9,114.3,51.8,33.8 -0.171000026419977,1.8290042372255524,3.010692959690218,916.0,2880.4,2821.9,68.7,106.4,47.6 -0.1709693381657898,1.728777201501448,0.0,1621.2,2751.2,2750.9,140.8,71.0,71.0 -0.17099888754949527,1.7292689278218094,0.1308996938995747,1705.3,1433.3,532.8,129.1,47.4,106.8 -0.1710593145903002,1.728885586493453,0.2617993877991494,1939.8,630.3,250.6,136.9,33.9,161.4 -0.1709885717143409,1.7290194234427751,0.39269908169872414,2430.5,392.2,173.0,173.6,31.9,252.6 -0.17100114876952657,1.7290018386142028,0.5235987755982988,3253.8,276.8,149.1,113.9,50.7,596.2 -0.1708494214949743,1.7291145649180737,0.6544984694978736,2801.0,210.1,151.0,68.5,632.5,968.8 -0.1710421220977605,1.729017016483805,0.7853981633974483,2721.1,170.9,170.4,40.9,1651.6,1651.1 -0.17074633822355512,1.7291814496691673,0.916297857297023,618.8,151.0,149.6,25.4,1683.4,1742.2 -0.1710204040634571,1.7291230613199402,1.0471975511965976,272.9,149.5,51.5,21.4,1859.3,1986.6 -0.17099408137467847,1.7290319072022104,1.1780972450961724,173.5,172.7,31.3,31.1,2261.5,2481.4 -0.17065554164532645,1.72894080967735,1.3089969389957472,136.8,160.9,33.4,72.2,3201.5,3132.3 -0.17088423410172762,1.7291081327477675,1.4398966328953218,129.2,106.5,48.0,571.0,2878.1,2820.3 -0.17100255586749505,1.729010122090229,1.5707963267948966,140.9,71.0,70.7,1621.0,2750.9,2751.3 -0.17098146587049415,1.729000301998672,1.7016960206944713,171.7,47.4,105.8,1660.5,1370.4,542.0 -0.1708900167399209,1.728979266208476,1.832595714594046,73.6,34.3,161.9,1848.3,629.3,250.2 -0.1711891275345699,1.7288644368175115,1.9634954084936205,32.2,32.4,253.1,2269.9,392.2,172.8 -0.17101965027541308,1.729075586297348,2.0943951023931953,21.2,51.2,595.4,3184.3,276.8,149.5 -0.17100195977079,1.7290225447332614,2.2252947962927703,25.8,632.2,974.6,2842.2,209.8,151.0 -0.17115748901708158,1.7289849489953233,2.356194490192345,41.6,1651.1,1651.4,2721.0,170.4,170.9 -0.17125352594321863,1.7290261632332844,2.4870941840919194,68.6,1683.3,1742.3,1213.2,151.1,150.0 -0.1709525173806403,1.72897962875142,2.6179938779914944,114.4,1861.0,1988.8,547.0,149.1,51.5 -0.17112735569093285,1.7290956691832515,2.748893571891069,191.7,2265.7,2485.7,333.7,173.7,31.7 -0.17087308522107897,1.7288473127443813,2.8797932657906435,608.0,3203.0,3130.8,229.9,161.2,33.8 -0.17099322890799384,1.7289913940232329,3.010692959690218,831.0,2880.4,2822.2,172.2,106.4,47.6 -0.1709650524321688,1.6287718004684846,0.0,1521.5,2751.0,2751.1,240.8,71.0,71.0 -0.17099647356560058,1.6292669158201158,0.1308996938995747,1601.8,1732.5,916.8,232.6,47.5,106.8 -0.17105795725758718,1.628885475018302,0.2617993877991494,1824.8,829.8,450.1,252.4,33.9,161.4 -0.17098644823784617,1.6290222620126693,0.39269908169872414,2289.2,533.5,314.2,191.2,31.9,252.6 -0.17100147753197023,1.629001699591175,0.5235987755982988,3119.7,392.3,264.7,113.9,50.8,473.6 -0.17085318353711848,1.629112331547199,0.6544984694978736,2801.0,313.6,254.5,68.5,529.1,1360.2 -0.17104528535824895,1.6290156893089864,0.7853981633974483,2721.4,270.9,270.3,40.9,1551.3,1550.8 -0.17075134296823472,1.629181672616631,0.916297857297023,1090.7,254.5,149.6,25.4,1579.7,1638.6 -0.1710237260380022,1.6291235549182401,1.0471975511965976,472.5,265.0,51.5,21.4,1744.0,1870.9 -0.17099400897825562,1.6290313608949145,1.1780972450961724,315.2,252.2,31.3,31.1,2121.0,2340.1 -0.17067365515814675,1.6289723014633521,1.3089969389957472,252.4,160.9,33.4,72.2,3002.9,3131.8 -0.1709035585286119,1.629130581793253,1.4398966328953218,232.6,106.4,48.0,490.3,2878.6,2820.3 -0.17101550212464775,1.6288577506521782,1.5707963267948966,240.9,71.0,70.6,1521.1,2751.5,2751.6 -0.17099317905591904,1.6290435018288614,1.7016960206944713,233.8,47.4,105.8,1557.0,1760.0,931.6 -0.17090267246094487,1.628983543126705,1.832595714594046,73.6,34.3,161.9,1732.2,828.6,449.5 -0.17120116312306505,1.6288677680824806,1.9634954084936205,32.2,32.4,253.1,2128.5,533.4,314.0 -0.17101960634525737,1.6290819704121668,2.0943951023931953,21.2,51.2,431.4,3028.5,392.3,265.0 -0.1708995524618737,1.6290973845633885,2.2252947962927703,25.8,528.9,1359.6,2841.9,313.3,254.4 -0.17117831828466576,1.6289998170853282,2.356194490192345,41.6,1551.1,1552.0,2720.3,270.3,270.9 -0.1712494707837472,1.628984600205581,2.4870941840919194,68.6,1580.0,1639.0,1598.5,254.6,150.0 -0.17099713666591002,1.6289963447528253,2.6179938779914944,114.4,1745.6,1873.0,746.3,264.7,51.5 -0.1711355299675771,1.6290967908312912,2.748893571891069,191.7,2124.5,2343.9,475.1,251.7,31.7 -0.1709042230401793,1.6288741490107321,2.8797932657906435,393.0,3004.1,3130.9,345.4,161.2,33.8 -0.1708832411043868,1.6288045742448751,3.010692959690218,830.8,2880.5,2822.0,275.8,106.4,47.5 -0.17103095556378153,1.528839175782786,0.0,1421.0,2750.8,2751.5,340.9,71.0,71.0 -0.17101801567547892,1.5291376862807957,0.1308996938995747,1498.0,2116.9,1300.9,336.3,47.5,106.8 -0.1710611349663433,1.5288555078061243,0.2617993877991494,1708.9,1029.2,649.5,349.1,33.9,161.4 -0.17091959318208702,1.5291291187132425,0.39269908169872414,2147.1,674.6,455.3,191.2,31.8,456.6 -0.17111571202689288,1.528902296182917,0.5235987755982988,3098.7,508.0,380.4,113.9,50.8,429.9 -0.17087503136133497,1.529085475310672,0.6544984694978736,2800.7,417.1,358.1,68.5,425.5,1256.4 -0.17115384352466398,1.5289814918160385,0.7853981633974483,2720.8,370.9,370.4,40.9,1451.5,1451.1 -0.1707698193777327,1.5291594540165687,0.916297857297023,1477.3,358.0,149.6,25.4,1476.4,1535.0 -0.17102426371801308,1.529113227396771,1.0471975511965976,672.4,380.6,51.5,21.4,1628.1,1755.9 -0.17090530704201956,1.528988174433866,1.1780972450961724,456.9,252.3,31.3,31.1,1978.9,2198.0 -0.17096639830337948,1.5290602221549667,1.3089969389957472,368.0,161.0,33.4,72.1,2801.5,3132.9 -0.17069199010188096,1.528918833895617,1.4398966328953218,336.1,106.4,48.1,236.8,2878.8,2819.9 -0.17093446740300658,1.529097704406047,1.5707963267948966,340.8,71.0,70.7,1420.9,2751.5,2751.1 -0.17094852532957813,1.5289126679031524,1.7016960206944713,233.8,47.4,105.8,1453.5,2149.9,1407.0 -0.17089513604143863,1.529149772088103,1.832595714594046,73.6,34.3,161.9,1617.0,1071.6,648.6 -0.17123119896890784,1.5288821218431154,1.9634954084936205,32.2,32.4,457.2,1987.3,674.4,455.1 -0.17102998085998697,1.5290882584854768,2.0943951023931953,21.2,51.2,431.4,2828.3,507.8,380.6 -0.1709056961712029,1.5291000997630086,2.2252947962927703,25.8,425.4,1256.5,2842.5,416.9,358.0 -0.1711799656045049,1.5290014972867332,2.356194490192345,41.6,1451.1,1451.8,2720.4,370.4,370.9 -0.17124568941681023,1.5290383191140742,2.4870941840919194,68.6,1476.3,1535.2,1984.1,358.2,150.0 -0.17084332495900065,1.5289535163598926,2.6179938779914944,114.3,1629.3,1757.7,945.4,380.4,51.5 -0.1711049589611337,1.5290992065989033,2.748893571891069,191.7,1982.7,2202.9,616.4,251.6,31.7 -0.17090287355209652,1.5288880183807645,2.8797932657906435,349.1,2804.2,3131.1,461.0,161.2,33.8 -0.1708814063666045,1.5288126754939806,3.010692959690218,1233.7,2880.5,2821.8,379.3,106.4,47.5 -0.17087266045300065,1.428567351688384,0.0,1321.3,2751.3,2751.0,440.8,71.0,71.0 -0.17095376941209128,1.4293031844398025,0.1308996938995747,1394.4,2499.2,1683.9,439.7,47.4,106.7 -0.17103585462376497,1.4289087187549263,0.2617993877991494,1593.3,1228.5,848.9,349.1,33.9,161.4 -0.17092586205373111,1.4291209974323653,0.39269908169872414,2005.5,816.0,596.6,191.1,31.8,252.6 -0.17111983616471668,1.428897343501793,0.5235987755982988,2899.7,623.6,495.9,113.9,50.8,473.8 -0.17087414302119727,1.4290848635088627,0.6544984694978736,2800.4,520.7,461.7,68.5,319.3,1130.1 -0.17115304725141955,1.4289812991370927,0.7853981633974483,2721.6,470.9,470.3,40.9,1351.6,1351.0 -0.17070262310723455,1.4290910785577942,0.916297857297023,1780.2,461.5,149.7,25.4,1372.8,1431.6 -0.17103326805318514,1.4290925417523337,1.0471975511965976,871.9,431.6,51.5,21.4,1512.5,1640.0 -0.17104995140501206,1.4290643311524045,1.1780972450961724,598.6,252.3,31.3,31.1,1838.7,2057.4 -0.17083106223339947,1.4289048019810053,1.3089969389957472,483.6,161.0,33.4,354.6,2601.9,2981.7 -0.17095124415290866,1.429074252780305,1.4398966328953218,439.6,106.5,48.0,236.3,2878.8,2820.2 -0.1711702498534188,1.429025639853649,1.5707963267948966,440.9,70.9,70.6,1321.1,2751.7,2750.8 -0.17105493706316233,1.4289702385539906,1.7016960206944713,233.8,47.4,105.8,1350.0,2540.2,1710.8 -0.17084340313876237,1.4291327077477078,1.832595714594046,73.8,34.4,161.9,1500.7,1228.4,848.6 -0.1710886167539638,1.428843473448831,1.9634954084936205,32.2,32.4,253.2,1845.6,815.5,596.2 -0.17102502340367887,1.4290671736004439,2.0943951023931953,21.2,51.2,431.4,2629.1,623.4,496.1 -0.17089960189781306,1.4290914305542137,2.2252947962927703,25.8,321.6,1129.9,2842.5,520.2,461.5 -0.17117838987866668,1.4289969904164297,2.356194490192345,41.6,1351.0,1351.8,2720.2,470.3,470.9 -0.171241166063334,1.4290353652310328,2.4870941840919194,68.6,1372.9,1432.2,2370.0,461.6,149.9 -0.1708425319822258,1.4289524697267002,2.6179938779914944,114.3,1514.2,1641.8,1144.6,430.5,51.5 -0.17110532791931635,1.4290991120356382,2.748893571891069,191.7,1841.5,2061.9,757.9,251.7,31.7 -0.17090305923101198,1.428887981965163,2.8797932657906435,349.1,2604.0,2983.6,576.6,161.2,33.8 -0.17088331210244273,1.428815673275263,3.010692959690218,1130.1,2880.4,2821.3,482.8,106.4,47.5 -0.17087399525927194,1.3285694986933607,0.0,1221.3,2751.0,2751.2,540.9,71.0,71.0 -0.1709544644427907,1.32930318945927,0.1308996938995747,1290.9,2823.1,2067.9,543.3,47.4,106.8 -0.17103622584115266,1.3289085667260032,0.2617993877991494,1477.8,1428.2,1048.3,349.1,33.9,161.4 -0.17092599140921694,1.3291210146190853,0.39269908169872414,1864.1,957.0,737.9,191.2,31.8,252.6 -0.17111986164134116,1.3288973895574459,0.5235987755982988,2700.4,739.3,611.6,113.9,286.8,429.9 -0.17087415697398675,1.32908488400943,0.6544984694978736,2800.5,624.1,565.2,68.5,149.6,1138.6 -0.17115304953621785,1.328981309264413,0.7853981633974483,2721.2,570.9,570.4,40.9,1251.9,1250.8 -0.17076972858454,1.3291594360002208,0.916297857297023,2165.3,565.1,149.5,25.4,1269.3,1328.3 -0.1710298309149586,1.329114597795626,1.0471975511965976,1071.5,431.6,51.5,21.4,1397.4,1524.7 -0.1710511448232365,1.3290789745454274,1.1780972450961724,740.3,252.2,31.3,31.1,1697.4,1916.7 -0.1708284206778974,1.3289102615432626,1.3089969389957472,599.1,161.0,33.4,239.1,2402.9,2782.0 -0.17095082294002864,1.3290772367015702,1.4398966328953218,543.1,106.5,48.0,236.3,2878.6,2820.3 -0.17117068915344621,1.3290284253271816,1.5707963267948966,540.9,70.9,70.6,1221.2,2751.3,2751.2 -0.171055245168651,1.328969500886958,1.7016960206944713,233.9,47.4,105.8,1246.7,2820.5,2100.7 -0.17085927843402288,1.3289081624774972,1.832595714594046,73.8,34.4,187.5,1385.8,1426.5,1091.3 -0.17095573699843553,1.3290030671382165,1.9634954084936205,32.2,32.4,253.3,1704.3,956.3,737.4 -0.171222237364476,1.3289663876439626,2.0943951023931953,21.2,286.0,430.9,2427.9,739.2,611.8 -0.17086678988996162,1.3291234642449172,2.2252947962927703,25.8,151.2,974.2,2842.1,623.8,565.0 -0.17115813113673306,1.329013429399277,2.356194490192345,41.6,1251.2,1251.7,2720.9,570.3,570.9 -0.1713358170534425,1.3292221936963027,2.4870941840919194,68.6,1269.2,1328.2,2800.7,565.2,150.4 -0.17080094764556006,1.3290242049672103,2.6179938779914944,280.8,1398.7,1526.3,1344.2,430.7,51.5 -0.1710804515807799,1.3291307848523375,2.748893571891069,191.7,1700.3,1920.5,899.3,251.6,31.7 -0.17089261460697616,1.328904605866622,2.8797932657906435,392.9,2404.3,2784.2,692.0,161.2,33.8 -0.17087671022278686,1.3288274316266102,3.010692959690218,1004.0,2880.3,2821.6,586.4,106.4,47.5 -0.17086804320669646,1.2285798052566204,0.0,1121.2,2750.6,2750.6,640.9,71.0,71.0 -0.1709518322094097,1.22930406433152,0.1308996938995747,1187.5,2822.9,2451.4,646.9,47.4,106.8 -0.17103521621145945,1.228907955424528,0.2617993877991494,1362.2,1627.3,1291.8,349.1,33.9,161.4 -0.17092551851252288,1.2291207017041414,0.39269908169872414,1722.2,1098.3,878.9,191.1,231.3,252.6 -0.17111962256925659,1.228897252367299,0.5235987755982988,2501.0,854.8,727.3,113.9,94.6,429.9 -0.1708740779168281,1.2290847950755088,0.6544984694978736,2800.7,727.8,668.7,68.5,149.6,969.0 -0.1711530289606126,1.2289812610907607,0.7853981633974483,2721.6,670.9,670.5,40.9,1151.7,1151.2 -0.17076973721150868,1.2291594030902173,0.916297857297023,2551.8,668.6,149.5,25.4,1165.8,1224.6 -0.1710326433025023,1.2291152741400455,1.0471975511965976,1271.1,431.8,51.5,21.4,1281.8,1408.8 -0.17105376914455897,1.229079936953899,1.1780972450961724,882.0,252.2,31.3,204.3,1555.9,1775.3 -0.1708289418946401,1.2289099660663707,1.3089969389957472,714.8,161.0,33.4,72.1,2203.4,2582.5 -0.17101033010830183,1.2291817353096621,1.4398966328953218,646.4,106.4,48.1,322.1,2878.4,2820.2 -0.1710627279202285,1.2287708342236399,1.5707963267948966,640.9,71.0,70.6,1121.2,2751.3,2750.8 -0.17102207843807207,1.2291632806579549,1.7016960206944713,234.0,47.4,105.8,1143.0,2820.6,2491.2 -0.17093936228482648,1.2287575206447454,1.832595714594046,73.6,34.3,162.1,1270.1,1624.4,1245.7 -0.17095221255390405,1.2290429265876501,1.9634954084936205,32.2,231.3,284.5,1562.7,1097.4,878.3 -0.17124078429972212,1.2289821940824788,2.0943951023931953,21.2,95.0,431.0,2227.8,854.9,727.4 -0.17087244791962028,1.229133236059123,2.2252947962927703,25.8,151.2,974.0,2842.7,727.5,668.6 -0.17116005402690088,1.2290183477991121,2.356194490192345,41.6,1151.2,1151.6,2720.1,670.4,671.0 -0.171225322453083,1.2290477253989502,2.4870941840919194,68.6,1165.7,1225.0,2801.1,668.7,149.9 -0.17084087982586846,1.2289596761694428,2.6179938779914944,114.3,1282.9,1410.9,1543.2,430.5,51.5 -0.17110541792058132,1.2291030630567192,2.748893571891069,191.7,1558.7,1778.8,1040.9,251.7,31.7 -0.17090239677964364,1.228889206729106,2.8797932657906435,349.1,2205.3,2585.6,807.6,161.2,33.8 -0.17088651042480074,1.228822627070987,3.010692959690218,915.9,2880.6,2821.4,689.8,106.4,47.5 -0.17087612570810592,1.128574642454336,0.0,1021.2,2750.8,2750.5,740.8,71.0,71.0 -0.17095560753953046,1.1293032670867929,0.1308996938995747,1083.7,2823.2,2882.3,750.4,47.4,106.8 -0.1710368712896355,1.1289082154636259,0.2617993877991494,1246.6,1826.7,1447.3,349.1,33.9,161.4 -0.17092620454042506,1.129121021331882,0.39269908169872414,1580.7,1239.4,1020.0,191.2,31.8,252.5 -0.17111989091144172,1.1288974704155312,0.5235987755982988,2301.8,970.6,842.8,113.9,50.8,429.9 -0.17087417852958992,1.129084915138964,0.6544984694978736,2800.3,831.3,772.2,68.5,234.5,969.0 -0.17115305107256037,1.1289813265751134,0.7853981633974483,2721.0,770.9,770.4,40.9,1051.7,1051.1 -0.17076973844246826,1.1291594497505688,0.916297857297023,2842.8,772.0,149.6,25.4,1062.3,1121.3 -0.1710353184057938,1.129115948949896,1.0471975511965976,1470.9,431.7,51.5,21.4,1166.1,1293.4 -0.1710562712983801,1.1290808743387093,1.1780972450961724,1023.8,252.3,31.3,31.1,1415.0,1634.0 -0.1708294353675978,1.1289096921612056,1.3089969389957472,830.4,161.0,33.4,72.0,2004.0,2384.0 -0.17101041900085598,1.129181357577397,1.4398966328953218,749.9,106.4,48.1,236.4,2878.5,2819.9 -0.1710628982355852,1.1287706714733692,1.5707963267948966,740.9,71.0,70.7,1021.1,2751.5,2751.4 -0.17102215948927518,1.1291633071632048,1.7016960206944713,233.9,47.4,105.8,1039.5,2820.8,2879.4 -0.17093942104593796,1.1287575715607452,1.832595714594046,73.6,34.3,187.6,1154.7,1823.4,1444.9 -0.17095208867834805,1.1290460381675733,1.9634954084936205,32.2,32.4,253.4,1421.0,1238.5,1019.4 -0.17124050118235457,1.1289862996907951,2.0943951023931953,21.2,51.1,430.9,2028.4,970.2,842.9 -0.170872529362083,1.1291350824203938,2.2252947962927703,25.8,236.4,974.0,2843.0,830.8,772.1 -0.17116059143991658,1.1290190837009795,2.356194490192345,41.6,1051.0,1051.6,2720.2,770.3,770.9 -0.17122160689323002,1.1290482368287151,2.4870941840919194,68.6,1062.4,1121.5,2800.4,772.4,149.9 -0.17083992713412396,1.12896009932856,2.6179938779914944,114.3,1167.4,1295.1,1742.3,430.5,51.5 -0.17110550392425236,1.1291035625209727,2.748893571891069,191.7,1417.1,1637.4,1182.2,251.6,31.7 -0.1709023939391514,1.1288894031595984,2.8797932657906435,349.1,2006.0,2385.9,923.1,161.2,33.8 -0.17088824669554495,1.1288257313068115,3.010692959690218,830.7,2881.3,2822.2,793.3,106.4,47.5 -0.2709389649875579,1.829194537367861,0.0,1720.7,2651.2,2650.9,41.0,171.0,171.0 -0.27096927161083223,1.8289115357711418,0.1308996938995747,1808.6,964.8,148.9,25.6,151.0,210.3 -0.27112650773081653,1.8289613400156406,0.2617993877991494,2056.0,431.0,51.3,21.3,149.4,276.9 -0.2710323992075201,1.829030838669132,0.39269908169872414,2572.2,251.1,31.8,32.0,173.5,394.2 -0.2710190348287386,1.8290177810255612,0.5235987755982988,3004.4,161.2,33.5,72.1,250.0,737.3 -0.2708518619624328,1.8291284177474938,0.6544984694978736,2697.0,106.6,47.5,172.1,736.2,1567.1 -0.27117009251775537,1.8289939629088392,0.7853981633974483,2621.5,70.9,70.4,140.9,1751.8,1751.1 -0.2707773333005617,1.8291639654297887,0.916297857297023,232.0,47.5,106.3,128.9,1787.1,1845.8 -0.27103618643934035,1.8291171182560635,1.0471975511965976,73.2,33.9,161.2,136.9,1974.6,2101.9 -0.2710572616314036,1.8290818353285845,1.1780972450961724,31.7,31.5,173.0,172.3,2403.3,2622.6 -0.2708294170652326,1.828909722437329,1.3089969389957472,21.2,51.0,149.0,271.4,3144.5,3016.4 -0.2710103445943455,1.8291812511191567,1.4398966328953218,25.7,152.1,151.5,626.0,2775.2,2717.0 -0.27106289642123343,1.8287706562137906,1.5707963267948966,40.9,171.0,170.7,1721.2,2651.7,2651.0 -0.27102215549857955,1.82916331974553,1.7016960206944713,68.2,150.9,209.2,1763.8,1067.0,152.2 -0.2709394184015474,1.8287575809590204,1.832595714594046,114.1,150.0,277.7,1964.2,429.7,50.9 -0.2710968309349378,1.828997182850595,1.9634954084936205,173.3,174.2,395.1,2412.9,250.6,31.6 -0.2712284583998348,1.8291423148678976,2.0943951023931953,136.7,250.8,631.0,3184.0,161.3,34.0 -0.27108047294564447,1.8290919569861646,2.2252947962927703,129.3,735.9,1566.6,2738.5,106.3,47.4 -0.2710733903177761,1.8290612527966408,2.356194490192345,141.6,1751.5,1751.7,2620.1,70.3,70.9 -0.271206066785063,1.8290674452545506,2.4870941840919194,172.2,1787.1,1845.7,826.9,47.5,106.6 -0.27084180430506966,1.8289715515395175,2.6179938779914944,230.0,1976.8,2104.5,347.9,33.5,161.2 -0.2711056063073363,1.8291086391696956,2.748893571891069,333.2,2407.4,2627.2,192.2,32.2,173.1 -0.27090123020810075,1.828890684693416,2.8797932657906435,723.6,3143.3,3015.2,114.3,51.8,149.4 -0.2709484688492395,1.828834564697893,3.010692959690218,1521.9,2777.0,2717.8,68.8,151.7,151.0 -0.2709091914476188,1.7286036705756835,0.0,1621.1,2651.0,2651.2,140.8,171.0,171.0 -0.2709754808272247,1.72929618092982,0.1308996938995747,1704.7,1348.4,532.7,129.1,151.0,210.3 -0.2710461897851685,1.7289051191517888,0.2617993877991494,1940.2,630.3,250.6,136.9,149.5,277.0 -0.2710519159037479,1.7289089232999866,0.39269908169872414,2430.7,392.3,173.0,173.7,173.6,394.2 -0.2708586935324108,1.7291269356756722,0.5235987755982988,3004.8,276.7,149.1,229.5,250.0,629.1 -0.2708226874495069,1.7291449130956367,0.6544984694978736,2697.1,210.1,151.0,172.0,620.1,1463.5 -0.2711437925789047,1.7289577100082907,0.7853981633974483,2620.3,170.9,170.4,140.9,1651.5,1651.0 -0.27077022270912643,1.729122284684844,0.916297857297023,618.7,151.0,209.8,128.9,1683.5,1742.3 -0.27115951534258986,1.7291443836432423,1.0471975511965976,272.8,149.5,251.1,136.9,1859.5,1986.9 -0.2708735992392601,1.7289490984722913,1.1780972450961724,173.5,172.7,173.0,172.2,2261.8,2480.9 -0.2707049065616731,1.7291044810992726,1.3089969389957472,136.8,250.3,149.1,271.4,3144.8,3017.3 -0.27087290256563773,1.7291366233521066,1.4398966328953218,129.2,209.9,151.5,625.9,2775.4,2716.4 -0.2710866057500448,1.729088827235892,1.5707963267948966,140.9,170.9,170.6,1620.9,2651.1,2651.3 -0.2710200593381259,1.7289642542734456,1.7016960206944713,171.7,150.8,209.3,1660.2,1370.8,542.0 -0.2708256538853389,1.7289032812780625,1.832595714594046,229.6,150.0,277.7,1848.1,629.3,250.2 -0.27093734469347724,1.728992806574243,1.9634954084936205,173.3,174.1,395.0,2271.5,391.8,172.7 -0.2710765514287949,1.7291455219333018,2.0943951023931953,136.7,250.7,630.9,3095.1,276.8,149.6 -0.27104580284925694,1.7290302152969508,2.2252947962927703,129.3,623.8,1447.0,2738.5,209.7,151.0 -0.2710451587436101,1.7290275082094289,2.356194490192345,141.6,1651.0,1651.7,2620.4,170.4,170.9 -0.271201505704856,1.7290473933481487,2.4870941840919194,172.1,1683.3,1742.6,1297.6,151.1,210.1 -0.2708440257617808,1.7289631739130946,2.6179938779914944,229.9,1861.0,1988.6,547.0,149.1,250.6 -0.27110743033642637,1.7291050391585276,2.748893571891069,333.1,2266.3,2486.2,333.6,173.7,173.1 -0.27090232251624186,1.7288891637583532,2.8797932657906435,548.6,3143.3,3015.7,229.8,251.3,149.4 -0.27089222604451285,1.7288324089296614,3.010692959690218,1440.9,2777.3,2718.7,172.3,209.9,151.1 -0.2708800683153245,1.6285816851763726,0.0,1521.3,2650.4,2650.7,240.8,171.0,171.0 -0.2709576749301276,1.6292216523397183,0.1308996938995747,1601.7,1731.9,916.3,232.6,151.0,210.3 -0.271050683073762,1.6288325600350615,0.2617993877991494,1824.6,829.7,450.1,252.5,149.5,277.0 -0.27090248474317435,1.6291395484279354,0.39269908169872414,2289.3,533.5,314.1,315.2,173.5,598.2 -0.27111119581438275,1.6289033555197376,0.5235987755982988,3054.4,392.4,264.7,229.5,250.1,673.0 -0.27087570449001375,1.629084244308163,0.6544984694978736,2696.8,313.7,254.6,172.0,535.3,1354.6 -0.2711540956912581,1.628980923779331,0.7853981633974483,2621.0,270.9,270.4,140.9,1551.5,1551.1 -0.2707698273450156,1.6291590441573445,0.916297857297023,1005.6,254.5,313.4,128.9,1579.8,1638.8 -0.2711682756142472,1.6291652602183058,1.0471975511965976,472.2,265.1,251.1,137.0,1743.9,1871.4 -0.2708722732694751,1.6289560814759998,1.1780972450961724,315.2,313.8,173.0,172.2,2120.5,2339.9 -0.2707049390074784,1.6291101905414305,1.3089969389957472,252.4,276.8,149.1,271.4,3000.0,3136.1 -0.27087124774266264,1.629136721515268,1.4398966328953218,232.6,209.9,151.5,711.6,2775.0,2717.3 -0.2710852270908924,1.6290888595772903,1.5707963267948966,240.9,170.9,170.6,1521.1,2651.5,2651.3 -0.2710195282170736,1.6289643982840323,1.7016960206944713,275.2,150.9,209.3,1556.6,1760.1,931.8 -0.2708251683824264,1.6289034376183542,1.832595714594046,273.1,150.0,277.6,1732.6,872.5,449.4 -0.27093717392366484,1.6289926402811978,1.9634954084936205,173.3,174.1,599.1,2129.5,532.9,313.8 -0.2710763934513774,1.6291453685779116,2.0943951023931953,136.6,250.7,630.9,3027.7,392.4,265.1 -0.27105264007467983,1.6290422522912271,2.2252947962927703,129.3,538.7,1361.8,2738.9,313.3,254.5 -0.27105074002048035,1.6290340657338587,2.356194490192345,141.6,1551.2,1551.6,2620.2,270.3,270.9 -0.2712028345033109,1.6290512816304918,2.4870941840919194,172.1,1579.9,1639.1,1598.3,254.6,313.6 -0.2708436177117515,1.6289647515520744,2.6179938779914944,229.9,1745.8,1873.0,746.2,264.8,250.7 -0.2711070465091727,1.6291056896588463,2.748893571891069,333.1,2124.6,2344.6,475.1,315.1,173.1 -0.27090211386844754,1.6288894508473049,2.8797932657906435,548.6,3003.1,3140.1,345.4,276.8,149.4 -0.2708939089221579,1.628835708534444,3.010692959690218,1337.3,2777.3,2718.0,275.8,209.9,151.0 -0.2708812010903275,1.528584086445759,0.0,1421.2,2651.3,2651.1,340.8,171.0,171.0 -0.2709582786631376,1.5293033781163379,0.1308996938995747,1498.1,2116.1,1384.8,336.2,151.0,210.4 -0.27103832275854733,1.5289075651625934,0.2617993877991494,1708.9,1073.0,649.5,368.1,149.5,277.0 -0.2710452376014155,1.5289121000353099,0.39269908169872414,2147.2,674.7,455.4,332.4,173.5,394.2 -0.27085709556802184,1.5291266325932387,0.5235987755982988,3005.0,508.0,380.3,229.5,518.1,629.0 -0.27082820100998384,1.5291404557495532,0.6544984694978736,2696.8,417.2,358.1,172.1,620.0,1354.6 -0.2711831831274259,1.5289929010111991,0.7853981633974483,2621.6,370.9,370.4,140.9,1451.8,1451.2 -0.27078367893704464,1.529159538811958,0.916297857297023,1392.2,358.0,416.9,128.9,1476.4,1534.9 -0.27081246507908124,1.5290694678662806,1.0471975511965976,671.7,380.6,250.9,136.9,1628.6,1756.0 -0.2711311023900046,1.5291684719074277,1.1780972450961724,456.7,393.7,173.0,172.4,1980.4,2200.0 -0.2707163348840079,1.5289713956876207,1.3089969389957472,368.0,276.6,149.0,470.1,2803.4,3016.6 -0.27079133007460127,1.5289325290273161,1.4398966328953218,336.2,209.8,151.5,626.7,2774.6,2716.8 -0.2709836314820744,1.5290759236656355,1.5707963267948966,340.9,170.9,170.7,1421.0,2651.3,2651.5 -0.2709675520064994,1.52882136991859,1.7016960206944713,378.7,150.9,209.2,1453.3,2150.0,1321.4 -0.2708936251587138,1.529151632663589,1.832595714594046,272.9,149.9,277.6,1616.8,1027.8,648.7 -0.27122149011558877,1.5288898724604043,1.9634954084936205,173.4,174.1,394.8,1986.7,674.3,455.2 -0.27094343869335813,1.5291739341627837,2.0943951023931953,136.7,517.1,631.0,2828.7,507.8,380.6 -0.2709163351602167,1.529121349777276,2.2252947962927703,129.3,624.0,1361.9,2739.0,416.7,358.0 -0.27120285304746616,1.5290149506401332,2.356194490192345,141.6,1451.1,1451.8,2620.1,370.3,370.9 -0.2712225959413515,1.5290529218817435,2.4870941840919194,172.2,1476.5,1535.4,1983.1,358.1,417.2 -0.2708347657924829,1.5289605564679125,2.6179938779914944,229.9,1630.3,1757.3,945.6,380.3,250.7 -0.2711045154791966,1.5291045751080719,2.748893571891069,333.1,1982.8,2203.2,616.5,393.1,173.1 -0.27090231199772924,1.5288902581854533,2.8797932657906435,548.6,2803.7,3016.3,461.0,276.8,149.4 -0.27089507858247175,1.5288380925737006,3.010692959690218,1217.8,2777.5,2718.8,379.3,209.9,151.0 -0.27088197912191303,1.4285858661182025,0.0,1321.2,2651.3,2650.8,440.8,171.0,171.0 -0.2709586949885709,1.4293033867191531,0.1308996938995747,1394.8,2499.9,1684.2,439.8,151.0,210.4 -0.2710385542001287,1.4289074441320109,0.2617993877991494,1593.4,1228.6,849.0,483.5,149.5,422.1 -0.27104544148792475,1.4289119622078208,0.39269908169872414,2005.6,815.8,596.7,332.3,173.5,394.3 -0.27105350392238814,1.4289226841020728,0.5235987755982988,2899.8,623.7,496.0,229.5,402.3,629.1 -0.2708303184252421,1.4291004059374983,0.6544984694978736,2697.4,520.7,461.6,172.0,535.3,1350.0 -0.27115513572456257,1.428982036295412,0.7853981633974483,2620.9,470.9,470.4,140.9,1351.2,1350.8 -0.2707758349250428,1.429157335813989,0.916297857297023,1778.9,461.6,520.5,128.9,1372.8,1431.7 -0.2708051177877577,1.4290657624722354,1.0471975511965976,871.2,496.2,250.8,136.9,1512.7,1640.4 -0.2711303233055466,1.4291686031261475,1.1780972450961724,598.3,393.8,173.0,172.3,1839.3,2058.8 -0.2707167436186807,1.4289720233149463,1.3089969389957472,483.5,276.6,149.0,271.5,2603.2,2983.2 -0.27079167471294474,1.428933189418316,1.4398966328953218,439.5,209.8,151.5,626.7,2774.8,2716.6 -0.27098374329747704,1.4292141883253144,1.5707963267948966,440.9,170.9,170.7,1321.2,2651.0,2651.1 -0.27097121728583373,1.4288538719335981,1.7016960206944713,482.0,150.9,209.3,1350.1,2539.4,1711.0 -0.2709041979394162,1.4291305990975478,1.832595714594046,272.9,149.9,422.0,1501.3,1227.2,848.1 -0.27122996952773537,1.4288849579538163,1.9634954084936205,173.4,174.1,394.9,1845.8,815.7,596.3 -0.27094263329565166,1.4291767765909038,2.0943951023931953,136.7,401.4,631.2,2628.9,623.3,496.1 -0.27091515858180704,1.4291234905151264,2.2252947962927703,129.3,538.7,1350.1,2738.8,520.3,461.4 -0.2712028894954585,1.4290159430593778,2.356194490192345,141.6,1350.9,1351.7,2620.4,470.3,470.9 -0.2712195448384496,1.4290537344965037,2.4870941840919194,172.1,1372.8,1432.0,2368.8,461.7,520.7 -0.27083403127976946,1.42896108657976,2.6179938779914944,230.0,1514.1,1641.6,1144.6,496.1,250.6 -0.27110457059975424,1.4291050523975388,2.748893571891069,333.1,1841.6,2061.7,757.9,393.1,173.1 -0.2709022881467447,1.4288904375873481,2.8797932657906435,548.6,2604.2,2984.2,576.5,276.8,149.4 -0.27091781656876,1.4286829753465085,3.010692959690218,1218.1,2777.6,2718.5,482.7,209.9,151.0 -0.2710439090990391,1.3288052676802389,0.0,1221.1,2651.0,2651.1,540.9,171.0,171.0 -0.2710255793241709,1.329129868680052,0.1308996938995747,1291.0,2719.2,2069.1,543.3,151.0,210.3 -0.271003267843256,1.329122771911328,0.2617993877991494,1477.9,1472.1,1048.5,548.7,149.5,276.9 -0.2711215593680672,1.3288481850477991,0.39269908169872414,1863.9,956.9,737.6,332.4,372.4,394.4 -0.2711311262642516,1.3288606382637287,0.5235987755982988,2700.4,739.3,611.5,229.5,250.1,629.3 -0.27084070816676825,1.329087841691048,0.6544984694978736,2696.8,624.3,565.1,172.0,535.4,1269.4 -0.2708345522486544,1.3290648001596774,0.7853981633974483,2621.2,570.9,570.4,140.8,1251.6,1251.2 -0.2707767793161179,1.3290646194334337,0.916297857297023,2168.4,565.2,537.0,128.9,1269.0,1328.0 -0.27078948321357255,1.3290270237514763,1.0471975511965976,1071.6,611.6,251.1,136.8,1397.2,1524.4 -0.27113815006083003,1.3291444011569005,1.1780972450961724,740.1,393.8,173.0,203.4,1697.7,1917.2 -0.27072978061667646,1.3289644669795981,1.3089969389957472,599.2,276.5,149.0,271.6,2404.6,2784.3 -0.2708003707335944,1.3289279322083813,1.4398966328953218,543.0,209.8,151.5,1046.2,2774.3,2716.8 -0.27098900637214735,1.329211770632246,1.5707963267948966,540.9,170.9,170.7,1221.1,2651.0,2651.0 -0.27095546577765156,1.3292099681888434,1.7016960206944713,585.7,150.8,209.3,1246.5,2717.9,2096.6 -0.2710199733140488,1.3288237770010543,1.832595714594046,272.8,150.0,277.6,1385.5,1426.2,1047.0 -0.2712332071398093,1.328960535580943,1.9634954084936205,173.2,372.3,426.3,1704.3,956.2,737.3 -0.27105839613632954,1.3290968900992297,2.0943951023931953,136.7,250.8,631.1,2429.0,738.8,611.6 -0.27096244720736756,1.3289131395698637,2.2252947962927703,129.4,538.8,1269.3,2738.3,623.8,564.8 -0.2712381274750242,1.3289300110550428,2.356194490192345,141.7,1251.2,1251.7,2620.3,570.3,570.9 -0.2713413423857288,1.3291937229953001,2.4870941840919194,172.1,1269.3,1328.0,2697.0,565.2,536.6 -0.27079154770841596,1.3290070538274708,2.6179938779914944,229.9,1398.5,1526.4,1344.1,611.7,250.7 -0.2710806804839036,1.329125055947248,2.748893571891069,333.1,1700.4,1920.6,899.3,393.0,173.1 -0.27089462005846926,1.3289036257925702,2.8797932657906435,548.5,2404.9,2784.2,692.2,276.8,149.4 -0.2709134023866092,1.3288942271004203,3.010692959690218,1246.8,2777.3,2718.4,586.2,209.9,151.0 -0.2708920456262257,1.2286286146975072,0.0,1121.0,2651.1,2651.0,640.8,171.0,171.0 -0.27096217570592995,1.2293057975020476,0.1308996938995747,1187.4,2719.5,2452.0,647.0,151.0,210.3 -0.2710412476220784,1.228904776491642,0.2617993877991494,1362.3,1627.5,1247.8,548.5,149.5,277.0 -0.2710479796199744,1.2289092050537174,0.39269908169872414,1722.4,1098.1,879.1,332.4,173.5,394.3 -0.2710562629360409,1.2289201772089053,0.5235987755982988,2501.1,854.9,727.2,229.5,250.0,629.1 -0.27083052435372723,1.2290998272162907,0.6544984694978736,2696.8,727.8,668.7,172.0,1004.8,1165.9 -0.2708236105653016,1.2290735047135661,0.7853981633974483,2621.3,670.9,670.3,140.8,1151.6,1151.1 -0.27077539888424934,1.22906967374321,0.916297857297023,2556.1,668.5,537.0,128.9,1165.8,1224.3 -0.27078839643653574,1.229031133016503,1.0471975511965976,1271.2,631.3,251.1,136.8,1281.8,1409.1 -0.27113763470509605,1.2291464369945206,1.1780972450961724,881.7,393.8,173.0,172.3,1556.8,1775.5 -0.2707290794470259,1.2289653260063607,1.3089969389957472,714.6,276.5,149.0,271.5,2204.8,2584.1 -0.27079995175478355,1.2289286409481426,1.4398966328953218,646.4,209.8,151.5,965.5,2775.2,2716.2 -0.27098869975662515,1.2292119560670638,1.5707963267948966,641.0,170.9,170.7,1121.0,2651.2,2651.2 -0.2709552063893951,1.2292101548589112,1.7016960206944713,622.1,150.8,209.3,1143.1,2717.4,2485.6 -0.2709136297057444,1.2291962277001072,1.832595714594046,272.6,149.9,277.7,1270.2,1668.2,1245.5 -0.27113778878824807,1.228876705298793,1.9634954084936205,173.3,205.4,395.2,1562.8,1128.4,878.3 -0.271297950860524,1.2290532887346985,2.0943951023931953,136.7,250.8,631.2,2229.8,854.6,727.2 -0.27082532936641057,1.229178629831161,2.2252947962927703,129.3,1004.4,1165.5,2738.6,727.2,668.4 -0.27116201338023316,1.2290342306916235,2.356194490192345,141.6,1151.4,1151.6,2620.5,670.3,670.8 -0.2713090586402624,1.2292446349141863,2.4870941840919194,172.1,1165.4,1224.8,2696.4,668.7,536.6 -0.27079012218548204,1.2290353682512771,2.6179938779914944,229.9,1282.9,1410.7,1543.6,629.9,250.7 -0.27107932366350923,1.2291383016811432,2.748893571891069,364.3,1558.9,1779.2,1040.6,393.0,173.1 -0.27089159626030257,1.2289077190343165,2.8797932657906435,548.5,2205.3,2584.6,807.6,276.8,149.4 -0.2709115645565183,1.2288976826278728,3.010692959690218,1143.2,2777.1,2718.4,689.7,209.8,151.0 -0.27089035931930766,1.128631737676965,0.0,1021.3,2651.3,2651.0,740.8,170.9,171.0 -0.2709612903593327,1.1293061265990243,0.1308996938995747,1083.8,2719.5,2779.2,750.5,151.0,210.3 -0.2710410256301089,1.1289043992871708,0.2617993877991494,1246.6,1826.6,1447.3,548.5,149.5,277.0 -0.27104788356116993,1.1289089074434284,0.39269908169872414,1580.6,1270.5,1020.2,332.4,173.5,394.3 -0.271056212759162,1.128919929184132,0.5235987755982988,2301.8,970.4,842.7,229.5,293.8,629.2 -0.2708304564543895,1.1290997110957899,0.6544984694978736,2697.1,831.4,772.3,172.0,901.3,1062.2 -0.27082354792746816,1.1290734103312408,0.7853981633974483,2621.3,770.8,770.3,140.8,1051.6,1051.1 -0.2707777802926265,1.1290695185941373,0.916297857297023,2739.3,772.1,537.2,128.9,1062.2,1121.2 -0.27079069391620936,1.1290312396344877,1.0471975511965976,1470.7,631.2,251.0,136.8,1166.2,1293.6 -0.27113809629376,1.1291460966582259,1.1780972450961724,1023.4,393.8,173.0,172.3,1415.5,1634.4 -0.2707291691768218,1.1289649572167462,1.3089969389957472,830.4,276.5,149.0,271.6,2005.5,2385.2 -0.2707999803273099,1.1289283049593037,1.4398966328953218,749.8,209.8,151.5,862.1,2774.7,2717.0 -0.27098876106705955,1.1292118826288453,1.5707963267948966,740.9,170.9,170.7,1021.0,2651.4,2651.2 -0.2709552633436781,1.1292100815348978,1.7016960206944713,622.1,150.8,209.3,1039.7,2717.7,2776.0 -0.27091368961816426,1.1291961558970331,1.832595714594046,272.6,149.9,277.7,1154.8,1823.5,1444.6 -0.2711377998344142,1.1288766978395774,1.9634954084936205,173.3,174.2,395.2,1421.5,1238.4,1019.3 -0.27129796485373936,1.1290532845054786,2.0943951023931953,136.7,294.7,631.0,2030.0,970.1,842.7 -0.2708253301301111,1.1291786258867917,2.2252947962927703,129.3,878.0,1062.1,2739.1,830.8,772.0 -0.27116200753231756,1.1290342288467463,2.356194490192345,141.6,1051.0,1051.7,2620.1,770.3,770.9 -0.2711501079646094,1.1292653867003002,2.4870941840919194,172.2,1062.4,1121.5,2697.1,772.5,535.2 -0.27074220121260206,1.1290221248117285,2.6179938779914944,230.0,1167.3,1295.1,1741.8,629.5,250.6 -0.2710862725635541,1.1291498917997034,2.748893571891069,333.2,1417.6,1637.4,1182.1,393.0,173.1 -0.2708946306362496,1.1289130968229517,2.8797932657906435,548.5,2005.7,2385.9,923.4,276.8,149.4 -0.2709144795320088,1.1289031081427487,3.010692959690218,1039.8,2777.3,2718.7,793.3,209.9,151.0 -0.3709560370272465,1.8292033722081653,0.0,1721.1,2551.1,2550.9,40.9,271.0,271.0 -0.3709771281180925,1.8289188591656678,0.1308996938995747,1808.8,964.7,148.9,25.6,254.6,313.9 -0.37113045693247443,1.8289674445239155,0.2617993877991494,2055.7,430.9,51.3,21.3,265.0,392.5 -0.3709141322316646,1.8292146021646998,0.39269908169872414,2572.5,251.0,31.7,31.9,315.2,536.0 -0.3711431147509891,1.8289167002778335,0.5235987755982988,2888.4,161.1,33.5,72.2,449.4,828.5 -0.3708891821929592,1.829091854716181,0.6544984694978736,2593.3,106.6,47.5,231.3,1005.8,1787.1 -0.3708824358778367,1.8290667728410914,0.7853981633974483,2521.3,70.9,70.4,240.8,1751.5,1751.2 -0.3708274307427325,1.8291179485172118,0.916297857297023,232.3,47.5,106.3,232.4,1786.7,1845.7 -0.3708454509949016,1.8290624775297193,1.0471975511965976,73.2,33.9,161.3,252.4,1974.7,2102.3 -0.3711400631221659,1.8291525526945391,1.1780972450961724,31.7,31.5,250.7,313.6,2403.9,2623.1 -0.37072177649768506,1.8289628179673492,1.3089969389957472,21.2,51.1,264.6,471.0,3157.8,2901.3 -0.37079453354187636,1.8289251444785803,1.4398966328953218,25.8,152.6,254.9,1017.2,2671.2,2612.9 -0.3709862460968821,1.8292122526428685,1.5707963267948966,40.9,270.9,270.7,1721.0,2551.8,2551.4 -0.3709532309548635,1.8292104683855381,1.7016960206944713,68.2,254.3,312.8,1764.0,978.7,151.6 -0.37091178561781646,1.829196570679533,1.832595714594046,114.0,265.6,393.3,1964.4,429.6,50.8 -0.37113704505793066,1.8288766578989861,1.9634954084936205,192.5,315.9,536.9,2413.0,250.6,31.6 -0.37129721644336194,1.8290532464485554,2.0943951023931953,252.3,450.5,830.8,2979.2,161.3,34.1 -0.3708251887352648,1.8291784775774536,2.2252947962927703,232.8,926.5,1786.3,2635.1,106.2,47.5 -0.3711620052126641,1.8290341362497184,2.356194490192345,241.6,1751.0,1751.8,2520.4,70.3,70.9 -0.3711462830347968,1.829305439375017,2.4870941840919194,275.7,1786.9,1846.3,911.8,47.6,106.7 -0.3707731060311675,1.8290450182952076,2.6179938779914944,345.7,1976.9,2104.4,347.6,33.5,161.2 -0.3710888811670482,1.8291545740481108,2.748893571891069,474.6,2407.6,2627.5,192.2,32.2,252.3 -0.3708920437476835,1.8289116549936213,2.8797932657906435,748.0,3159.2,2900.3,114.3,51.8,264.9 -0.37091240334450476,1.8289013989593013,3.010692959690218,1604.7,2673.7,2615.5,68.7,151.8,254.5 -0.37089089153561683,1.7286350723185737,0.0,1621.3,2550.9,2551.1,140.8,271.0,271.0 -0.3709615422573938,1.7293060434873577,0.1308996938995747,1705.4,1347.8,532.4,129.1,254.6,313.9 -0.37093784688881865,1.7292981581987297,0.2617993877991494,1940.6,630.1,250.4,136.8,265.0,392.5 -0.3711210390921074,1.7288770682376007,0.39269908169872414,2430.7,392.3,173.0,173.7,315.3,739.9 -0.3711264762261649,1.728884893411303,0.5235987755982988,2888.4,276.7,149.1,271.5,723.7,828.6 -0.3708465270256524,1.7290951898937108,0.6544984694978736,2593.3,210.1,151.0,275.6,921.2,1683.5 -0.3708399127282425,1.729070259617549,0.7853981633974483,2521.5,170.9,170.4,240.8,1651.9,1650.9 -0.37078813431216584,1.7290692892424646,0.916297857297023,619.6,151.0,209.8,232.4,1683.3,1741.6 -0.37080048256699477,1.7290327762427515,1.0471975511965976,272.9,149.5,276.8,252.4,1859.1,1986.4 -0.37113990973121325,1.7291447966856177,1.1780972450961724,173.4,172.7,314.7,313.5,2262.4,2481.3 -0.3707293991376938,1.7289635124927205,1.3089969389957472,136.8,250.4,264.6,701.3,3028.0,2900.9 -0.37080000773369276,1.7289269691876834,1.4398966328953218,129.2,313.2,254.9,1483.0,2671.5,2613.3 -0.3709889492115474,1.7292116176795769,1.5707963267948966,140.9,270.9,270.7,1621.1,2551.2,2551.0 -0.37095543955575916,1.7292098170508279,1.7016960206944713,171.7,254.3,312.8,1660.2,1367.9,540.7 -0.3709138804070665,1.7291958977969577,1.832595714594046,229.7,265.5,393.3,1848.9,628.7,249.9 -0.3711378307123948,1.728876664130805,1.9634954084936205,314.5,315.9,740.9,2271.2,391.8,172.7 -0.371298007056304,1.7290532632312463,2.0943951023931953,252.2,738.2,830.8,2978.5,276.8,149.6 -0.37082533017099545,1.7291786159166833,2.2252947962927703,232.8,926.6,1683.2,2635.9,209.7,151.0 -0.3711619950906497,1.7290342236907223,2.356194490192345,241.6,1651.2,1651.6,2520.6,170.3,170.9 -0.3711500957036174,1.7292653802634903,2.4870941840919194,275.8,1683.4,1742.5,1212.5,151.1,210.3 -0.37074221227120674,1.729022114588893,2.6179938779914944,345.7,1861.0,1988.9,546.9,149.1,276.9 -0.3710862737691908,1.7291498781657264,2.748893571891069,474.6,2266.2,2486.5,333.6,173.6,314.4 -0.3708946429961134,1.728913088855367,2.8797932657906435,748.1,3028.0,2899.4,229.8,251.3,264.9 -0.3709144907876616,1.728903100701112,3.010692959690218,1661.1,2673.5,2614.7,172.3,313.4,254.5 -0.3708924717587221,1.628636399396263,0.0,1521.5,2550.9,2551.2,240.8,271.0,270.9 -0.37096239067027326,1.6293058590532654,0.1308996938995747,1601.8,1731.8,1000.8,232.6,254.6,313.9 -0.37093855727778735,1.6292979323282266,0.2617993877991494,1824.8,829.4,449.8,252.4,265.1,392.5 -0.3711213120618656,1.628877084924187,0.39269908169872414,2289.1,533.4,314.1,315.3,315.3,536.0 -0.3711267183446416,1.6288848776185387,0.5235987755982988,3011.9,392.3,264.8,345.1,608.1,828.6 -0.3708465845097716,1.6290952183616432,0.6544984694978736,2594.2,313.7,254.6,275.6,921.0,1579.8 -0.3708399678924572,1.6290702787707827,0.7853981633974483,2521.5,270.9,270.3,240.8,1551.7,1551.0 -0.3707904867097966,1.6290692438198393,0.916297857297023,1007.0,254.4,313.3,232.4,1579.6,1638.3 -0.3708027524892265,1.6290329875650869,1.0471975511965976,472.6,265.0,392.3,252.4,1743.9,1871.3 -0.37114035647431154,1.6291445010740442,1.1780972450961724,315.0,313.8,314.7,313.5,2121.6,2340.8 -0.370729471375917,1.6289631645792082,1.3089969389957472,252.3,392.1,264.6,514.9,3002.4,2901.0 -0.37080002580335736,1.6289266503447,1.4398966328953218,232.7,313.3,254.9,1356.5,2671.1,2613.5 -0.37089335238274185,1.6289057610178492,1.5707963267948966,241.0,270.8,270.6,1521.1,2551.1,2551.1 -0.3708934163260513,1.6289057211383866,1.7016960206944713,275.2,254.3,312.7,1557.0,1757.5,1015.8 -0.37089171806897975,1.6289045973701695,1.832595714594046,345.3,265.5,393.2,1732.6,828.0,449.2 -0.37094775785993095,1.6289404205146434,1.9634954084936205,314.1,315.8,568.2,2130.7,532.7,313.8 -0.3709652755834427,1.6289606715466847,2.0943951023931953,252.1,606.8,831.2,2978.8,392.3,265.0 -0.3709562323557974,1.6289413788567475,2.2252947962927703,232.7,926.9,1579.7,2635.0,313.3,254.5 -0.3709621651775824,1.628964331532052,2.356194490192345,241.5,1550.8,1551.7,2520.2,270.4,271.0 -0.37113338345552555,1.6290200683731184,2.4870941840919194,275.6,1579.9,1638.8,1598.9,254.6,313.7 -0.3711309415739109,1.6290306772402814,2.6179938779914944,345.5,1745.4,1872.8,746.4,264.8,392.4 -0.3711077101341771,1.629062835648487,2.748893571891069,474.4,2124.0,2344.2,475.2,315.1,314.5 -0.370869976018808,1.6288433904738917,2.8797932657906435,748.0,3003.5,2900.3,345.4,392.4,264.9 -0.3708866637047351,1.628835243588909,3.010692959690218,1557.0,2673.6,2614.8,275.8,313.4,254.6 -0.3708731329019683,1.5285797908394005,0.0,1421.2,2550.9,2550.8,340.8,271.0,271.0 -0.370952667944828,1.5293068594704895,0.1308996938995747,1498.3,2115.1,1300.1,336.3,254.5,313.9 -0.3709307648680721,1.529299525457247,0.2617993877991494,1709.3,1028.9,649.2,367.9,265.0,392.6 -0.37111789925319943,1.5288770437969865,0.39269908169872414,2147.8,674.5,455.3,457.0,315.3,536.0 -0.3711236440105934,1.528885191286875,0.5235987755982988,2888.8,508.0,380.3,345.2,449.4,828.6 -0.37084590905093473,1.5290948640885018,0.6544984694978736,2593.6,417.1,358.1,275.6,1315.3,1476.5 -0.3708393169042924,1.5290700258170042,0.7853981633974483,2521.4,370.8,370.3,240.9,1451.7,1450.8 -0.3707917786933266,1.529068925655971,0.916297857297023,1394.3,358.0,416.9,232.4,1476.2,1535.2 -0.3708040000934584,1.5290328088709986,1.0471975511965976,672.2,380.6,450.7,252.4,1628.5,1755.5 -0.3711406321533291,1.5291442306792618,1.1780972450961724,456.8,455.0,314.7,313.5,1980.4,2199.7 -0.37072955653174083,1.5289629291990547,1.3089969389957472,368.0,392.1,264.6,471.0,2803.1,2939.2 -0.3708000640952255,1.5289264399535565,1.4398966328953218,336.2,313.3,254.9,1276.0,2671.3,2613.4 -0.370893393034161,1.528905550760563,1.5707963267948966,340.9,270.8,270.7,1421.0,2551.1,2551.4 -0.3708934751591356,1.5289055121654251,1.7016960206944713,378.6,254.3,312.7,1453.5,2146.8,1319.2 -0.37089179795586313,1.5289043953361605,1.832595714594046,461.0,265.5,393.2,1617.4,1027.3,648.3 -0.37094785635816563,1.528940231094123,1.9634954084936205,314.2,315.9,536.9,1988.6,673.7,454.7 -0.37096538786637945,1.5289604982310894,2.0943951023931953,252.1,450.6,831.1,2830.3,507.8,380.5 -0.37095635330857357,1.5289412229798638,2.2252947962927703,232.7,1314.9,1476.1,2634.7,416.6,358.1 -0.3709622897600149,1.5289641934326448,2.356194490192345,241.5,1451.0,1451.4,2520.5,370.3,371.0 -0.371133403658246,1.5290199873710584,2.4870941840919194,275.6,1476.4,1535.5,1984.8,358.1,417.2 -0.3711309577654271,1.5290306095492117,2.6179938779914944,345.5,1629.8,1757.6,945.8,380.4,450.0 -0.3711077237848032,1.5290627726372843,2.748893571891069,474.4,1983.0,2202.7,616.6,456.6,314.4 -0.37086998832146006,1.528843367234986,2.8797932657906435,748.1,2803.7,2939.9,461.0,392.4,265.0 -0.3708866716341632,1.5288352227496271,3.010692959690218,1453.7,2673.4,2614.7,379.3,313.4,254.5 -0.3708731418851279,1.4285797733869823,0.0,1321.1,2550.9,2551.0,440.9,271.0,271.0 -0.37095267288078365,1.4293068474329118,0.1308996938995747,1394.4,2499.4,1684.0,439.7,254.6,313.9 -0.37093076873147657,1.4292995132248918,0.2617993877991494,1593.6,1228.2,848.7,483.6,265.0,392.6 -0.3711178988139992,1.4288770398370496,0.39269908169872414,2005.7,815.7,596.4,473.5,513.6,536.0 -0.3711236440603325,1.4288851879042286,0.5235987755982988,2863.1,623.6,496.0,345.1,449.4,828.5 -0.3708459105743925,1.4290948610663967,0.6544984694978736,2593.7,520.7,461.7,275.6,1211.9,1372.7 -0.37083931827921424,1.4290700225467123,0.7853981633974483,2520.9,470.8,470.4,240.8,1351.6,1351.2 -0.37079328125537797,1.4290688801448046,0.916297857297023,1781.4,461.5,520.4,232.4,1372.7,1431.4 -0.37080544994865217,1.4290329273301194,1.0471975511965976,871.9,496.1,450.6,252.4,1512.7,1639.8 -0.3711409214353173,1.4291440364640748,1.1780972450961724,598.4,535.5,314.7,344.5,1838.4,2058.4 -0.3707296046690259,1.4289627053299343,1.3089969389957472,483.6,392.1,264.6,470.9,2603.5,2900.6 -0.37080007714287705,1.428926234839653,1.4398966328953218,439.6,313.3,254.9,1172.3,2671.4,2613.3 -0.37089341320975955,1.4289053446550426,1.5707963267948966,440.9,270.9,270.7,1320.7,2551.1,2551.1 -0.3708935156150097,1.4289053073639344,1.7016960206944713,482.2,254.2,312.7,1349.9,2614.7,1708.5 -0.37089186059711354,1.428904197765834,1.832595714594046,471.7,265.5,393.2,1501.4,1226.2,847.4 -0.37094793837755025,1.4289400465005397,1.9634954084936205,314.2,513.3,537.0,1846.9,814.8,595.9 -0.370965484240368,1.4289603301660314,2.0943951023931953,252.0,450.6,831.2,2630.4,623.2,496.1 -0.3709564587473267,1.4289410728640248,2.2252947962927703,232.7,1211.4,1372.4,2635.6,520.3,461.5 -0.37096239907157375,1.4289640616531174,2.356194490192345,241.5,1351.1,1352.1,2520.5,470.4,471.1 -0.3711334046904501,1.429019910030466,2.4870941840919194,275.6,1372.8,1432.0,2370.6,461.7,520.7 -0.3711309550451929,1.4290305450695433,2.6179938779914944,370.9,1514.0,1641.7,1145.0,496.0,450.0 -0.37110771861963965,1.4290627128583904,2.748893571891069,474.4,1841.4,2061.5,758.0,534.5,314.5 -0.370869991168084,1.4288433487045435,2.8797932657906435,748.2,2603.8,2899.9,576.5,392.4,265.0 -0.37088667152292754,1.428835205862224,3.010692959690218,1350.1,2673.3,2614.5,482.8,313.4,254.5 -0.37087314353364853,1.328579760013988,0.0,1221.1,2551.0,2551.2,540.9,271.0,271.0 -0.37095267453946756,1.3293068370336303,0.1308996938995747,1290.9,2615.8,2067.7,543.3,254.6,313.9 -0.3709307699666536,1.3292995028250612,0.2617993877991494,1478.1,1427.5,1091.9,599.1,265.0,392.6 -0.37111789755711844,1.328877035873127,0.39269908169872414,1864.7,956.9,737.5,473.5,315.2,536.0 -0.3711236433719156,1.328885184599753,0.5235987755982988,2701.0,739.1,611.6,345.1,493.2,828.7 -0.37084591191733884,1.3290948579739843,0.6544984694978736,2593.3,624.2,565.2,275.6,1085.4,1269.4 -0.37083931947870846,1.32907001922695,0.7853981633974483,2521.2,570.9,570.3,240.8,1251.6,1251.2 -0.37079585855032254,1.329068689546932,0.916297857297023,2168.8,565.0,623.8,232.4,1269.3,1327.7 -0.37080794447814885,1.3290329956280527,1.0471975511965976,1071.5,611.6,450.8,252.4,1397.3,1524.7 -0.37114145642220303,1.3291436372247898,1.1780972450961724,740.2,535.5,314.7,313.5,1697.9,1917.0 -0.3707297204665086,1.3289622885519994,1.3089969389957472,599.0,392.1,264.6,471.0,2404.6,2783.7 -0.3708001180596589,1.3289258580813597,1.4398966328953218,543.0,313.3,255.0,1017.1,2671.6,2613.4 -0.37089346198258427,1.3289049673833813,1.5707963267948966,541.0,270.9,270.7,1221.0,2551.3,2551.1 -0.37089359839609104,1.3289049324795732,1.7016960206944713,585.7,254.2,312.7,1246.5,2613.8,2097.3 -0.37089198176356936,1.3289038355092289,1.832595714594046,471.6,265.5,393.3,1385.8,1425.5,1046.7 -0.3709480933239611,1.3289397070739488,1.9634954084936205,314.2,347.1,536.8,1705.2,955.8,737.0 -0.3709656641725412,1.3289600198223388,2.0943951023931953,252.1,450.6,831.0,2431.3,738.8,611.6 -0.3709566544109771,1.3289407939649167,2.2252947962927703,232.7,1085.0,1268.9,2634.6,623.7,565.0 -0.3709626013925913,1.3289638148510765,2.356194490192345,241.5,1251.0,1251.7,2520.5,570.3,570.9 -0.3711334141119887,1.3290197644404609,2.4870941840919194,275.6,1269.4,1328.3,2593.1,565.2,624.3 -0.3711309572585776,1.329030423740996,2.6179938779914944,345.5,1398.5,1526.0,1344.2,611.5,450.0 -0.3711077165003931,1.3290625997267886,2.748893571891069,505.5,1700.2,1920.0,899.4,534.7,314.5 -0.3708699990837243,1.3288433103825543,2.8797932657906435,748.0,2404.5,2784.5,692.1,392.4,264.9 -0.37088667327020103,1.3288351709318698,3.010692959690218,1246.6,2673.1,2614.9,586.2,313.4,254.6 -0.3708731477649606,1.2285797308671298,0.0,1121.1,2551.1,2551.3,640.8,271.0,270.9 -0.37095267743715377,1.2293068255800026,0.1308996938995747,1187.6,2616.3,2451.4,646.8,254.6,313.9 -0.3709307722849694,1.22929949132785,0.2617993877991494,1362.7,1627.1,1247.7,714.9,431.5,392.6 -0.3711178965185813,1.2288770319228661,0.39269908169872414,1722.5,1129.3,878.8,473.5,315.2,536.1 -0.3711236428769734,1.228885181283403,0.5235987755982988,2501.5,854.7,727.2,345.2,449.4,828.5 -0.3708459132849635,1.229094854920479,0.6544984694978736,2593.8,727.9,668.8,275.6,1090.7,1165.6 -0.37083932070101,1.2290700159375727,0.7853981633974483,2521.4,670.8,670.5,240.8,1151.7,1151.1 -0.3708405012010982,1.229071862740288,0.916297857297023,2635.7,668.4,727.3,232.4,1165.7,1224.3 -0.370850670479944,1.229042147028212,1.0471975511965976,1270.9,727.1,450.6,252.4,1281.7,1409.3 -0.3708727604764598,1.2290055081230116,1.1780972450961724,882.0,535.6,314.6,313.4,1556.7,1775.7 -0.3708630493572548,1.2290145396356271,1.3089969389957472,714.7,392.2,264.6,470.6,2203.8,2583.0 -0.3708699623351171,1.2290115690346022,1.4398966328953218,646.4,313.3,255.0,1015.9,2671.8,2613.5 -0.3709355114582546,1.2289964415595132,1.5707963267948966,640.9,270.9,270.7,1121.2,2551.3,2551.1 -0.37092191928440843,1.2289955043797987,1.7016960206944713,689.0,254.2,312.7,1143.0,2614.1,2488.9 -0.37091203190457267,1.228991673152434,1.832595714594046,472.0,432.0,393.2,1270.2,1625.2,1246.4 -0.37096250054792274,1.2290236587513754,1.9634954084936205,314.3,315.8,536.8,1562.9,1097.2,878.2 -0.37097627530269006,1.2290394866106173,2.0943951023931953,252.1,450.5,1036.2,2229.7,854.4,727.2 -0.3709648467668503,1.2290157048523949,2.2252947962927703,232.7,1096.7,1165.6,2635.0,727.2,668.4 -0.3709696442271367,1.2290341077426654,2.356194490192345,241.5,1151.0,1151.7,2520.7,670.4,671.0 -0.371169076681097,1.229057949672122,2.4870941840919194,275.7,1165.9,1224.8,2594.1,668.8,727.8 -0.37116859791343176,1.229061345432569,2.6179938779914944,345.6,1282.9,1410.6,1542.8,727.3,449.9 -0.371146167575274,1.2290915852451847,2.748893571891069,474.5,1558.8,1778.7,1040.8,534.5,314.5 -0.37088541439911105,1.228846223494311,2.8797932657906435,748.2,2205.4,2585.5,807.7,392.4,264.9 -0.37090118812560013,1.2288385435202462,3.010692959690218,1143.3,2673.4,2614.6,689.8,313.4,254.5 -0.3708858288617225,1.1285815526421903,0.0,1021.2,2550.7,2551.5,740.9,270.9,271.0 -0.37095832430527614,1.1293044291764578,0.1308996938995747,1083.8,2616.4,2675.4,750.5,254.6,313.9 -0.37093524237170505,1.1292967402671514,0.2617993877991494,1246.9,1826.7,1447.1,747.7,265.1,392.6 -0.37111945396104407,1.1288769644099892,0.39269908169872414,1580.8,1239.1,1020.0,473.5,315.3,536.0 -0.3711250683452595,1.1288849777426435,0.5235987755982988,2302.2,970.4,842.9,345.2,449.4,896.2 -0.37084619342544184,1.129095002927441,0.6544984694978736,2593.2,831.3,772.2,275.5,921.1,1062.1 -0.37083958990606763,1.1290701187314696,0.7853981633974483,2521.7,770.9,770.3,240.8,1051.6,1051.0 -0.3708064976739175,1.1290640016226865,0.916297857297023,2635.4,772.0,830.9,232.4,1062.1,1120.8 -0.3708174351392026,1.1290318920254645,1.0471975511965976,1515.0,830.9,450.8,252.4,1166.3,1293.3 -0.37114254801098673,1.1291452871713368,1.1780972450961724,1023.5,535.5,314.7,313.5,1415.5,1634.9 -0.37072666299901585,1.1289593104619138,1.3089969389957472,830.3,392.1,264.6,471.0,2005.9,2385.1 -0.370798390809006,1.1289221847057274,1.4398966328953218,749.9,313.3,254.9,1081.8,2671.3,2613.7 -0.37089246198798237,1.128901151743214,1.5707963267948966,741.1,270.8,270.7,1021.0,2551.2,2551.3 -0.3708930692817346,1.12890115012745,1.7016960206944713,792.6,254.2,312.7,1039.6,2613.9,2672.8 -0.3708918031531443,1.1289001662436298,1.832595714594046,471.6,265.5,393.2,1154.6,1823.8,1444.7 -0.37094818139723734,1.1289362209414078,1.9634954084936205,314.2,347.0,537.0,1421.5,1237.9,1019.0 -0.3709659389584705,1.1289567563113816,2.0943951023931953,252.1,450.6,920.4,2031.2,969.8,842.4 -0.37095704922511236,1.1289377599405284,2.2252947962927703,232.7,926.9,1061.9,2635.0,830.7,772.0 -0.37096305092225856,1.1289610147595734,2.356194490192345,241.5,1051.3,1051.7,2520.5,770.3,770.9 -0.37113241905628636,1.1290182590316007,2.4870941840919194,275.6,1062.2,1121.3,2593.3,772.3,831.3 -0.37112987918613444,1.1290292148196355,2.6179938779914944,345.5,1167.3,1294.9,1742.9,829.1,450.1 -0.37110659984205463,1.1290614738152573,2.748893571891069,474.4,1417.0,1637.2,1182.5,534.6,314.5 -0.37086957883767235,1.1288431199004136,2.8797932657906435,907.9,2005.8,2385.5,923.3,392.4,264.9 -0.3708862649444937,1.1288349749503541,3.010692959690218,1039.8,2673.6,2614.9,793.4,313.4,254.5 -0.4709552322112855,1.8290530812283567,0.0,1720.8,2451.1,2451.2,41.0,371.0,371.0 -0.47098038706489415,1.8289349291958372,0.1308996938995747,1808.6,965.0,148.9,25.5,358.2,417.5 -0.4711307614955159,1.8289825894831957,0.2617993877991494,2055.9,431.0,51.3,21.3,380.6,508.1 -0.4710567343300485,1.8289360506667711,0.39269908169872414,2571.9,251.1,31.8,32.0,456.8,881.4 -0.4710468671604634,1.8289272515338635,0.5235987755982988,2773.3,161.2,33.5,72.2,839.6,1027.4 -0.47082391036514043,1.8291045708711777,0.6544984694978736,2489.9,106.5,47.5,231.5,1626.1,1786.6 -0.47081661712448913,1.8290764901704681,0.7853981633974483,2421.4,70.9,70.4,340.8,1751.6,1751.3 -0.47081796265835835,1.8290750261866926,0.916297857297023,232.2,47.4,106.3,335.9,1786.7,1845.3 -0.47082910392829674,1.829042302256832,1.0471975511965976,73.2,33.9,161.2,367.9,1974.8,2102.3 -0.4708528018130051,1.8290032047602724,1.1780972450961724,31.7,31.5,250.7,454.5,2403.3,2622.5 -0.4708450794843813,1.8290104182639615,1.3089969389957472,21.1,50.9,380.2,817.1,2913.3,2785.2 -0.47085420694379837,1.8290062682304689,1.4398966328953218,25.7,152.2,358.4,1563.5,2568.3,2509.7 -0.47092204368350965,1.8289906342708175,1.5707963267948966,40.9,370.9,370.7,1721.5,2451.4,2451.7 -0.4709105828706892,1.8289897567242779,1.7016960206944713,68.2,357.8,416.2,1764.1,1065.8,151.9 -0.47090260008428436,1.8289864521272492,1.832595714594046,114.0,381.1,508.8,1964.0,429.9,50.8 -0.470954667914855,1.8290193893879385,1.9634954084936205,192.4,457.5,882.7,2413.3,250.5,31.5 -0.4709696451879907,1.8290364435796125,2.0943951023931953,349.9,838.1,1030.4,2863.4,161.2,33.9 -0.4709590205541456,1.829047567490738,2.2252947962927703,336.3,1625.7,1786.6,2531.4,106.2,47.4 -0.47096692221755526,1.8290403547196985,2.356194490192345,341.5,1751.1,1751.7,2420.2,70.3,70.9 -0.4711375198280126,1.829062360429365,2.4870941840919194,379.2,1787.1,1846.2,826.9,47.5,106.6 -0.47113771555055983,1.8290640843735237,2.6179938779914944,461.3,1976.7,2104.6,347.7,33.5,161.2 -0.4711160890370959,1.829093280196037,2.748893571891069,616.0,2407.5,2627.3,192.2,32.3,252.3 -0.47087235066671446,1.8288528650745437,2.8797932657906435,991.4,2911.6,2784.5,114.3,51.8,380.5 -0.4708902287062958,1.8288440623757418,3.010692959690218,1764.4,2570.2,2511.0,68.7,151.9,358.1 -0.47087585067086296,1.7285871185967676,0.0,1621.3,2451.3,2451.2,140.8,371.0,371.0 -0.47095382667563773,1.7293065638275573,0.1308996938995747,1705.2,1347.5,532.4,129.1,358.1,417.5 -0.47093162902117996,1.7292991397587232,0.2617993877991494,1940.1,630.1,250.5,136.8,380.6,508.2 -0.4711182650994262,1.7288769964375457,0.39269908169872414,2431.0,392.2,173.0,173.7,456.9,677.8 -0.47112398528182714,1.7288851189451286,0.5235987755982988,2772.7,276.8,149.1,271.5,692.5,1027.8 -0.4708459844555141,1.7290948796018049,0.6544984694978736,2490.2,210.1,151.0,379.2,1522.4,1683.3 -0.4708393891569459,1.7290700301927022,0.7853981633974483,2421.1,170.9,170.4,340.8,1651.6,1650.9 -0.47084056926284057,1.729071877245225,0.916297857297023,619.5,150.9,209.8,335.9,1683.2,1742.4 -0.4708507371114359,1.7290421648379255,1.0471975511965976,272.8,149.5,276.8,367.9,1859.0,1986.6 -0.470847108797591,1.7290465344868786,1.1780972450961724,173.4,172.7,391.8,454.6,2262.1,2481.5 -0.47086160308822567,1.729032986466874,1.3089969389957472,136.8,250.2,380.2,669.9,2956.9,2785.9 -0.4708750425434583,1.7290265579613635,1.4398966328953218,129.2,416.8,358.5,1405.7,2568.2,2509.7 -0.47093989684502036,1.7290116054307414,1.5707963267948966,140.9,370.8,370.7,1621.2,2451.6,2451.1 -0.4709232724840784,1.7290105766825383,1.7016960206944713,171.6,357.8,416.2,1660.5,1369.8,541.5 -0.4709099394790301,1.7290057079311567,1.832595714594046,229.6,381.2,508.8,1848.1,629.2,250.1 -0.4709573211894581,1.7290357644092786,1.9634954084936205,334.2,457.5,709.9,2271.8,391.7,172.6 -0.4709687587502133,1.7290490872944546,2.0943951023931953,367.6,650.1,1030.5,2984.8,276.8,149.5 -0.47095583605482927,1.7290225146937528,2.2252947962927703,336.2,1521.8,1683.0,2531.2,209.7,151.0 -0.47095996260974965,1.7290380271832357,2.356194490192345,341.5,1651.3,1651.5,2420.6,170.3,170.9 -0.4711777352706784,1.729059186829084,2.4870941840919194,379.2,1683.6,1742.8,1212.2,151.0,210.1 -0.4711774703830008,1.7290616668591636,2.6179938779914944,461.4,1860.8,1989.0,547.0,149.1,276.7 -0.4711251529736613,1.7291402901756048,2.748893571891069,616.1,2266.0,2486.3,333.7,173.7,393.8 -0.47090024058417274,1.7288834164049725,2.8797932657906435,947.9,2959.4,2784.4,229.8,251.4,380.5 -0.47092124905611804,1.7288728824093136,3.010692959690218,1660.9,2570.1,2511.5,172.2,416.8,358.1 -0.4709019512835838,1.6286089142237807,0.0,1521.1,2450.8,2451.2,240.8,371.0,371.0 -0.4709395712218054,1.6292860562358014,0.1308996938995747,1601.7,1732.0,916.4,232.6,358.2,417.5 -0.47092884111235617,1.6292822233903217,0.2617993877991494,1824.4,829.5,449.9,252.4,380.7,508.1 -0.4711124949422483,1.6288730457545406,0.39269908169872414,2288.9,533.4,314.2,315.3,457.0,677.7 -0.4711189974868486,1.6288820137399154,0.5235987755982988,2772.8,392.5,264.7,460.7,648.7,1027.7 -0.47084400096258117,1.6290931855664996,0.6544984694978736,2489.9,313.6,254.6,379.1,1419.1,1579.5 -0.470837525336123,1.6290688337383912,0.7853981633974483,2421.3,270.9,270.4,340.9,1551.2,1551.2 -0.4708387099092094,1.6290706955431102,0.916297857297023,1006.5,254.5,313.3,335.9,1579.6,1638.5 -0.4708489241617131,1.6290408559086047,1.0471975511965976,472.4,265.0,392.3,367.9,1744.1,1871.1 -0.47087111177759927,1.6290040826544094,1.1780972450961724,315.1,313.8,456.4,454.5,2120.9,2340.1 -0.4708615285269671,1.629013006883063,1.3089969389957472,252.3,449.6,380.2,670.0,2913.1,2785.6 -0.47086858543374654,1.6290099660920783,1.4398966328953218,232.6,416.8,358.4,1405.7,2568.6,2510.3 -0.470934282384997,1.6289948165114154,1.5707963267948966,240.9,370.9,370.7,1521.1,2451.8,2451.0 -0.4708764521071589,1.6289890300201129,1.7016960206944713,275.1,357.7,416.2,1557.1,1759.2,931.1 -0.4708962174429718,1.6289943047693716,1.832595714594046,345.2,381.1,508.8,1732.7,828.5,449.3 -0.4709531465488985,1.629030379900305,1.9634954084936205,455.4,457.5,678.5,2130.3,532.9,313.8 -0.4709670546273815,1.6290463728209228,2.0943951023931953,367.6,650.2,1030.6,2863.3,392.3,265.0 -0.47095468239103694,1.6290208290896677,2.2252947962927703,336.2,1398.7,1579.9,2531.7,313.2,254.5 -0.4709588979329078,1.6290367045407101,2.356194490192345,341.4,1551.2,1551.5,2420.7,270.4,270.9 -0.4711766266538561,1.6290585408238607,2.4870941840919194,379.2,1580.2,1639.2,1597.5,254.6,313.7 -0.4711763235013165,1.6290611677447335,2.6179938779914944,461.3,1745.6,1872.9,790.1,264.7,392.4 -0.4711541124987809,1.6290909697793399,2.748893571891069,616.1,2124.9,2344.5,475.1,315.1,455.9 -0.47088962776404564,1.628844617816322,2.8797932657906435,947.7,2911.6,2783.8,345.4,450.8,380.5 -0.4709048483184096,1.628837232726592,3.010692959690218,1557.1,2570.3,2511.1,275.8,416.9,358.1 -0.4708891465182756,1.5285801084461998,0.0,1421.2,2451.0,2451.0,340.8,371.0,371.0 -0.47095980414724153,1.5293037157514318,0.1308996938995747,1498.1,2115.7,1300.3,336.2,358.1,417.5 -0.47093642138664654,1.529295936975503,0.2617993877991494,1708.8,1028.9,649.4,368.0,380.7,508.1 -0.4711198408345022,1.5288769383564627,0.39269908169872414,2147.5,674.6,455.3,457.0,654.7,677.7 -0.47112542345134234,1.5288849191688967,0.5235987755982988,2856.6,507.8,380.3,460.7,648.7,1028.0 -0.47084626562333964,1.5290950326295414,0.6544984694978736,2489.7,417.2,358.1,379.1,1306.7,1476.6 -0.47083965890769264,1.5290701362093133,0.7853981633974483,2421.1,370.9,370.4,340.8,1451.7,1450.9 -0.4708408379452453,1.529071989135074,0.916297857297023,1393.8,358.0,416.9,335.9,1476.1,1535.2 -0.4708509984180252,1.529042297271428,1.0471975511965976,672.2,380.5,507.9,367.9,1628.1,1756.1 -0.4708730711029846,1.5290056821762144,1.1780972450961724,456.8,455.0,456.4,629.3,1979.8,2198.8 -0.47086333800271696,1.5290147320940575,1.3089969389957472,367.9,507.9,380.2,713.9,2802.6,2927.1 -0.4708702264368557,1.5290117734754718,1.4398966328953218,336.1,416.8,358.4,1405.8,2568.3,2509.7 -0.4709357501950625,1.5289966500509795,1.5707963267948966,340.9,370.9,370.6,1421.2,2451.3,2451.2 -0.47092213510357395,1.5289957110365535,1.7016960206944713,378.6,357.6,416.2,1453.6,2148.5,1320.7 -0.47091222755455153,1.5289918736451773,1.832595714594046,460.8,381.1,621.3,1616.8,1027.6,648.6 -0.4709626793654114,1.5290238483852097,1.9634954084936205,455.5,654.7,678.4,1988.2,673.9,454.8 -0.47097644176542786,1.5290396626933365,2.0943951023931953,367.7,650.2,1030.6,2829.0,507.7,380.5 -0.4709650048329309,1.5290158668940639,2.2252947962927703,336.2,1313.6,1476.2,2531.8,416.7,358.0 -0.4709697978000149,1.529034255003781,2.356194490192345,341.5,1451.2,1451.5,2420.3,370.3,370.9 -0.4711693447628588,1.529058012172434,2.4870941840919194,379.2,1476.5,1535.5,1983.0,358.1,417.2 -0.4711688702090531,1.5290613895078786,2.6179938779914944,461.3,1629.9,1757.7,945.3,380.3,508.0 -0.4711464406077511,1.5290916255156377,2.748893571891069,616.0,1983.3,2203.1,616.5,456.6,455.9 -0.47084812950180915,1.5288103696953605,2.8797932657906435,947.7,2804.5,2925.2,460.9,507.9,380.5 -0.47086918070733186,1.5287999809547637,3.010692959690218,1453.6,2570.5,2511.5,379.3,416.9,358.1 -0.4708621396425053,1.4285505214132999,0.0,1321.1,2450.8,2451.3,440.9,371.0,371.0 -0.4709457107245003,1.4293065017961308,0.1308996938995747,1394.5,2512.7,1684.1,439.8,358.1,417.5 -0.4709247746947627,1.4292994633567546,0.2617993877991494,1593.6,1228.1,848.7,483.6,380.6,508.2 -0.47111525383013364,1.428876698283326,0.39269908169872414,2006.0,815.8,596.6,598.6,456.9,677.7 -0.4711213370408464,1.4288852045756684,0.5235987755982988,2773.2,623.6,495.9,460.8,648.7,1027.9 -0.470845349544097,1.4290945001583282,0.6544984694978736,2489.7,520.7,461.6,379.1,1306.7,1372.9 -0.4708387787990052,1.4290697526054215,0.7853981633974483,2421.2,470.9,470.3,340.9,1351.5,1351.2 -0.4708399610441523,1.429071580587237,0.916297857297023,1780.9,461.4,520.3,336.0,1372.7,1431.4 -0.4708501469511142,1.4290418160337768,1.0471975511965976,871.7,496.0,623.4,367.9,1512.7,1640.2 -0.47087227010282645,1.429005129589068,1.1780972450961724,598.4,596.0,456.4,454.5,1838.7,2057.7 -0.4708626018987606,1.4290141238877538,1.3089969389957472,483.6,507.9,380.2,670.0,2602.3,2786.0 -0.4708695630906541,1.4290111289624572,1.4398966328953218,439.6,416.8,358.4,1392.8,2568.4,2510.0 -0.47093516168323746,1.4289959930343228,1.5707963267948966,440.8,370.9,370.7,1321.2,2451.1,2450.8 -0.4709216152735135,1.4289950590932456,1.7016960206944713,482.1,357.7,416.1,1350.1,2510.9,1710.1 -0.4709117684118407,1.4289912401353482,1.832595714594046,576.4,381.1,508.8,1501.3,1226.9,847.8 -0.47096227022840603,1.4290232471487174,1.9634954084936205,455.4,488.7,678.4,1846.5,815.1,596.0 -0.4709760695759755,1.429039102022412,2.0943951023931953,367.7,650.2,1030.6,2629.7,623.4,496.1 -0.4709646579441328,1.4290153489581359,2.2252947962927703,336.2,1313.3,1372.7,2531.5,520.2,461.5 -0.4709694641827523,1.4290337816533858,2.356194490192345,341.5,1351.2,1351.4,2420.8,470.2,470.9 -0.47116872594810827,1.4290577943579958,2.4870941840919194,379.2,1373.0,1432.0,2368.6,461.6,520.7 -0.4711682373600978,1.4290612307690091,2.6179938779914944,461.2,1514.3,1641.9,1144.7,496.1,623.8 -0.47114580159878977,1.4290914843403342,2.748893571891069,616.1,1841.5,2061.5,757.9,598.1,456.0 -0.47088525678398374,1.4288462614764468,2.8797932657906435,947.8,2604.3,2784.3,576.6,507.9,380.5 -0.4709010506974423,1.4288385709154028,3.010692959690218,1350.2,2569.7,2510.8,482.7,417.0,358.1 -0.4708857103013378,1.3285815921338417,0.0,1221.1,2450.7,2451.0,540.8,371.0,371.0 -0.4709582705026704,1.3293044166003773,0.1308996938995747,1290.9,2512.5,2067.8,543.3,358.1,417.4 -0.47093519820727214,1.329296731105151,0.2617993877991494,1478.0,1427.5,1048.0,599.1,380.6,508.1 -0.4711194316942222,1.328876945581246,0.39269908169872414,1864.4,987.9,737.8,614.7,457.0,677.6 -0.4711250505793145,1.3288849638604234,0.5235987755982988,2700.7,739.2,611.6,460.7,648.6,1152.7 -0.47084619438833103,1.3290949870261977,0.6544984694978736,2489.6,624.2,565.2,379.1,1305.5,1269.2 -0.4708395904196895,1.3290701025218574,0.7853981633974483,2420.7,570.9,570.4,340.8,1251.6,1251.0 -0.4708407696428388,1.3290719521797116,0.916297857297023,2168.4,565.0,623.7,335.9,1269.3,1328.4 -0.47085093250488136,1.3290422529852548,1.0471975511965976,1071.3,611.7,650.4,521.3,1397.1,1524.5 -0.4708730099760879,1.3290056307996576,1.1780972450961724,740.1,677.2,456.3,454.5,1697.6,1916.8 -0.4708632831515691,1.329014675142815,1.3089969389957472,599.2,507.8,380.2,670.0,2403.4,2782.8 -0.4708701786708854,1.3290117128839898,1.4398966328953218,543.1,416.8,358.4,1289.3,2568.2,2509.9 -0.47093570968399273,1.3289965881155923,1.5707963267948966,540.9,370.9,370.7,1221.1,2451.3,2451.2 -0.4709221013887298,1.3289956495117194,1.7016960206944713,585.6,357.7,416.1,1246.7,2510.8,2099.7 -0.47091219987498867,1.3289918139418075,1.832595714594046,671.1,381.1,508.7,1385.6,1425.9,1046.9 -0.4709626566010978,1.3290237918272148,1.9634954084936205,455.4,457.5,678.5,1704.8,956.3,737.1 -0.4709764226697689,1.329039610123211,2.0943951023931953,367.7,650.1,1151.7,2430.0,738.8,611.5 -0.4709649882467781,1.3290158186446082,2.2252947962927703,336.3,1305.2,1268.9,2531.6,623.8,565.1 -0.47096978248334037,1.3290342112160922,2.356194490192345,341.4,1251.2,1251.7,2420.6,570.4,570.8 -0.4711693076410029,1.3290579901709538,2.4870941840919194,379.1,1269.2,1328.4,2490.3,565.1,624.2 -0.4711688317558605,1.329061373002364,2.6179938779914944,461.2,1398.6,1526.3,1343.9,611.6,649.1 -0.4711464011590485,1.3290916112900115,2.748893571891069,616.1,1700.4,1920.4,899.3,675.8,455.9 -0.4708855271951138,1.3288461938810638,2.8797932657906435,1113.4,2404.8,2759.1,692.0,507.9,380.5 -0.47090128870935677,1.3288385205008546,3.010692959690218,1246.7,2569.9,2511.3,586.4,416.9,358.1 -0.4708859242483963,1.2285815307753265,0.0,1121.1,2451.1,2451.0,640.8,370.9,371.0 -0.4709583660532525,1.2293043669516588,0.1308996938995747,1187.4,2511.9,2451.7,646.9,358.1,417.5 -0.4709352742636299,1.2292966756874024,0.2617993877991494,1362.3,1627.1,1247.3,714.8,380.6,508.1 -0.47111945613199313,1.2288769416681455,0.39269908169872414,1722.7,1098.1,878.9,614.6,456.9,677.8 -0.47112507324600594,1.2288849581688395,0.5235987755982988,2501.6,854.7,727.2,460.8,648.7,1141.8 -0.4708461995735179,1.2290949871313626,0.6544984694978736,2489.9,727.7,668.7,379.0,1224.8,1165.5 -0.4708395953401602,1.229070101772611,0.7853981633974483,2421.1,670.8,670.4,340.8,1151.7,1151.3 -0.4708407745098014,1.2290719508686947,0.916297857297023,2532.1,668.5,727.4,336.0,1165.5,1224.6 -0.4708509374311642,1.2290422512493775,1.0471975511965976,1270.7,727.2,650.3,368.0,1281.7,1409.2 -0.4708730150413902,1.2290056287153717,1.1780972450961724,881.8,677.3,456.4,485.5,1556.5,1775.5 -0.4708632884515774,1.2290146727630349,1.3089969389957472,714.7,507.8,380.3,670.0,2203.9,2583.7 -0.47087018425681015,1.2290117103084555,1.4398966328953218,646.4,416.8,358.4,1185.6,2568.0,2510.0 -0.4709357155468749,1.228996585437093,1.5707963267948966,640.9,370.9,370.7,1121.1,2451.1,2450.8 -0.47092210757390557,1.2289956468164696,1.7016960206944713,689.0,357.7,416.2,1143.1,2510.4,2568.6 -0.4709122063605357,1.2289918113301819,1.832595714594046,671.2,381.1,508.7,1270.0,1625.1,1245.9 -0.47096266330277714,1.2290237893453957,1.9634954084936205,455.4,488.7,678.4,1563.1,1097.4,878.3 -0.4709764295487601,1.229039607822525,2.0943951023931953,367.7,650.1,1140.7,2230.2,854.4,727.1 -0.47096499525042196,1.229015816588932,2.2252947962927703,336.2,1224.4,1165.7,2531.3,727.3,668.5 -0.4709697895315631,1.2290342093935163,2.356194490192345,341.4,1151.1,1151.7,2421.0,670.3,671.0 -0.471169316764427,1.2290579884113602,2.4870941840919194,379.3,1166.0,1224.7,2490.4,668.6,727.9 -0.4711688408037763,1.2290613714828371,2.6179938779914944,461.3,1283.2,1410.6,1543.3,727.2,649.1 -0.471146409964992,1.2290916101649936,2.748893571891069,616.1,1559.0,1779.2,1040.7,675.9,456.0 -0.47088553212615425,1.2288461923865222,2.8797932657906435,1023.2,2205.7,2585.3,807.8,507.9,380.5 -0.47090129318211116,1.2288385192679923,3.010692959690218,1143.2,2570.1,2511.2,689.8,416.8,358.1 -0.4708859288875784,1.1285815300878765,0.0,1021.3,2451.3,2451.2,740.8,371.0,371.1 -0.4709583678621134,1.1293043599101065,0.1308996938995747,1084.0,2512.5,2572.3,750.5,358.1,417.5 -0.470935275525545,1.1292966685646082,0.2617993877991494,1246.9,1826.4,1446.7,830.2,380.6,508.2 -0.4711194554172585,1.1288769386266662,0.39269908169872414,1580.8,1239.3,1020.0,614.8,456.9,677.8 -0.4711250729456512,1.1288849556021314,0.5235987755982988,2302.2,970.3,842.7,460.6,648.7,1028.0 -0.4708462002751709,1.1290949847429783,0.6544984694978736,2490.2,831.4,772.2,379.1,1121.4,1062.4 -0.47083959595543134,1.1290700992717093,0.7853981633974483,2420.9,770.9,770.3,340.8,1051.5,1051.1 -0.470840775087563,1.129071947686208,0.916297857297023,2532.5,772.2,830.9,335.9,1062.2,1120.8 -0.4708509381929813,1.1290422472854038,1.0471975511965976,1470.5,842.8,650.3,368.0,1166.5,1293.6 -0.47087301618978034,1.1290056240515083,1.1780972450961724,1023.7,677.3,456.4,454.5,1415.3,1634.2 -0.47086329015347916,1.1290146675297468,1.3089969389957472,830.4,507.8,380.2,670.0,2004.8,2383.8 -0.4708701866023378,1.1290117047007457,1.4398966328953218,749.9,416.8,358.4,1082.0,2568.0,2510.0 -0.47093571853755467,1.1289965796636028,1.5707963267948966,740.8,371.0,370.7,1021.2,2451.3,2451.3 -0.4709221112249249,1.1289956410503572,1.7016960206944713,792.5,357.7,416.2,1039.7,2511.0,2569.1 -0.4709122106106781,1.1289918057383725,1.832595714594046,671.1,381.2,508.8,1154.6,1824.7,1445.5 -0.47096266801571296,1.129023784041849,1.9634954084936205,455.4,457.5,678.5,1421.3,1238.3,1019.3 -0.4709764346214633,1.12903960289932,2.0943951023931953,367.6,650.1,1030.3,2030.5,969.8,842.5 -0.47096500057227364,1.1290158121213019,2.2252947962927703,336.2,1120.8,1062.5,2531.8,830.7,772.1 -0.4709697949631279,1.129034205378792,2.356194490192345,341.5,1051.0,1051.7,2420.1,770.4,770.8 -0.47116932284848423,1.1290579856442111,2.4870941840919194,379.2,1062.3,1121.3,2490.1,772.3,831.3 -0.47116884674785253,1.129061369230576,2.6179938779914944,461.3,1167.6,1295.3,1742.5,842.7,649.1 -0.4711464156392723,1.129091608388931,2.748893571891069,615.9,1417.6,1637.6,1182.2,675.9,455.9 -0.4708855356432317,1.1288461912524421,2.8797932657906435,947.6,2006.0,2386.1,923.1,507.9,380.5 -0.4709012964116665,1.12883851830511,3.010692959690218,1039.8,2570.2,2511.6,793.4,416.9,358.1 -0.570968152500873,1.82905000105298,0.0,1720.7,2350.5,2351.1,41.0,471.0,470.9 -0.5709850833717504,1.8289344316266543,0.1308996938995747,1808.4,1049.2,148.9,25.5,461.6,521.1 -0.5711346861092487,1.8289818642382603,0.2617993877991494,2055.7,431.0,51.3,21.3,496.0,623.7 -0.5710597859346717,1.8289347832829475,0.39269908169872414,2572.2,251.1,31.8,32.0,598.4,819.1 -0.5710498941165464,1.8289259700858205,0.5235987755982988,2658.0,161.2,33.5,72.2,847.7,1226.8 -0.5708245551952956,1.829104668246837,0.6544984694978736,2386.4,106.5,47.5,231.5,1692.7,1786.9 -0.57081726915729,1.8290766279420991,0.7853981633974483,2320.8,70.9,70.4,440.8,1751.8,1751.0 -0.5708186104312741,1.8290752204786482,0.916297857297023,232.2,47.4,106.3,439.4,1786.9,1845.6 -0.5708297320922157,1.8290425514798836,1.0471975511965976,73.2,33.9,161.2,483.5,1975.1,2102.6 -0.570853397420756,1.8290034979600809,1.1780972450961724,31.7,31.5,250.7,595.5,2403.6,2622.8 -0.5708456364113768,1.8290107437108247,1.3089969389957472,21.1,50.9,430.2,869.4,2797.8,2670.0 -0.5708547216924829,1.8290066147949162,1.4398966328953218,25.7,152.1,461.8,1783.5,2464.7,2406.1 -0.5709225150816176,1.8289909871384813,1.5707963267948966,40.9,470.8,470.7,1720.8,2351.2,2351.4 -0.5709110152551125,1.8289901063991851,1.7016960206944713,68.2,461.1,519.7,1764.1,980.1,151.9 -0.5709029979345766,1.8289867921116718,1.832595714594046,114.0,496.9,624.4,1964.0,429.9,50.8 -0.5709550370071323,1.8290197110355317,1.9634954084936205,192.4,599.2,882.5,2413.6,250.5,31.5 -0.5709699931900025,1.8290367419556273,2.0943951023931953,349.8,849.9,1230.1,2747.9,161.2,33.9 -0.570959353646871,1.8290142886934675,2.2252947962927703,439.8,1701.1,1786.3,2427.7,106.2,47.4 -0.5709645463115035,1.8290340874342572,2.356194490192345,441.4,1751.1,1751.6,2320.8,70.3,70.9 -0.5711514381582679,1.829060775095223,2.4870941840919194,482.8,1787.2,1846.1,826.7,47.5,106.6 -0.5711508367004351,1.8290649493307178,2.6179938779914944,576.9,1977.2,2104.2,347.7,33.5,161.2 -0.5711282897709882,1.8290955195207288,2.748893571891069,757.4,2407.8,2627.2,192.2,32.3,252.3 -0.5708766112740429,1.8288508902175984,2.8797932657906435,1147.0,2796.2,2669.0,114.3,51.8,431.6 -0.570893805698639,1.8288424511771262,3.010692959690218,1763.9,2465.9,2408.0,68.7,151.9,461.6 -0.5708791033191414,1.7285855275429756,0.0,1621.3,2351.1,2350.7,140.8,471.0,471.0 -0.5709552954881931,1.7293058067253197,0.1308996938995747,1705.0,1347.8,532.4,129.0,461.7,521.1 -0.5709328098541059,1.7292982971329045,0.2617993877991494,1940.2,630.1,250.5,136.8,496.3,623.8 -0.5711227679533732,1.7288751720410798,0.39269908169872414,2430.9,392.2,173.0,173.6,598.5,819.3 -0.5711291394893557,1.7288840177214744,0.5235987755982988,2657.1,276.7,149.1,271.6,848.1,1227.3 -0.570846914951253,1.7290950336967665,0.6544984694978736,2385.9,210.1,151.0,482.6,1742.6,1683.5 -0.5708402900971323,1.72907006229472,0.7853981633974483,2321.4,170.9,170.4,440.8,1651.9,1651.4 -0.5708414659389957,1.7290719538273487,0.916297857297023,704.6,151.0,209.8,439.4,1683.3,1742.0 -0.5708516037574081,1.7290423300329198,1.0471975511965976,272.9,149.5,276.8,483.5,1859.5,1986.7 -0.5708736338529221,1.7290057800974712,1.1780972450961724,173.4,172.7,391.8,595.6,2262.2,2481.1 -0.5708638455726235,1.729014879921446,1.3089969389957472,136.7,250.2,495.8,869.4,2913.6,2670.3 -0.5708706716282883,1.7290119535441675,1.4398966328953218,129.2,520.3,461.9,1702.8,2465.3,2406.5 -0.5709361306473411,1.7289968445630364,1.5707963267948966,140.9,470.9,470.7,1620.8,2351.6,2351.0 -0.5709224554791141,1.728995903577145,1.7016960206944713,171.6,461.2,519.7,1660.6,1369.6,541.6 -0.5709124945500591,1.7289920504554175,1.832595714594046,229.6,496.7,624.4,1848.4,629.2,250.1 -0.5709629013315648,1.7290239980706128,1.9634954084936205,334.2,599.2,820.2,2272.1,391.7,172.6 -0.5709766299289339,1.7290397779618991,2.0943951023931953,483.3,849.8,1230.5,2747.9,276.7,149.5 -0.5709651709207672,1.7290159439689035,2.2252947962927703,439.7,1742.1,1683.2,2428.3,209.7,150.9 -0.5709699529377283,1.7290342920373547,2.356194490192345,441.5,1651.1,1651.5,2320.5,170.3,170.9 -0.5711661794658001,1.7290592084515861,2.4870941840919194,482.7,1683.2,1742.8,1212.2,151.0,210.1 -0.5711656458484835,1.729062846122,2.6179938779914944,576.9,1861.2,1989.0,546.9,149.1,276.8 -0.5711431802004691,1.7290931547316772,2.748893571891069,757.4,2266.1,2485.4,333.6,173.7,393.7 -0.5708839314333384,1.7288473091179255,2.8797932657906435,1147.1,2915.4,2669.1,229.9,251.3,496.1 -0.5709000030682027,1.7288394696770182,3.010692959690218,1660.8,2466.5,2407.7,172.2,520.4,461.5 -0.5708847449723776,1.628582452963712,0.0,1521.3,2351.3,2350.7,240.8,471.1,471.0 -0.5709578286402497,1.629304604149044,0.1308996938995747,1601.8,1731.3,916.3,232.7,461.6,521.0 -0.5709348391348599,1.6292969437390874,0.2617993877991494,1824.9,829.3,449.9,252.4,496.2,623.7 -0.5711251780463252,1.6288739349821248,0.39269908169872414,2289.6,533.4,314.1,315.3,795.9,819.4 -0.5711317767642242,1.6288830377966175,0.5235987755982988,2657.5,392.4,264.7,470.8,848.0,1227.1 -0.5708473119978269,1.6290950328299352,0.6544984694978736,2386.0,313.6,254.6,482.7,1638.8,1579.9 -0.5708406828480922,1.6290700444613557,0.7853981633974483,2321.1,270.9,270.4,440.9,1551.8,1551.3 -0.570841856508225,1.629071968382243,0.916297857297023,1091.8,254.5,313.3,439.4,1579.5,1638.6 -0.5708519799343129,1.6290423880069165,1.0471975511965976,472.4,265.0,392.3,483.5,1744.1,1871.3 -0.5708739839743381,1.6290058773673732,1.1780972450961724,315.1,313.8,532.9,771.0,2120.8,2340.1 -0.5708641625051544,1.6290150070290288,1.3089969389957472,252.3,449.5,495.8,869.3,2798.0,2670.1 -0.5708709512951177,1.629012099994573,1.4398966328953218,232.6,520.3,461.9,1599.4,2464.6,2406.5 -0.5709363717865288,1.628996999174878,1.5707963267948966,240.9,470.9,470.6,1521.1,2351.0,2351.4 -0.5709226608598676,1.6289960568011672,1.7016960206944713,275.1,461.2,519.6,1557.2,1759.2,1016.8 -0.5709126681223425,1.628992194457009,1.832595714594046,345.2,496.8,624.3,1732.6,828.5,449.3 -0.5709630482535184,1.629024125878219,1.9634954084936205,475.8,795.9,820.2,2129.9,532.8,313.8 -0.5709767568785006,1.6290398851420411,2.0943951023931953,483.2,893.8,1230.3,2785.1,392.3,265.0 -0.5709652845862058,1.6290160285136963,2.2252947962927703,439.8,1638.1,1579.7,2428.3,313.2,254.4 -0.5709700599109383,1.6290343528627589,2.356194490192345,441.4,1550.9,1551.5,2320.7,270.3,271.0 -0.5711641794479145,1.629059679514777,2.4870941840919194,482.8,1580.0,1639.1,1597.4,254.5,313.7 -0.5711636348155087,1.629063393075365,2.6179938779914944,576.9,1745.4,1873.0,746.1,264.7,392.4 -0.5711411715254169,1.6290937107588546,2.748893571891069,757.3,2125.0,2344.9,475.0,315.1,535.2 -0.5708829699782783,1.6288478874763004,2.8797932657906435,1147.3,2796.3,2668.9,345.4,450.9,496.0 -0.5709381434604213,1.6288229421004494,3.010692959690218,1557.5,2466.8,2407.9,275.7,520.4,461.5 -0.5708972108232659,1.5285924043507306,0.0,1421.3,2350.9,2351.0,340.8,471.0,471.0 -0.5709619764872343,1.5292975130071618,0.1308996938995747,1498.2,2115.1,1300.1,336.2,461.7,521.1 -0.5709376037755056,1.5292894361204932,0.2617993877991494,1709.0,1028.7,649.3,368.0,496.3,623.7 -0.570866708148878,1.5292417314558036,0.39269908169872414,2147.6,674.4,455.3,456.9,598.6,819.4 -0.570860420688985,1.529235914308257,0.5235987755982988,2657.4,507.9,380.2,576.3,848.0,1384.0 -0.5708544374514962,1.5292208969459775,0.6544984694978736,2386.4,417.2,358.1,482.7,1535.6,1476.5 -0.5708304110035479,1.529118423918121,0.7853981633974483,2321.1,370.8,370.3,440.8,1451.7,1451.2 -0.5708302761886025,1.529147788250593,0.916297857297023,1393.1,357.9,416.7,439.5,1476.2,1535.2 -0.5708403136603443,1.5291169896054635,1.0471975511965976,671.8,380.5,507.8,483.7,1628.6,1755.5 -0.5708669801914441,1.5290720921068717,1.1780972450961724,456.7,454.8,598.2,595.8,1980.2,2199.3 -0.5708651585506186,1.5290729243905705,1.3089969389957472,367.8,623.6,495.9,869.6,2772.1,2670.4 -0.5708819312166415,1.5290639565581374,1.4398966328953218,335.9,520.3,461.9,1496.1,2464.9,2406.6 -0.5709582198216636,1.5290457625502891,1.5707963267948966,340.8,471.0,470.8,1421.1,2351.8,2351.1 -0.570954953288872,1.5290446076609179,1.7016960206944713,378.5,461.2,519.7,1453.7,2148.1,1319.7 -0.5709544528684309,1.5290430912790847,1.832595714594046,460.7,496.7,624.6,1616.8,1027.4,648.4 -0.5710128654548277,1.5290796314337995,1.9634954084936205,596.7,685.8,820.3,1988.2,673.8,454.6 -0.571032559446513,1.5291015153120915,2.0943951023931953,483.3,849.9,1382.7,2747.8,507.7,380.4 -0.5710248717287026,1.5290845596874272,2.2252947962927703,439.7,1535.3,1476.2,2428.0,416.7,357.9 -0.5710209934416458,1.5290617200165717,2.356194490192345,441.5,1451.0,1451.7,2320.6,370.2,370.7 -0.5710080129467394,1.5293281161119965,2.4870941840919194,482.7,1476.3,1535.7,1982.7,358.0,417.2 -0.5707047675715183,1.52908253573831,2.6179938779914944,643.7,1629.6,1757.4,946.0,380.2,507.7 -0.5710807450764211,1.5291844383701947,2.748893571891069,757.7,1983.7,2203.6,616.3,456.5,597.1 -0.570888825406708,1.5289266283917078,2.8797932657906435,1146.9,2771.5,2668.8,461.0,623.5,496.1 -0.5709115100596956,1.5289151062523967,3.010692959690218,1453.7,2467.4,2407.8,379.3,520.4,461.6 -0.570889352778243,1.4286470415730839,0.0,1321.4,2350.7,2350.7,440.8,471.0,471.0 -0.5709607955694019,1.429306541201488,0.1308996938995747,1394.8,2408.7,1684.1,439.8,461.7,521.1 -0.5709371854485114,1.4292986805015957,0.2617993877991494,1593.6,1228.2,848.9,483.5,496.2,623.8 -0.5709038503304664,1.429277013606895,0.39269908169872414,2006.3,815.8,596.5,598.6,598.5,819.2 -0.570874844749654,1.429246769953434,0.5235987755982988,2657.5,623.5,495.8,576.3,848.0,1373.1 -0.5708647260141791,1.429223916909899,0.6544984694978736,2386.4,520.6,461.5,482.6,1431.7,1372.6 -0.5708530341218899,1.4291779534675852,0.7853981633974483,2320.8,470.7,470.4,440.8,1351.7,1351.2 -0.570854350555259,1.4291681317183975,0.916297857297023,1780.3,461.4,520.3,439.5,1373.0,1431.6 -0.5708664919422255,1.4291305626687265,1.0471975511965976,871.6,496.1,623.4,483.6,1513.0,1640.3 -0.5708916669111314,1.4290880325336375,1.1780972450961724,598.4,596.0,598.1,595.7,1839.1,2057.9 -0.5708858092709456,1.4290926358683984,1.3089969389957472,483.4,623.3,495.9,869.6,2602.9,2739.1 -0.5708971844202526,1.429086548944519,1.4398966328953218,439.4,520.2,461.9,1392.6,2464.5,2406.2 -0.5709675702679441,1.42906968054737,1.5707963267948966,440.8,471.0,470.8,1321.1,2351.5,2351.0 -0.570958702817196,1.4290683213644688,1.7016960206944713,481.9,461.2,519.7,1350.4,2407.3,1709.5 -0.5709084219259141,1.4292067121311132,1.832595714594046,576.4,496.8,624.4,1501.2,1227.3,848.2 -0.5711108565410827,1.4293361070827593,1.9634954084936205,596.7,599.1,820.0,1845.8,846.5,596.1 -0.5713324707880758,1.4288892503653363,2.0943951023931953,483.3,849.8,1372.0,2628.3,623.5,496.2 -0.5709162435742914,1.4290884171168852,2.2252947962927703,439.8,1431.5,1372.6,2428.5,520.3,461.5 -0.5709144864701989,1.4290798877584923,2.356194490192345,441.6,1351.1,1351.6,2320.6,470.4,470.9 -0.571193114718247,1.4290709694924955,2.4870941840919194,482.7,1373.1,1431.8,2386.4,461.7,520.8 -0.5711947524943158,1.4290668657052332,2.6179938779914944,576.9,1514.5,1641.8,1188.4,496.1,623.6 -0.5711733726686148,1.4290952029388873,2.748893571891069,757.4,1841.7,2061.7,758.0,598.0,597.3 -0.5708969212248125,1.4288432266609585,2.8797932657906435,1229.1,2605.1,2741.1,576.6,623.4,496.0 -0.5709109116968226,1.428836490993326,3.010692959690218,1350.3,2466.4,2407.2,482.8,520.4,461.6 -0.5708944376777487,1.3285791396849667,0.0,1221.0,2350.6,2351.0,540.8,471.0,470.9 -0.5709623075589185,1.3293026600329092,0.1308996938995747,1290.9,2409.0,2068.1,543.3,461.6,521.1 -0.5709384587665698,1.3292947424187154,0.2617993877991494,1478.1,1427.6,1048.2,599.2,496.3,649.2 -0.5709054012523983,1.32927326185547,0.39269908169872414,1864.1,956.8,737.6,740.2,598.5,819.3 -0.5708767221737094,1.3292433824917627,0.5235987755982988,2657.0,739.1,611.5,576.3,847.9,1227.0 -0.5708668338722055,1.3292209780027813,0.6544984694978736,2386.1,624.1,565.1,482.7,1328.6,1269.6 -0.570855247664933,1.329175494138279,0.7853981633974483,2321.0,570.8,570.2,440.8,1251.7,1251.1 -0.5708565461578046,1.3291661286693062,0.916297857297023,2167.0,564.9,623.7,439.4,1269.4,1328.1 -0.5708685627448051,1.3291289686408798,1.0471975511965976,1071.1,611.5,738.9,483.6,1397.4,1524.5 -0.570893530160066,1.32908677733178,1.1780972450961724,740.1,737.2,598.2,626.8,1697.9,1916.7 -0.5708874113029653,1.3290916336454868,1.3089969389957472,599.0,623.4,495.8,869.5,2403.9,2669.9 -0.5708984917146726,1.329085713151549,1.4398966328953218,543.0,520.4,461.9,1289.2,2464.2,2406.3 -0.5709685697492608,1.3290689267612326,1.5707963267948966,540.8,470.9,470.6,1221.3,2350.8,2350.9 -0.5709594112659184,1.3290675698434953,1.7016960206944713,585.3,461.2,519.8,1246.9,2407.1,2099.1 -0.5709536493325827,1.3290644691431928,1.832595714594046,691.9,602.1,624.4,1386.0,1425.9,1046.8 -0.5710076779781231,1.3290982609038242,1.9634954084936205,596.7,599.3,820.4,1705.0,955.9,736.9 -0.5710241315881311,1.3291166586949463,2.0943951023931953,483.2,850.0,1230.2,2429.6,738.8,611.4 -0.5710143793065094,1.3290958657519294,2.2252947962927703,439.7,1328.1,1269.2,2428.2,623.6,564.9 -0.5710198125142317,1.3291174305523823,2.356194490192345,441.6,1251.2,1251.8,2320.8,570.2,570.8 -0.5710169458292136,1.3291467860375146,2.4870941840919194,482.7,1269.5,1328.6,2386.5,565.2,624.2 -0.5710208913270615,1.3291367869516502,2.6179938779914944,576.8,1398.8,1526.7,1343.5,611.5,739.2 -0.5710078562276544,1.3291521470466177,2.748893571891069,757.3,1700.5,1921.0,899.1,739.4,597.2 -0.5708258436693835,1.3289113527850454,2.8797932657906435,1233.7,2403.8,2669.4,692.2,623.7,496.1 -0.5708514301998613,1.3288983366682974,3.010692959690218,1246.9,2466.3,2407.7,586.3,520.5,461.6 -0.5708373953440382,1.228637560060832,0.0,1121.1,2351.2,2351.1,640.7,471.0,470.9 -0.5709551067638597,1.2292982244462551,0.1308996938995747,1187.4,2408.9,2468.3,646.9,461.7,521.1 -0.5709249946052073,1.2292882795956714,0.2617993877991494,1362.5,1627.0,1247.4,714.7,496.2,623.7 -0.5708912039149284,1.229266272221875,0.39269908169872414,1722.7,1098.0,878.7,755.8,598.6,819.4 -0.5708631616440024,1.2292369649196475,0.5235987755982988,2501.6,854.7,727.1,576.4,848.0,1227.1 -0.5708539714978526,1.2292156717843845,0.6544984694978736,2386.0,727.7,668.7,482.7,1225.1,1165.9 -0.5708428168193218,1.229171550197884,0.7853981633974483,2321.1,670.8,670.2,440.9,1151.7,1151.4 -0.5708441809684685,1.2291635564875492,0.916297857297023,2428.4,668.5,727.3,439.5,1165.8,1224.5 -0.5708559207560823,1.2291276802330464,1.0471975511965976,1270.7,727.1,850.0,483.6,1281.7,1409.1 -0.5708803257017278,1.2290865997514424,1.1780972450961724,881.7,819.0,598.2,595.8,1556.9,1776.1 -0.5708734310337992,1.229092303031574,1.3089969389957472,714.7,623.4,495.7,869.4,2204.1,2584.3 -0.570883591312721,1.2290869380915634,1.4398966328953218,646.4,520.4,461.8,1185.5,2464.7,2406.3 -0.5709526856047556,1.229070429938694,1.5707963267948966,640.8,470.9,470.7,1121.2,2351.3,2351.2 -0.5709425914479479,1.229069057599154,1.7016960206944713,688.9,461.2,519.7,1143.1,2407.1,2465.4 -0.5709360033997334,1.2290656777649263,1.832595714594046,807.5,496.7,624.5,1270.2,1625.0,1246.0 -0.5709893612413199,1.2290989992500179,1.9634954084936205,596.5,599.2,820.4,1563.3,1097.1,877.9 -0.571005350300206,1.2291168096970178,2.0943951023931953,483.2,850.0,1230.2,2230.3,854.1,726.9 -0.5709953583674608,1.2290953702246652,2.2252947962927703,439.8,1224.7,1165.7,2428.1,727.2,668.4 -0.571000752218814,1.229116297679823,2.356194490192345,441.5,1151.1,1151.9,2320.0,670.3,670.8 -0.5709980080523668,1.229145090372685,2.4870941840919194,482.8,1165.9,1225.2,2386.8,668.7,727.8 -0.5710022115362187,1.2291346289778726,2.6179938779914944,576.9,1283.2,1411.1,1542.8,727.1,848.1 -0.5709894967146834,1.22914965169483,2.748893571891069,757.4,1559.4,1779.3,1040.5,817.1,597.2 -0.5708181787127877,1.2289140015318365,2.8797932657906435,1146.1,2203.8,2583.3,807.9,623.6,496.1 -0.5708448938212792,1.2289003833831638,3.010692959690218,1143.2,2466.9,2408.3,689.9,520.4,461.6 -0.5708315490841225,1.1286398123592876,0.0,1021.1,2350.9,2350.9,740.8,471.0,470.9 -0.5709355972041673,1.1293187232026973,0.1308996938995747,1083.9,2409.4,2468.2,750.6,461.6,521.0 -0.5709173039131987,1.1293124639555316,0.2617993877991494,1247.2,1826.1,1446.6,830.3,496.3,623.7 -0.571119207950172,1.1288746071944862,0.39269908169872414,1580.8,1239.3,1051.1,756.0,598.6,819.3 -0.5711260183870013,1.1288839087161817,0.5235987755982988,2302.3,970.4,842.9,576.4,1023.8,1167.1 -0.5708462734268878,1.129094464314451,0.6544984694978736,2386.4,831.3,772.3,482.6,1121.4,1062.2 -0.5708396869877591,1.1290696554333994,0.7853981633974483,2320.7,770.8,770.3,440.8,1051.5,1051.2 -0.5708408641974129,1.1290715498920796,0.916297857297023,2428.4,772.1,830.8,439.4,1062.2,1121.2 -0.5708510175619707,1.1290418826120368,1.0471975511965976,1470.4,842.8,849.9,509.0,1166.0,1293.7 -0.5708730813186266,1.1290052860026107,1.1780972450961724,1023.5,819.0,598.2,595.8,1415.2,1634.3 -0.5708633372323642,1.1290143485262933,1.3089969389957472,830.3,623.4,495.8,1001.6,2004.5,2384.1 -0.5708702130551653,1.1290113977332532,1.4398966328953218,750.0,520.3,461.9,1082.2,2464.8,2406.3 -0.5709357231198986,1.1289962809950531,1.5707963267948966,740.9,470.8,470.7,1021.3,2351.3,2351.3 -0.57093476040301,1.1291953786820828,1.7016960206944713,792.5,461.3,519.6,1039.5,2406.9,2465.8 -0.5709017279650053,1.1291843176948246,1.832595714594046,870.2,522.3,624.5,1154.4,1824.0,1445.3 -0.5709234667121256,1.1291981260978852,1.9634954084936205,596.6,599.3,820.4,1421.4,1238.1,1019.1 -0.5709135050336418,1.1291883938326377,2.0943951023931953,483.2,1047.8,1165.9,2030.9,969.8,842.6 -0.5708865093098724,1.1291353251465424,2.2252947962927703,439.8,1121.0,1062.3,2428.0,830.6,771.9 -0.5708842164174625,1.129123166331144,2.356194490192345,441.6,1051.2,1051.8,2320.3,770.4,770.9 -0.5711963048162797,1.1291081982449254,2.4870941840919194,482.9,1062.2,1121.6,2386.4,772.3,831.4 -0.5711982432007072,1.129103084128689,2.6179938779914944,577.0,1167.6,1295.3,1741.5,842.9,848.0 -0.5711765653926784,1.1291315193292268,2.748893571891069,757.7,1417.7,1638.2,1181.6,817.0,597.2 -0.5708955950598186,1.1288543650109528,2.8797932657906435,1128.1,2005.9,2386.2,923.3,623.5,496.0 -0.5709116237538863,1.1288465218931845,3.010692959690218,1039.7,2466.5,2407.8,793.3,520.4,461.5 -0.670976269824446,1.829051038502581,0.0,1721.0,2251.3,2251.2,41.0,571.0,571.0 -0.670988051480694,1.8289343994505607,0.1308996938995747,1808.5,964.9,148.9,25.5,565.3,624.6 -0.6709881327649007,1.828934417215431,0.2617993877991494,2055.8,430.9,51.3,21.3,611.8,739.2 -0.6709777440390003,1.829006688446965,0.39269908169872414,2572.5,251.1,31.8,32.0,740.0,960.8 -0.6709803729235737,1.8290106811299607,0.5235987755982988,2542.2,161.2,33.5,72.2,1046.9,1426.0 -0.6709885038834534,1.8290229384095673,0.6544984694978736,2282.9,106.6,47.5,231.4,1846.1,1787.1 -0.6709846396200229,1.8290118758963154,0.7853981633974483,2220.8,70.9,70.4,540.8,1751.6,1751.0 -0.6707929771677344,1.8290425318132884,0.916297857297023,232.3,47.5,106.3,543.0,1786.8,1845.7 -0.6708031891008726,1.8290128235297014,1.0471975511965976,73.2,34.0,161.3,599.0,1975.0,2102.3 -0.6708284079310698,1.8289714656265883,1.1780972450961724,31.7,31.5,250.7,736.7,2403.5,2622.4 -0.6708238508085238,1.8289758871495772,1.3089969389957472,21.1,50.9,430.2,1068.7,2683.0,2554.4 -0.6708370097163495,1.828969765205853,1.4398966328953218,25.7,152.2,565.3,1806.1,2361.2,2302.9 -0.6709091501810112,1.8289532746743027,1.5707963267948966,40.9,570.9,570.6,1721.1,2251.3,2251.3 -0.670901718692408,1.8289526656985915,1.7016960206944713,68.2,564.7,623.0,1763.9,980.4,152.0 -0.6708972769322713,1.8289505853771728,1.832595714594046,113.9,612.3,740.0,1963.8,430.0,50.9 -0.6709522626428399,1.8289854634010339,1.9634954084936205,192.4,741.0,961.8,2413.1,250.6,31.5 -0.6709693854838183,1.8290048970020352,2.0943951023931953,349.9,1049.5,1429.9,2632.4,161.2,34.0 -0.6709601097655404,1.8289850755638057,2.2252947962927703,543.2,1845.6,1786.7,2324.8,106.2,47.5 -0.6709659303270178,1.829007564654576,2.356194490192345,541.5,1751.2,1751.6,2220.2,70.3,70.9 -0.6709634060212801,1.8290378417605173,2.4870941840919194,586.3,1787.2,1846.3,911.6,47.5,106.6 -0.6709675961849065,1.8290288322144885,2.6179938779914944,692.4,1976.8,2104.4,347.9,33.5,161.2 -0.6709546810030796,1.8289117927655423,2.748893571891069,898.8,2407.3,2627.5,192.2,32.3,252.3 -0.6708332269451347,1.8288568442241533,2.8797932657906435,1345.8,2681.9,2554.2,114.3,51.7,431.3 -0.6708530370667162,1.82884707089799,3.010692959690218,1764.2,2363.1,2304.7,68.7,151.6,565.0 -0.6708417889018321,1.7285908539885466,0.0,1621.3,2250.6,2251.0,140.8,571.0,571.0 -0.6709396491275403,1.72931452524092,0.1308996938995747,1705.0,1347.3,616.7,129.1,565.4,624.6 -0.6709205615460919,1.7293080378113765,0.2617993877991494,1940.2,630.0,250.5,136.8,611.8,739.3 -0.6708873433816291,1.729286382185612,0.39269908169872414,2431.1,392.2,172.9,173.6,937.2,961.0 -0.6708575304463599,1.7292551607080477,0.5235987755982988,2542.0,276.7,149.0,271.4,1047.3,1590.0 -0.6708467115866099,1.7292308466985238,0.6544984694978736,2282.8,210.0,151.0,586.1,1742.5,1683.6 -0.670834743666931,1.7291832763437587,0.7853981633974483,2221.6,170.8,170.3,540.8,1651.8,1651.5 -0.6708361807246358,1.7291719011784783,0.916297857297023,618.8,150.9,209.7,543.0,1683.3,1742.0 -0.6708488094964065,1.7291329548884353,1.0471975511965976,272.6,149.4,276.7,599.1,1859.5,1986.7 -0.670874756172005,1.7290893370356692,1.1780972450961724,173.2,172.5,391.7,912.8,2262.6,2482.0 -0.6708698156701526,1.7290931344042844,1.3089969389957472,136.6,250.0,611.4,1068.9,2682.2,2554.3 -0.6708821929854257,1.729086507647009,1.4398966328953218,129.1,541.8,565.5,1702.8,2361.1,2302.8 -0.6709536103188699,1.7290694269716205,1.5707963267948966,140.8,570.8,570.6,1621.3,2251.4,2251.1 -0.6709457006382915,1.7290680838694925,1.7016960206944713,171.6,564.8,623.1,1660.4,1368.9,540.9 -0.6709410700326255,1.7290652423782464,1.832595714594046,229.5,612.4,740.0,1848.6,628.8,249.8 -0.670996062611662,1.7290995598774288,1.9634954084936205,334.1,937.0,962.1,2271.9,391.4,172.5 -0.6710132570747831,1.7291186603090407,2.0943951023931953,549.5,1049.8,1588.2,2632.5,276.6,149.4 -0.6710040317307421,1.7290986410559286,2.2252947962927703,543.3,1742.1,1683.4,2324.9,209.6,150.9 -0.671009757473991,1.729121041028216,2.356194490192345,541.4,1651.0,1651.8,2220.0,170.2,170.8 -0.6710069298564534,1.7291512429184346,2.4870941840919194,586.2,1683.6,1742.9,1211.3,150.9,210.0 -0.67101073130848,1.729141997968656,2.6179938779914944,692.5,1861.2,1989.1,546.7,149.0,276.7 -0.6709973321494203,1.7291580173476477,2.748893571891069,898.8,2266.3,2486.6,333.4,173.6,393.7 -0.6708195387949145,1.7289154629257277,2.8797932657906435,1345.6,2681.5,2554.4,229.9,251.0,611.7 -0.6708460962982812,1.72890192253875,3.010692959690218,1661.0,2363.7,2304.6,172.3,537.7,565.1 -0.6708324715571657,1.6286411814882165,0.0,1521.4,2251.0,2251.3,240.8,571.0,570.8 -0.6709360839137146,1.6293185975784685,0.1308996938995747,1602.1,1731.2,1000.5,232.7,565.3,624.7 -0.6709177066825365,1.629312313095797,0.2617993877991494,1824.8,829.3,449.9,252.4,611.8,739.4 -0.6708842753073335,1.6292905070111183,0.39269908169872414,2289.1,533.2,314.0,315.2,740.3,961.0 -0.6708541037297923,1.629258877239657,0.5235987755982988,2541.8,392.2,264.6,470.6,1047.2,1499.7 -0.6708430169028442,1.6292340312450273,0.6544984694978736,2283.1,313.5,254.5,586.2,1639.0,1580.0 -0.6708309307302986,1.629185886678757,0.7853981633974483,2220.8,270.8,270.3,540.9,1551.6,1551.3 -0.6708289343822674,1.629215723732073,0.916297857297023,1006.0,254.4,313.2,543.1,1579.7,1638.7 -0.6708501845763606,1.6291486479853057,1.0471975511965976,472.2,264.9,392.2,599.1,1744.3,1871.5 -0.6711264603209339,1.6291678489180819,1.1780972450961724,314.8,313.9,533.3,737.4,2122.5,2341.9 -0.6709448505711025,1.629334396870671,1.3089969389957472,252.3,450.0,611.5,1069.8,2760.3,2553.3 -0.6707847986493713,1.6288596633446215,1.4398966328953218,232.6,623.6,565.4,1599.1,2361.4,2302.9 -0.6710485401836007,1.6288013910481116,1.5707963267948966,240.9,570.8,570.5,1521.1,2251.4,2250.9 -0.6709774828643877,1.6292332535744398,1.7016960206944713,275.2,564.7,623.2,1557.1,1756.7,929.8 -0.6707366416414551,1.6291570829575717,1.832595714594046,345.3,612.6,820.0,1733.2,827.8,449.0 -0.671107260666683,1.6287954710641837,1.9634954084936205,476.0,826.7,962.2,2130.2,532.8,313.8 -0.6712763092752205,1.6289816300320747,2.0943951023931953,598.8,1049.8,1474.0,2773.1,392.3,265.1 -0.6708138190310475,1.6291402083593876,2.2252947962927703,543.2,1638.5,1579.4,2324.7,313.2,254.5 -0.6708055350819342,1.629101421632918,2.356194490192345,541.6,1551.4,1551.6,2220.8,270.3,270.9 -0.6711593693270026,1.629119912924415,2.4870941840919194,586.3,1580.2,1639.1,1598.1,254.5,313.7 -0.6711677711750902,1.6290938906471748,2.6179938779914944,842.6,1745.4,1873.2,746.3,264.7,392.4 -0.6711509984760754,1.6291149496339072,2.748893571891069,899.0,2124.6,2344.8,475.0,315.1,535.1 -0.6708859537943307,1.6288571282693474,2.8797932657906435,1485.7,2760.2,2553.2,345.4,450.9,611.7 -0.6709021995045688,1.628849170542915,3.010692959690218,1557.1,2363.2,2304.1,275.8,623.9,565.1 -0.6708858584086825,1.5285908521962348,0.0,1421.4,2251.0,2251.2,340.8,571.0,571.0 -0.6709586536579926,1.5293048891933578,0.1308996938995747,1498.0,2115.7,1300.3,336.2,565.4,624.7 -0.6709355476506825,1.5292971928439014,0.2617993877991494,1709.3,1028.7,649.3,368.0,611.9,739.4 -0.670902429053326,1.529275661443882,0.39269908169872414,2147.4,674.5,455.3,456.8,740.1,961.1 -0.6708735372171875,1.5292455331782884,0.5235987755982988,2541.8,507.8,380.3,669.7,1047.2,1426.2 -0.6708634791238568,1.5292227835331123,0.6544984694978736,2282.8,417.1,358.1,586.2,1535.7,1476.6 -0.6708518221993176,1.5291769241922533,0.7853981633974483,2221.0,370.8,370.3,540.8,1451.8,1451.1 -0.6708531440081579,1.5291671975665193,0.916297857297023,1393.1,357.9,416.8,543.0,1476.3,1535.2 -0.670865269001637,1.5291297162595598,1.0471975511965976,671.9,380.5,507.8,599.1,1628.8,1755.7 -0.6708904107997463,1.5290872672545897,1.1780972450961724,456.7,454.8,674.1,736.9,1980.3,2199.5 -0.6708845030916383,1.5290919319755825,1.3089969389957472,367.8,648.6,611.4,1068.9,2681.9,2554.6 -0.6708958166139463,1.5290858839299597,1.4398966328953218,336.0,623.7,565.4,1496.1,2361.7,2302.8 -0.6709661355347533,1.5290690433406355,1.5707963267948966,340.8,570.9,570.7,1421.2,2251.2,2251.0 -0.6709572022716075,1.5290676885126835,1.7016960206944713,378.5,564.6,623.2,1453.5,2147.8,1319.8 -0.67095164425143,1.5290646353621264,1.832595714594046,460.8,612.5,740.1,1616.8,1027.1,648.3 -0.6710058463033753,1.5290985222744071,1.9634954084936205,617.6,741.0,962.0,1988.2,673.8,454.7 -0.6710224329707476,1.529117046970954,2.0943951023931953,598.7,1049.8,1430.0,2632.9,507.7,380.4 -0.6710127744279561,1.52909639442911,2.2252947962927703,543.4,1535.2,1476.3,2324.8,416.7,357.9 -0.6710182587456963,1.5291181101326132,2.356194490192345,541.5,1451.3,1451.7,2220.9,370.3,370.8 -0.6710153978904607,1.5291476175350667,2.4870941840919194,586.2,1476.4,1535.9,1982.5,358.0,417.2 -0.671019315739671,1.5291377537743984,2.6179938779914944,692.5,1630.2,1757.7,944.9,380.2,507.9 -0.6710062146976304,1.5291532312373946,2.748893571891069,898.8,1983.8,2203.6,616.4,456.4,676.4 -0.6708248094052351,1.5289120783165118,2.8797932657906435,1474.9,2681.6,2554.2,461.1,649.7,611.7 -0.6708505499990415,1.5288989787972131,3.010692959690218,1453.7,2363.3,2304.4,379.3,624.0,565.0 -0.6708365800404037,1.4286382095425576,0.0,1321.3,2250.5,2251.3,440.8,571.0,570.8 -0.6709378903048852,1.4293176464994475,0.1308996938995747,1394.4,2305.7,1683.6,439.8,565.2,624.7 -0.6709191442926914,1.4293112518097675,0.2617993877991494,1593.7,1228.0,848.7,483.6,611.9,739.4 -0.67088572401706,1.4292894590020992,0.39269908169872414,2006.1,815.6,596.3,598.6,740.1,961.1 -0.6708556386390304,1.4292579322147343,0.5235987755982988,2657.6,623.5,495.8,691.9,1047.2,1426.8 -0.6708446226732375,1.4292332328227366,0.6544984694978736,2282.7,520.6,461.6,586.1,1431.8,1373.0 -0.6708325651042731,1.4291852481601057,0.7853981633974483,2221.2,470.8,470.4,540.8,1351.6,1351.2 -0.6708340190896229,1.4291734777993106,0.916297857297023,1779.8,461.4,520.3,543.0,1372.9,1431.6 -0.6708467575658796,1.4291341775711484,1.0471975511965976,871.6,496.1,623.4,764.9,1512.9,1640.2 -0.6708728857789182,1.4290902678141149,1.1780972450961724,598.3,596.0,739.8,767.9,1839.0,2058.4 -0.6708681725736455,1.4290938474759272,1.3089969389957472,483.4,738.9,611.4,1068.8,2603.2,2554.8 -0.6708808054833563,1.4290870775416078,1.4398966328953218,439.5,623.7,565.4,1392.5,2360.7,2303.1 -0.6709524891129376,1.4290699278263546,1.5707963267948966,440.8,570.9,570.7,1321.2,2251.4,2251.1 -0.6709448308173533,1.429068583777959,1.7016960206944713,482.0,564.6,623.2,1350.2,2303.8,1709.1 -0.6709404268851274,1.4290658003404488,1.832595714594046,576.4,612.3,740.1,1501.7,1226.4,847.3 -0.6709956119030639,1.429100226251919,1.9634954084936205,737.6,740.9,962.2,1846.8,814.6,595.8 -0.6710129525357751,1.4291194692516598,2.0943951023931953,598.7,1049.9,1430.1,2630.1,623.1,496.0 -0.6710038235430889,1.4290996118094395,2.2252947962927703,543.3,1431.6,1372.7,2324.4,520.2,461.3 -0.6710095959895305,1.4291221825230682,2.356194490192345,541.6,1351.3,1351.6,2220.8,470.2,470.8 -0.6710067672761614,1.429152549762046,2.4870941840919194,586.3,1373.3,1432.2,2282.9,461.5,520.8 -0.6710105265937014,1.4291434512582486,2.6179938779914944,692.4,1514.4,1642.0,1143.9,495.8,623.6 -0.6709970516458211,1.4291595913521502,2.748893571891069,898.9,1842.2,2062.4,757.9,597.9,738.5 -0.6708188866677631,1.4289163056482996,2.8797932657906435,1345.3,2602.5,2558.4,576.7,739.3,611.8 -0.6708454811231991,1.4289027432820218,3.010692959690218,1350.6,2363.5,2304.4,482.9,624.1,565.0 -0.6708318496695684,1.3286419885660825,0.0,1221.2,2251.1,2251.1,540.7,571.0,570.8 -0.6709358578146783,1.3293187661003592,0.1308996938995747,1290.8,2305.1,2067.4,543.4,565.4,624.7 -0.6709175353455954,1.3293124981729694,0.2617993877991494,1478.2,1427.2,1048.1,599.1,611.9,739.4 -0.6708840960050451,1.3292906865518765,0.39269908169872414,1864.2,956.7,737.5,740.3,740.2,960.9 -0.6708539050608733,1.3292590350588545,0.5235987755982988,2541.9,739.1,611.4,691.9,1047.2,1398.3 -0.6708428031319048,1.329234159504702,0.6544984694978736,2282.6,624.2,565.1,586.1,1328.3,1269.5 -0.6708307101891176,1.3291859826120769,0.7853981633974483,2221.1,570.8,570.2,540.8,1251.8,1251.3 -0.6708321767643318,1.329174027201607,0.916297857297023,2166.9,565.0,623.7,543.1,1269.4,1328.1 -0.6708449714122869,1.3291345624602597,1.0471975511965976,1070.8,611.6,738.9,599.0,1397.3,1525.0 -0.6708711895791203,1.3290905211618531,1.1780972450961724,739.9,737.1,739.8,736.8,1697.8,1917.0 -0.6708665847624155,1.3290940031393133,1.3089969389957472,599.0,739.1,611.4,1232.8,2404.0,2554.5 -0.6708793370643221,1.3290871680547829,1.4398966328953218,542.8,623.8,565.3,1289.1,2361.1,2302.6 -0.6709511440488676,1.3290699910076795,1.5707963267948966,540.8,570.9,570.7,1221.2,2251.3,2250.8 -0.6709436008418376,1.3290686481201985,1.7016960206944713,585.4,564.8,623.1,1246.5,2304.0,2098.8 -0.6709393011735267,1.3290658886188886,1.832595714594046,692.0,612.4,740.2,1386.0,1425.5,1046.6 -0.6709945750300207,1.329100362998886,1.9634954084936205,737.8,741.1,962.2,1705.0,955.9,736.7 -0.6710119839138309,1.3291196707712298,2.0943951023931953,598.7,1049.9,1397.2,2430.3,738.6,611.4 -0.6710029033354867,1.3290998847413016,2.2252947962927703,543.3,1328.1,1269.2,2324.6,623.6,564.9 -0.6710087025354629,1.3291225324836922,2.356194490192345,541.5,1251.1,1251.8,2220.5,570.2,570.8 -0.6710058772437005,1.3291529776585667,2.4870941840919194,586.3,1269.5,1328.7,2283.6,565.2,624.2 -0.6710096230249133,1.3291439485614105,2.6179938779914944,692.6,1399.1,1526.2,1343.2,611.5,739.3 -0.6709961144298354,1.3291601491910834,2.748893571891069,898.9,1700.5,1920.7,899.0,739.4,738.6 -0.6708183133656771,1.3289166900791378,2.8797932657906435,1385.0,2403.2,2553.9,692.4,739.3,611.7 -0.6708449949286793,1.3289030806269855,3.010692959690218,1246.9,2363.5,2304.5,586.4,624.1,565.2 -0.6708313994320415,1.228642328386073,0.0,1121.3,2251.3,2251.1,640.7,571.0,570.8 -0.6709356630212396,1.2293188712301584,0.1308996938995747,1187.3,2305.1,2365.2,647.0,565.3,624.6 -0.6709173793418602,1.2293126149186633,0.2617993877991494,1362.5,1626.7,1247.4,714.8,611.7,739.5 -0.6708839374622695,1.229290801070618,0.39269908169872414,1723.0,1098.0,878.7,881.8,740.2,961.1 -0.6708537360753907,1.2292591372892867,0.5235987755982988,2502.1,854.7,727.0,691.9,1164.8,1282.8 -0.6708426257298985,1.22923424454331,0.6544984694978736,2282.5,727.6,668.7,586.2,1224.9,1166.0 -0.6708305293426085,1.2291860489489297,0.7853981633974483,2221.1,670.7,670.2,540.9,1152.0,1151.3 -0.6708319971363894,1.229174075532838,0.916297857297023,2324.8,668.4,727.4,542.9,1165.7,1224.5 -0.6708447972488814,1.229134594793916,1.0471975511965976,1270.6,727.2,854.3,599.1,1281.6,1409.5 -0.670871024177843,1.229090540728943,1.1780972450961724,881.8,878.3,739.8,736.8,1556.8,1775.9 -0.6708664299160881,1.2290940132225603,1.3089969389957472,714.7,738.9,611.5,1112.7,2204.6,2554.1 -0.6708791938333157,1.2290871718126466,1.4398966328953218,646.4,623.6,565.3,1185.7,2360.8,2302.8 -0.6709510128022326,1.229069992151862,1.5707963267948966,640.8,570.9,570.7,1121.2,2251.6,2250.7 -0.6709434807774162,1.229068649412071,1.7016960206944713,689.0,587.4,623.2,1143.4,2303.5,2362.2 -0.6709391912336551,1.2290658922490298,1.832595714594046,807.6,612.4,740.0,1270.3,1624.9,1246.0 -0.6709944736927617,1.2291003713503108,1.9634954084936205,737.6,741.0,962.1,1563.2,1096.9,878.0 -0.6710118891762126,1.2291196854280677,2.0943951023931953,598.7,1137.9,1281.4,2230.4,854.3,726.9 -0.6710028132885094,1.229099906331036,2.2252947962927703,543.3,1224.4,1165.7,2324.7,727.2,668.3 -0.6710086150821748,1.229122561537003,2.356194490192345,541.5,1151.1,1151.8,2221.0,670.2,670.7 -0.6710057901194729,1.2291530142677356,2.4870941840919194,586.3,1165.6,1225.0,2283.0,668.7,727.7 -0.6710095346051829,1.2291439918990368,2.6179938779914944,692.4,1283.3,1411.0,1542.3,727.1,854.8 -0.6709960227556839,1.2291601984099207,2.748893571891069,898.8,1559.0,1779.4,1040.5,880.8,738.6 -0.6708182581841835,1.2289167253123834,2.8797932657906435,1269.4,2203.9,2554.3,807.9,739.2,611.7 -0.6708449485637727,1.2289031111043678,3.010692959690218,1143.3,2363.5,2304.8,689.9,624.0,565.0 -0.6708313568621486,1.1286423593285777,0.0,1021.2,2251.3,2251.0,740.9,570.9,570.9 -0.6709356456431231,1.1293188817991076,0.1308996938995747,1083.7,2305.1,2364.9,750.6,565.3,624.7 -0.6709173642815027,1.1293126261889546,0.2617993877991494,1246.8,1826.4,1446.6,830.5,611.8,739.3 -0.6708839212787804,1.1292908116027092,0.39269908169872414,1581.0,1238.9,1019.9,896.8,740.2,960.9 -0.670853718302825,1.1292591460390513,0.5235987755982988,2302.0,970.3,842.7,692.0,1153.9,1167.3 -0.6708426067807571,1.1292342509937157,0.6544984694978736,2282.7,831.4,772.3,586.1,1121.3,1062.1 -0.670830509899825,1.1291860529422526,0.7853981633974483,2221.1,770.8,770.3,540.8,1051.7,1051.4 -0.6708319778223271,1.129174077162598,0.916297857297023,2325.1,771.9,830.8,543.1,1062.2,1121.2 -0.6708447786270463,1.129134594324635,1.0471975511965976,1469.9,842.8,970.0,599.2,1166.2,1293.6 -0.6708710066904787,1.1290905385819254,1.1780972450961724,1023.6,960.5,739.9,736.9,1415.5,1634.9 -0.6708664138169723,1.1290940098274644,1.3089969389957472,830.3,739.1,611.5,1068.8,2005.5,2384.8 -0.6708791792643068,1.1290871675960572,1.4398966328953218,749.9,623.7,565.4,1082.1,2361.2,2302.5 -0.6709509997994876,1.129069987609508,1.5707963267948966,740.8,570.9,570.7,1021.1,2251.3,2251.2 -0.6709434692433108,1.129068644918178,1.7016960206944713,792.3,564.7,623.2,1039.7,2303.9,2362.2 -0.6709391810178705,1.1290658880978488,1.832595714594046,923.3,612.4,740.1,1154.7,1823.8,1445.1 -0.6709944645712763,1.1291003678401905,1.9634954084936205,737.5,741.0,962.1,1421.1,1237.9,1019.1 -0.6710118808805933,1.1291196827594012,2.0943951023931953,598.7,1152.4,1166.1,2030.9,969.5,842.6 -0.6710028055668544,1.1290999045834933,2.2252947962927703,543.2,1120.8,1062.2,2324.4,830.5,772.0 -0.6710086076620152,1.1291225607551887,2.356194490192345,541.4,1051.3,1051.7,2220.3,770.3,770.9 -0.6710057827187702,1.1291530144453947,2.4870941840919194,586.2,1062.3,1121.5,2283.1,772.1,831.4 -0.6710095270206001,1.1291439929310154,2.6179938779914944,692.5,1167.5,1295.2,1741.5,842.8,970.5 -0.6709960147586306,1.1291602001815377,2.748893571891069,898.9,1417.9,1637.9,1181.9,958.4,738.7 -0.6708182530488767,1.1289167276434569,2.8797932657906435,1153.7,2004.3,2384.1,923.5,739.2,611.7 -0.6708449444738864,1.1289031128761156,3.010692959690218,1039.8,2363.9,2304.9,793.5,624.0,565.0 -0.770910161042096,1.829109128500156,0.0,1721.1,2150.9,2150.8,41.0,670.9,670.9 -0.7709645544421906,1.8289407216482978,0.1308996938995747,1808.4,964.8,148.9,25.5,668.9,728.2 -0.7711167998708331,1.8289889107503716,0.2617993877991494,2056.0,431.0,51.3,21.3,727.2,854.8 -0.7710454921822608,1.8289440508106587,0.39269908169872414,2571.9,251.1,31.8,32.0,1078.3,1102.5 -0.7710353998501991,1.8289349594076878,0.5235987755982988,2426.7,161.2,33.5,72.2,1246.0,1705.4 -0.7708223467260499,1.8291053611862562,0.6544984694978736,2179.1,106.6,47.5,231.5,1845.9,1787.0 -0.7708149611864508,1.8290768764098615,0.7853981633974483,2121.2,70.9,70.4,640.8,1751.5,1751.2 -0.7708173392255175,1.8290694791585935,0.916297857297023,232.2,47.4,106.3,646.5,1786.8,1845.3 -0.7708273603734551,1.8290402964291252,1.0471975511965976,73.2,33.9,161.3,714.6,1974.7,2102.4 -0.7708506596565322,1.8290018470439886,1.1780972450961724,31.7,31.5,250.6,1054.3,2403.5,2622.9 -0.7708430318047258,1.8290089728505483,1.3089969389957472,21.1,50.9,430.3,1268.0,2566.3,2438.7 -0.7708525076282208,1.8290046351821192,1.4398966328953218,25.7,152.2,668.8,1806.3,2258.0,2199.5 -0.7709207922980029,1.8289889007505666,1.5707963267948966,40.9,670.9,670.7,1721.4,2151.2,2151.2 -0.7709097778095756,1.8289880378196788,1.7016960206944713,68.2,668.1,726.6,1763.6,980.1,151.9 -0.7709022010052217,1.8289848523103829,1.832595714594046,114.0,728.0,855.6,1963.8,429.9,50.8 -0.770954608870566,1.829018000198648,1.9634954084936205,192.4,1077.8,1103.8,2413.7,250.5,31.5 -0.7709698391709399,1.8290353236738288,2.0943951023931953,349.9,1249.4,1704.0,2517.5,161.2,33.9 -0.7709593785697622,1.8290131906639306,2.2252947962927703,646.8,1845.5,1787.0,2220.9,106.2,47.4 -0.7709646557795817,1.82903332198244,2.356194490192345,641.5,1751.3,1752.1,2120.6,70.3,70.9 -0.7709621556824857,1.8290613686382966,2.4870941840919194,689.8,1786.7,1846.4,826.5,47.5,106.6 -0.770966881737248,1.8290503625451335,2.6179938779914944,808.1,1976.8,2104.6,347.7,33.5,161.2 -0.7709548732421259,1.8290651119753039,2.748893571891069,1040.2,2408.1,2627.9,192.2,32.2,252.4 -0.7708210624668846,1.8288783108130913,2.8797932657906435,1691.8,2566.1,2438.5,114.3,51.7,431.3 -0.7708485272616187,1.8288644049754479,3.010692959690218,1764.6,2259.8,2201.0,68.7,151.6,668.6 -0.7708382979977876,1.728606658113069,0.0,1620.9,2151.5,2151.2,140.8,670.9,670.9 -0.7709365972739309,1.7293148186195715,0.1308996938995747,1705.1,1347.7,532.3,129.0,668.8,728.2 -0.7709176194410176,1.7293083579091673,0.2617993877991494,1940.6,629.9,250.5,136.8,727.5,880.4 -0.7708844043614771,1.729286691625729,0.39269908169872414,2431.2,392.1,172.9,173.6,882.0,1102.7 -0.7708545814012141,1.729255435738689,0.5235987755982988,2425.9,276.6,149.0,271.4,1246.5,1714.0 -0.7708437515317186,1.7292310719206445,0.6544984694978736,2179.4,210.0,151.0,617.0,1742.4,1683.3 -0.7708317971205859,1.7291834595740478,0.7853981633974483,2121.1,170.8,170.3,640.9,1651.7,1651.1 -0.7708332502623764,1.7291720425534627,0.916297857297023,618.7,150.9,209.7,646.6,1683.3,1741.9 -0.770845904144538,1.7291330640914997,1.0471975511965976,272.6,149.4,276.7,714.6,1859.5,1986.6 -0.7708718840591573,1.7290894356962467,1.1780972450961724,173.3,172.5,391.7,878.1,2262.5,2481.4 -0.7708669699963681,1.7290932236198644,1.3089969389957472,136.6,250.0,629.4,1268.1,2566.6,2438.5 -0.7708793693505193,1.7290865833153974,1.4398966328953218,129.1,541.8,668.7,1703.2,2257.8,2199.1 -0.7709508079531011,1.7290695109435517,1.5707963267948966,140.8,670.9,670.7,1621.3,2151.7,2151.1 -0.7709429150988845,1.729068169657455,1.7016960206944713,171.6,668.1,726.6,1660.7,1368.7,540.9 -0.7709383034439526,1.729065317171465,1.832595714594046,229.5,728.0,1019.7,1848.4,628.8,249.8 -0.7709933135974286,1.7290996360186734,1.9634954084936205,334.1,967.8,1103.9,2271.7,391.5,172.5 -0.7710105240856654,1.7292181056953033,2.0943951023931953,549.4,1249.4,1717.7,2517.0,276.6,149.3 -0.7708405649039897,1.7291472276628208,2.2252947962927703,646.8,1741.9,1683.5,2221.7,209.8,150.9 -0.7708382091871272,1.7291354901504472,2.356194490192345,641.5,1651.2,1651.6,2120.5,170.3,170.8 -0.7711895401338795,1.7290961014706472,2.4870941840919194,689.8,1683.8,1742.8,1212.1,151.0,210.1 -0.7711931630480134,1.7290855174642632,2.6179938779914944,808.2,1861.2,1988.8,546.9,149.1,276.7 -0.7711726918838143,1.729112311028867,2.748893571891069,1040.4,2266.4,2486.0,333.6,173.7,393.7 -0.7708944486541103,1.7288498484804657,2.8797932657906435,1590.1,2565.4,2437.7,229.8,251.4,631.1 -0.7709093508716429,1.7288426138976558,3.010692959690218,1661.0,2259.4,2200.7,172.2,539.2,668.6 -0.770892676893768,1.6285846576382266,0.0,1521.1,2151.0,2151.2,240.8,670.9,671.0 -0.7709615781160918,1.6293032219940513,0.1308996938995747,1601.6,1731.9,916.3,232.6,668.9,728.2 -0.7709378606617657,1.629295343187446,0.2617993877991494,1824.8,829.3,449.9,252.4,727.4,854.9 -0.7709047682477441,1.6292738385444547,0.39269908169872414,2289.4,533.3,314.1,315.2,881.8,1102.8 -0.7708760274381417,1.6292438892059464,0.5235987755982988,2426.3,392.3,264.6,470.5,1246.6,1625.7 -0.7708660923761359,1.6292213923260492,0.6544984694978736,2179.6,313.6,254.5,689.9,1638.9,1580.1 -0.7708544860612414,1.629175808819157,0.7853981633974483,2121.0,270.8,270.3,640.9,1551.7,1551.3 -0.7708557897255633,1.6291663475761318,0.916297857297023,1006.2,254.4,313.2,646.5,1579.7,1638.8 -0.7708678341500006,1.6291291022543377,1.0471975511965976,472.2,264.9,392.3,714.7,1744.0,1871.6 -0.7708928470205219,1.6290868420605178,1.1780972450961724,315.0,313.7,532.7,877.9,2121.1,2340.6 -0.7708867840555833,1.6290916469888541,1.3089969389957472,252.2,449.3,727.0,1268.2,2566.5,2438.6 -0.7708979264761964,1.6290856925684931,1.4398966328953218,232.5,727.3,668.8,1599.3,2257.6,2199.4 -0.7709680683918156,1.629068891549853,1.5707963267948966,240.8,671.0,670.7,1521.1,2151.3,2151.6 -0.7709589700562235,1.6290675354198458,1.7016960206944713,275.1,668.2,726.5,1557.1,1758.6,930.5 -0.7709532623985972,1.6290644482227792,1.832595714594046,345.1,728.1,855.6,1732.8,828.3,449.2 -0.7710073366810654,1.629098265751448,1.9634954084936205,475.8,882.8,1104.0,2129.9,532.7,313.6 -0.7710238251327017,1.6291166976158595,2.0943951023931953,714.3,1249.4,1629.7,2517.0,392.2,264.9 -0.7710140969595013,1.6290959426743914,2.2252947962927703,646.8,1638.2,1579.8,2221.2,313.1,254.4 -0.771019542788784,1.6291175477288373,2.356194490192345,641.5,1551.3,1551.7,2120.4,270.2,270.8 -0.7710166770376009,1.629146943135398,2.4870941840919194,689.8,1580.3,1639.3,1596.8,254.5,313.6 -0.7710206144475279,1.6291369797327473,2.6179938779914944,833.6,1745.7,1873.4,745.9,264.6,392.3 -0.7710075619271637,1.6291523703562418,2.748893571891069,1040.4,2124.8,2345.3,474.9,315.0,535.1 -0.7708256433728595,1.6289115018841607,2.8797932657906435,1545.0,2565.8,2438.5,345.5,450.5,727.2 -0.7708512604174154,1.6288984692327135,3.010692959690218,1557.5,2260.1,2200.9,275.8,727.5,668.7 -0.7708372422234732,1.5286377000949052,0.0,1421.4,2150.9,2151.1,340.8,671.1,670.8 -0.7709381867787821,1.529317491196813,0.1308996938995747,1498.1,2200.0,1299.8,336.2,668.7,728.3 -0.7709193723568041,1.5293110761931894,0.2617993877991494,1708.9,1028.7,649.3,368.0,727.5,855.0 -0.7708859476606749,1.529289281908142,0.39269908169872414,2148.0,674.5,455.2,456.8,881.8,1102.7 -0.7708558718152879,1.5292577673178427,0.5235987755982988,2426.4,507.9,380.2,670.0,1246.2,1604.5 -0.7708448644508572,1.5292330866839081,0.6544984694978736,2179.0,417.1,358.1,689.7,1535.4,1476.6 -0.7708328102253206,1.529185122782453,0.7853981633974483,2121.4,370.8,370.3,640.8,1451.7,1450.9 -0.7708342624937166,1.5291733723722882,0.916297857297023,1392.9,357.8,416.8,646.6,1476.4,1535.2 -0.7708469946216853,1.529134089864951,1.0471975511965976,671.7,380.5,507.9,714.6,1628.2,1755.8 -0.770848028144436,1.5291303525427298,1.1780972450961724,456.6,454.9,674.0,909.2,1980.2,2199.2 -0.7708669944916481,1.5291118880136902,1.3089969389957472,367.8,648.8,727.1,1438.5,2566.6,2439.4 -0.7708859862804988,1.5291017555108717,1.4398966328953218,335.9,727.2,668.8,1495.9,2257.9,2199.4 -0.7709569541395754,1.529084786108019,1.5707963267948966,340.7,671.0,670.7,1421.3,2151.2,2151.3 -0.7709462930527418,1.5290833517776403,1.7016960206944713,378.5,668.2,726.6,1453.7,2200.3,1319.6 -0.7709384849006475,1.5290795440462621,1.832595714594046,460.7,728.1,855.7,1617.2,1071.1,648.2 -0.7709906217776187,1.529112065783262,1.9634954084936205,617.6,882.8,1103.8,1988.2,673.6,454.7 -0.7710056547374192,1.5291288363013786,2.0943951023931953,714.3,1249.6,1628.4,2585.9,507.7,380.4 -0.7709950500610376,1.529106224295107,2.2252947962927703,646.8,1535.0,1476.0,2221.8,416.6,357.9 -0.7710001595192261,1.5291259419040621,2.356194490192345,641.6,1451.1,1452.0,2120.3,370.2,370.8 -0.7709974263262424,1.5291535865209824,2.4870941840919194,689.9,1476.5,1535.6,1982.2,358.0,417.1 -0.7710019129250559,1.5291420963945495,2.6179938779914944,808.2,1630.4,1757.9,988.8,380.3,508.0 -0.7709605526143992,1.5292036226640884,2.748893571891069,1040.4,1983.4,2203.3,616.1,456.5,676.6 -0.7708286653099972,1.5289539555069838,2.8797932657906435,1544.7,2565.8,2438.6,461.1,649.8,727.3 -0.7708614636300828,1.5289370240743254,3.010692959690218,1453.8,2259.7,2201.4,379.4,727.5,668.6 -0.7708444710746333,1.42866938581061,0.0,1321.2,2150.9,2151.4,440.8,671.0,670.8 -0.770916332499821,1.4293015975963574,0.1308996938995747,1394.4,2201.5,1684.2,439.8,668.8,728.4 -0.770910123578487,1.4292991089972087,0.2617993877991494,1593.7,1228.3,848.8,483.5,727.4,854.8 -0.7708805852727637,1.4292797839860993,0.39269908169872414,2005.9,815.7,596.4,598.6,881.7,1102.7 -0.7708517190145404,1.4292495896857655,0.5235987755982988,2426.2,623.6,495.9,807.4,1396.2,1514.1 -0.7708411381938266,1.4292256807856862,0.6544984694978736,2178.7,520.6,461.5,689.8,1432.0,1372.9 -0.7708292141735283,1.4291782423291954,0.7853981633974483,2121.4,470.8,470.4,640.8,1351.9,1351.3 -0.7708306916293167,1.429166930129957,0.916297857297023,1780.1,461.4,520.3,646.5,1372.5,1431.7 -0.7708433561611676,1.4291280291378108,1.0471975511965976,871.5,496.0,623.3,714.6,1512.9,1640.2 -0.770869321007934,1.4290844336157031,1.1780972450961724,598.3,596.0,815.0,878.0,1838.8,2058.0 -0.770864400708496,1.4290882783609669,1.3089969389957472,483.4,848.1,727.0,1348.2,2566.2,2439.0 -0.77087678384809,1.4290817250303491,1.4398966328953218,439.3,727.2,668.8,1392.5,2258.1,2199.6 -0.7709481814508821,1.4290646657226156,1.5707963267948966,440.8,671.0,670.8,1321.2,2151.3,2151.3 -0.7708960192621389,1.4290585589488483,1.7016960206944713,482.0,668.2,726.5,1350.0,2200.2,1709.6 -0.7709207740971793,1.4290648152953163,1.832595714594046,576.4,801.2,855.7,1501.3,1226.9,847.5 -0.7710076386362393,1.4291152911171092,1.9634954084936205,759.2,882.9,1103.7,1846.9,814.8,595.8 -0.7710121414336798,1.4291206471975082,2.0943951023931953,714.2,1394.3,1512.8,2517.3,623.2,496.0 -0.7710002073055909,1.4290955250004886,2.2252947962927703,646.9,1431.4,1372.7,2221.1,520.2,461.4 -0.7710055972561752,1.4291163710373915,2.356194490192345,641.4,1351.1,1351.9,2120.1,470.3,470.8 -0.7710028292957848,1.429146301564363,2.4870941840919194,712.5,1372.9,1432.4,2179.7,461.5,520.7 -0.7710066154910677,1.429137218114221,2.6179938779914944,808.0,1514.3,1642.1,1144.3,495.9,623.6 -0.7709931348644649,1.4291534815694247,2.748893571891069,1040.2,1841.9,2062.2,757.7,597.9,818.0 -0.7708171203682764,1.4289151213726647,2.8797932657906435,1500.6,2566.0,2438.6,576.6,849.0,727.3 -0.7708435691151234,1.4289016398474454,3.010692959690218,1350.4,2259.8,2200.6,482.9,727.6,668.5 -0.7708301809822085,1.3286412260609402,0.0,1221.3,2151.1,2150.9,540.9,671.0,670.9 -0.7709351801895005,1.3293190864260764,0.1308996938995747,1291.0,2202.1,2067.5,543.4,669.0,728.1 -0.7709170101523961,1.329312864912954,0.2617993877991494,1478.1,1427.6,1048.0,599.2,727.4,855.0 -0.7708835648754262,1.3292910478962277,0.39269908169872414,1864.5,956.8,737.7,740.4,881.8,1102.5 -0.770853336572977,1.3292593531976031,0.5235987755982988,2458.0,764.5,611.3,807.4,1385.2,1398.4 -0.7708422039912033,1.3292344160142027,0.6544984694978736,2178.7,624.1,565.1,689.7,1328.3,1269.3 -0.77083009806093,1.329186171476834,0.7853981633974483,2121.0,570.9,570.3,640.8,1251.8,1251.1 -0.7708315687533127,1.32917415077356,0.916297857297023,2221.8,564.9,623.8,646.5,1269.5,1328.2 -0.7708443830097526,1.3291346279353156,1.0471975511965976,1070.8,611.6,738.9,714.6,1397.3,1524.7 -0.7708706327991166,1.3290905400441044,1.1780972450961724,740.0,737.0,881.5,878.0,1697.8,1917.1 -0.7708660664067705,1.3290939874637204,1.3089969389957472,598.9,854.5,727.0,1268.3,2403.8,2539.9 -0.7708788610675018,1.3290871295909334,1.4398966328953218,542.9,727.2,668.8,1289.2,2258.2,2199.3 -0.7709507116124734,1.3290699430495319,1.5707963267948966,540.8,670.8,670.7,1221.1,2151.4,2151.4 -0.7709432091468909,1.329068600932439,1.7016960206944713,585.4,668.2,726.5,1246.9,2200.5,2098.3 -0.7709389462220474,1.329065850459382,1.832595714594046,691.9,728.0,855.7,1386.0,1425.6,1046.8 -0.7709942510975734,1.3291003422385463,1.9634954084936205,878.6,882.9,1103.9,1705.2,955.9,736.8 -0.7710116837187589,1.3291196730141972,2.0943951023931953,714.3,1383.7,1397.2,2429.9,738.6,611.4 -0.7710026198123349,1.3290999124237408,2.2252947962927703,646.8,1327.7,1269.0,2221.3,623.7,564.8 -0.7710084280726747,1.3291225873039467,2.356194490192345,641.5,1251.3,1251.9,2120.6,570.3,570.8 -0.771005603866198,1.3291530596841703,2.4870941840919194,689.8,1269.3,1328.6,2179.4,565.1,624.3 -0.7710093447492044,1.3291440549396818,2.6179938779914944,808.1,1398.7,1526.9,1343.3,611.6,739.2 -0.7709958245847379,1.3291602767164634,2.748893571891069,1040.2,1700.8,1920.8,899.0,739.4,879.8 -0.770787864383515,1.3288882374378792,2.8797932657906435,1384.9,2402.8,2539.2,692.3,854.7,727.4 -0.7708185861483332,1.32887256192446,3.010692959690218,1247.1,2259.5,2200.8,586.3,727.5,668.6 -0.7708114268557492,1.2286176585757693,0.0,1121.3,2151.0,2151.1,640.9,671.1,670.8 -0.7709247097831696,1.2296358945661088,0.1308996938995747,1187.3,2201.6,2261.5,646.9,691.5,728.3 -0.7710284128731347,1.2288512389668338,0.2617993877991494,1362.3,1627.3,1247.9,714.8,727.3,855.0 -0.7710478586760492,1.2288637475327664,0.39269908169872414,1722.1,1129.3,879.0,881.9,881.7,1102.6 -0.7710619917887044,1.2288810967806343,0.5235987755982988,2426.5,855.0,727.2,807.6,1246.3,1282.9 -0.770821202993918,1.2290827238008561,0.6544984694978736,2179.4,727.7,668.9,689.7,1224.9,1165.8 -0.7708149222768238,1.229058933330015,0.7853981633974483,2121.5,670.8,670.3,640.8,1151.6,1151.1 -0.7708162188374784,1.2290593051780605,0.916297857297023,2221.7,668.5,727.5,646.6,1165.5,1224.4 -0.7708271098143351,1.2290275404428146,1.0471975511965976,1270.6,727.3,854.5,714.7,1281.9,1409.3 -0.7708505136343976,1.228989107689281,1.1780972450961724,881.7,878.5,881.4,877.9,1556.7,1775.7 -0.7708424262777576,1.228996776863914,1.3089969389957472,714.8,854.4,726.8,1268.3,2204.2,2439.4 -0.7708511322571795,1.2289929140716778,1.4398966328953218,646.5,727.1,668.8,1185.3,2258.1,2199.4 -0.7709185171080686,1.228977523727326,1.5707963267948966,640.8,670.9,670.6,1121.2,2151.5,2151.1 -0.7709065960256299,1.2289767338202835,1.7016960206944713,689.0,668.1,726.6,1143.2,2200.4,2258.5 -0.7708981850505028,1.2289733401203615,1.832595714594046,807.8,728.1,855.8,1270.3,1625.2,1246.0 -0.7709498629616971,1.2290061192107529,1.9634954084936205,878.6,882.7,1104.0,1563.3,1097.2,878.2 -0.7709645246590273,1.229022947443085,2.0943951023931953,714.1,1249.4,1281.9,2229.8,854.3,727.1 -0.7709537213489179,1.2290001893162015,2.2252947962927703,646.7,1224.5,1165.5,2221.2,727.2,668.6 -0.7709588580687547,1.2290196640386966,2.356194490192345,641.4,1151.3,1151.5,2120.4,670.3,670.9 -0.7709563811203863,1.2290471118204083,2.4870941840919194,689.9,1165.7,1224.9,2179.6,668.7,727.8 -0.770961336440251,1.2290355668886468,2.6179938779914944,808.2,1283.2,1410.8,1542.6,727.3,855.0 -0.7709496242145505,1.229049922869322,2.748893571891069,1040.4,1559.3,1779.2,1040.5,880.9,879.7 -0.7708242541083837,1.2288698653258057,2.8797932657906435,1269.3,2203.9,2438.0,807.7,854.8,727.1 -0.7708522866774663,1.2288556854203998,3.010692959690218,1143.3,2259.9,2201.0,689.9,727.4,668.7 -0.7708426400591872,1.12859823006613,0.0,1021.1,2151.2,2151.1,740.8,671.0,670.9 -0.7709378366439602,1.1293132218351962,0.1308996938995747,1083.7,2201.4,2261.3,750.6,668.8,728.2 -0.7709184192299705,1.129306629540507,0.2617993877991494,1246.8,1826.2,1446.7,830.4,727.3,855.1 -0.7708852597019574,1.1292850026042203,0.39269908169872414,1581.1,1239.2,1020.0,1023.6,881.8,1211.8 -0.7708555853807612,1.1292539117746154,0.5235987755982988,2302.3,970.1,842.7,807.5,1246.4,1167.1 -0.7708448710888546,1.129229772385443,0.6544984694978736,2178.9,831.2,772.1,689.7,1121.4,1062.4 -0.7708329720767867,1.1291824081297794,0.7853981633974483,2121.3,770.9,770.2,641.0,1051.6,1051.1 -0.7708344154165749,1.1291712286819793,0.916297857297023,2221.6,772.0,830.7,646.6,1062.4,1121.1 -0.7708470033677872,1.1291324636812057,1.0471975511965976,1470.1,842.7,969.9,714.6,1166.4,1293.7 -0.7708728742770179,1.1290890129680218,1.1780972450961724,1023.5,1019.6,881.4,878.1,1415.7,1634.8 -0.7708678225991014,1.1290929324533314,1.3089969389957472,830.2,854.6,727.1,1247.1,2005.1,2384.5 -0.7708800668959603,1.1290863770561537,1.4398966328953218,749.9,727.2,668.7,1082.3,2257.9,2199.5 -0.7709513442522695,1.1290693470133215,1.5707963267948966,740.7,671.0,670.8,1021.3,2151.8,2150.9 -0.7709432993826787,1.1290680056296836,1.7016960206944713,792.4,668.3,726.7,1039.9,2200.0,2258.9 -0.770938551442094,1.129065115578377,1.832595714594046,923.3,728.1,855.8,1154.4,1823.8,1445.1 -0.7709934459544864,1.1290993680314312,1.9634954084936205,878.7,882.9,1211.8,1421.8,1269.1,1019.0 -0.7710105687464651,1.1291183912114773,2.0943951023931953,714.2,1293.4,1166.3,2030.9,969.7,842.4 -0.7710013108908281,1.129098275006235,2.2252947962927703,646.7,1120.8,1062.3,2221.4,830.7,771.9 -0.7710070328752089,1.1291205801258242,2.356194490192345,641.5,1051.1,1051.7,2120.2,770.2,770.9 -0.7710042174518761,1.1291507047417921,2.4870941840919194,689.8,1062.4,1121.6,2179.5,772.2,831.3 -0.7710080614333757,1.129141390315893,2.6179938779914944,808.1,1167.4,1295.3,1741.4,842.8,970.5 -0.7709947002308263,1.129157365086718,2.748893571891069,1085.5,1418.2,1638.0,1181.7,1022.1,879.9 -0.7708189260548666,1.1289152372619804,2.8797932657906435,1153.7,2004.7,2383.9,923.4,854.9,727.3 -0.7708457589692821,1.1289015522829626,3.010692959690218,1039.7,2260.3,2200.8,793.5,727.7,668.6 -0.8709110404225283,1.8291077741550847,0.0,1720.9,2050.9,2051.0,41.0,771.0,770.9 -0.8709648436121006,1.8289405732530861,0.1308996938995747,1808.7,964.9,148.9,25.6,772.5,831.7 -0.8711170500541127,1.8289887512599776,0.2617993877991494,2055.7,431.0,51.3,21.3,843.1,970.4 -0.8710457060659367,1.828943869303531,0.39269908169872414,2571.8,251.1,31.8,32.0,1023.3,1244.0 -0.8710356236063499,1.8289347896272554,0.5235987755982988,2311.5,161.2,33.5,72.2,1445.1,1824.5 -0.8708195567913095,1.8291028560239957,0.6544984694978736,2076.1,106.5,47.5,231.6,1846.0,1786.8 -0.8708119875364693,1.829073503445074,0.7853981633974483,2021.2,70.9,70.4,740.9,1751.5,1751.3 -0.8708133692267677,1.8290714176424994,0.916297857297023,232.2,47.4,106.3,750.0,1786.7,1846.0 -0.8708246432021267,1.8290383347298438,1.0471975511965976,73.2,33.9,161.3,830.1,1975.0,2102.8 -0.8708485259394394,1.8289990285806794,1.1780972450961724,31.7,31.5,250.7,1019.0,2403.6,2622.5 -0.8708409964478382,1.829006103129511,1.3089969389957472,21.1,50.9,430.2,1467.3,2450.9,2323.1 -0.8708503200449929,1.8290018614407446,1.4398966328953218,25.7,152.2,772.3,1806.0,2154.2,2095.9 -0.8709183505679182,1.828986231213269,1.5707963267948966,40.9,770.8,770.7,1721.1,2051.3,2051.0 -0.870907057435178,1.8289853869987702,1.7016960206944713,68.2,771.4,830.0,1763.9,979.9,151.9 -0.8708992217560333,1.8289821220894096,1.832595714594046,114.0,843.7,971.4,1964.1,429.9,50.8 -0.8709514039427877,1.82901514513141,1.9634954084936205,192.5,1108.8,1245.6,2413.7,250.6,31.5 -0.870966461142884,1.829032307916321,2.0943951023931953,349.9,1449.1,1829.1,2401.5,161.2,33.9 -0.8709559053330336,1.8290099701924512,2.2252947962927703,750.2,1845.1,1786.7,2117.5,106.2,47.4 -0.8709611517835849,1.829029892038502,2.356194490192345,741.3,1750.7,1751.8,2020.7,70.3,70.9 -0.8709586665106408,1.8290577559280623,2.4870941840919194,793.2,1787.0,1845.8,826.5,47.5,106.6 -0.8709634749845856,1.829046585083661,2.6179938779914944,923.7,1977.2,2104.0,347.6,33.5,161.2 -0.8709515573101371,1.829061220522015,2.748893571891069,1181.8,2407.6,2627.9,192.2,32.3,252.3 -0.8708212666845759,1.8288762493813264,2.8797932657906435,1745.0,2450.2,2322.4,114.3,51.7,431.3 -0.8708490836288306,1.8288621640624279,3.010692959690218,1764.6,2156.5,2097.3,68.7,151.6,772.0 -0.8708390943357653,1.728899182521047,0.0,1621.6,2050.9,2051.0,140.8,770.9,770.8 -0.8709534414690934,1.7292943746199692,0.1308996938995747,1705.3,1347.4,532.3,129.0,772.5,831.9 -0.8709232327018858,1.7292844044373885,0.2617993877991494,1940.4,629.9,250.5,136.8,842.9,970.5 -0.8708897493405501,1.7292625895719587,0.39269908169872414,2431.0,423.2,172.9,173.6,1023.5,1244.3 -0.8708620442168487,1.7292336347304391,0.5235987755982988,2310.4,276.6,149.0,271.3,1445.7,1860.8 -0.8708530866612317,1.7292127650085165,0.6544984694978736,2075.5,210.0,151.0,617.1,1742.6,1683.5 -0.8708420577169503,1.7291691070025355,0.7853981633974483,2021.0,170.8,170.3,740.9,1651.7,1651.3 -0.8708434196545317,1.7291615520280252,0.916297857297023,618.8,150.9,209.7,749.9,1683.3,1742.3 -0.8708550537071029,1.7291260746777128,1.0471975511965976,272.6,149.4,276.7,830.1,1859.5,1987.0 -0.8708792738862882,1.7290853413999594,1.1780972450961724,173.3,172.5,391.7,1019.1,2262.3,2481.6 -0.8708721308334703,1.729091302241332,1.3089969389957472,136.6,250.0,629.5,1467.5,2450.9,2323.2 -0.870882002637166,1.7290860992688142,1.4398966328953218,129.1,541.8,772.1,1702.9,2154.1,2096.2 -0.8709507935157215,1.7290696865066109,1.5707963267948966,140.8,770.9,770.6,1621.3,2051.5,2051.4 -0.8709404093135527,1.7290683185233147,1.7016960206944713,171.5,771.7,830.1,1660.8,1368.7,540.9 -0.8709335636115717,1.7290648560327186,1.832595714594046,229.5,843.6,1063.6,1848.6,628.9,249.9 -0.8709867038166278,1.7290980459349474,1.9634954084936205,334.0,1024.7,1245.4,2271.7,391.5,172.5 -0.8710025307657813,1.7291156906244374,2.0943951023931953,549.4,1449.2,1859.0,2401.9,276.6,149.4 -0.8709924473161651,1.7290940538517594,2.2252947962927703,750.3,1742.4,1683.0,2117.9,209.6,150.8 -0.8709978098868056,1.7291147804351998,2.356194490192345,741.4,1651.1,1652.0,2020.5,170.2,170.8 -0.8709950809007405,1.7291433934576532,2.4870941840919194,793.2,1683.7,1743.0,1211.4,150.9,210.0 -0.8709993552837827,1.7291327731128048,2.6179938779914944,1041.6,1861.5,1989.4,546.6,149.0,276.7 -0.8709867278559554,1.7291476783952546,2.748893571891069,1181.9,2266.3,2486.7,333.5,173.6,393.7 -0.87081789207003,1.7289131649377225,2.8797932657906435,1744.5,2450.2,2322.9,229.9,251.0,630.4 -0.8708448695499751,1.7288994108655993,3.010692959690218,1661.1,2156.2,2097.7,172.3,537.9,772.0 -0.8708316860934433,1.6286388798541176,0.0,1521.3,2050.8,2051.0,240.8,770.8,771.0 -0.8709355667746199,1.6293185689149774,0.1308996938995747,1601.8,1731.0,916.0,232.6,772.6,831.8 -0.8709172277840547,1.629312296498331,0.2617993877991494,1824.5,829.3,449.9,252.4,843.0,970.6 -0.870883793605263,1.6292904877340253,0.39269908169872414,2289.5,533.2,314.1,315.3,1023.7,1244.4 -0.8708536124171345,1.6292588449930427,0.5235987755982988,2310.7,392.2,264.6,470.6,1601.8,1745.2 -0.8708425173531863,1.629233980281332,0.6544984694978736,2075.5,313.5,254.5,793.3,1638.7,1579.9 -0.870830429995709,1.6291858167892403,0.7853981633974483,2021.2,270.8,270.3,741.0,1551.9,1551.1 -0.8708318977213654,1.6291738737225965,0.916297857297023,1005.7,254.3,313.2,750.0,1579.9,1638.6 -0.8708446906514389,1.6291344208245837,1.0471975511965976,472.2,264.9,392.3,830.2,1744.1,1871.5 -0.8708709050842347,1.6290903916190649,1.1780972450961724,314.9,313.7,532.9,1050.1,2121.2,2340.3 -0.8708662937246853,1.6290938823851382,1.3089969389957472,252.2,449.3,828.7,1553.8,2451.0,2323.0 -0.8708790375288301,1.62908705227455,1.4398966328953218,232.5,830.6,772.5,1599.3,2154.2,2095.8 -0.8709508350967954,1.6290698800671246,1.5707963267948966,240.8,770.9,770.7,1521.0,2051.8,2050.8 -0.8709432826646024,1.629068538043484,1.7016960206944713,275.0,771.6,830.1,1557.1,1758.4,930.3 -0.8709389750296496,1.6290657748844133,1.832595714594046,345.1,843.8,971.4,1732.9,828.1,449.0 -0.8709942418820616,1.6291002447421372,1.9634954084936205,475.8,1024.6,1245.5,2130.2,532.6,313.6 -0.8710116456867392,1.6291195473098055,2.0943951023931953,749.1,1600.2,1743.7,2401.1,392.1,264.9 -0.8710025635634673,1.629099754137478,2.2252947962927703,750.3,1638.5,1579.9,2117.6,313.1,254.4 -0.8710083634517207,1.6291223949339808,2.356194490192345,741.5,1551.3,1551.8,2020.1,270.2,270.8 -0.8710055396900585,1.6291528350587583,2.4870941840919194,793.3,1580.1,1639.3,1596.4,254.5,313.6 -0.8710092897379849,1.629143801539189,2.6179938779914944,923.8,1745.9,1873.3,745.9,264.6,392.3 -0.8709957841238045,1.6291600001837927,2.748893571891069,1181.4,2125.1,2345.0,506.0,315.0,535.2 -0.870818242687529,1.6289166383440696,2.8797932657906435,1731.8,2450.3,2322.5,345.5,450.4,829.7 -0.870844959893729,1.6289030102234603,3.010692959690218,1557.4,2156.9,2097.4,275.8,831.0,772.1 -0.8708313863364429,1.5286422655541598,0.0,1421.1,2051.4,2051.0,340.8,771.1,770.9 -0.8709356633621408,1.5293188609950215,0.1308996938995747,1498.0,2097.9,1300.0,336.2,772.4,831.9 -0.8709173632522786,1.529312600026516,0.2617993877991494,1709.1,1028.6,649.3,368.0,1001.2,970.5 -0.8708839097909535,1.5292907794152226,0.39269908169872414,2147.1,674.4,455.2,456.9,1023.6,1244.3 -0.8708537002431179,1.5292591073348585,0.5235987755982988,2310.9,507.8,380.2,669.9,1489.8,1629.6 -0.8708425846033278,1.5292342053552366,0.6544984694978736,2075.9,417.0,358.0,793.3,1535.5,1476.3 -0.8708304859148259,1.529186000303251,0.7853981633974483,2021.1,370.8,370.3,740.9,1451.9,1451.3 -0.8708319538931668,1.5291740176959587,0.916297857297023,1392.8,357.9,416.7,750.0,1476.2,1535.2 -0.8708447564663189,1.529134528837037,1.0471975511965976,671.8,380.5,507.8,920.6,1628.3,1755.9 -0.8708709876855891,1.5290904683347315,1.1780972450961724,456.7,454.9,674.0,1019.4,1980.3,2199.3 -0.8708663989136994,1.5290939359605475,1.3089969389957472,367.8,648.7,842.8,1568.7,2559.2,2323.1 -0.8708791688740694,1.5290870914544974,1.4398966328953218,336.0,830.6,772.3,1496.1,2154.3,2096.0 -0.8709509938029728,1.5290699108156807,1.5707963267948966,340.8,771.0,770.7,1421.0,2051.5,2051.2 -0.8709434675274786,1.529068568596849,1.7016960206944713,378.5,771.6,830.0,1453.7,2096.5,1319.8 -0.8709391830521807,1.5290658131106774,1.832595714594046,460.8,1000.4,971.3,1617.2,1027.1,648.1 -0.8709944693702905,1.5291002948850243,1.9634954084936205,617.5,1024.5,1245.4,1988.6,673.7,454.6 -0.8710118876829613,1.529119612359093,2.0943951023931953,829.8,1493.0,1628.3,2405.5,507.6,380.4 -0.8710028137429789,1.5290998369725164,2.2252947962927703,750.3,1534.9,1476.4,2117.7,416.6,357.8 -0.8710086164495489,1.529122495798899,2.356194490192345,741.5,1451.4,1451.9,2020.7,370.3,370.8 -0.8710057914478173,1.5291529520024865,2.4870941840919194,793.3,1476.7,1535.8,2066.9,358.0,417.2 -0.8710095352323448,1.5291439328207468,2.6179938779914944,949.4,1630.2,1757.5,945.1,380.2,508.0 -0.8709960219931515,1.529160142088589,2.748893571891069,1181.6,1983.5,2203.7,616.2,456.5,676.6 -0.8708182682250687,1.528916702887388,2.8797932657906435,1616.1,2558.2,2322.8,461.1,649.7,842.8 -0.8708449618143873,1.52890308703243,3.010692959690218,1453.9,2156.5,2097.2,379.3,831.1,772.0 -0.8708313754930138,1.4286423409084636,0.0,1321.3,2051.1,2051.1,440.7,771.0,770.9 -0.8709356705227714,1.4293188728197697,0.1308996938995747,1394.7,2098.5,1683.6,439.8,772.3,831.8 -0.8709173707378058,1.4293126119640105,0.2617993877991494,1593.4,1228.0,892.6,483.5,843.0,970.5 -0.8708839156182331,1.4292907903640772,0.39269908169872414,2006.3,815.6,596.3,598.5,1023.6,1244.4 -0.8708537042945294,1.4292591164715376,0.5235987755982988,2310.9,623.3,495.9,869.2,1446.1,1514.2 -0.8708425874190733,1.429234212297581,0.6544984694978736,2075.8,520.5,461.6,793.3,1432.0,1372.9 -0.8708304880763742,1.429186004846823,0.7853981633974483,2021.1,470.8,470.3,740.8,1351.7,1351.2 -0.8708319560666163,1.4291740199510776,0.916297857297023,1780.0,461.4,520.3,750.0,1372.9,1431.4 -0.8708447592019938,1.4291345290215358,1.0471975511965976,915.2,496.0,623.4,830.3,1513.0,1640.4 -0.8708709914084787,1.4290904667450324,1.1780972450961724,598.4,596.0,815.3,1019.1,1838.9,2058.2 -0.8708664039571398,1.4290939330579027,1.3089969389957472,483.4,848.1,842.5,1467.5,2450.6,2323.4 -0.870879175431795,1.429087087737957,1.4398966328953218,439.4,830.7,772.1,1392.6,2154.7,2096.2 -0.8709510019253065,1.429069906665168,1.5707963267948966,440.7,770.9,770.6,1321.3,2051.4,2051.2 -0.8709434771449248,1.4290685644758647,1.7016960206944713,482.0,771.7,830.0,1350.1,2096.6,1709.2 -0.8709391939857284,1.429065809445042,1.832595714594046,576.4,843.5,971.4,1501.6,1226.4,847.4 -0.8709944813839783,1.4291002919146631,1.9634954084936205,759.3,1024.5,1245.5,1846.5,814.6,595.7 -0.8710119004910531,1.4291196102530974,2.0943951023931953,829.8,1449.2,1512.4,2401.7,648.6,495.8 -0.8710028270040242,1.4290998358762295,2.2252947962927703,750.3,1431.5,1372.7,2117.8,520.1,461.3 -0.871008629866469,1.4291224957100384,2.356194490192345,741.4,1351.3,1351.9,2020.1,470.2,470.8 -0.871005804792964,1.4291529528140576,2.4870941840919194,793.3,1373.0,1432.2,2075.7,461.5,520.6 -0.8710095482434826,1.4291439344361079,2.6179938779914944,923.8,1514.6,1642.4,1144.0,495.9,623.6 -0.8709960345881648,1.4291601443121829,2.748893571891069,1181.6,1842.1,2062.2,757.6,597.9,818.1 -0.870818270195853,1.4289167041065856,2.8797932657906435,1500.8,2450.1,2323.0,576.8,849.2,843.0 -0.8708861196443882,1.4288851283867183,3.010692959690218,1350.5,2156.6,2097.3,482.8,831.1,772.2 -0.8708453330412349,1.3286523666203913,0.0,1221.3,2051.3,2050.8,540.8,770.8,770.9 -0.8709403976739816,1.3293112072673696,0.1308996938995747,1291.0,2098.4,2151.9,543.4,772.5,831.8 -0.8709205693222845,1.32930448615109,0.2617993877991494,1478.1,1427.4,1048.0,599.2,843.0,970.6 -0.8708491977600598,1.329256393866664,0.39269908169872414,1865.0,956.8,737.6,740.1,1023.6,1244.3 -0.8708416747599007,1.32924913642085,0.5235987755982988,2451.3,739.0,611.5,923.0,1446.0,1398.5 -0.8708346666599386,1.3292320414312064,0.6544984694978736,2075.4,624.1,565.2,793.4,1328.3,1269.3 -0.8708101468615717,1.3291269914551083,0.7853981633974483,2021.2,570.8,570.3,740.7,1252.0,1251.2 -0.8708101376524486,1.329154354600023,0.916297857297023,2118.1,564.9,623.8,749.9,1269.3,1328.3 -0.8708208204650326,1.3291216326001922,1.0471975511965976,1070.9,611.7,738.9,855.8,1397.3,1524.8 -0.8708485523471733,1.3290751493789097,1.1780972450961724,740.0,737.1,956.4,1019.2,1698.1,1917.0 -0.8708480350292946,1.329074793802092,1.3089969389957472,599.0,970.2,842.7,1452.8,2403.8,2323.0 -0.870866254238932,1.3290650352752507,1.4398966328953218,542.9,830.6,772.4,1289.1,2154.7,2095.5 -0.8709440402849518,1.3290465004390783,1.5707963267948966,540.8,770.9,770.6,1221.2,2051.5,2051.1 -0.8709421743122937,1.3290453585788748,1.7016960206944713,585.4,771.6,830.2,1246.8,2096.9,2155.4 -0.8709429405516936,1.3290441433252826,1.832595714594046,691.9,869.2,971.4,1386.0,1425.6,1046.5 -0.8710024302734428,1.3290812781974704,1.9634954084936205,901.0,1024.6,1245.3,1705.1,955.8,736.8 -0.8710229492334092,1.3291039524621553,2.0943951023931953,829.8,1449.1,1397.3,2401.2,738.6,611.4 -0.8710158376971646,1.3290878730696563,2.2252947962927703,750.2,1328.2,1269.2,2118.0,623.5,564.9 -0.8710123015042585,1.3290660890261083,2.356194490192345,741.5,1251.0,1251.8,2020.3,570.4,570.9 -0.8709993387977706,1.329332868368564,2.4870941840919194,793.3,1269.6,1328.8,2075.9,565.2,624.3 -0.8707010530572167,1.3290861878386524,2.6179938779914944,923.6,1398.2,1526.2,1344.8,611.3,739.0 -0.8710801775958577,1.329192311203739,2.748893571891069,1182.1,1700.8,1921.4,899.0,739.5,959.4 -0.8708869413417711,1.3289288346625234,2.8797932657906435,1384.6,2404.2,2322.5,692.1,970.2,842.7 -0.8709101704391592,1.3289170186571275,3.010692959690218,1246.6,2156.0,2097.1,586.4,831.1,772.0 -0.8708881056850967,1.228648839333366,0.0,1121.4,2050.9,2050.9,640.8,771.0,771.0 -0.8709602250001104,1.2293067924534606,0.1308996938995747,1187.3,2098.2,2157.8,647.0,772.6,831.8 -0.8709366941391606,1.2292989560091372,0.2617993877991494,1362.5,1627.2,1247.4,714.7,843.0,970.6 -0.8709033314542354,1.2292772710868332,0.39269908169872414,1722.5,1098.1,878.6,882.0,1023.5,1353.4 -0.8708742823191902,1.2292469785748075,0.5235987755982988,2310.3,854.7,726.8,923.1,1410.5,1282.8 -0.8708641306665978,1.2292240611949912,0.6544984694978736,2075.9,727.7,668.6,793.3,1224.9,1165.7 -0.8708524251814965,1.229178028870617,0.7853981633974483,2021.2,670.9,670.3,741.0,1151.6,1151.0 -0.8708537453923635,1.2291681405117598,0.916297857297023,2118.0,668.4,727.2,750.1,1165.8,1224.7 -0.8708659064872296,1.2291305124339909,1.0471975511965976,1270.8,727.2,854.6,830.3,1281.7,1409.3 -0.8708911136403684,1.229087935420257,1.1780972450961724,881.8,878.3,1023.2,1019.1,1556.7,1775.7 -0.8708852953279778,1.2290925036839397,1.3089969389957472,714.6,970.3,842.7,1363.0,2204.5,2323.0 -0.8708967136950259,1.2290863936168122,1.4398966328953218,646.4,830.7,772.4,1185.7,2154.4,2095.8 -0.8709671434953511,1.2290695163796477,1.5707963267948966,640.8,771.0,770.7,1121.4,2051.0,2050.9 -0.8709583175156396,1.2290681585818817,1.7016960206944713,688.9,771.6,830.2,1143.3,2097.1,2155.3 -0.8709528553912659,1.229065134814675,1.832595714594046,807.7,843.7,971.4,1270.3,1625.2,1246.2 -0.8710071379062306,1.2290990700745856,1.9634954084936205,1020.0,1024.5,1353.0,1563.0,1097.1,878.0 -0.8710237842020504,1.2291176566599997,2.0943951023931953,829.8,1408.9,1281.8,2230.2,854.3,727.0 -0.8710141590414899,1.2290970778838464,2.2252947962927703,750.4,1224.5,1165.7,2118.0,727.0,668.5 -0.8710196536728497,1.2291188682237015,2.356194490192345,741.5,1151.2,1151.7,2020.5,670.2,670.8 -0.8710167852137615,1.2291484420383685,2.4870941840919194,793.2,1165.9,1225.3,2076.1,668.7,727.7 -0.8710206750119608,1.2291386363706007,2.6179938779914944,923.7,1283.3,1411.0,1542.8,727.1,854.8 -0.8710075397572709,1.229154155926158,2.748893571891069,1227.1,1558.8,1779.1,1040.4,880.7,1021.4 -0.8708250278424745,1.2289124276117525,2.8797932657906435,1269.4,2203.8,2323.0,808.0,970.4,842.8 -0.8708506666709515,1.2288993806881452,3.010692959690218,1143.5,2156.2,2097.6,689.9,831.1,772.1 -0.870836629329204,1.1286385933219685,0.0,1021.3,2051.1,2051.0,740.8,771.0,771.0 -0.8709379836482523,1.1293176773198796,0.1308996938995747,1084.0,2098.1,2157.7,750.6,772.4,831.9 -0.8709192120879292,1.1293112753454888,0.2617993877991494,1246.9,1826.6,1447.0,830.4,843.0,970.4 -0.8708857705752006,1.1292894702201433,0.39269908169872414,1581.0,1239.1,1019.9,1023.6,1023.5,1244.4 -0.8708556689392423,1.1292579273102565,0.5235987755982988,2302.6,970.4,842.5,923.1,1294.8,1167.6 -0.8708446423637243,1.1292332098534792,0.6544984694978736,2075.9,831.3,772.1,793.3,1121.4,1062.2 -0.870832579438585,1.1291852060884007,0.7853981633974483,2021.1,770.8,770.2,741.0,1051.8,1051.2 -0.8708340333636903,1.1291734173621728,0.916297857297023,2118.8,771.8,830.8,750.1,1062.2,1121.2 -0.8708467762883617,1.129134100648264,1.0471975511965976,1470.1,842.5,970.0,830.1,1166.3,1293.7 -0.8708729124992924,1.1290901770653083,1.1780972450961724,1023.4,1019.4,1023.2,1019.0,1415.4,1634.8 -0.8708682100438873,1.1290937463867006,1.3089969389957472,830.2,970.3,842.6,1247.3,2004.8,2323.4 -0.870880855145834,1.1290869700767816,1.4398966328953218,749.7,830.6,772.1,1082.0,2154.5,2096.0 -0.8709525510712702,1.129069817470246,1.5707963267948966,740.8,770.9,770.6,1021.4,2051.4,2051.2 -0.8709449046661181,1.1290684740953845,1.7016960206944713,792.4,771.7,830.1,1039.6,2096.9,2155.3 -0.8709405111393286,1.129065694474963,1.832595714594046,923.1,843.6,971.3,1154.6,1824.2,1444.8 -0.8709957042981361,1.1291001260322373,1.9634954084936205,1019.8,1024.6,1245.8,1421.5,1238.0,1019.0 -0.871013050847017,1.1291193760164933,2.0943951023931953,829.8,1293.4,1166.1,2030.5,969.8,842.5 -0.8710039253476263,1.129099526588163,2.2252947962927703,750.4,1121.0,1062.0,2117.6,830.7,772.0 -0.8710096990003684,1.1291221050698006,2.356194490192345,741.5,1051.2,1051.8,2020.5,770.3,770.9 -0.8710068697492831,1.129152479272525,2.4870941840919194,793.3,1062.1,1121.3,2076.0,772.2,831.3 -0.8710106267168723,1.1291433870919612,2.6179938779914944,923.8,1167.7,1295.2,1741.3,842.9,970.5 -0.8709971487207885,1.1291595321299335,2.748893571891069,1244.2,1417.5,1637.8,1181.8,1022.4,1021.5 -0.8708189245657643,1.1289162793727874,2.8797932657906435,1153.9,2004.4,2322.8,923.5,970.5,842.7 -0.8708455142365509,1.128902719583856,3.010692959690218,1039.9,2156.6,2097.6,793.3,831.0,772.0 -0.9709107229057806,1.8291087123073555,0.0,1721.1,1951.2,1950.9,41.0,870.9,871.0 -0.9709647424546118,1.828940678904965,0.1308996938995747,1808.7,964.7,148.9,25.6,876.1,935.5 -0.9711169615710263,1.8289888604133986,0.2617993877991494,2055.3,430.9,51.3,21.3,958.4,1086.0 -0.9710456251618634,1.8289439829514025,0.39269908169872414,2572.2,251.1,31.8,32.0,1164.8,1386.1 -0.9710355353090079,1.8289348948674777,0.5235987755982988,2195.5,161.2,33.5,72.2,1644.5,1976.6 -0.9710478025468393,1.8289547037122331,0.6544984694978736,1972.3,106.6,47.5,231.4,1846.2,1787.1 -0.9710477231131988,1.8289598298916252,0.7853981633974483,1921.0,70.9,70.4,840.8,1751.8,1750.9 -0.9710474551309469,1.8290005397562767,0.916297857297023,317.8,47.5,106.3,853.5,1786.7,1845.4 -0.9710458785733916,1.8290089131372387,1.0471975511965976,73.3,34.0,161.3,945.6,1974.9,2102.4 -0.9710477406620082,1.8290044831491794,1.1780972450961724,31.8,31.6,250.7,1160.0,2403.1,2622.0 -0.9710124350571796,1.8290376166770872,1.3089969389957472,21.2,51.1,430.3,1810.6,2335.8,2207.7 -0.9709905081549738,1.8290503354138368,1.4398966328953218,25.8,152.4,875.9,1806.0,2051.0,1992.5 -0.9710260802589454,1.8290423446331319,1.5707963267948966,41.0,871.0,870.7,1720.9,1951.1,1951.1 -0.970984402582781,1.829040856028273,1.7016960206944713,68.3,875.1,933.5,1764.0,980.9,152.4 -0.9709494199783425,1.829029951339717,1.832595714594046,114.0,959.1,1253.4,1963.5,430.2,51.0 -0.9709788318386217,1.8290493084082518,1.9634954084936205,192.5,1166.1,1387.1,2412.9,250.8,31.6 -0.9709768606045279,1.8290488922419847,2.0943951023931953,349.9,1856.2,1975.1,2286.4,161.3,34.0 -0.97095521890864,1.8290070342024232,2.2252947962927703,831.3,1845.1,1786.6,2013.9,106.3,47.5 -0.970955216485663,1.8290065792851606,2.356194490192345,841.6,1751.1,1751.3,1920.3,70.4,71.0 -0.9709530674929875,1.8290147804166548,2.4870941840919194,896.9,1786.9,1846.2,827.3,47.5,106.6 -0.9709627940101706,1.8289862771558918,2.6179938779914944,1039.4,1976.7,2104.5,347.9,33.5,161.2 -0.9709597451304162,1.8289864711704524,2.748893571891069,1322.8,2407.2,2627.1,192.3,32.3,252.3 -0.9708551998561575,1.828847641859111,2.8797932657906435,1936.8,2333.9,2206.5,114.3,51.8,431.6 -0.9708799551037655,1.8288352620021375,3.010692959690218,1764.4,2052.5,1993.8,68.7,152.0,875.8 -0.970868787859998,1.728576827462796,0.0,1620.8,1950.8,1951.1,140.8,870.9,870.8 -0.9709488503938575,1.7293073934662808,0.1308996938995747,1705.2,1347.5,532.4,129.0,875.9,935.3 -0.9709269973267547,1.7293000705036494,0.2617993877991494,1940.2,673.8,250.5,136.8,958.7,1086.1 -0.9708938826323188,1.729278507936866,0.39269908169872414,2431.1,392.0,172.9,173.5,1165.6,1385.9 -0.9708647524110569,1.7292480611664698,0.5235987755982988,2195.0,276.6,149.0,271.4,1717.3,1861.1 -0.970854488999556,1.7292248470296223,0.6544984694978736,1972.2,210.0,151.0,617.1,1742.8,1683.7 -0.9708427769933398,1.7291784975225317,0.7853981633974483,1921.0,170.8,170.3,840.8,1651.8,1650.9 -0.9708441535097958,1.7291682955560015,0.916297857297023,704.1,150.9,209.7,853.5,1683.2,1742.0 -0.9708564443737581,1.7291304000080767,1.0471975511965976,316.5,149.3,276.7,945.7,1859.6,1986.8 -0.970881840014662,1.7290876455141402,1.1780972450961724,173.3,172.5,391.7,1191.6,2262.8,2481.6 -0.9708762153149949,1.729092081494733,1.3089969389957472,136.6,250.1,629.4,1800.1,2335.1,2207.3 -0.9708878282358749,1.7290858698666152,1.4398966328953218,129.1,541.7,875.7,1702.8,2050.8,1992.3 -0.9709584531937226,1.7290689852575147,1.5707963267948966,140.8,871.2,870.7,1621.3,1951.2,1951.3 -0.9709497997594292,1.7290676380823076,1.7016960206944713,171.5,875.2,933.6,1660.6,1368.9,626.5 -0.9709445006823434,1.7290646207885214,1.832595714594046,229.5,959.3,1087.1,1848.5,628.9,249.8 -0.9709989251177954,1.7290986170183962,1.9634954084936205,334.0,1166.3,1387.1,2272.4,391.5,172.5 -0.9710156865239539,1.7291172982027996,2.0943951023931953,549.4,1740.8,1859.5,2285.9,276.6,149.3 -0.9710061728463995,1.7290968041481372,2.2252947962927703,853.7,1741.9,1683.1,2014.3,209.6,150.8 -0.9710117535159861,1.7291187016078973,2.356194490192345,841.7,1651.2,1651.7,1920.7,170.2,170.8 -0.9710089195966594,1.7291484142599427,2.4870941840919194,896.9,1683.6,1742.9,1211.2,150.9,210.1 -0.9710128356012673,1.729138732582428,2.6179938779914944,1039.5,1861.3,1989.2,546.6,149.0,276.6 -0.9709996517799379,1.7291543875041118,2.748893571891069,1323.1,2266.7,2486.3,333.5,173.6,393.6 -0.9708219876523088,1.7289131686819512,2.8797932657906435,1847.5,2334.5,2207.0,229.9,251.0,630.3 -0.9708483725052343,1.7288997260809007,3.010692959690218,1661.2,2053.1,1993.8,172.3,537.9,875.5 -0.9708346996855283,1.628638986362707,0.0,1521.0,1951.2,1951.0,240.8,871.1,871.0 -0.9709369908935568,1.6293179966697637,0.1308996938995747,1601.6,1731.5,916.0,232.6,876.2,935.3 -0.9709183761904085,1.6293116415689908,0.2617993877991494,1824.9,829.4,449.8,252.4,958.7,1086.1 -0.9708849350264028,1.629289833354145,0.39269908169872414,2289.6,533.2,314.0,315.2,1165.4,1386.1 -0.970854802608118,1.6292582514009177,0.5235987755982988,2194.9,392.3,264.6,470.7,1645.1,1745.4 -0.9708437497856206,1.6292334769798127,0.6544984694978736,1972.0,313.5,254.6,896.8,1638.9,1580.1 -0.9708316781158147,1.6291854120207445,0.7853981633974483,1920.9,270.9,270.3,840.8,1551.6,1551.0 -0.9708331377043212,1.6291735640840797,0.916297857297023,1005.9,254.4,313.2,853.6,1579.8,1638.8 -0.9708459001875162,1.6291341953356109,1.0471975511965976,472.1,264.9,392.2,945.8,1744.1,1871.6 -0.9708720668405834,1.6290902319774656,1.1780972450961724,315.0,313.7,532.8,1160.5,2120.9,2340.7 -0.9708673994543111,1.6290937716486515,1.3089969389957472,252.2,449.4,828.7,1666.7,2335.3,2207.9 -0.9708800822805486,1.6290869748335763,1.4398966328953218,232.5,931.7,875.7,1599.8,2051.1,1992.5 -0.9709518168862371,1.629069815390218,1.5707963267948966,240.7,871.1,870.7,1521.2,1951.3,1951.1 -0.9709442061786919,1.6290684727731926,1.7016960206944713,275.0,875.1,933.7,1557.0,1758.0,930.2 -0.9709398453539616,1.629065699059928,1.832595714594046,345.0,959.5,1086.7,1732.6,828.0,449.0 -0.970995066459182,1.6291001450504186,1.9634954084936205,475.8,1166.3,1387.3,2130.7,532.5,313.6 -0.9710124347605512,1.6291194150310973,2.0943951023931953,749.2,1648.6,1743.9,2285.8,392.1,264.8 -0.9710033261743919,1.6290995866798634,2.2252947962927703,853.8,1638.4,1579.9,2014.4,313.1,254.4 -0.9710091103284718,1.6291221886283092,2.356194490192345,841.5,1551.1,1551.9,1920.1,270.2,270.8 -0.9710062834826921,1.629152588064658,2.4870941840919194,896.9,1580.1,1639.4,1596.4,254.5,313.6 -0.9710100384706942,1.6291435183407146,2.6179938779914944,1039.5,1745.3,1873.4,745.9,264.6,392.3 -0.9709965500362978,1.6291596842756273,2.748893571891069,1323.4,2125.4,2345.1,474.8,315.0,535.1 -0.9708186450205054,1.6289164090901176,2.8797932657906435,1731.7,2334.4,2207.3,345.5,450.4,829.7 -0.9708452923233225,1.6289028184778314,3.010692959690218,1557.6,2052.8,1993.7,275.8,924.2,875.7 -0.9708316901572263,1.5286420742272075,0.0,1421.0,1951.4,1950.8,340.8,871.0,870.9 -0.9709358113276975,1.5293187970490638,0.1308996938995747,1498.3,1995.0,1300.1,336.2,875.9,935.6 -0.9709174742370212,1.5293125251279494,0.2617993877991494,1709.3,1028.8,649.2,368.0,958.8,1086.1 -0.9708840139819735,1.5292907009971413,0.39269908169872414,2147.8,674.3,455.2,456.9,1165.4,1386.0 -0.9708538051743107,1.5292590307867326,0.5235987755982988,2194.9,508.0,380.3,670.1,1645.1,1630.0 -0.9708426911203383,1.529234133235771,0.6544984694978736,1972.4,417.1,358.1,896.9,1535.6,1476.6 -0.9708305928549565,1.5291859333474185,0.7853981633974483,1921.0,370.9,370.3,840.9,1451.9,1451.0 -0.9708320601144688,1.5291739557136474,0.916297857297023,1392.9,357.8,416.8,853.5,1476.5,1534.9 -0.9711514351554409,1.5291582230833634,1.0471975511965976,671.4,380.6,508.1,946.0,1628.9,1756.4 -0.97115022542236,1.529158027633739,1.1780972450961724,487.7,455.1,674.4,1161.1,1980.7,2200.0 -0.9711073673728007,1.5291969786191508,1.3089969389957472,367.8,649.2,958.0,1709.2,2334.7,2207.1 -0.9710759150341515,1.5292133844024116,1.4398966328953218,336.1,933.9,875.7,1495.7,2050.5,1992.1 -0.971101585310727,1.5292069782811335,1.5707963267948966,340.9,870.9,870.9,1421.1,1951.1,1951.0 -0.9710507820639679,1.529204389975627,1.7016960206944713,378.7,875.2,933.8,1453.8,1993.3,1318.0 -0.9710080166653944,1.5291900437324306,1.832595714594046,461.0,1043.2,1087.4,1617.7,1026.6,648.0 -0.9710310792870064,1.5292048323514478,1.9634954084936205,618.0,1167.1,1387.9,1989.3,673.4,454.6 -0.9710243899180543,1.5291991871134352,2.0943951023931953,945.2,1650.5,1627.7,2285.2,507.5,380.4 -0.9709998684376575,1.5291514544555316,2.2252947962927703,853.8,1534.9,1476.2,2013.6,416.5,357.8 -0.970998438806105,1.529145092518007,2.356194490192345,841.6,1451.2,1451.7,1920.2,370.1,370.9 -0.9709959438334871,1.5291478311618447,2.4870941840919194,897.2,1476.7,1536.1,1972.4,358.1,417.3 -0.9710067615914846,1.5291141523535137,2.6179938779914944,1039.9,1630.4,1758.6,944.2,380.3,508.2 -0.9710053786868547,1.5291099566196933,2.748893571891069,1324.1,1984.0,2204.4,615.8,456.6,676.9 -0.9710297099526753,1.5290875197120415,2.8797932657906435,1615.3,2333.3,2205.8,486.0,650.8,958.1 -0.9710380455826472,1.52908256662089,3.010692959690218,1453.7,2051.8,1993.2,379.0,934.3,875.7 -0.9710006167093583,1.4287991691821549,0.0,1321.5,1950.8,1951.2,440.6,871.0,871.1 -0.9710128164396987,1.4293346785624448,0.1308996938995747,1394.3,1994.5,1685.4,439.8,876.3,935.3 -0.97097385902781,1.4293220556787083,0.2617993877991494,1593.2,1228.6,848.8,483.6,958.6,1085.9 -0.9709350014469136,1.4292969790024637,0.39269908169872414,2005.5,815.7,596.5,598.5,1165.2,1385.8 -0.9709036365126352,1.4292643723508682,0.5235987755982988,2195.2,623.6,495.8,868.8,1642.1,1514.1 -0.9708923953789949,1.4292396958891112,0.6544984694978736,1972.0,520.7,461.6,897.0,1432.4,1373.2 -0.9708800824816464,1.4291920290904574,0.7853981633974483,1921.2,470.9,470.3,840.8,1351.8,1351.2 -0.9708777916686528,1.4292226681943707,0.916297857297023,1781.4,461.4,520.2,853.6,1372.8,1431.2 -0.9708986639222695,1.429155892125522,1.0471975511965976,871.8,495.9,623.2,945.9,1512.8,1640.3 -0.9709280070736184,1.4291062532615966,1.1780972450961724,598.4,595.9,815.0,1160.2,1838.7,2057.6 -0.9709228446122841,1.4291099554493436,1.3089969389957472,483.3,847.8,958.3,1594.4,2335.2,2207.9 -0.9709332330666053,1.4291042893621733,1.4398966328953218,439.5,934.2,875.8,1392.6,2051.0,1992.5 -0.9710019760455717,1.4290876081417694,1.5707963267948966,440.8,871.2,870.8,1321.4,1951.2,1950.9 -0.9709914188238832,1.4290861067464622,1.7016960206944713,482.0,875.1,933.6,1350.2,1993.5,1710.4 -0.9709843479962615,1.429082657774543,1.832595714594046,576.4,959.4,1086.8,1501.5,1227.0,847.7 -0.9710372671065645,1.4291157756924062,1.9634954084936205,759.1,1166.2,1387.0,1846.4,815.1,595.9 -0.971052871266541,1.4291333067116891,2.0943951023931953,945.5,1640.3,1512.9,2385.6,623.2,496.0 -0.9710424620448018,1.4291116333173837,2.2252947962927703,854.0,1431.8,1372.7,2014.1,520.2,461.3 -0.9710474750490092,1.4291322407380953,2.356194490192345,841.6,1351.5,1351.9,1920.4,470.3,470.8 -0.9710402886262,1.4292116762920726,2.4870941840919194,897.0,1372.8,1432.0,1972.0,461.5,520.6 -0.9710546609343024,1.4291668891953178,2.6179938779914944,1039.5,1514.4,1642.0,1144.7,495.8,623.5 -0.9710464271418506,1.4291743744548742,2.748893571891069,1323.1,1841.5,2062.0,757.7,597.8,817.9 -0.9708355727174548,1.4289152871701734,2.8797932657906435,1500.4,2335.1,2206.9,576.7,849.0,958.5 -0.9708590129478617,1.428903389152068,3.010692959690218,1350.3,2052.8,1994.1,482.8,934.5,875.6 -0.970843313090147,1.3286419899512891,0.0,1221.0,1951.2,1950.9,540.8,871.1,870.9 -0.970941535221755,1.3293167233270786,0.1308996938995747,1290.9,1994.6,2054.2,543.4,876.0,935.3 -0.9709221997800744,1.3293101522799247,0.2617993877991494,1477.9,1427.5,1047.9,599.2,958.5,1086.0 -0.9708887310398493,1.3292883420093797,0.39269908169872414,1864.6,956.7,737.6,740.3,1165.3,1494.3 -0.9708587139167355,1.32925691155677,0.5235987755982988,2194.5,739.1,611.5,1038.8,1525.9,1398.7 -0.9708477636702219,1.329232365375489,0.6544984694978736,1972.3,624.3,565.1,896.8,1328.5,1269.2 -0.9708357236035002,1.3291845458323555,0.7853981633974483,1921.0,570.8,570.3,840.9,1251.6,1251.4 -0.9708371580875358,1.3291729357840922,0.916297857297023,2014.8,565.0,623.8,853.5,1269.2,1328.0 -0.9708498397572942,1.329133775550893,1.0471975511965976,1071.0,611.4,739.0,945.6,1397.6,1524.9 -0.9708758819001343,1.3290899695635294,1.1780972450961724,740.1,737.1,956.4,1160.3,1698.0,1916.9 -0.9708710731826221,1.3290936265365594,1.3089969389957472,599.0,1047.3,958.3,1478.2,2335.5,2207.4 -0.9708836049816771,1.3290869118736448,1.4398966328953218,542.9,934.1,875.8,1289.0,2050.6,1992.4 -0.9709551847095164,1.3290697781487957,1.5707963267948966,540.7,870.9,870.6,1221.2,1951.2,1951.2 -0.9709474317917025,1.3290684325516846,1.7016960206944713,585.4,875.1,933.5,1246.8,1993.6,2052.0 -0.970942940096654,1.329065637638306,1.832595714594046,692.0,959.1,1087.2,1386.1,1425.7,1046.7 -0.9709980486515277,1.3291000271214908,1.9634954084936205,901.0,1166.3,1494.0,1705.1,956.0,737.0 -0.971015328820484,1.3291192177506497,2.0943951023931953,945.2,1524.5,1397.1,2285.9,738.7,611.4 -0.9710061499315167,1.3290993068821462,2.2252947962927703,853.7,1328.0,1269.1,2013.7,623.6,564.8 -0.9710118889597719,1.3291218155171984,2.356194490192345,841.5,1251.3,1251.8,1920.1,570.3,570.8 -0.9710090504763748,1.3291521125370251,2.4870941840919194,896.9,1269.7,1328.7,1972.3,565.2,624.2 -0.9710128104892553,1.3291429517071802,2.6179938779914944,1039.2,1398.8,1526.4,1343.4,611.5,739.2 -0.9709993638332945,1.3291590312523764,2.748893571891069,1368.4,1700.8,1921.0,898.9,739.3,959.4 -0.9708199271848816,1.328915842945877,2.8797932657906435,1385.1,2334.6,2207.6,692.2,1048.4,958.6 -0.9708463068322792,1.328902395155426,3.010692959690218,1246.9,2053.1,1994.3,586.4,934.6,875.8 -0.9708325839571541,1.228641641451608,0.0,1121.3,1951.2,1951.5,640.8,870.9,870.8 -0.9709362447960003,1.2293186267329812,0.1308996938995747,1187.6,1994.7,2054.2,646.9,875.9,935.4 -0.9709178256491875,1.2293123302682598,0.2617993877991494,1362.4,1627.0,1247.5,714.7,958.4,1086.2 -0.9708843629878339,1.229290506131987,0.39269908169872414,1722.8,1097.9,878.8,882.1,1165.3,1386.0 -0.9708541683305476,1.2292588536865914,0.5235987755982988,2258.7,854.9,727.0,1038.8,1410.5,1283.0 -0.9708430666046978,1.2292339826291978,0.6544984694978736,1972.1,727.7,668.7,897.0,1225.2,1165.8 -0.9708309728352505,1.229185811615514,0.7853981633974483,1921.1,670.8,670.3,840.9,1151.6,1151.3 -0.9708324376517932,1.2293082796617019,0.916297857297023,2014.9,668.6,727.3,853.5,1165.6,1224.8 -0.9711515447888256,1.2291580925153287,1.0471975511965976,1269.7,727.3,854.8,946.1,1282.2,1409.6 -0.9711503311067745,1.2291579027373203,1.1780972450961724,881.4,878.6,1098.0,1160.8,1557.3,1776.4 -0.9711074665287408,1.2291968605389898,1.3089969389957472,714.4,1085.3,958.1,1362.4,2206.1,2342.7 -0.971076005962374,1.2292132721322209,1.4398966328953218,646.4,934.0,875.6,1185.3,2050.7,1992.3 -0.9711016669897048,1.2292068684947688,1.5707963267948966,640.9,870.8,870.8,1121.1,1951.1,1950.6 -0.971050854857146,1.2292042807972061,1.7016960206944713,689.1,875.3,933.7,1143.3,1993.1,2052.4 -0.9710080809990959,1.2291899337709986,1.832595714594046,807.9,959.5,1087.4,1270.6,1623.8,1245.2 -0.9710311362224109,1.229204718949099,1.9634954084936205,1043.3,1167.0,1387.9,1563.7,1096.5,877.8 -0.9710244411667094,1.2291990685177998,2.0943951023931953,945.1,1408.5,1281.5,2231.7,853.9,727.0 -0.9709999153947153,1.2291513303723263,2.2252947962927703,853.9,1224.2,1165.6,2013.8,727.0,668.3 -0.9709984833840489,1.2291449622438952,2.356194490192345,841.8,1151.2,1151.8,1920.3,670.3,671.0 -0.9709959884495856,1.229147694276525,2.4870941840919194,920.0,1166.2,1225.4,1972.4,668.8,727.9 -0.9710068073685,1.2291140099328168,2.6179938779914944,1039.9,1283.3,1411.6,1541.4,727.3,855.2 -0.9710054279606551,1.2291098092650083,2.748893571891069,1324.2,1559.8,1779.8,1040.0,881.1,1101.2 -0.9710297630529614,1.2290873690998732,2.8797932657906435,1268.7,2207.6,2344.6,807.1,1085.3,958.1 -0.9710381031344084,1.2290824142514198,3.010692959690218,1143.0,2052.3,1993.4,689.4,934.2,875.6 -0.9710006788119194,1.1287990214051955,0.0,1021.2,1950.9,1951.4,740.6,871.1,871.1 -0.9710128898085372,1.129334641172278,0.1308996938995747,1083.8,1994.5,2053.9,750.5,875.9,935.4 -0.9709739357035575,1.1293220196207767,0.2617993877991494,1246.6,1827.3,1447.5,830.3,958.6,1085.9 -0.9709350801264176,1.1292969446950791,0.39269908169872414,1580.8,1239.4,1020.0,1023.5,1164.9,1384.8 -0.9709037161965927,1.129264339911089,0.5235987755982988,2195.0,970.5,842.7,1039.0,1295.1,1167.4 -0.9708924756415606,1.129239665458928,0.6544984694978736,1972.2,831.2,772.3,896.9,1121.5,1062.4 -0.9708801624657933,1.129192000326225,0.7853981633974483,1920.7,770.9,770.2,840.9,1051.8,1051.2 -0.9708813398287996,1.1291806468744032,0.916297857297023,2014.0,772.1,830.8,853.4,1062.5,1120.9 -0.9708936971273165,1.1291416642965684,1.0471975511965976,1470.8,842.7,969.8,945.7,1166.4,1293.7 -0.9709193702162077,1.1290978238333287,1.1780972450961724,1023.6,1019.3,1165.1,1160.1,1415.1,1634.5 -0.970914297591962,1.1291014234853036,1.3089969389957472,830.2,1086.0,958.4,1247.5,2004.6,2207.7 -0.9709266564634771,1.1290946956495305,1.4398966328953218,749.9,934.3,875.8,1082.2,2050.9,1992.9 -0.9709981163871092,1.1290773850502895,1.5707963267948966,740.8,870.9,870.7,1021.3,1951.3,1951.2 -0.9709903110674133,1.1290759700084432,1.7016960206944713,792.5,875.1,933.5,1039.7,1993.1,2051.7 -0.9709857512559185,1.1290732782843924,1.832595714594046,923.1,959.2,1086.7,1154.5,1824.9,1445.9 -0.971040779779549,1.129107714620107,1.9634954084936205,1161.1,1166.1,1384.1,1421.4,1238.5,1019.3 -0.9710579483438561,1.1291269222305944,2.0943951023931953,945.5,1293.8,1166.4,2030.4,969.8,842.6 -0.971048531859741,1.1291071039635505,2.2252947962927703,853.8,1121.0,1062.3,2014.3,830.6,771.8 -0.9710566961571716,1.129137138416169,2.356194490192345,841.6,1051.3,1051.9,1920.4,770.4,770.9 -0.9710539117947645,1.1291619079117918,2.4870941840919194,896.9,1062.4,1121.5,1972.1,772.2,831.3 -0.9710577096763675,1.1291515791336764,2.6179938779914944,1039.3,1167.4,1295.0,1742.4,842.5,970.4 -0.9710440246229101,1.1291676664976489,2.748893571891069,1323.1,1417.4,1637.4,1182.1,1022.0,1162.9 -0.9708356343683231,1.128913763255704,2.8797932657906435,1153.6,2004.5,2207.3,923.6,1086.0,958.3 -0.9708585923782103,1.1289021247702964,3.010692959690218,1039.7,2052.6,1994.1,793.4,934.5,875.7 -1.0709226782044978,1.8291046413202632,0.0,1720.8,1851.2,1851.0,41.0,971.1,970.7 -1.070969135561879,1.828940140281333,0.1308996938995747,1808.8,964.6,233.4,25.5,979.7,1038.9 -1.0711206774650126,1.8289881230546456,0.2617993877991494,2055.4,430.9,51.3,21.3,1074.1,1201.5 -1.0710485053203112,1.8289427263667826,0.39269908169872414,2544.8,251.1,31.8,32.0,1306.7,1527.5 -1.071038393520928,1.8289336260717495,0.5235987755982988,2079.6,161.2,33.5,72.2,1963.1,1976.8 -1.071050774671147,1.8289536681385519,0.6544984694978736,1868.7,106.6,47.5,231.4,1846.2,1787.1 -1.0710507609187936,1.8289591240056529,0.7853981633974483,1821.2,70.9,70.4,940.9,1751.9,1751.0 -1.0710504713948523,1.829000170863801,0.916297857297023,232.6,47.5,106.3,956.9,1786.6,1845.8 -1.071048790942256,1.8290088509109608,1.0471975511965976,73.3,34.0,161.3,1061.0,1974.4,2101.9 -1.0710504857650875,1.8290046725465685,1.1780972450961724,31.8,31.6,250.7,1301.2,2403.1,2555.2 -1.071014974307795,1.829037990197183,1.3089969389957472,21.2,51.0,430.2,1865.4,2220.0,2092.1 -1.0709928195875549,1.8290508261787848,1.4398966328953218,25.8,152.4,979.3,1806.3,1947.3,1888.8 -1.0710281577903256,1.8290428880488587,1.5707963267948966,41.0,970.9,970.7,1721.1,1851.1,1851.0 -1.0709862623279947,1.8290413941301171,1.7016960206944713,68.3,978.6,1036.8,1763.9,980.9,238.1 -1.0709510852125743,1.8290304353118687,1.832595714594046,114.0,1074.8,1253.3,1963.9,430.2,51.0 -1.0709803322027733,1.829049697557229,1.9634954084936205,192.5,1307.7,1528.9,2413.2,250.7,31.6 -1.070978234782179,1.8290491594848737,2.0943951023931953,349.9,1961.1,1974.7,2170.6,161.3,34.0 -1.070956507674918,1.8290071641138321,2.2252947962927703,831.3,1845.5,1786.6,1910.3,106.3,47.5 -1.0709564599573342,1.8290065636449409,2.356194490192345,941.5,1750.9,1751.3,1820.2,70.4,71.0 -1.0709543047639953,1.829014621965498,2.4870941840919194,1000.5,1786.9,1846.0,827.2,47.5,106.6 -1.0709640597291552,1.8289859894118181,2.6179938779914944,1240.8,1976.9,2104.2,347.9,33.5,161.2 -1.0709610691638707,1.8289860732329895,2.748893571891069,1464.4,2407.3,2549.8,192.3,32.3,252.3 -1.0708568571597787,1.8288475226019123,2.8797932657906435,1962.2,2218.3,2091.4,114.3,51.8,431.7 -1.0708815079732874,1.8288351989305889,3.010692959690218,1764.3,1949.0,1889.9,68.7,151.9,974.8 -1.0708701671160914,1.7285765660398418,0.0,1621.2,1850.9,1850.8,140.8,970.9,970.7 -1.0709494759945255,1.7293071512555453,0.1308996938995747,1705.2,1347.5,616.8,129.0,979.8,1038.9 -1.0709274838535117,1.7292997864399897,0.2617993877991494,1940.5,629.9,294.4,136.8,1074.1,1201.5 -1.0708943596861804,1.7292782200125627,0.39269908169872414,2431.2,392.0,172.9,173.6,1307.0,1527.6 -1.0708652483993506,1.7292477970600388,0.5235987755982988,2079.5,276.6,149.0,271.3,1844.5,1861.1 -1.0708550023845413,1.7292246202234054,0.6544984694978736,1868.8,210.0,151.0,617.1,1742.6,1683.5 -1.0708432970589699,1.7291783120507371,0.7853981633974483,1820.9,170.8,170.3,940.8,1651.8,1651.3 -1.070844670188036,1.7291681500620493,0.916297857297023,618.7,150.9,209.7,957.3,1683.5,1741.9 -1.0708569482882542,1.729130289976931,1.0471975511965976,272.6,149.4,276.7,1061.5,1859.6,1987.0 -1.0708823239169496,1.7290875634296106,1.1780972450961724,173.2,172.5,391.8,1301.8,2262.4,2481.2 -1.0708766756773425,1.7290920201336142,1.3089969389957472,136.6,250.1,629.4,1866.0,2220.0,2092.0 -1.0708882628945504,1.729085822569827,1.4398966328953218,129.1,541.8,979.1,1702.9,1947.4,1888.6 -1.0709588612279268,1.7290689436120694,1.5707963267948966,140.8,970.8,970.6,1621.3,1851.3,1851.3 -1.0709501831461992,1.729067596362854,1.7016960206944713,171.5,978.4,1036.9,1660.6,1368.8,540.9 -1.0709448615559578,1.7290645746075106,1.832595714594046,229.5,1074.9,1202.5,1848.3,672.7,249.9 -1.0709992664963954,1.7290985607966498,1.9634954084936205,334.0,1308.2,1529.0,2272.1,391.4,172.5 -1.071016012710254,1.7291172282811378,2.0943951023931953,549.4,1848.3,1859.5,2170.1,276.6,149.4 -1.0710064877810168,1.729096719295947,2.2252947962927703,957.4,1742.0,1683.5,1910.6,209.6,150.9 -1.0710120617600627,1.7291186002015586,2.356194490192345,941.4,1651.3,1651.7,1820.1,170.3,170.8 -1.0710092264611255,1.729148295564961,2.4870941840919194,1000.4,1683.6,1742.8,1211.3,150.9,210.0 -1.0710131446323012,1.7291385984525676,2.6179938779914944,1155.1,1861.1,1988.7,590.5,149.0,276.7 -1.0709999680645097,1.729154239494627,2.748893571891069,1464.7,2266.3,2486.5,333.4,173.6,393.7 -1.0708221596887033,1.7289130640046775,2.8797932657906435,1847.4,2219.3,2091.5,229.9,251.0,630.4 -1.0708485170842494,1.728899636086561,3.010692959690218,1660.9,1949.3,1890.3,172.3,537.9,979.0 -1.0708348340002358,1.6286388978530923,0.0,1521.0,1851.2,1850.9,240.8,970.8,971.0 -1.0709370648212722,1.629317979303523,0.1308996938995747,1601.6,1731.4,915.9,232.6,979.5,1038.9 -1.0709184255319208,1.6293116168340065,0.2617993877991494,1824.9,829.2,449.9,252.4,1074.2,1202.0 -1.070884976588079,1.6292898040945272,0.39269908169872414,2289.5,533.1,314.1,315.2,1307.0,1527.7 -1.070854841469513,1.629258219727942,0.5235987755982988,2079.4,392.3,264.6,470.6,1873.2,1745.2 -1.0708437875140548,1.6292334438754212,0.6544984694978736,1868.5,313.5,254.5,1000.3,1638.9,1580.0 -1.0708317152599958,1.6291853777979872,0.7853981633974483,1821.4,270.8,270.2,940.8,1551.8,1551.3 -1.0708331746436466,1.6291735288336562,0.916297857297023,1005.8,254.4,313.2,957.0,1579.9,1638.9 -1.070845937208231,1.6291341591977986,1.0471975511965976,472.1,264.9,392.3,1086.8,1743.8,1871.4 -1.0708721041917473,1.6290901950830463,1.1780972450961724,315.0,313.7,532.9,1301.5,2121.5,2340.5 -1.0708674374296137,1.6290937341818583,1.3089969389957472,252.2,449.2,828.8,1825.3,2219.7,2091.8 -1.070880120966206,1.6290869371216965,1.4398966328953218,232.5,931.6,979.0,1599.4,1947.4,1888.9 -1.0709518561625624,1.6290697776796912,1.5707963267948966,240.8,970.7,970.7,1521.3,1851.5,1851.0 -1.0709442460907912,1.6290684353511617,1.7016960206944713,275.0,978.6,1037.1,1557.3,1758.0,930.2 -1.0709398857165726,1.629065662161453,1.832595714594046,345.1,1241.2,1202.6,1732.8,828.1,449.0 -1.0709951069306485,1.6291001086375536,1.9634954084936205,475.8,1308.0,1529.1,2130.4,532.6,313.6 -1.0710124751743018,1.6291193791020198,2.0943951023931953,749.2,1845.6,1743.9,2170.2,392.1,264.9 -1.0710033663789105,1.6290995512730615,2.2252947962927703,957.3,1638.6,1580.0,1910.6,313.1,254.3 -1.071009150210779,1.6291221535007372,2.356194490192345,941.5,1551.5,1551.8,1820.6,270.3,270.8 -1.0710063230803293,1.629152552990351,2.4870941840919194,1000.4,1580.2,1639.4,1596.6,254.5,313.6 -1.0710100777643166,1.6291434833017917,2.6179938779914944,1155.2,1745.6,1873.9,745.9,264.6,392.4 -1.0709965892552613,1.6291596491340097,2.748893571891069,1464.7,2125.3,2344.6,474.7,315.0,535.1 -1.070818666636436,1.6289163904715387,2.8797932657906435,1731.8,2219.0,2091.7,345.6,450.4,829.8 -1.0708453118358638,1.628902800916883,3.010692959690218,1557.3,1948.8,1890.5,275.8,924.2,979.0 -1.0708317106658714,1.5286420593647456,0.0,1421.1,1851.4,1851.1,340.8,971.0,971.0 -1.0709358343367907,1.5293188042768242,0.1308996938995747,1498.1,1891.4,1299.8,336.2,979.7,1038.8 -1.0709174825982375,1.5293125279598216,0.2617993877991494,1709.3,1028.7,693.1,368.0,1074.0,1201.6 -1.0708840142775728,1.5292906989529262,0.39269908169872414,2148.1,674.4,455.2,456.9,1306.9,1527.8 -1.0708538004673356,1.5292590235652317,0.5235987755982988,2079.4,507.7,380.2,669.8,1757.2,1629.8 -1.0708426833818274,1.5292341206402282,0.6544984694978736,1868.4,417.1,358.1,1000.4,1535.5,1476.6 -1.0708305837819714,1.5291859153429486,0.7853981633974483,1821.4,370.7,370.3,940.8,1451.7,1451.2 -1.0708320511435194,1.5291739325465121,0.916297857297023,1393.1,357.9,416.7,957.0,1476.7,1535.3 -1.070844853253697,1.5291344435470784,1.0471975511965976,671.9,380.5,507.8,1061.4,1628.9,1755.8 -1.070871084183621,1.5290903827998394,1.1780972450961724,456.6,454.8,674.0,1301.4,1980.5,2199.5 -1.0708664955768337,1.529093850206316,1.3089969389957472,367.9,648.7,1028.2,1709.5,2219.5,2091.9 -1.070879265790917,1.5290870058447812,1.4398966328953218,336.0,1037.6,979.2,1496.1,1947.3,1889.2 -1.0709510906837483,1.5290698254525752,1.5707963267948966,340.8,971.0,970.6,1421.2,1851.2,1851.1 -1.0709435645784533,1.5290684837928343,1.7016960206944713,378.5,978.7,1037.3,1453.9,1889.8,1319.6 -1.0709392800061035,1.5290657291530843,1.832595714594046,460.7,1074.8,1202.6,1617.3,1027.3,648.3 -1.0709945656749795,1.529100211431751,1.9634954084936205,617.5,1308.1,1529.0,1988.4,673.7,454.7 -1.0710119832248706,1.5291195292396218,2.0943951023931953,948.7,1755.6,1628.3,2170.1,507.7,380.5 -1.0710029084132344,1.5290997542366347,2.2252947962927703,957.2,1535.1,1476.3,1910.5,416.6,357.9 -1.0710087102310095,1.5291224128968843,2.356194490192345,941.6,1451.2,1451.7,1820.3,370.2,370.8 -1.0710058846674504,1.5291528684649616,2.4870941840919194,1000.5,1476.6,1535.8,1868.8,358.0,417.2 -1.0710096280014483,1.5291438487375089,2.6179938779914944,1155.2,1630.2,1757.6,944.7,380.2,507.9 -1.0709961149908178,1.529160057270323,2.748893571891069,1464.7,1983.2,2203.5,616.2,456.5,676.4 -1.0708183217125005,1.5289166578698268,2.8797932657906435,1616.4,2219.5,2091.5,461.1,649.7,1028.9 -1.070845009990863,1.5289030447998155,3.010692959690218,1454.0,1949.1,1890.8,379.3,1038.2,979.3 -1.070831425401985,1.4286423043226462,0.0,1321.4,1851.1,1851.0,440.9,971.0,970.9 -1.0709357163617754,1.42931887491411,0.1308996938995747,1394.6,1891.1,1684.0,439.8,979.5,1038.9 -1.0709173890075379,1.4293126059058663,0.2617993877991494,1593.6,1228.0,848.6,483.6,1074.0,1201.8 -1.0708839184297687,1.4292907751101738,0.39269908169872414,2006.2,815.6,596.4,598.7,1307.1,1635.2 -1.0708536973701337,1.4292590913107155,0.5235987755982988,2079.6,623.4,495.8,869.2,1642.1,1514.4 -1.0708425745216599,1.4292341767554457,0.6544984694978736,1868.6,520.4,461.6,1000.3,1432.0,1372.9 -1.0708304724969897,1.4291859587974023,0.7853981633974483,1821.0,470.8,470.2,940.7,1351.6,1351.3 -1.070831940620557,1.4291739638206966,0.916297857297023,1779.9,461.4,520.3,957.1,1372.8,1431.9 -1.0708447463694508,1.429134463982345,1.0471975511965976,871.3,496.0,623.3,1061.3,1513.3,1640.3 -1.0708709831708323,1.4290903945304771,1.1780972450961724,598.3,596.0,815.0,1301.5,1838.7,2058.6 -1.0708664016945604,1.4290938554730528,1.3089969389957472,483.4,848.0,1073.9,1594.3,2360.1,2092.1 -1.0708791797829325,1.4290870068274717,1.4398966328953218,439.4,1037.4,979.3,1392.5,1947.4,1889.1 -1.0709510128022206,1.4290698246200164,1.5707963267948966,440.8,970.8,970.8,1321.3,1851.7,1851.1 -1.0709434942947156,1.4290684830630132,1.7016960206944713,481.9,978.5,1037.1,1350.3,1890.1,1709.0 -1.070939216585321,1.4290657300739578,1.832595714594046,576.3,1074.8,1202.6,1501.8,1226.4,847.5 -1.0709945080702126,1.4291002155880435,1.9634954084936205,759.2,1308.0,1635.0,1846.8,814.8,595.8 -1.0710119300674297,1.4291195376889014,2.0943951023931953,1060.7,1639.9,1512.7,2170.5,623.0,495.9 -1.0710028583671412,1.4290997674330863,2.2252947962927703,957.3,1431.4,1372.6,1910.9,520.1,461.4 -1.071008661863734,1.4291224311698492,2.356194490192345,941.4,1351.4,1351.6,1820.5,470.3,470.8 -1.0710058364731017,1.429152891824585,2.4870941840919194,1000.5,1372.9,1432.5,1868.7,461.6,520.7 -1.0710095788552028,1.4291438766275921,2.6179938779914944,1155.1,1514.7,1642.3,1144.1,495.9,623.5 -1.0709960636407805,1.4291600890783112,2.748893571891069,1509.7,1841.8,2062.0,757.7,598.0,818.2 -1.0708182883082324,1.428916680389156,2.8797932657906435,1500.9,2359.4,2091.8,576.8,849.0,1074.1 -1.0708449816076706,1.428903064602971,3.010692959690218,1350.5,1949.1,1890.4,482.8,1038.2,979.2 -1.0708313991860094,1.3286423244791883,0.0,1221.3,1851.2,1851.0,540.9,971.1,970.9 -1.0709357063717644,1.3293188818807762,0.1308996938995747,1290.9,1891.7,1950.6,543.4,979.6,1039.1 -1.070917379887655,1.3293126131408854,0.2617993877991494,1478.1,1427.4,1048.0,599.2,1073.9,1201.6 -1.070883908227314,1.3292907816575688,0.39269908169872414,1864.1,956.9,737.6,740.2,1306.7,1527.7 -1.070853685912996,1.329259096477303,0.5235987755982988,2079.3,739.0,611.5,1068.5,1525.9,1398.4 -1.070842562163742,1.3292341801955518,0.6544984694978736,1868.4,624.1,565.1,1000.4,1328.5,1269.6 -1.0708304597545724,1.329185960404021,0.7853981633974483,1821.1,570.8,570.3,940.8,1251.7,1251.2 -1.0708319279622989,1.3291739636646571,0.916297857297023,1911.2,565.0,623.8,979.8,1269.5,1328.0 -1.0708447342175142,1.3291344622602812,1.0471975511965976,1071.1,611.6,739.0,1061.4,1397.2,1524.8 -1.0708459009936178,1.3291305277917036,1.1780972450961724,740.0,737.2,956.2,1301.5,1697.7,1917.0 -1.0708649986582248,1.3291119455630724,1.3089969389957472,599.0,1047.7,1073.9,1478.4,2219.6,2092.1 -1.0708841460345078,1.3291017285972297,1.4398966328953218,542.9,1037.4,979.1,1289.0,1947.2,1889.0 -1.0709552781067149,1.3290847233467864,1.5707963267948966,540.7,970.9,970.7,1221.2,1851.5,1851.0 -1.0709447717852238,1.3290832914822897,1.7016960206944713,585.5,978.5,1037.1,1246.9,1889.7,1948.5 -1.0709371038832614,1.3290795172056735,1.832595714594046,691.9,1075.0,1202.6,1386.0,1425.6,1046.6 -1.0709893594901423,1.3291121050343295,1.9634954084936205,900.8,1308.2,1529.0,1705.2,956.0,736.8 -1.0710044832976153,1.329128963411163,2.0943951023931953,1060.8,1524.4,1397.2,2170.2,738.8,611.4 -1.07099394266007,1.3291064482244874,2.2252947962927703,957.3,1328.2,1269.1,1910.4,623.5,564.8 -1.070999086955456,1.329126269408288,2.356194490192345,941.4,1251.0,1251.6,1820.5,570.2,570.8 -1.0709963576064936,1.329154018197704,2.4870941840919194,1000.5,1269.5,1328.5,1869.1,565.2,624.2 -1.0710008254425443,1.32914262088596,2.6179938779914944,1155.1,1399.1,1526.5,1343.4,611.5,739.3 -1.0709594139534553,1.3292042376161617,2.748893571891069,1527.0,1700.9,1920.7,899.1,739.3,959.5 -1.0708279818268338,1.328954401935591,2.8797932657906435,1385.0,2219.2,2091.7,692.2,1048.5,1074.0 -1.0708608917150366,1.3289374101048996,3.010692959690218,1247.0,1949.3,1890.2,586.4,1038.0,978.9 -1.070843949555975,1.228669781975495,0.0,1121.0,1851.2,1851.2,640.7,970.9,971.0 -1.0709161377959084,1.2293017226338083,0.1308996938995747,1187.3,1891.0,1950.6,646.9,979.4,1038.9 -1.070909947597996,1.2292992399430742,0.2617993877991494,1362.6,1626.9,1247.6,714.6,1073.9,1201.8 -1.070880385886662,1.2292799002762278,0.39269908169872414,1722.7,1098.0,878.7,882.0,1307.1,1525.3 -1.070851492480802,1.2292496763649519,0.5235987755982988,2220.2,854.7,727.2,1154.3,1410.5,1283.0 -1.0708408920814396,1.2292257303317566,0.6544984694978736,1868.7,727.7,668.7,1000.3,1224.9,1165.7 -1.0708289596439988,1.2291782524246684,0.7853981633974483,1821.3,670.8,670.3,940.8,1151.7,1151.1 -1.070830438798183,1.2291669021643037,0.916297857297023,1910.9,668.5,727.2,957.0,1165.8,1224.6 -1.0708431141765606,1.229127967394823,1.0471975511965976,1270.6,727.1,854.4,1061.1,1281.8,1409.4 -1.0708690970790429,1.2290843448368216,1.1780972450961724,881.8,878.2,1097.3,1301.7,1556.6,1776.1 -1.070864199208179,1.229088169394164,1.3089969389957472,714.7,1201.4,1074.0,1362.9,2204.0,2092.1 -1.0708766070948663,1.2290816029464993,1.4398966328953218,646.2,1037.6,979.1,1185.6,1947.4,1889.0 -1.070948029779244,1.2290645386142782,1.5707963267948966,640.8,971.1,970.6,1121.1,1851.2,1851.2 -1.0708958952163097,1.2290584333260814,1.7016960206944713,688.9,978.6,1037.1,1143.2,1889.9,1948.2 -1.07092066867586,1.2290646948659467,1.832595714594046,807.7,1074.9,1202.6,1270.2,1625.0,1245.9 -1.0709819688429734,1.2291030120169428,1.9634954084936205,1042.7,1308.1,1525.1,1563.1,1097.1,878.2 -1.0709992127418726,1.2291221532615633,2.0943951023931953,1060.7,1409.0,1281.7,2170.4,854.2,727.0 -1.0709889895479496,1.2291002702974465,2.2252947962927703,957.4,1224.5,1165.6,1910.5,727.1,668.4 -1.0709941225058262,1.2291200377216709,2.356194490192345,941.6,1151.3,1151.6,1820.4,670.3,670.8 -1.0709914401783565,1.2291474907222413,2.4870941840919194,1000.5,1166.0,1224.9,1868.4,668.7,727.7 -1.070996022594355,1.2291357923433612,2.6179938779914944,1155.0,1283.3,1411.1,1542.4,727.1,854.9 -1.0709839726849588,1.2291497668294487,2.748893571891069,1464.6,1559.2,1779.3,1040.5,880.8,1100.8 -1.0708162266976,1.2289162885956373,2.8797932657906435,1269.5,2203.9,2091.9,807.9,1201.6,1074.1 -1.0708431416385507,1.2289025589939913,3.010692959690218,1143.3,1949.6,1890.2,689.9,1038.1,979.2 -1.0708298142981458,1.1286418733526846,0.0,1021.0,1851.0,1851.0,740.9,970.9,970.8 -1.0709349990847699,1.1293192462436887,0.1308996938995747,1083.7,1891.3,1950.4,750.5,979.5,1038.9 -1.0709168074699211,1.1293130180303619,0.2617993877991494,1246.8,1826.3,1446.7,830.2,1074.2,1201.6 -1.0708833273207787,1.1292911788860507,0.39269908169872414,1581.0,1239.0,1019.8,1023.5,1431.2,1415.3 -1.070853069136757,1.129495455695058,0.5235987755982988,2079.2,995.6,842.7,1154.2,1295.0,1167.3 -1.0711878504408847,1.1289942754963564,0.6544984694978736,1868.4,831.1,772.2,1000.1,1121.3,1062.3 -1.071188266982766,1.12900237473825,0.7853981633974483,1820.9,770.9,770.5,940.7,1051.6,1051.2 -1.0711869844354818,1.1290501401380952,0.916297857297023,1911.1,772.2,831.0,957.2,1062.1,1121.2 -1.0711823111740202,1.1290658785539733,1.0471975511965976,1469.6,842.9,970.3,1061.4,1166.4,1293.7 -1.071179471413266,1.1290678238517105,1.1780972450961724,1023.4,1020.0,1239.4,1407.9,1415.8,1634.7 -1.0711383844064635,1.1291053527951402,1.3089969389957472,830.2,1201.1,1073.7,1246.9,2005.5,2142.4 -1.0711102330637101,1.129120435208442,1.4398966328953218,750.1,1037.5,979.2,1081.9,1947.1,1888.5 -1.0711396877809694,1.1291135318728482,1.5707963267948966,741.0,971.2,970.9,1021.1,1851.3,1851.0 -1.0710924365220158,1.1291115628102681,1.7016960206944713,792.7,978.7,1037.2,1039.8,1890.2,1948.2 -1.0710526505488174,1.1290988001241917,1.832595714594046,923.5,1075.1,1203.2,1154.7,1823.6,1444.9 -1.07107799520913,1.1291156942824239,1.9634954084936205,1184.9,1430.0,1414.8,1421.9,1237.9,1019.1 -1.0710727980397823,1.1291123864591586,2.0943951023931953,1060.8,1292.8,1166.0,2031.7,969.7,842.6 -1.0710489734787938,1.1290670840735477,2.2252947962927703,957.3,1120.8,1062.0,1910.6,830.7,772.0 -1.0710476393473083,1.129063005183899,2.356194490192345,941.7,1051.3,1051.5,1820.1,770.2,771.0 -1.0710448423436474,1.129067714281057,2.4870941840919194,1000.7,1062.3,1121.4,1868.7,772.3,831.4 -1.0710549664788216,1.12903574870235,2.6179938779914944,1155.5,1167.7,1295.4,1740.9,843.0,970.9 -1.0710527913529129,1.1290329370948204,2.748893571891069,1417.0,1418.1,1638.0,1181.6,1022.7,1242.8 -1.0710761188018214,1.1290116599202495,2.8797932657906435,1153.2,2007.0,2144.0,922.9,1201.2,1073.8 -1.0710833590728606,1.1290076401043758,3.010692959690218,1039.7,1948.8,1889.8,793.2,1038.0,979.1 -1.1711187295509122,1.8291439077840985,0.0,1721.2,1750.5,1750.7,40.9,1071.0,1071.2 -1.171039060743734,1.8289412772321305,0.1308996938995747,1808.5,964.8,148.9,25.5,1083.3,1142.5 -1.1710389732932625,1.8289414042081946,0.2617993877991494,2055.6,430.9,51.3,21.3,1189.7,1317.2 -1.1710375495093697,1.8289406873010015,0.39269908169872414,2404.2,251.1,31.8,32.0,1448.1,1668.7 -1.1710415224586102,1.8289470826323186,0.5235987755982988,1963.9,161.2,33.5,72.2,2042.9,1976.3 -1.1710542883149557,1.8289682285559152,0.6544984694978736,1765.6,106.6,47.5,231.4,1846.3,1786.8 -1.1710529735761155,1.828968941162789,0.7853981633974483,1720.9,70.9,70.4,1040.9,1751.9,1751.1 -1.1710526943833577,1.8290035564142981,0.916297857297023,232.6,47.5,106.3,1060.6,1786.6,1845.7 -1.1710527705012563,1.82900582607415,1.0471975511965976,117.3,34.0,161.3,1176.7,1975.0,2102.0 -1.17105770498672,1.8289961483134292,1.1780972450961724,31.8,31.6,250.7,1442.3,2402.7,2449.8 -1.1710264175881107,1.8290253149374398,1.3089969389957472,21.2,51.0,430.3,2056.4,2104.0,1976.3 -1.1710091057186693,1.8290354461766662,1.4398966328953218,25.8,152.4,981.0,1806.5,1843.9,1785.2 -1.1710495216305856,1.8290262855990904,1.5707963267948966,40.9,1071.1,1070.6,1721.3,1751.3,1751.3 -1.1710123895139146,1.8290249392005304,1.7016960206944713,68.3,1082.2,1140.5,1763.9,980.9,152.4 -1.1709814341222424,1.829015297303,1.832595714594046,114.0,1190.5,1318.1,1963.4,430.2,51.0 -1.1710141584102425,1.8290368358472193,1.9634954084936205,192.5,1449.8,1670.4,2413.2,250.8,31.6 -1.1710145700344554,1.8290391700591002,2.0943951023931953,349.9,2048.1,1974.8,2054.5,161.3,34.0 -1.1709943520048192,1.8290003158873414,2.2252947962927703,831.3,1845.2,1786.6,1806.8,106.3,47.5 -1.1709948703134614,1.829002908596,2.356194490192345,1041.6,1751.1,1751.8,1720.3,70.4,70.9 -1.1709924322110392,1.8290139496038063,2.4870941840919194,1104.1,1787.2,1846.0,827.2,47.5,106.6 -1.1710012306147983,1.8289878723329416,2.6179938779914944,1295.9,1977.0,2104.5,347.9,33.5,161.2 -1.1709967741783072,1.8289900103280696,2.748893571891069,1605.9,2407.1,2454.7,192.3,32.3,252.3 -1.1708711700391476,1.8288400633090058,2.8797932657906435,1962.5,2102.6,1975.0,114.3,51.9,431.8 -1.1708939639459865,1.8288287333221513,3.010692959690218,1764.4,1845.9,1786.5,68.7,152.0,975.3 -1.1708816793115264,1.7285700433381832,0.0,1621.5,1751.1,1751.0,140.8,1070.9,1071.0 -1.17095455326352,1.7293045722118543,0.1308996938995747,1705.2,1347.6,532.4,129.1,1083.3,1142.5 -1.1709315311733004,1.7292968991030362,0.2617993877991494,1940.8,630.0,250.5,136.8,1189.7,1317.2 -1.1708984348508438,1.7292753674059091,0.39269908169872414,2403.4,392.2,172.9,173.5,1448.6,1669.2 -1.1708695611356823,1.72924522839204,0.5235987755982988,1963.7,276.7,149.0,271.3,1988.7,1861.1 -1.1708595110469415,1.7292224568868244,0.6544984694978736,1765.2,210.0,151.0,617.0,1742.7,1683.3 -1.1708478845010415,1.7291765908592418,0.7853981633974483,1721.3,170.8,170.3,1040.6,1651.7,1651.4 -1.1708492269369701,1.729166854798471,0.916297857297023,618.9,150.9,209.7,1060.6,1683.1,1742.1 -1.1708613741272553,1.7291293729280435,1.0471975511965976,272.6,149.4,276.7,1319.7,1859.6,1987.1 -1.170886541104234,1.7290869472297143,1.1780972450961724,173.3,172.6,391.7,1442.9,2262.7,2413.2 -1.170880643113854,1.729091627401875,1.3089969389957472,136.6,250.1,629.5,1940.8,2104.0,1976.3 -1.170891955995091,1.7290855796714606,1.4398966328953218,129.0,541.7,1082.6,1702.8,1844.2,1785.7 -1.1709622708964578,1.7290687622680387,1.5707963267948966,140.8,1071.0,1070.6,1621.3,1751.2,1751.0 -1.1709533288623115,1.7290674124124428,1.7016960206944713,171.5,1082.1,1140.5,1660.7,1368.9,541.0 -1.1709477676846696,1.7290643375445143,1.832595714594046,229.5,1190.4,1318.2,1848.3,629.1,249.8 -1.1710019680075379,1.7290982133396786,1.9634954084936205,334.0,1449.8,1670.7,2272.0,391.5,203.5 -1.171018556618354,1.7291167325017038,2.0943951023931953,549.4,1986.6,1859.2,2054.8,276.6,149.3 -1.171008918466525,1.729096060809749,2.2252947962927703,1060.8,1741.7,1683.1,1807.2,209.6,150.9 -1.1710144286521738,1.7291177652046428,2.356194490192345,1041.8,1650.9,1651.7,1720.3,170.2,170.8 -1.171011584012625,1.729147280438665,2.4870941840919194,1104.0,1683.7,1742.8,1211.4,150.9,210.1 -1.1710155311075088,1.7291374229436427,2.6179938779914944,1270.7,1861.4,1988.9,546.7,149.0,276.7 -1.1710024318847412,1.729152922840767,2.748893571891069,1606.2,2266.7,2407.8,333.5,173.6,393.7 -1.1708235922876042,1.7289121456820538,2.8797932657906435,1847.6,2103.3,1975.9,229.9,251.0,630.6 -1.1708497217858904,1.7288988405992503,3.010692959690218,1661.1,1845.6,1786.9,172.3,537.9,1082.9 -1.1708359448577976,1.6286380984828424,0.0,1521.2,1751.0,1751.0,240.8,1071.0,1070.9 -1.1709375668348723,1.629317732862421,0.1308996938995747,1601.7,1787.4,915.9,232.6,1083.3,1142.4 -1.1709188175194993,1.629311337521083,0.2617993877991494,1824.9,829.2,449.9,252.4,1189.6,1317.5 -1.170885364442221,1.6292895240558107,0.39269908169872414,2289.7,533.4,314.0,315.2,1448.5,1669.3 -1.1708552476405834,1.6292579623423022,0.5235987755982988,1963.6,392.2,264.7,470.6,1872.9,1745.3 -1.1708442096904932,1.6292332204714441,0.6544984694978736,1765.0,313.6,254.5,1002.8,1639.2,1579.8 -1.1708321437556735,1.6291851918221316,0.7853981633974483,1721.2,270.8,270.3,1040.9,1551.8,1551.1 -1.1708336002860695,1.629173378929365,0.916297857297023,1005.8,254.4,313.2,1060.7,1579.8,1638.6 -1.1708463515609833,1.6291340413466697,1.0471975511965976,472.2,264.9,392.3,1176.9,1744.2,1871.5 -1.1708725007349285,1.6290901026994713,1.1780972450961724,314.9,313.7,532.8,1442.6,2121.1,2340.1 -1.1708678128571208,1.6290936607025832,1.3089969389957472,252.3,449.4,828.8,1825.2,2104.1,1976.7 -1.1708804732157483,1.629086876442974,1.4398966328953218,232.5,931.9,1082.5,1599.6,1843.6,1785.1 -1.1709521843247195,1.6290697223776758,1.5707963267948966,240.8,1070.8,1070.6,1521.2,1751.3,1750.8 -1.1709445519002197,1.6290683800955361,1.7016960206944713,275.0,1082.0,1140.4,1557.0,1786.7,930.3 -1.1709401711249714,1.6290656027590602,1.832595714594046,345.0,1241.4,1318.3,1732.8,828.0,449.0 -1.1709953746612496,1.6291000400796127,1.9634954084936205,475.8,1449.5,1671.1,2130.3,532.6,313.6 -1.1710127291727475,1.6291192980923768,2.0943951023931953,749.1,1871.2,1743.6,2054.7,392.1,264.9 -1.1710036103876988,1.6290994565917267,2.2252947962927703,1061.0,1638.7,1580.0,1807.2,313.1,254.4 -1.1710093884292843,1.629122043736825,2.356194490192345,1041.5,1551.2,1551.9,1720.4,270.2,270.8 -1.1710065602717876,1.62915242764824,2.4870941840919194,1104.1,1580.2,1639.3,1596.9,254.5,313.6 -1.171010317247385,1.6291433440967351,2.6179938779914944,1270.7,1745.6,1873.6,745.9,264.6,392.4 -1.1709968354153697,1.6291594976364456,2.748893571891069,1605.9,2125.1,2345.2,474.9,315.0,535.1 -1.170818811219442,1.6289162912311457,2.8797932657906435,1732.0,2103.6,1976.0,345.5,450.3,829.8 -1.1708454350242123,1.628902713183247,3.010692959690218,1557.4,1845.9,1787.0,275.8,924.3,1082.8 -1.1708318268094993,1.5286419738124937,0.0,1421.2,1751.0,1750.9,340.8,1071.0,1070.8 -1.1709358977852231,1.5293187826859673,0.1308996938995747,1497.9,1787.5,1300.0,336.2,1083.2,1142.6 -1.1709175242206116,1.5293124998847945,0.2617993877991494,1709.4,1028.8,649.2,368.0,1189.9,1317.3 -1.1708840486822794,1.529290666731934,0.39269908169872414,2147.7,674.3,455.2,457.0,1448.6,1776.7 -1.1708538321552242,1.529258988922303,0.5235987755982988,1963.7,507.8,380.2,670.0,1757.0,1629.7 -1.170842713820923,1.529234084351661,0.6544984694978736,1764.7,417.1,358.1,1103.9,1535.8,1476.5 -1.1708306135930227,1.52918587765805,0.7853981633974483,1721.1,370.8,370.3,1040.8,1451.6,1451.3 -1.1708320807747123,1.5291738935368697,0.916297857297023,1392.9,357.9,416.8,1060.8,1476.3,1535.2 -1.1708448830702223,1.5291344033862897,1.0471975511965976,671.6,380.4,507.9,1177.0,1628.6,1755.7 -1.170871114495181,1.5290903416898138,1.1780972450961724,456.5,454.9,674.0,1442.9,1980.0,2199.5 -1.1708665267026228,1.5290938083761574,1.3089969389957472,367.8,648.7,1028.0,1710.0,2104.2,1976.2 -1.1708792978296425,1.5290869636682605,1.4398966328953218,335.9,1141.2,1082.7,1496.0,1844.0,1785.6 -1.1709511235121908,1.5290697832589524,1.5707963267948966,340.7,1070.9,1070.7,1421.5,1751.5,1751.0 -1.1709435982309673,1.529068441895879,1.7016960206944713,378.5,1082.1,1140.6,1453.8,1786.4,1319.8 -1.1708985069803006,1.52920622391977,1.832595714594046,460.8,1190.4,1318.2,1616.9,1027.7,648.8 -1.1711008669637313,1.52933557562837,1.9634954084936205,617.7,1449.3,1776.1,1987.9,674.1,455.0 -1.1709879139437855,1.5292147480573897,2.0943951023931953,948.6,1755.4,1628.2,2054.9,507.9,380.5 -1.1709434175666558,1.5291287027144813,2.2252947962927703,1061.0,1535.2,1476.2,1807.3,416.7,357.9 -1.170940772831236,1.5291150779391822,2.356194490192345,1041.7,1451.1,1451.6,1720.3,370.3,370.8 -1.1709388717694118,1.529121448287927,2.4870941840919194,1104.0,1476.5,1535.8,1765.0,358.1,417.2 -1.1709481019990116,1.5290945670956113,2.6179938779914944,1270.5,1629.9,1757.6,945.3,380.2,508.0 -1.1709434532650533,1.5290969577579883,2.748893571891069,1651.5,1983.3,2203.1,616.4,456.5,676.3 -1.17081762272076,1.5289063223712953,2.8797932657906435,1616.2,2103.5,1975.7,461.1,649.9,1029.2 -1.1708450098866703,1.5288923876118266,3.010692959690218,1453.8,1845.7,1786.9,379.4,1141.6,1082.6 -1.1708323190396084,1.4286314814898242,0.0,1321.3,1751.2,1751.2,440.8,1070.9,1071.0 -1.1709351688777418,1.4293180430810102,0.1308996938995747,1394.7,1787.6,1683.6,439.7,1083.0,1142.5 -1.1709166433150966,1.4293117140741205,0.2617993877991494,1593.6,1227.8,848.7,483.6,1189.8,1317.1 -1.170883205120493,1.4292899014211522,0.39269908169872414,2006.0,815.6,596.4,598.6,1448.5,1669.5 -1.1708530623620252,1.4292582954044695,0.5235987755982988,1963.8,623.3,495.9,869.4,1641.8,1513.9 -1.170841998959406,1.4292334851478574,0.6544984694978736,1765.0,520.7,461.5,1104.1,1432.0,1373.0 -1.1708299330501344,1.429185387647899,0.7853981633974483,1721.3,470.9,470.2,1041.0,1351.8,1351.4 -1.1708314022890633,1.429173507313696,0.916297857297023,1807.4,461.4,520.3,1060.6,1373.1,1431.7 -1.1708441818176887,1.4291341127136787,1.0471975511965976,871.2,495.9,623.3,1176.9,1512.9,1640.2 -1.1708703719132203,1.4290901375636151,1.1780972450961724,598.3,596.1,815.2,1442.7,1839.1,2057.6 -1.1708657251132546,1.429093667821713,1.3089969389957472,483.4,848.1,1189.5,1593.8,2103.7,1976.2 -1.1708784263563847,1.4290868610735523,1.4398966328953218,439.4,1140.8,1082.6,1392.5,1843.7,1785.8 -1.1709501786730312,1.4290697061438116,1.5707963267948966,440.8,1070.8,1070.8,1321.2,1751.4,1751.3 -1.1709425826047402,1.4290683657329133,1.7016960206944713,482.0,1082.1,1140.3,1350.4,1786.4,1709.0 -1.1709382367603678,1.4290655878303293,1.832595714594046,576.4,1190.6,1318.3,1501.4,1226.4,847.5 -1.1709934708838947,1.429100037336262,1.9634954084936205,759.3,1449.6,1670.7,1846.7,814.7,595.7 -1.1710108503278474,1.429119315405059,2.0943951023931953,1148.7,1639.9,1512.8,2055.0,623.2,495.9 -1.1710017566564515,1.4290994910604042,2.2252947962927703,1060.8,1431.5,1372.8,1807.1,520.1,461.4 -1.171007554413382,1.4291221007026313,2.356194490192345,1041.6,1351.1,1352.0,1720.3,470.3,470.9 -1.171004734002983,1.4291525150208835,2.4870941840919194,1103.9,1372.9,1432.2,1765.4,461.6,520.7 -1.1710084976906512,1.4291434582532743,2.6179938779914944,1270.5,1514.8,1642.0,1143.9,495.9,623.6 -1.1709950047297677,1.4291596417653578,2.748893571891069,1668.7,1842.2,2062.4,757.5,598.0,818.0 -1.1708181073019406,1.4289164874628293,2.8797932657906435,1500.7,2103.8,1975.8,576.7,849.1,1189.6 -1.1708449122647113,1.4289028132849602,3.010692959690218,1350.5,1845.7,1786.6,482.8,1141.7,1082.9 -1.1708313879604313,1.3286420804856132,0.0,1221.4,1751.0,1750.6,540.8,1070.9,1070.9 -1.170935672110168,1.3293188565499716,0.1308996938995747,1291.0,1787.5,1847.0,543.3,1083.1,1142.7 -1.1709173314473904,1.329312583591864,0.2617993877991494,1478.2,1427.5,1047.9,599.2,1189.6,1317.2 -1.1708838545507545,1.329290748885808,0.39269908169872414,1864.4,956.8,737.6,740.3,1448.8,1666.5 -1.1708536301685817,1.3292590613262307,0.5235987755982988,1963.7,739.1,611.5,1068.5,1526.1,1398.6 -1.1708425053392382,1.3292341428966472,0.6544984694978736,1764.9,624.1,565.2,1104.0,1328.3,1269.4 -1.1708304029003793,1.3291859213851591,0.7853981633974483,1721.3,570.7,570.4,1040.8,1251.5,1251.3 -1.1708318713754222,1.329173922924542,0.916297857297023,1807.5,564.8,623.8,1060.7,1269.5,1327.9 -1.170844678339153,1.3291344201581574,1.0471975511965976,1071.1,611.6,739.0,1176.8,1397.3,1524.6 -1.1708709170906304,1.329090348795315,1.1780972450961724,739.9,737.4,956.2,1442.5,1697.5,1917.4 -1.1708683170533394,1.3290917643425766,1.3089969389957472,599.0,1047.6,1189.4,1478.5,2160.7,1976.5 -1.170879452136626,1.3290857744570015,1.4398966328953218,542.9,1141.1,1082.5,1288.9,1843.9,1785.3 -1.1709509513988254,1.3290686737096595,1.5707963267948966,540.7,1070.9,1070.7,1221.4,1751.6,1750.7 -1.170943486242244,1.3290673353778528,1.7016960206944713,585.4,1082.1,1140.5,1246.8,1786.7,1844.8 -1.170939375602164,1.3290646342306172,1.832595714594046,692.1,1190.5,1318.4,1386.0,1425.5,1046.7 -1.170994840648667,1.3290992299571531,1.9634954084936205,900.8,1449.6,1666.0,1704.9,955.9,736.9 -1.1710123992663086,1.3291187004625211,2.0943951023931953,1176.3,1524.4,1397.0,2186.5,738.7,611.4 -1.1710034159167821,1.3290990971964503,2.2252947962927703,1060.8,1328.1,1269.3,1806.9,623.6,564.8 -1.1710092590756858,1.329121934142985,2.356194490192345,1041.4,1251.1,1251.9,1720.7,570.4,570.9 -1.1710064276885586,1.3291525601335938,2.4870941840919194,1104.1,1269.4,1328.6,1765.3,565.1,624.2 -1.1710101261748103,1.329143690319949,2.6179938779914944,1270.9,1399.1,1526.5,1343.3,611.6,739.2 -1.1709965364703216,1.3291600232674348,2.748893571891069,1605.9,1700.9,1920.7,899.0,739.4,959.4 -1.1708183959623677,1.328916489651141,2.8797932657906435,1385.0,2160.1,1976.3,692.4,1048.4,1189.8 -1.170845064835623,1.3289028871779265,3.010692959690218,1246.9,1845.7,1787.1,586.4,1141.5,1082.7 -1.1708314875154266,1.2286421703821606,0.0,1121.4,1750.8,1751.3,640.9,1070.8,1071.0 -1.1709357560757339,1.2293188580958923,0.1308996938995747,1187.4,1787.5,1846.8,646.9,1083.2,1142.7 -1.1709174090440608,1.2293125833037724,0.2617993877991494,1362.4,1626.9,1247.5,714.8,1189.8,1317.1 -1.1708839300006744,1.229290747589605,0.39269908169872414,1722.8,1097.9,878.8,881.9,1572.3,1556.5 -1.17085370455369,1.2292590595233872,0.5235987755982988,1963.3,854.5,727.0,1267.9,1410.7,1282.8 -1.170842579203295,1.2292341409206484,0.6544984694978736,1764.9,727.7,668.6,1104.0,1224.9,1165.9 -1.1708304760514583,1.2291859190164582,0.7853981633974483,1721.1,670.9,670.2,1040.8,1151.6,1151.1 -1.1708319441316417,1.2291739202342316,0.916297857297023,1808.1,668.3,727.2,1060.7,1165.7,1224.5 -1.1708447508014048,1.229134417047241,1.0471975511965976,1270.6,727.2,854.5,1176.9,1282.0,1409.3 -1.1708709893154579,1.2290903449276172,1.1780972450961724,881.8,878.4,1097.5,1550.2,1556.6,1775.7 -1.1708664101302506,1.2291809686796404,1.3089969389957472,714.6,1246.5,1189.5,1362.8,2104.1,1976.2 -1.1709325050636392,1.2290620392520153,1.4398966328953218,646.5,1140.9,1082.5,1185.7,1844.0,1785.7 -1.1709648813123015,1.2290539015352921,1.5707963267948966,640.7,1070.9,1070.8,1121.1,1751.5,1751.2 -1.1709476865615176,1.229052212086264,1.7016960206944713,688.9,1081.9,1140.4,1143.2,1786.2,1845.0 -1.170943507522765,1.229049474263657,1.832595714594046,807.7,1190.5,1318.3,1270.3,1625.1,1245.8 -1.1710014150873516,1.229085591078998,1.9634954084936205,1042.8,1602.9,1556.1,1563.3,1097.2,877.9 -1.1710214063390603,1.2291076670938685,2.0943951023931953,1176.2,1409.0,1281.8,2054.6,854.1,726.9 -1.1710141040791662,1.2290912053212246,2.2252947962927703,1060.9,1224.3,1165.7,1807.1,727.0,668.4 -1.1710207212885182,1.229117381696184,2.356194490192345,1041.7,1151.6,1152.0,1720.7,670.3,670.9 -1.1710177759684188,1.2291512213861977,2.4870941840919194,1104.0,1165.9,1225.3,1765.2,668.6,727.7 -1.1710206115231936,1.2291451832311813,2.6179938779914944,1270.7,1283.4,1410.9,1542.3,727.1,854.8 -1.1710055575055571,1.2291638582250402,2.748893571891069,1558.7,1559.2,1779.0,1040.4,880.8,1101.0 -1.170819181003711,1.2289154548091612,2.8797932657906435,1269.6,2103.8,1976.1,807.9,1247.9,1189.4 -1.1708863028197112,1.2288842420374753,3.010692959690218,1143.3,1846.0,1787.0,689.8,1141.6,1082.8 -1.1708456356755363,1.1286516159671467,0.0,1021.1,1751.1,1751.3,740.8,1070.9,1070.7 -1.170940639191191,1.1293111216585197,0.1308996938995747,1084.0,1787.3,1847.0,750.4,1083.0,1142.5 -1.1709207665397394,1.1293043879797504,0.2617993877991494,1246.8,1826.0,1446.7,830.3,1189.7,1317.3 -1.1708493766399277,1.1292562858808752,0.39269908169872414,1581.1,1239.3,1020.0,1023.7,1448.5,1415.4 -1.1708418459184466,1.129249022215159,0.5235987755982988,2059.3,970.3,842.6,1269.8,1295.1,1167.2 -1.170834833253849,1.1292319216716273,0.6544984694978736,1765.0,831.3,772.2,1103.9,1121.2,1062.1 -1.1708103101560638,1.1291268653346047,0.7853981633974483,1721.4,770.8,770.4,1040.8,1051.7,1051.2 -1.1708103002481065,1.1291542229629088,0.916297857297023,1807.7,771.9,830.6,1060.6,1062.4,1121.2 -1.1708209837430115,1.1291214957091285,1.0471975511965976,1470.1,842.7,970.0,1176.8,1166.4,1293.6 -1.170848717539919,1.1290750075178508,1.1780972450961724,1023.4,1019.4,1238.8,1442.7,1415.5,1634.9 -1.1708482037745116,1.1290746482788916,1.3089969389957472,830.2,1316.9,1189.3,1247.2,2005.4,2097.6 -1.1708664272070681,1.1290648880617145,1.4398966328953218,749.8,1141.2,1082.6,1082.2,1844.1,1785.6 -1.170944217147963,1.1290463523382899,1.5707963267948966,740.8,1071.1,1070.5,1021.1,1751.2,1751.2 -1.1709423552316742,1.1290452113747846,1.7016960206944713,792.4,1082.0,1140.7,1039.7,1786.3,1844.6 -1.170943124620305,1.1290439987573189,1.832595714594046,923.2,1190.4,1318.3,1154.7,1824.3,1445.1 -1.1710026161014375,1.1290811361733073,1.9634954084936205,1184.5,1449.6,1415.1,1421.5,1238.2,1019.0 -1.1710231359625556,1.1291038130616786,2.0943951023931953,1176.5,1293.4,1166.1,2030.4,969.7,842.4 -1.1710160241706966,1.1290877369054066,2.2252947962927703,1060.8,1120.9,1062.2,1806.9,830.6,771.8 -1.1710124870064638,1.1290659559281448,2.356194490192345,1041.5,1051.0,1051.8,1720.3,770.1,770.8 -1.1709995239612243,1.1293327343666477,2.4870941840919194,1103.9,1062.3,1121.4,1765.2,772.4,831.4 -1.170698994502069,1.1290891766891527,2.6179938779914944,1270.3,1167.2,1294.9,1743.7,842.7,970.2 -1.1707314938611944,1.1290193801068575,2.748893571891069,1418.1,1417.1,1637.0,1182.7,1022.0,1241.7 -1.170803568030766,1.1289654858034086,2.8797932657906435,1153.8,2005.5,2117.0,923.3,1317.1,1189.7 -1.1708176495177123,1.1289583123410534,3.010692959690218,1039.7,1845.8,1787.0,793.2,1141.6,1082.5 -1.2708859657992082,1.8291737579656275,0.0,1721.0,1651.1,1651.0,40.9,1170.8,1170.9 -1.2709566176004543,1.8289476832017373,0.1308996938995747,1808.6,964.6,148.9,25.5,1186.7,1245.9 -1.2711095049393981,1.8289960372230647,0.2617993877991494,2055.8,431.0,51.3,21.3,1305.2,1432.4 -1.2710390562501777,1.8289516922024704,0.39269908169872414,2271.3,251.1,31.8,32.0,1589.9,1810.5 -1.2710284883069534,1.8289420539154402,0.5235987755982988,1848.5,161.2,33.5,72.2,2104.5,1976.2 -1.2710402101269815,1.828960790525845,0.6544984694978736,1661.7,106.6,47.5,231.4,1846.3,1786.9 -1.2710398587580314,1.8289646429033415,0.7853981633974483,1621.3,70.9,70.4,1140.9,1751.5,1751.4 -1.2710396497874075,1.8290041015347218,0.916297857297023,317.8,47.5,106.3,1164.2,1786.5,1845.8 -1.2710384312985439,1.829011345185777,1.0471975511965976,73.3,34.0,161.3,1292.2,1974.9,2102.3 -1.2710408835967673,1.8290059841972282,1.1780972450961724,31.8,31.6,250.7,1583.4,2403.0,2321.8 -1.271006314196558,1.8290384270779074,1.3089969389957472,21.2,51.0,430.2,2056.3,1988.5,1861.2 -1.270985211464219,1.8290506962486388,1.4398966328953218,25.8,152.4,981.3,1806.5,1740.6,1682.0 -1.2710216381479436,1.8290424947693675,1.5707963267948966,41.0,1170.8,1170.6,1721.2,1651.3,1651.3 -1.2709807634746837,1.829041012481406,1.7016960206944713,68.3,1185.3,1244.0,1763.8,981.0,152.4 -1.2709465019251531,1.829030299926036,1.832595714594046,114.0,1306.0,1459.4,1963.7,430.3,51.0 -1.2709765239799422,1.8290500066448456,1.9634954084936205,192.5,1591.4,1812.2,2413.4,250.7,62.7 -1.2709750157465594,1.8290500458841867,2.0943951023931953,349.9,2101.9,1974.9,1939.1,161.3,34.0 -1.2709536804868615,1.8290087019362955,2.2252947962927703,831.3,1845.5,1786.5,1703.6,106.3,47.5 -1.2709538293504261,1.8290087886096948,2.356194490192345,1141.9,1751.4,1751.6,1620.4,70.4,70.9 -1.2709516822156772,1.8290175152559782,2.4870941840919194,1207.4,1787.2,1846.0,827.3,47.5,106.6 -1.2709612820974148,1.8289894796514372,2.6179938779914944,1386.2,1976.8,2104.7,347.9,33.5,161.2 -1.2709579995324247,1.8289900629016884,2.748893571891069,1747.3,2407.4,2295.6,192.3,32.3,252.3 -1.2709792636007904,1.8289716509212406,2.8797932657906435,1962.9,1987.1,1859.9,114.3,51.8,431.6 -1.270983925310795,1.8289697122371342,3.010692959690218,1764.5,1742.2,1683.1,68.7,151.9,974.8 -1.2709410818555094,1.7286826287094312,0.0,1621.4,1650.7,1651.1,140.8,1171.2,1171.0 -1.2709858139697658,1.7292959305519107,0.1308996938995747,1705.3,1348.3,532.6,129.0,1186.6,1246.2 -1.2709575447487862,1.7292866711051404,0.2617993877991494,1940.1,630.2,250.5,136.8,1305.2,1433.1 -1.2709242489293024,1.7292651135915025,0.39269908169872414,2262.5,392.2,172.9,173.5,1589.9,1810.7 -1.2708962234598966,1.7292360685715698,0.5235987755982988,1848.3,276.6,174.5,271.3,1988.8,1861.2 -1.2708869275911177,1.7292149485608674,0.6544984694978736,1661.6,210.1,151.0,616.8,1742.7,1683.6 -1.2708755469299262,1.7291708677965927,0.7853981633974483,1621.4,170.8,170.3,1140.7,1651.7,1651.3 -1.2708767168906494,1.7291628626032165,0.916297857297023,619.3,150.9,209.7,1164.1,1683.5,1742.2 -1.2708882846367104,1.7292116997767621,1.0471975511965976,272.7,149.4,276.7,1292.4,1859.4,1987.0 -1.2711416831037905,1.7291515738462049,1.1780972450961724,173.3,172.7,392.0,1584.2,2263.0,2310.2 -1.2709595841302013,1.729318676053665,1.3089969389957472,162.2,250.5,629.9,1939.9,1987.8,1860.0 -1.271043917225505,1.7292741185132945,1.4398966328953218,129.2,543.0,1185.9,1702.8,1740.5,1682.0 -1.271096315628625,1.7292617914184802,1.5707963267948966,140.9,1171.2,1170.8,1620.9,1651.3,1651.0 -1.2710412723812927,1.7292592066379875,1.7016960206944713,171.7,1185.6,1244.2,1660.7,1367.5,540.6 -1.27098543528736,1.7292410541472267,1.832595714594046,229.7,1397.7,1434.0,1848.5,628.7,249.9 -1.270994915655032,1.7292473921378773,1.9634954084936205,334.4,1592.0,1813.6,2272.7,391.4,172.6 -1.270977527816106,1.7292302412108003,2.0943951023931953,550.0,1986.2,1859.0,1938.9,276.6,149.4 -1.2709460698868946,1.7291695479015854,2.2252947962927703,1164.3,1741.8,1683.3,1703.2,209.6,150.9 -1.270941546557232,1.7291496902162868,2.356194490192345,1141.6,1651.2,1651.5,1620.3,170.2,170.9 -1.2709396084110003,1.729139515681289,2.4870941840919194,1207.8,1683.5,1742.9,1209.9,150.9,210.1 -1.2709539421760019,1.7290945499592807,2.6179938779914944,1386.7,1861.4,1989.0,546.3,149.0,276.8 -1.270958542283288,1.7290810379399475,2.748893571891069,1748.3,2267.3,2314.7,364.4,173.6,393.9 -1.270990334075489,1.7290517689456237,2.8797932657906435,1846.4,1986.8,1859.5,229.6,251.3,631.6 -1.2710069775050026,1.7290424980098138,3.010692959690218,1660.7,1741.8,1682.7,172.0,539.7,1186.2 -1.2709794427868149,1.6287665782379526,0.0,1521.4,1650.9,1651.0,240.6,1171.1,1170.8 -1.271004636551199,1.6293379885750856,0.1308996938995747,1601.3,1684.0,916.7,232.6,1186.7,1246.3 -1.2709680687466256,1.6293260976822768,0.2617993877991494,1824.4,829.7,450.0,252.4,1305.0,1432.8 -1.2709293345872317,1.6293010801385077,0.39269908169872414,2262.5,533.3,314.1,315.2,1590.0,1918.7 -1.2708975945180068,1.6292680383926985,0.5235987755982988,1848.2,392.4,264.6,470.4,1873.2,1745.4 -1.2708860190657891,1.6292426887073992,0.6544984694978736,1661.7,313.6,254.5,1002.0,1639.3,1579.9 -1.2708735571677865,1.629194263926265,0.7853981633974483,1621.0,270.9,270.3,1140.8,1551.7,1551.3 -1.2708747808034686,1.629182175624748,0.916297857297023,1006.6,254.3,313.1,1163.9,1579.6,1638.7 -1.2708873589951641,1.629142537115549,1.0471975511965976,472.3,264.9,392.1,1292.3,1743.9,1871.1 -1.27091338719915,1.6290981656211032,1.1780972450961724,315.0,313.6,532.7,1583.8,2120.8,2271.3 -1.270908748283344,1.6291013737135367,1.3089969389957472,252.2,449.2,828.4,1825.3,1988.5,1861.0 -1.2709215866100494,1.6290943908995053,1.4398966328953218,232.5,930.8,1185.9,1599.4,1740.5,1682.0 -1.2709935402839585,1.6290769686286075,1.5707963267948966,240.8,1170.8,1170.4,1521.3,1651.1,1651.2 -1.2709861960167896,1.6290755612062164,1.7016960206944713,274.9,1185.3,1244.1,1557.2,1682.7,931.0 -1.2709820507620702,1.6290729756749849,1.832595714594046,345.1,1306.2,1433.5,1732.4,828.5,449.1 -1.2710374309284527,1.629107609799839,1.9634954084936205,475.7,1591.6,1917.9,2130.0,532.6,313.6 -1.2710548687715606,1.6291270764140522,2.0943951023931953,748.9,1871.5,1744.0,1939.5,392.2,264.9 -1.271045637888849,1.6291075475423797,2.2252947962927703,1164.4,1639.1,1579.8,1703.7,313.1,254.4 -1.2710511946284402,1.6291303795959713,2.356194490192345,1141.4,1551.5,1552.0,1620.7,270.3,270.8 -1.2710481511694156,1.6291608433633518,2.4870941840919194,1207.5,1580.3,1638.9,1661.3,254.5,313.6 -1.2710515787802632,1.6291517958195838,2.6179938779914944,1386.4,1745.7,1873.2,746.0,264.6,392.2 -1.2710379425073,1.6291678242087286,2.748893571891069,1824.0,2124.5,2266.3,475.0,315.0,535.0 -1.2708333450168154,1.628915410476139,2.8797932657906435,1731.9,1988.0,1860.4,345.5,450.5,829.8 -1.270856666050474,1.6289035761881603,3.010692959690218,1557.6,1742.5,1683.2,275.8,924.4,1186.3 -1.2708411374420985,1.5286423304057322,0.0,1421.3,1651.0,1651.0,340.7,1171.1,1170.7 -1.270940734855902,1.5293173520997165,0.1308996938995747,1498.0,1684.0,1300.0,336.2,1186.7,1246.1 -1.2709215689028106,1.5293108322048192,0.2617993877991494,1709.2,1028.7,649.2,368.0,1305.2,1432.8 -1.2708880621660614,1.5292889959047757,0.39269908169872414,2147.8,674.4,455.2,456.8,1590.2,1811.4 -1.2708579719974467,1.52925748324372,0.5235987755982988,1848.1,507.9,380.3,669.8,1757.1,1629.8 -1.270846966009396,1.5292328276550133,0.6544984694978736,1661.4,417.1,357.9,1207.3,1535.4,1476.5 -1.2708349013867728,1.5291848893887756,0.7853981633974483,1621.1,370.8,370.3,1140.8,1451.8,1451.3 -1.2708363417539332,1.5291731653009282,0.916297857297023,1392.9,357.9,416.7,1164.2,1476.2,1535.3 -1.2708490563584653,1.529133903365369,1.0471975511965976,671.8,380.5,507.8,1292.5,1628.5,1755.9 -1.2708751524352888,1.5290900148290985,1.1780972450961724,456.6,454.8,674.1,1583.7,1980.5,2198.9 -1.2708704103591588,1.5290936105023323,1.3089969389957472,367.7,648.7,1027.9,1709.8,1988.5,1861.0 -1.270883016197525,1.52908685576636,1.4398966328953218,336.0,1244.6,1186.2,1496.2,1740.6,1682.1 -1.2709546721923695,1.529069704506313,1.5707963267948966,340.8,1170.9,1170.9,1421.4,1651.3,1651.3 -1.2709469909340765,1.5290683602107986,1.7016960206944713,378.6,1185.6,1243.7,1453.6,1682.6,1319.7 -1.270942563597505,1.5290655822187993,1.832595714594046,460.7,1306.0,1433.8,1617.0,1027.3,648.3 -1.2709977261399281,1.5291000028640267,1.9634954084936205,617.6,1591.2,1812.3,1988.4,673.7,454.6 -1.2710150472329929,1.5291192342506847,2.0943951023931953,948.8,1755.7,1628.2,1939.2,507.7,380.4 -1.2710058960547126,1.5290993688635597,2.2252947962927703,1164.1,1535.1,1476.1,1703.3,416.6,357.9 -1.2710116491560568,1.529121925316415,2.356194490192345,1141.6,1451.0,1451.5,1620.5,370.2,370.8 -1.2710088112118554,1.5291522692111188,2.4870941840919194,1207.7,1476.6,1535.8,1661.6,358.0,417.2 -1.2710125609180176,1.529143150149613,2.6179938779914944,1386.1,1630.1,1758.0,945.0,380.3,507.9 -1.2709990936927247,1.5291592650265258,2.748893571891069,1809.7,1983.4,2203.8,616.3,456.5,676.5 -1.2708197077890828,1.528916007952284,2.8797932657906435,1616.4,1988.0,1860.8,461.1,649.8,1029.2 -1.270846116400774,1.5289025442061766,3.010692959690218,1453.9,1742.3,1683.3,379.4,1245.1,1186.4 -1.2708324095330075,1.428641798713488,0.0,1321.3,1651.2,1651.0,440.8,1171.1,1170.7 -1.2709362072030754,1.4293186957935933,0.1308996938995747,1394.6,1683.9,1743.6,439.8,1186.6,1246.1 -1.2709177711052488,1.4293123943585444,0.2617993877991494,1593.6,1228.1,848.7,483.5,1305.4,1432.9 -1.2708842858930822,1.4292905563969187,0.39269908169872414,2006.1,815.8,596.4,598.7,1590.2,1807.8 -1.2708540722688335,1.4292588837558817,0.5235987755982988,1848.2,623.4,495.9,869.2,1641.9,1514.3 -1.2708429578349072,1.429233989243319,0.6544984694978736,1661.3,520.5,461.6,1207.4,1431.7,1372.9 -1.2708308584949446,1.4291857937633796,0.7853981633974483,1621.2,470.8,470.2,1140.9,1351.6,1351.2 -1.2708323241118284,1.4291738205363356,0.916297857297023,1704.3,461.4,520.3,1164.1,1373.0,1431.5 -1.2708451223533053,1.4291343399115202,1.0471975511965976,871.3,495.9,623.3,1292.5,1512.8,1640.3 -1.2708713478157145,1.4290902852746301,1.1780972450961724,598.2,596.0,815.3,1583.9,1839.1,2058.2 -1.2708667535573472,1.429093757189823,1.3089969389957472,483.4,848.1,1227.3,1593.9,1988.2,1860.6 -1.2708795178531065,1.429086916287432,1.4398966328953218,439.5,1244.2,1186.2,1392.4,1740.2,1682.3 -1.2709513364159506,1.4290697371100367,1.5707963267948966,440.7,1170.7,1170.7,1321.0,1651.4,1651.3 -1.270943804720338,1.4290683958648192,1.7016960206944713,482.0,1185.5,1244.0,1350.1,1682.9,1741.0 -1.2709395147480451,1.4290656412483334,1.832595714594046,576.4,1306.3,1433.9,1501.4,1226.5,847.5 -1.270994795217077,1.429100121762608,1.9634954084936205,759.2,1591.2,1807.4,1846.8,814.7,595.7 -1.2710122084283415,1.4291194367085223,2.0943951023931953,1148.6,1640.0,1512.8,1939.2,623.1,495.9 -1.2710031298450395,1.4290996587956815,2.2252947962927703,1164.2,1431.6,1372.9,1703.5,520.1,461.3 -1.2710089288879407,1.429122313544057,2.356194490192345,1141.5,1351.1,1351.7,1620.8,470.2,470.8 -1.271006102254609,1.4291527643214454,2.4870941840919194,1207.6,1373.1,1432.3,1661.5,461.6,520.6 -1.2710098452731105,1.4291437403538874,2.6179938779914944,1386.2,1514.5,1642.3,1144.0,495.9,623.6 -1.2709963341830706,1.4291599446207395,2.748893571891069,1747.7,1842.2,2062.6,757.5,597.9,818.1 -1.2708184290193387,1.4289165891211535,2.8797932657906435,1500.6,1987.5,1860.4,576.7,849.0,1228.4 -1.2708451003668217,1.428902985067072,3.010692959690218,1350.4,1742.1,1683.5,482.8,1245.2,1186.3 -1.2708315120589428,1.3286422496501373,0.0,1221.1,1651.0,1651.2,540.8,1171.0,1170.9 -1.270935781852743,1.3293188753261733,0.1308996938995747,1291.1,1684.1,1743.3,543.4,1186.8,1246.1 -1.2709174214736036,1.3293125965293262,0.2617993877991494,1478.3,1427.4,1047.9,599.1,1305.3,1432.9 -1.2708839343098728,1.3292907559207598,0.39269908169872414,1864.2,956.8,737.7,740.3,1713.7,1697.5 -1.2708537034983007,1.3292590623392626,0.5235987755982988,1847.9,739.1,611.4,1068.5,1526.1,1398.2 -1.2708425748216974,1.3292341378840182,0.6544984694978736,1661.3,624.2,565.1,1207.5,1328.3,1269.2 -1.2708304701267548,1.3291859099889507,0.7853981633974483,1621.0,570.8,570.3,1140.7,1251.6,1251.0 -1.2708319382647575,1.329173905487809,0.916297857297023,1704.2,564.9,623.8,1164.1,1269.4,1328.4 -1.2708447463818908,1.3291343972061824,1.0471975511965976,1070.8,611.6,738.9,1292.6,1397.3,1524.6 -1.2708709874521122,1.3290903209056741,1.1780972450961724,739.9,737.2,956.3,1692.2,1697.8,1917.2 -1.270866411604525,1.3290937767059328,1.3089969389957472,599.0,1047.4,1305.0,1478.3,2129.6,1860.8 -1.2708791959593964,1.3290869248734154,1.4398966328953218,542.9,1244.3,1186.0,1289.1,1740.7,1682.2 -1.2709510351793079,1.3290697415475852,1.5707963267948966,540.8,1170.9,1170.7,1221.3,1651.4,1651.1 -1.2709435226567103,1.3290684005979236,1.7016960206944713,585.4,1185.8,1244.0,1246.8,1682.8,1741.3 -1.2709392501421235,1.329065649597745,1.832595714594046,691.9,1306.2,1434.0,1386.2,1425.4,1046.5 -1.2709945455071547,1.3291001380444754,1.9634954084936205,901.0,1743.8,1697.3,1704.8,955.8,736.8 -1.2710119702267548,1.3291194637644441,2.0943951023931953,1292.0,1524.8,1397.4,1939.3,738.7,611.4 -1.2710029001685434,1.3290996974848381,2.2252947962927703,1164.4,1328.1,1269.3,1703.5,623.6,564.8 -1.2710087042054061,1.3291223649602137,2.356194490192345,1141.5,1251.3,1251.8,1620.4,570.2,570.9 -1.2710058784672478,1.3291528289809211,2.4870941840919194,1207.5,1269.5,1328.5,1661.9,565.0,624.2 -1.2710096197750507,1.329143816798926,2.6179938779914944,1386.4,1398.8,1526.4,1343.3,611.6,739.3 -1.270996103078329,1.3291600316696215,2.748893571891069,1700.1,1700.9,1920.9,899.1,739.3,959.5 -1.2708183082195106,1.3289166554231646,2.8797932657906435,1384.9,2128.9,1860.4,692.2,1048.2,1305.1 -1.2708450016849453,1.3289030395048786,3.010692959690218,1246.8,1742.4,1683.4,586.3,1245.1,1186.3 -1.270831423104426,1.2286423050022344,0.0,1121.2,1651.1,1651.1,640.8,1171.1,1170.9 -1.2709357425699568,1.2293188952101402,0.1308996938995747,1187.4,1684.1,1743.2,646.9,1186.6,1246.0 -1.2709173884946814,1.2293126183060292,0.2617993877991494,1362.5,1626.7,1247.2,714.9,1305.5,1433.0 -1.2708839001477743,1.2292907768471042,0.39269908169872414,1722.7,1098.1,878.8,882.0,1590.4,1556.6 -1.2708536668839647,1.2292590804276666,0.5235987755982988,1847.9,854.5,727.0,1267.7,1410.6,1282.9 -1.270842536310254,1.2292341521538719,0.6544984694978736,1661.5,727.8,668.6,1207.7,1224.9,1165.8 -1.2708304308506406,1.2291859201543498,0.7853981633974483,1621.0,670.6,670.3,1141.0,1151.6,1151.0 -1.270828438755117,1.2292156603771032,0.916297857297023,1704.1,668.4,727.3,1164.1,1165.7,1224.4 -1.2708497099379734,1.2291485179671657,1.0471975511965976,1270.5,727.1,854.6,1292.4,1281.9,1409.0 -1.2708796024980047,1.229098673337627,1.1780972450961724,881.7,878.4,1097.5,1583.9,1556.8,1775.9 -1.27087494086173,1.2291022274328662,1.3089969389957472,714.6,1246.7,1305.3,1362.9,1988.2,1860.9 -1.270885770252504,1.2290964284725487,1.4398966328953218,646.3,1244.8,1186.1,1185.5,1740.4,1682.1 -1.270954912585323,1.2290798688759093,1.5707963267948966,640.8,1170.9,1170.6,1121.2,1651.6,1651.0 -1.270944668456673,1.2290784414964024,1.7016960206944713,688.8,1185.5,1243.9,1143.2,1683.0,1741.3 -1.270937903459407,1.2290749385042141,1.832595714594046,807.5,1306.3,1433.9,1270.4,1624.8,1245.8 -1.270991105065537,1.2291081177407328,1.9634954084936205,1042.9,1591.6,1555.8,1563.5,1097.1,878.0 -1.2710069771471653,1.2291257787445273,2.0943951023931953,1291.9,1408.8,1281.7,1987.2,854.2,727.0 -1.2708412788369052,1.2291488175875336,2.2252947962927703,1164.6,1224.6,1165.6,1703.8,727.4,668.5 -1.2708389531233901,1.229137234776824,2.356194490192345,1141.4,1151.2,1151.7,1620.3,670.4,670.8 -1.2708340505441456,1.229171768536608,2.4870941840919194,1207.3,1165.8,1224.9,1661.4,668.6,727.8 -1.2708584983849547,1.2290949895691379,2.6179938779914944,1385.9,1282.5,1410.3,1543.9,726.9,854.7 -1.2708694027675844,1.2290728537630784,2.748893571891069,1559.3,1558.6,1777.9,1041.2,880.3,1100.1 -1.270903509727514,1.229041982885481,2.8797932657906435,1269.6,1988.1,1860.2,807.8,1248.1,1305.1 -1.270920709913823,1.2290328219967097,3.010692959690218,1143.5,1742.2,1683.1,689.8,1244.9,1186.1 -1.2708921567074083,1.1287561634267924,0.0,1021.4,1651.1,1650.9,740.5,1171.0,1171.1 -1.2709669782368165,1.1293334505497197,0.1308996938995747,1083.6,1684.0,1743.0,750.5,1186.4,1246.1 -1.2709408134303903,1.1293247501428,0.2617993877991494,1246.8,1860.0,1447.1,830.2,1305.2,1432.5 -1.2709045053206887,1.1293011851901218,0.39269908169872414,1580.6,1239.3,1020.0,1023.7,1590.5,1415.4 -1.2708730454124522,1.1292682961076244,0.5235987755982988,1848.0,970.4,842.7,1385.6,1295.2,1167.3 -1.2708613277324918,1.1292424558664957,0.6544984694978736,1661.4,831.3,772.4,1207.3,1121.8,1062.3 -1.270848865778639,1.1291933513934689,0.7853981633974483,1621.2,770.7,770.2,1141.0,1051.6,1051.4 -1.2708502391127756,1.1291805601952527,0.916297857297023,1704.2,771.9,830.7,1164.1,1062.2,1121.0 -1.2708631358318434,1.1291403166993927,1.0471975511965976,1470.6,842.7,970.0,1292.3,1166.4,1293.6 -1.2708896090664545,1.1290955319955445,1.1780972450961724,1023.6,1019.2,1238.6,1581.8,1415.2,1634.6 -1.2708854325578518,1.12909844863964,1.3089969389957472,855.8,1432.7,1305.1,1247.5,1962.8,1860.9 -1.2708987308823918,1.1290912645742108,1.4398966328953218,749.7,1244.5,1186.1,1082.3,1740.6,1682.1 -1.2709711337722136,1.129073826056191,1.5707963267948966,740.8,1170.8,1170.8,1021.3,1651.4,1650.9 -1.2709641839922363,1.1290724517951585,1.7016960206944713,792.3,1185.6,1244.0,1039.9,1682.8,1741.2 -1.2709604035628175,1.1290699045821733,1.832595714594046,923.1,1306.2,1433.9,1154.8,1860.3,1445.3 -1.2710161041806416,1.129104675771558,1.9634954084936205,1184.4,1591.5,1415.3,1421.4,1238.2,1019.3 -1.2710338102108834,1.1291243426290585,2.0943951023931953,1291.9,1293.6,1166.2,1939.4,969.9,842.5 -1.2710248342227137,1.1291050070731663,2.2252947962927703,1164.4,1121.0,1062.4,1703.8,830.7,771.7 -1.2710305947439704,1.1291280824640673,2.356194490192345,1141.4,1051.2,1051.8,1620.7,770.2,770.8 -1.271027655426834,1.1291588548566036,2.4870941840919194,1207.4,1062.5,1121.6,1661.9,772.2,831.5 -1.2710311528292981,1.1291501002002637,2.6179938779914944,1386.2,1167.4,1295.3,1741.8,842.8,970.4 -1.2710174368981852,1.1291664435419588,2.748893571891069,1417.5,1417.6,1637.5,1182.0,1022.1,1242.2 -1.2708249067357644,1.1289174553851669,2.8797932657906435,1153.8,1962.7,1860.5,923.5,1432.8,1305.6 -1.270849854135445,1.1289047577711224,3.010692959690218,1040.1,1742.0,1683.7,793.5,1245.4,1186.0 -1.3709144953655017,1.8291089836117194,0.0,1721.2,1551.2,1550.9,41.0,1270.8,1270.9 -1.370915586456752,1.8285208638267731,0.1308996938995747,1808.4,967.1,149.6,25.6,1290.0,1349.3 -1.370888487545004,1.8282293143313089,0.2617993877991494,2054.7,431.8,51.7,21.5,1420.0,1547.7 -1.3706930824339454,1.8263110320468834,0.39269908169872414,2126.2,255.7,35.5,35.5,1727.7,1947.6 -1.3705312516302885,1.8265147722303223,0.5235987755982988,1733.6,164.5,36.5,77.2,2102.5,1974.2 -1.3705236687802334,1.8265111445302404,0.6544984694978736,1558.7,109.5,50.2,240.5,1844.2,1784.6 -1.3705110337555189,1.826472575138777,0.7853981633974483,1521.6,73.6,72.9,1240.6,1749.0,1748.5 -1.3705145473812266,1.8264666020708,0.916297857297023,243.6,50.2,108.8,1267.1,1783.5,1842.1 -1.3705323209523228,1.8264334625428704,1.0471975511965976,78.7,37.0,164.0,1516.9,1970.9,2098.3 -1.3705649010606986,1.8263981967017466,1.1780972450961724,35.5,35.2,253.9,1722.5,2353.3,2132.2 -1.3706660494327474,1.8260916285720412,1.3089969389957472,24.9,57.2,436.0,2053.4,1874.2,1746.6 -1.3706794976786238,1.8263287780829918,1.4398966328953218,28.3,161.9,990.3,1804.0,1637.0,1578.9 -1.3709707072512407,1.8262763179854025,1.5707963267948966,43.4,1270.8,1270.5,1718.7,1551.3,1551.2 -1.3709348356181155,1.8269422457620084,1.7016960206944713,70.6,1288.8,1347.6,1761.6,986.8,245.9 -1.3707085119103226,1.82688024917989,1.832595714594046,116.7,1422.0,1550.2,1961.8,433.9,55.2 -1.3708626357238956,1.8262339729825992,1.9634954084936205,196.2,1731.5,1952.4,2281.3,286.1,35.6 -1.3707728817611444,1.826305720519029,2.0943951023931953,355.4,2099.0,1971.7,1823.9,164.6,37.3 -1.3707485725673445,1.8262766910697628,2.2252947962927703,842.0,1842.7,1783.7,1600.5,109.2,50.4 -1.3707427457594001,1.826267502408801,2.356194490192345,1241.5,1748.6,1748.7,1520.7,73.2,73.7 -1.3707421188153202,1.8262602809549073,2.4870941840919194,1310.8,1784.0,1843.1,838.3,50.4,109.5 -1.3707617464590782,1.8262179657888722,2.6179938779914944,1501.6,1973.5,2101.1,353.5,36.7,164.4 -1.3707749974019312,1.8262102040839887,2.748893571891069,1888.2,2345.5,2125.2,227.3,36.2,256.1 -1.3708617146650648,1.8259401840370195,2.8797932657906435,1957.5,1871.4,1744.0,117.9,58.6,439.1 -1.3708647106529228,1.826102278137562,3.010692959690218,1761.0,1637.6,1579.2,71.3,163.2,989.9 -1.3709096042443898,1.7258785390308777,0.0,1618.7,1550.9,1551.0,143.3,1271.0,1271.0 -1.3709545785625536,1.727045898440875,0.1308996938995747,1703.2,1355.5,540.5,131.3,1290.1,1349.8 -1.3709390143168434,1.727051693529716,0.2617993877991494,1938.3,634.2,254.8,139.3,1420.8,1548.7 -1.3709139738245577,1.7270488791092933,0.39269908169872414,2126.7,395.1,175.9,176.6,1731.9,2055.8 -1.3708892592992417,1.7270373202826226,0.5235987755982988,1732.4,279.1,151.5,275.7,1986.2,1858.3 -1.3708800322235764,1.7270305458486308,0.6544984694978736,1557.9,212.3,153.2,625.6,1740.2,1681.3 -1.3708679436138296,1.7269978541807476,0.7853981633974483,1521.1,173.0,172.5,1240.9,1649.5,1649.1 -1.3708690242608808,1.7269992258736242,0.916297857297023,627.2,153.1,211.9,1267.7,1681.0,1740.1 -1.3708817579498975,1.7269724420906454,1.0471975511965976,320.8,151.9,279.2,1408.0,1857.2,1984.4 -1.3709078497825793,1.7269417703748202,1.1780972450961724,176.3,175.6,394.8,1725.2,2259.5,2147.5 -1.3709019056445382,1.7269598782981919,1.3089969389957472,139.1,254.4,633.8,1938.2,1872.9,1745.0 -1.3709104901295304,1.7269687613433404,1.4398966328953218,131.3,550.4,1289.7,1700.6,1637.0,1578.5 -1.3709739444569546,1.726967124242866,1.5707963267948966,142.9,1271.2,1270.8,1619.2,1551.3,1551.2 -1.3709539817888112,1.7269790634028226,1.7016960206944713,173.8,1289.1,1347.3,1658.4,1377.1,549.4 -1.3709337661638206,1.726985240555571,1.832595714594046,232.0,1421.9,1549.6,1845.9,633.2,254.1 -1.370971347403016,1.7270225011202671,1.9634954084936205,337.1,1733.5,2055.2,2269.1,394.5,175.5 -1.3709722999844847,1.7270381812803377,2.0943951023931953,553.8,1983.8,1856.9,1823.6,279.1,151.8 -1.370950692469492,1.727009261089528,2.2252947962927703,1227.6,1740.1,1681.0,1600.0,211.8,153.1 -1.3709499602141157,1.7270189239703106,2.356194490192345,1241.6,1649.1,1649.7,1520.4,172.4,173.0 -1.3709477104133305,1.7270355778028452,2.4870941840919194,1311.1,1681.6,1740.5,1219.3,153.1,212.3 -1.3709586387411623,1.7270152286647091,2.6179938779914944,1502.0,1859.0,1986.5,550.8,151.5,279.2 -1.3709572228363949,1.7270249240109448,2.748893571891069,1962.3,2263.5,2151.6,336.4,176.5,396.7 -1.3709286117137889,1.727040844483264,2.8797932657906435,1843.3,1870.6,1743.1,231.5,255.4,636.2 -1.3709535481277337,1.7270387630643513,3.010692959690218,1658.6,1637.8,1579.6,173.9,548.5,1289.3 -1.3709506778193048,1.6267918280900673,0.0,1519.6,1550.9,1551.2,242.5,1271.0,1271.2 -1.370974487885853,1.627914496696972,0.1308996938995747,1600.5,1580.6,921.1,234.0,1290.6,1372.6 -1.37095453077309,1.6279145670469242,0.2617993877991494,1823.6,832.0,452.4,253.9,1421.0,1548.4 -1.370930632392389,1.6279070598543557,0.39269908169872414,2121.2,535.1,315.8,317.1,1731.9,1952.8 -1.370908912900237,1.6278931576810802,0.5235987755982988,1732.8,393.6,266.1,473.3,1871.3,1743.6 -1.370902608129921,1.6278861854142344,0.6544984694978736,1558.0,314.9,255.8,1008.0,1637.3,1578.6 -1.370892172428193,1.6278548309502154,0.7853981633974483,1521.4,272.1,271.6,1240.7,1550.4,1549.9 -1.370893105118637,1.627858056299775,0.916297857297023,1011.0,255.7,314.6,1267.8,1578.5,1637.4 -1.370903845403532,1.6278326244618286,1.0471975511965976,474.8,266.4,393.8,1408.1,1742.3,1869.7 -1.3709266392639599,1.6278018654576683,1.1780972450961724,316.8,315.5,534.7,1725.1,2119.5,2165.9 -1.3709170572409515,1.6278180144282668,1.3089969389957472,253.7,452.0,831.2,1823.5,1873.0,1745.2 -1.3709226380908615,1.627823131350347,1.4398966328953218,233.9,936.7,1289.8,1598.1,1636.7,1578.4 -1.370984593651126,1.6278164110132975,1.5707963267948966,242.1,1270.6,1270.5,1519.8,1551.3,1551.1 -1.3709650726057347,1.627822942290758,1.7016960206944713,276.4,1288.9,1347.6,1555.7,1579.4,935.4 -1.3709471785109324,1.6278244136217705,1.832595714594046,346.6,1421.7,1549.3,1731.3,830.8,451.7 -1.3709884380893507,1.627858536501181,1.9634954084936205,477.6,1733.3,1954.2,2128.5,534.4,315.4 -1.3709934228152862,1.6278730606587093,2.0943951023931953,751.8,1869.6,1742.3,1824.0,393.6,266.4 -1.370975155518416,1.6278448922245743,2.2252947962927703,1267.8,1637.2,1578.4,1600.0,314.4,255.7 -1.3709762308308828,1.6278567147758463,2.356194490192345,1241.5,1549.7,1550.4,1520.4,271.5,272.1 -1.3709737779647952,1.627875949049363,2.4870941840919194,1311.2,1579.0,1638.0,1558.2,255.8,314.9 -1.3709825471559358,1.6278575298684146,2.6179938779914944,1501.9,1744.1,1872.0,748.3,266.1,393.8 -1.3709776046813202,1.6278676570499717,2.748893571891069,1888.9,2122.9,2170.6,476.6,316.8,536.9 -1.370936055668858,1.6278842943080603,2.8797932657906435,1729.0,1870.5,1742.8,371.4,453.7,834.5 -1.3709572456318297,1.6278790232525613,3.010692959690218,1555.6,1637.8,1579.1,276.5,934.4,1289.6 -1.3709544599901873,1.527632378900553,0.0,1420.4,1550.9,1550.7,341.6,1270.8,1271.4 -1.3709756162433424,1.528767335314556,0.1308996938995747,1497.5,1580.2,1301.6,336.6,1290.3,1349.7 -1.3709560405242753,1.5287631310471275,0.2617993877991494,1708.7,1029.6,650.2,368.5,1420.9,1548.7 -1.3709341063240628,1.5287514976778254,0.39269908169872414,2121.0,675.0,455.9,457.5,1731.7,1948.7 -1.3709151987266033,1.5287350804981068,0.5235987755982988,1732.5,508.3,380.7,670.8,1757.0,1629.1 -1.370911520267571,1.528727350834027,0.6544984694978736,1558.0,417.5,358.5,1311.2,1534.9,1476.2 -1.3709026303822651,1.5286966412098209,0.7853981633974483,1520.8,371.3,370.7,1240.7,1451.3,1451.0 -1.3709035010383845,1.5287010231891045,0.916297857297023,1394.7,358.3,417.2,1267.6,1475.8,1534.7 -1.3709125267929256,1.5286763377747918,1.0471975511965976,672.8,381.0,508.3,1407.9,1627.9,1755.4 -1.370932447425332,1.5286450584765345,1.1780972450961724,457.3,455.5,674.7,1725.1,1979.4,2129.2 -1.3709197027807718,1.5286589669513768,1.3089969389957472,368.4,649.6,1029.0,1709.2,1872.7,1745.3 -1.3709227643918345,1.528660172847676,1.4398966328953218,336.4,1323.5,1289.5,1495.2,1636.9,1578.4 -1.3709836816881114,1.5286484028690883,1.5707963267948966,341.2,1271.1,1270.7,1421.0,1551.3,1550.9 -1.3709649870838438,1.528649643077082,1.7016960206944713,379.0,1289.0,1347.3,1453.2,1579.5,1321.4 -1.3709497302138876,1.5286465605100528,1.832595714594046,461.3,1422.1,1549.5,1616.7,1028.3,649.1 -1.3709949094365954,1.5286777573130053,1.9634954084936205,618.2,1733.3,1947.5,1987.7,674.3,455.3 -1.371004097608841,1.5286913610621249,2.0943951023931953,949.9,1754.9,1627.7,1823.8,508.2,380.9 -1.3709893081813218,1.528664156845155,2.2252947962927703,1267.9,1534.7,1475.9,1600.1,417.1,358.3 -1.370992292656168,1.5286783535566344,2.356194490192345,1241.5,1450.5,1451.6,1520.6,370.7,371.3 -1.3709896879766232,1.5287004028878914,2.4870941840919194,1311.0,1476.1,1535.3,1557.8,358.4,417.6 -1.370996339045908,1.5286841383227177,2.6179938779914944,1501.9,1629.7,1757.4,945.8,380.8,508.4 -1.3709878347611637,1.5286949391416211,2.748893571891069,1889.1,1983.1,2124.7,616.8,457.1,677.2 -1.3709258071253496,1.5286843921121327,2.8797932657906435,1614.7,1870.7,1743.1,460.6,651.7,1032.6 -1.3709451540880697,1.5286753233451729,3.010692959690218,1453.4,1637.7,1579.6,379.1,1319.3,1289.5 -1.3709413757780244,1.4284272285099557,0.0,1321.1,1551.1,1551.0,440.9,1271.1,1271.3 -1.370973015440401,1.4292821838806598,0.1308996938995747,1394.5,1580.1,1639.8,439.8,1290.5,1349.6 -1.3709443972251074,1.4292728457009862,0.2617993877991494,1593.4,1228.0,848.6,483.6,1421.1,1548.4 -1.3709122188459717,1.4292519599260352,0.39269908169872414,2006.1,815.6,596.4,598.6,1854.7,1838.5 -1.370885440241,1.4292241618254788,0.5235987755982988,1732.5,623.4,495.8,869.2,1641.7,1513.8 -1.3708770015181895,1.42920453561864,0.6544984694978736,1557.9,520.7,461.5,1310.9,1432.0,1372.8 -1.370866129667099,1.4291621232603846,0.7853981633974483,1521.0,470.8,470.3,1241.0,1351.5,1351.2 -1.3708673266871134,1.429155694091751,0.916297857297023,1600.5,461.4,520.3,1267.8,1372.7,1431.5 -1.3708785478207857,1.4291211783337903,1.0471975511965976,871.4,496.0,623.4,1408.0,1513.1,1640.4 -1.3709021879996715,1.4290812073162602,1.1780972450961724,598.4,595.9,815.1,1833.8,1838.9,2057.9 -1.370894374073653,1.4290877076314519,1.3089969389957472,483.4,848.1,1227.2,1594.0,1873.0,1745.2 -1.3709035342058327,1.429082841474606,1.4398966328953218,439.4,1347.9,1289.6,1392.6,1637.1,1578.7 -1.3709716122234628,1.4290665988450084,1.5707963267948966,440.8,1271.0,1270.7,1321.1,1551.4,1550.9 -1.3709605630681971,1.4290652449872026,1.7016960206944713,481.9,1289.2,1347.3,1350.1,1579.8,1637.9 -1.3709531097448975,1.4290616613758325,1.832595714594046,576.2,1421.7,1549.6,1501.8,1226.5,847.5 -1.3710057053260678,1.4290946207761022,1.9634954084936205,759.3,1885.3,1838.4,1846.6,814.8,595.8 -1.3710210758323786,1.4291119475762508,2.0943951023931953,1148.7,1640.0,1512.6,1823.6,623.2,496.0 -1.3710106426909519,1.4290899177686716,2.2252947962927703,1267.8,1431.5,1372.7,1600.2,520.2,461.3 -1.37101576975293,1.4291101938858284,2.356194490192345,1241.8,1351.1,1351.7,1520.3,470.3,470.9 -1.3710129300656921,1.4291383342703605,2.4870941840919194,1311.1,1373.1,1432.1,1558.1,461.6,520.8 -1.3710172307410557,1.4291272533195514,2.6179938779914944,1501.7,1514.6,1642.2,1144.2,495.9,623.6 -1.3710047500592655,1.429141748099809,2.748893571891069,1841.7,1841.8,2062.1,757.6,597.9,818.0 -1.3708289647956722,1.4289057273275136,2.8797932657906435,1500.8,1872.2,1744.6,576.7,849.2,1228.7 -1.3708549259535523,1.4288925304755953,3.010692959690218,1350.4,1638.8,1579.8,482.9,1348.4,1289.8 -1.3708411980652841,1.3286318354522146,0.0,1221.1,1551.1,1551.1,540.8,1271.1,1270.9 -1.3709395342493982,1.3293162464231338,0.1308996938995747,1291.1,1580.3,1639.6,543.4,1290.3,1349.8 -1.3709202613052287,1.3293096948361427,0.2617993877991494,1478.3,1427.1,1048.1,599.2,1421.0,1548.5 -1.3708868288282496,1.329287902078251,0.39269908169872414,1864.3,956.6,737.5,740.3,1731.8,1697.8 -1.3708568411417534,1.3292564903689223,0.5235987755982988,1732.5,739.1,611.4,1068.5,1526.1,1398.4 -1.3708459078023225,1.3292319601718527,0.6544984694978736,1558.1,624.2,565.2,1311.0,1328.6,1269.3 -1.3708338881594209,1.3291841648063856,0.7853981633974483,1521.2,570.8,570.2,1241.0,1251.5,1251.0 -1.3708353313513837,1.3291725756420392,0.916297857297023,1600.8,564.9,623.8,1267.4,1269.3,1328.0 -1.3708480166837222,1.3291334377925121,1.0471975511965976,1071.0,611.5,738.8,1407.8,1397.5,1524.7 -1.3708740595717417,1.3290896619037924,1.1780972450961724,740.0,737.1,956.4,1724.8,1698.0,1916.9 -1.3708692413402714,1.3290933402025389,1.3089969389957472,599.0,1047.3,1420.6,1478.4,1872.6,1745.3 -1.370881756787047,1.329086634689508,1.4398966328953218,543.0,1348.2,1289.5,1289.2,1637.0,1578.2 -1.3709533177164002,1.329069516809926,1.5707963267948966,540.8,1270.8,1270.8,1221.2,1551.3,1551.1 -1.3709455449031178,1.32906817380242,1.7016960206944713,585.4,1288.9,1347.7,1246.7,1579.6,1637.9 -1.3709410377196687,1.3290653645930413,1.832595714594046,692.0,1421.8,1549.4,1385.8,1426.0,1046.8 -1.3709961335155745,1.3290997417391925,1.9634954084936205,901.2,1733.0,1697.1,1704.9,955.9,736.9 -1.3710134058139192,1.3291189207532217,2.0943951023931953,1348.2,1524.4,1397.1,1824.2,738.7,611.5 -1.3710042314864115,1.3290989905885775,2.2252947962927703,1267.9,1327.9,1269.3,1600.4,623.6,564.9 -1.3710099809697398,1.3291214832682303,2.356194490192345,1241.3,1251.1,1251.8,1520.3,570.2,570.9 -1.3710071512326478,1.3291517743029921,2.4870941840919194,1311.3,1269.4,1328.5,1558.2,565.1,624.2 -1.3710109288641004,1.3291426083079805,2.6179938779914944,1501.9,1398.7,1526.5,1343.3,611.5,739.3 -1.3709974883043627,1.329158692500255,2.748893571891069,1699.8,1700.5,1920.8,899.1,739.4,959.3 -1.37081935883892,1.3289157968133791,2.8797932657906435,1385.4,1872.6,1744.9,692.3,1048.3,1420.9 -1.3708459301551894,1.3289022483809814,3.010692959690218,1246.8,1638.8,1579.7,586.4,1348.8,1289.6 -1.3708323089051178,1.2286415155828436,0.0,1121.1,1551.4,1551.3,640.8,1271.0,1271.1 -1.3709361236786002,1.2293186655165498,0.1308996938995747,1187.7,1580.5,1640.0,647.0,1290.2,1349.6 -1.3709176773959104,1.2293123616222514,0.2617993877991494,1362.6,1626.9,1247.5,714.7,1421.0,1548.4 -1.370884185782707,1.229290520337941,0.39269908169872414,1723.0,1097.8,878.6,882.0,1731.7,1556.5 -1.3708539679730096,1.2292588436986194,0.5235987755982988,1732.4,854.7,727.1,1267.9,1410.3,1283.0 -1.3708428505320143,1.229233944433028,0.6544984694978736,1557.8,727.7,668.7,1310.9,1224.9,1165.9 -1.3708307501449095,1.2291857442222134,0.7853981633974483,1521.1,670.8,670.2,1240.7,1151.8,1151.1 -1.3708322157312163,1.229173766022613,0.916297857297023,1600.3,668.4,727.3,1267.7,1165.8,1224.6 -1.3708450152435474,1.229134280900039,1.0471975511965976,1270.5,727.0,854.5,1408.0,1281.8,1409.1 -1.370871243198837,1.2290902229729943,1.1780972450961724,881.6,878.5,1097.5,1723.3,1556.7,1775.5 -1.3708666519623072,1.2290936920748885,1.3089969389957472,714.7,1246.8,1420.6,1362.8,1961.6,1744.9 -1.3708794196039964,1.2290868488890858,1.4398966328953218,646.4,1347.8,1289.5,1185.8,1636.8,1578.5 -1.3709512416558747,1.229069669162156,1.5707963267948966,640.7,1270.8,1270.5,1121.3,1551.3,1551.2 -1.3709437134810023,1.2290683278939307,1.7016960206944713,688.7,1289.1,1347.4,1143.2,1579.2,1637.7 -1.3709394269763937,1.2290655734586153,1.832595714594046,807.7,1422.0,1549.4,1270.1,1624.7,1246.0 -1.370994710378231,1.2291000552001905,1.9634954084936205,1042.6,1733.4,1556.1,1563.1,1097.1,878.0 -1.3710121260594395,1.229119372189075,2.0943951023931953,1407.2,1408.9,1281.7,1942.7,854.4,727.0 -1.3710030498330077,1.2290995964576972,2.2252947962927703,1267.7,1224.4,1165.7,1600.0,727.1,668.2 -1.3710088506505176,1.2291222537680813,2.356194490192345,1241.5,1151.4,1151.8,1520.3,670.2,670.8 -1.3710060248241764,1.2291527076794977,2.4870941840919194,1311.1,1166.1,1224.9,1558.3,668.7,727.8 -1.3710097683011992,1.2291436868032886,2.6179938779914944,1502.0,1283.2,1410.9,1542.5,727.0,855.0 -1.3709962563446463,1.229159894373453,2.748893571891069,1558.5,1559.1,1779.5,1040.4,880.9,1100.8 -1.3708184048274252,1.22891657140636,2.8797932657906435,1269.2,1960.6,1744.8,807.8,1247.8,1421.1 -1.3708450864105046,1.2289029625189576,3.010692959690218,1143.2,1639.0,1579.8,690.1,1348.4,1289.7 -1.3708315059561336,1.1286422317998686,0.0,1021.3,1551.1,1550.9,740.8,1270.9,1271.0 -1.3709357936493956,1.129318865879279,0.1308996938995747,1083.7,1580.5,1639.7,750.5,1290.5,1349.7 -1.37091741891792,1.1293125834182516,0.2617993877991494,1247.0,1744.9,1446.6,830.3,1421.0,1548.5 -1.3708839224909373,1.129290738026803,0.39269908169872414,1581.2,1238.9,1019.8,1023.5,1634.8,1415.2 -1.3708536851886897,1.129259038673873,0.5235987755982988,1732.5,970.4,842.8,1467.1,1294.9,1167.3 -1.3708425520831387,1.1292341076785195,0.6544984694978736,1558.1,831.2,772.3,1311.0,1121.4,1062.4 -1.370830445075741,1.1291858728170618,0.7853981633974483,1521.2,770.8,770.4,1240.6,1051.9,1051.2 -1.3708319127664566,1.1291738612848148,0.916297857297023,1600.5,772.1,830.8,1267.7,1062.3,1121.1 -1.370844722245227,1.1291343464836663,1.0471975511965976,1470.2,842.7,970.0,1407.8,1166.3,1293.9 -1.3708458963590286,1.1291303990781048,1.1780972450961724,1023.2,1019.5,1238.7,1581.6,1415.4,1634.7 -1.3708650017280855,1.129111809056642,1.3089969389957472,830.3,1446.1,1420.8,1247.2,1873.1,1745.6 -1.3708841587768756,1.129101586544391,1.4398966328953218,749.9,1348.1,1289.6,1082.2,1636.9,1578.4 -1.370955301043151,1.1290845789561086,1.5707963267948966,740.7,1270.9,1270.8,1021.0,1551.3,1551.2 -1.3709448049527686,1.1290831475669616,1.7016960206944713,792.4,1289.1,1347.5,1039.8,1579.3,1638.0 -1.3709371462878124,1.1290793761390194,1.832595714594046,923.4,1422.1,1549.6,1154.6,1744.8,1445.1 -1.3709894091696164,1.12911196866866,1.9634954084936205,1184.3,1634.2,1414.8,1421.4,1238.2,1019.0 -1.3710045384309195,1.1291288331881288,2.0943951023931953,1407.4,1293.5,1165.9,1823.7,969.6,842.6 -1.370994001486398,1.1291063250061697,2.2252947962927703,1267.8,1121.1,1062.3,1600.2,830.7,772.0 -1.3709991475397774,1.1291261531527677,2.356194490192345,1241.7,1051.3,1051.7,1520.4,770.2,770.6 -1.370996418222642,1.1291539086129787,2.4870941840919194,1311.2,1062.4,1121.4,1558.2,772.2,831.5 -1.3710008846153108,1.1291425175644585,2.6179938779914944,1501.9,1167.8,1295.3,1732.4,842.8,970.5 -1.370959470263657,1.129204139978172,2.748893571891069,1417.0,1417.6,1637.8,1181.8,1022.4,1242.4 -1.3708253994444224,1.1289545316805076,2.8797932657906435,1154.0,1872.5,1744.7,923.7,1447.0,1420.9 -1.3708580217929343,1.1289376966537326,3.010692959690218,1039.9,1638.6,1579.8,793.4,1348.8,1289.8 diff --git a/tools/localisation_machine_learning/data/sector2.csv b/tools/localisation_machine_learning/data/sector2.csv deleted file mode 100644 index 603dec1a..00000000 --- a/tools/localisation_machine_learning/data/sector2.csv +++ /dev/null @@ -1,2496 +0,0 @@ -0.17085815683124295,0.17093761986366207,0.0,63.1,2751.1,2751.2,1698.9,71.0,70.9 -0.17094947221024442,0.17104270734636717,0.1308996938995747,91.5,2823.1,2882.5,823.6,47.4,106.7 -0.1709496078811476,0.17104255893099518,0.2617993877991494,139.4,3131.3,3259.4,349.1,187.6,95.1 -0.17115929112583556,0.1706904708575998,0.39269908169872414,223.5,2592.6,2372.8,191.2,109.8,62.8 -0.17118833318596033,0.17072432732583742,0.5235987755982988,392.8,2078.4,1950.3,113.9,50.8,59.6 -0.1712190003752866,0.17078004965106697,0.6544984694978736,911.8,1823.2,1764.2,68.5,129.3,70.2 -0.17122590238284915,0.1708178526094699,0.7853981633974483,2721.2,1729.0,1728.4,40.9,93.5,93.0 -0.17122425551149908,0.1708878663756379,0.916297857297023,2842.6,973.3,150.1,25.4,70.4,129.2 -0.1712145989160796,0.1709218750762722,1.0471975511965976,3210.3,431.6,51.5,105.7,59.1,186.4 -0.1712032994977258,0.1709383803425879,1.1780972450961724,2381.2,252.3,31.4,31.1,62.8,282.0 -0.17115163597302172,0.17098704685478539,1.3089969389957472,1938.4,161.1,33.5,72.2,94.9,474.0 -0.17111138458605363,0.17100995522815143,1.4398966328953218,1741.3,106.5,93.6,90.7,236.9,1065.5 -0.17112789867930928,0.1710068653247805,1.5707963267948966,1699.3,71.0,70.8,62.9,2751.1,2750.8 -0.1710165549053984,0.17100641972516528,1.7016960206944713,234.2,47.5,105.9,48.2,2820.6,2997.2 -0.17099866555606144,0.1710015475557074,1.832595714594046,73.8,187.1,94.9,46.6,3131.4,3259.2 -0.17102042569758322,0.17101709140928123,1.9634954084936205,32.3,109.7,62.8,63.2,2590.8,2402.5 -0.17100698492933147,0.17100554586646766,2.0943951023931953,21.3,51.3,59.1,116.7,2077.3,1949.9 -0.17097652499786095,0.17094878266832692,2.2252947962927703,25.9,129.1,70.3,318.1,1822.4,1763.9 -0.17097203956387164,0.17093179265782088,2.356194490192345,41.7,92.9,93.5,2720.6,1728.3,1729.5 -0.1709699909273402,0.17092371938009165,2.4870941840919194,68.7,70.2,129.3,2800.8,969.4,150.2 -0.17098381573273613,0.17088071338247945,2.6179938779914944,73.3,59.6,187.2,3119.8,430.8,51.7 -0.17098817879247838,0.17086886893600073,2.748893571891069,62.3,62.3,282.4,2537.5,251.8,31.8 -0.17101931458595437,0.17084135190666427,2.8797932657906435,46.3,94.4,474.3,2030.3,161.4,33.9 -0.1710350904405713,0.17083380536485193,3.010692959690218,48.0,234.1,1057.0,1784.6,106.4,93.2 -0.1710943433586279,0.27113861822661,0.0,162.9,2750.6,2751.2,1599.0,71.1,71.1 -0.17104015363096756,0.2706767843031961,0.1308996938995747,195.0,2823.2,2883.0,822.7,47.5,106.8 -0.17106921417466772,0.27068640941810806,0.2617993877991494,254.9,3131.9,3157.4,348.9,33.9,161.4 -0.17110504422922315,0.27070971767629515,0.39269908169872414,365.4,2450.5,2262.4,191.1,92.1,203.9 -0.1711339613035949,0.2707435125746236,0.5235987755982988,592.4,1962.5,1834.9,113.9,161.8,175.2 -0.17116171185081197,0.2707935983040435,0.6544984694978736,1298.3,1719.8,1661.0,68.5,232.8,173.7 -0.17116702456502347,0.27082372861556125,0.7853981633974483,2721.2,1629.0,1628.7,40.8,193.5,193.0 -0.17116574827046618,0.2708858280007782,0.916297857297023,2842.6,972.3,149.8,25.4,173.9,232.7 -0.17115842907553327,0.27091261308492887,1.0471975511965976,3210.6,431.4,51.4,21.3,174.7,302.0 -0.17115104338301398,0.27092329651112945,1.1780972450961724,2239.3,252.2,31.3,62.2,204.0,423.2 -0.1711041674034751,0.2709676390385791,1.3089969389957472,1822.5,161.0,33.5,72.2,294.3,673.6 -0.17106922641592637,0.2709876973480032,1.4398966328953218,1637.8,106.5,48.1,194.1,627.2,1456.5 -0.17109122954384604,0.2709835093734574,1.5707963267948966,1599.0,71.0,70.8,162.9,2751.5,2751.4 -0.171036670885852,0.2709822898570282,1.7016960206944713,233.6,47.4,105.9,151.7,2821.3,2879.7 -0.17099003002762486,0.27096849318330185,1.832595714594046,73.7,34.4,162.1,162.3,3132.6,3155.0 -0.17100944394557685,0.2709824559465379,1.9634954084936205,32.2,92.0,203.9,204.9,2449.1,2230.1 -0.17099978324205292,0.27097488346863563,2.0943951023931953,21.2,160.9,174.6,316.4,1961.0,1833.9 -0.17097308675957462,0.2709246961696634,2.2252947962927703,25.9,232.6,173.9,706.0,1719.0,1660.2 -0.1709706127653999,0.27091540166223327,2.356194490192345,41.6,192.9,193.5,2720.8,1628.4,1629.2 -0.17096842778566085,0.2709150827132836,2.4870941840919194,145.9,173.7,232.8,2800.8,968.2,149.8 -0.17098040893123723,0.27087896638388,2.6179938779914944,114.4,175.2,302.9,3120.1,430.4,51.6 -0.17098125315720042,0.2708729795631757,2.748893571891069,172.6,203.8,423.9,2395.1,251.6,31.7 -0.17100797427482925,0.2708498239899779,2.8797932657906435,161.8,294.0,674.1,1914.7,161.3,33.9 -0.17101870539364672,0.27084511335896844,3.010692959690218,151.5,621.8,1445.5,1681.3,106.4,47.6 -0.1710717526497094,0.3711452153643109,0.0,262.9,2751.3,2751.3,1499.1,71.0,71.0 -0.17102852450112457,0.37067068549273907,0.1308996938995747,298.6,2822.8,2882.2,822.9,47.5,106.8 -0.17106037627323636,0.3706811697991892,0.2617993877991494,370.6,3131.4,2958.1,349.0,33.9,250.5 -0.1710973226692275,0.3707051597969335,0.39269908169872414,507.0,2309.7,2090.3,191.1,31.9,252.7 -0.17112676876064437,0.37073948469671225,0.5235987755982988,791.6,1846.9,1719.2,113.9,172.8,290.8 -0.17115482840910284,0.37079004609551336,0.6544984694978736,1683.9,1616.1,1557.0,68.5,149.7,277.3 -0.17116028601911615,0.3708206184165592,0.7853981633974483,2721.1,1528.7,1528.6,40.8,293.5,293.0 -0.17115906003488415,0.3708831533754533,0.916297857297023,2842.8,972.4,149.8,25.4,277.4,336.2 -0.17115168390581167,0.3709103461801415,1.0471975511965976,2983.5,431.5,51.4,21.3,290.2,417.5 -0.1711441381549154,0.37092136267184417,1.1780972450961724,2097.9,252.1,31.3,31.1,345.2,564.3 -0.1710970444977021,0.3709659824900857,1.3089969389957472,1706.9,161.0,33.4,116.0,493.5,872.9 -0.1710618357148742,0.37098625650376227,1.4398966328953218,1534.2,106.5,48.1,297.6,1017.3,1846.1 -0.17108353505214383,0.37098215033229653,1.5707963267948966,1499.0,71.0,70.7,262.9,2751.5,2751.4 -0.17102868548605737,0.3709809351316473,1.7016960206944713,233.7,47.4,105.9,255.2,2821.1,2879.6 -0.17098177690714964,0.3709670859227068,1.832595714594046,73.7,34.4,250.2,277.9,3132.0,2955.9 -0.17100097714876283,0.3709808993634409,1.9634954084936205,32.2,32.5,253.5,346.6,2308.3,2088.8 -0.17099117909490946,0.3709731221139172,2.0943951023931953,21.2,171.9,290.1,516.2,1846.2,1718.3 -0.1709644045149276,0.37092273696858835,2.2252947962927703,25.9,151.7,277.4,1093.4,1615.5,1557.0 -0.17096192232940696,0.3709132447036587,2.356194490192345,41.6,293.0,293.4,2720.0,1528.5,1529.3 -0.17095980508602862,0.37091273728049057,2.4870941840919194,68.6,277.2,336.4,2800.4,968.6,149.8 -0.1709718713989232,0.370876488411493,2.6179938779914944,228.5,290.8,418.6,3120.4,430.6,51.6 -0.17097285464098852,0.37087039770845265,2.748893571891069,191.8,345.2,565.2,2253.9,251.6,31.7 -0.17099969588896324,0.37084719068641414,2.8797932657906435,277.4,493.6,873.5,1799.4,161.3,33.9 -0.17101054404506916,0.37084246206061255,3.010692959690218,254.9,1009.2,1832.5,1577.8,106.4,47.6 -0.17106369832988091,0.4711426379095489,0.0,362.9,2750.6,2750.9,1399.1,71.0,71.0 -0.17102212476028372,0.47067008003930355,0.1308996938995747,402.1,2823.6,2882.5,823.1,47.5,106.8 -0.17105439938220887,0.4706806853017862,0.2617993877991494,486.1,3131.9,2759.6,349.0,33.9,161.4 -0.17109149825985548,0.470441419471034,0.39269908169872414,648.5,2168.6,1948.9,191.1,31.9,252.5 -0.17085427148909146,0.4710733244726941,0.5235987755982988,991.4,1731.0,1603.2,113.8,50.7,406.5 -0.17085485987811286,0.4710713892045473,0.6544984694978736,2072.1,1512.5,1453.8,68.4,149.8,381.0 -0.1708472830281023,0.4710420753545024,0.7853981633974483,2721.1,1428.9,1428.5,40.8,393.6,393.0 -0.1708484521365904,0.47104647266542066,0.916297857297023,2842.4,971.3,149.5,25.4,381.0,439.8 -0.17085734476449108,0.47102128740866167,1.0471975511965976,2783.1,431.1,51.3,21.3,406.0,533.3 -0.170876898720173,0.47098920429783653,1.1780972450961724,1955.6,252.0,31.2,31.1,486.6,705.9 -0.1708636750464779,0.4710017514841909,1.3089969389957472,1590.5,160.9,33.4,240.7,693.5,1073.1 -0.1708664938702624,0.4710010172065988,1.4398966328953218,1430.7,106.3,48.0,236.7,1409.0,2239.0 -0.17092774838437397,0.4709871839212554,1.5707963267948966,1398.8,70.8,70.7,363.0,2751.0,2751.4 -0.1709100551989278,0.47098629529655045,1.7016960206944713,233.0,47.3,105.8,358.9,2821.1,2880.0 -0.17089651450553112,0.4709813318382061,1.832595714594046,73.4,34.2,162.0,393.7,3132.6,2755.1 -0.17094388258159596,0.47101150140826276,1.9634954084936205,32.0,32.3,253.4,488.8,2166.2,1947.2 -0.17095531208287673,0.4710250270932941,2.0943951023931953,21.1,51.0,405.8,716.6,1730.1,1602.5 -0.1709424917420888,0.47099849687052364,2.2252947962927703,25.7,151.3,381.0,1483.0,1511.5,1452.9 -0.1709467288812746,0.471014070568627,2.356194490192345,41.5,393.1,393.6,2720.3,1428.3,1429.2 -0.17094433348480542,0.47103785071702453,2.4870941840919194,68.5,381.0,440.1,2801.2,967.0,149.1 -0.1709503343923226,0.47102303338983487,2.6179938779914944,114.3,406.7,534.4,3051.5,430.0,51.3 -0.17094025165513588,0.4710347498516354,2.748893571891069,314.1,487.0,707.1,2111.6,251.3,31.5 -0.17082878416418204,0.4708628416921523,2.8797932657906435,348.9,693.0,1072.5,1684.1,161.3,33.8 -0.17085777669935268,0.470848177770802,3.010692959690218,358.5,1395.4,2217.8,1474.5,106.3,47.5 -0.17093654749310697,0.571166683366112,0.0,463.0,2750.6,2750.9,1299.0,70.9,70.9 -0.170940296547169,0.570712473140152,0.1308996938995747,505.6,2823.2,2882.2,824.4,47.4,106.7 -0.17097756250453064,0.5707244104389428,0.2617993877991494,601.4,2941.9,2561.7,349.2,33.8,161.2 -0.17101189190273036,0.5707463644731725,0.39269908169872414,789.9,2027.8,1808.9,191.2,31.8,296.6 -0.17103758987955164,0.5707761013344392,0.5235987755982988,1189.0,1616.0,1488.3,113.9,50.5,429.4 -0.17106328759248024,0.5708210806295273,0.6544984694978736,2451.1,1409.4,1350.3,68.5,323.5,484.4 -0.17106774422073887,0.5708455843258013,0.7853981633974483,2721.3,1329.0,1328.4,40.8,493.6,493.0 -0.17106726699445757,0.5709026412170419,0.916297857297023,2842.1,974.1,150.0,25.4,484.4,543.1 -0.17106186162334946,0.5709251023725574,1.0471975511965976,2586.9,431.9,51.4,21.3,521.2,648.5 -0.1710570497559849,0.57093211624848,1.1780972450961724,1815.7,252.3,31.2,31.0,627.2,846.3 -0.17101330681016522,0.5709739978399195,1.3089969389957472,1476.3,161.1,33.3,71.9,891.4,1270.6 -0.1709817150300965,0.570992776751579,1.4398966328953218,1327.7,106.4,48.0,235.7,1793.8,2621.1 -0.17100699226157093,0.5709876671723633,1.5707963267948966,1299.0,70.9,70.6,462.9,2752.2,2750.5 -0.17095551039922477,0.5709864267940628,1.7016960206944713,234.0,47.4,105.7,462.1,2820.8,2879.0 -0.17089457855320436,0.5709710412937206,1.832595714594046,73.7,34.3,161.8,509.0,2938.5,2559.6 -0.17092602735529278,0.5709921294918539,1.9634954084936205,32.2,32.4,296.5,629.9,2027.0,1807.7 -0.17091984589937306,0.5709874393169625,2.0943951023931953,21.1,51.0,431.1,914.8,1615.5,1487.8 -0.17089418808308018,0.5709384839864502,2.2252947962927703,25.8,323.3,484.4,1865.1,1408.5,1349.9 -0.17089225113129805,0.5709297161475755,2.356194490192345,41.5,493.0,493.5,2720.5,1328.5,1328.7 -0.17089067565153773,0.5709296092849938,2.4870941840919194,68.5,484.4,543.3,2800.4,970.0,149.9 -0.17090287587367636,0.570893929070299,2.6179938779914944,114.3,522.0,649.5,2855.9,430.8,51.5 -0.17090413319133577,0.570888254312403,2.748893571891069,191.5,627.8,847.8,1971.9,251.8,31.6 -0.17093080382085324,0.5708655037907502,2.8797932657906435,348.8,891.9,1271.5,1568.5,161.3,33.8 -0.17094136789712214,0.5708610852390144,3.010692959690218,462.1,1780.8,2602.3,1371.0,106.4,47.5 -0.17099399001009402,0.6711607588160209,0.0,562.9,2751.2,2750.8,1199.1,71.0,70.9 -0.17096410599951398,0.6706741072636033,0.1308996938995747,609.2,2822.6,2882.7,824.3,47.4,106.7 -0.1709984740241243,0.6706852433948054,0.2617993877991494,717.1,2741.8,2362.1,349.3,33.8,161.3 -0.1710357709074256,0.670709189076196,0.39269908169872414,931.3,1886.7,1667.5,191.2,31.8,252.3 -0.17106503865337178,0.6707429277826156,0.5235987755982988,1387.9,1500.3,1372.8,113.9,50.6,429.5 -0.17109324117325647,0.67079284371262,0.6544984694978736,2777.9,1305.9,1246.8,68.5,427.1,587.9 -0.17109883506230422,0.6708226389387788,0.7853981633974483,2720.9,1229.2,1228.6,40.8,593.6,593.1 -0.17109811268047226,0.6708847096483954,0.916297857297023,2842.2,973.9,149.9,25.4,587.9,646.7 -0.1710912869568882,0.670911648067618,1.0471975511965976,2387.2,431.9,51.4,21.3,636.7,763.8 -0.1710841596134275,0.6709223667674578,1.1780972450961724,1673.6,252.3,31.2,31.0,768.3,987.2 -0.17103751733473055,0.6709669870784625,1.3089969389957472,1360.5,161.1,33.4,71.9,1090.9,1469.7 -0.1710026748198378,0.6709875358187405,1.4398966328953218,1224.1,106.5,48.0,388.2,2183.3,2820.5 -0.1710245808107373,0.6709833016556161,1.5707963267948966,1199.0,70.9,70.6,563.0,2751.3,2751.2 -0.17096992104712244,0.6709820641981981,1.7016960206944713,234.0,47.4,105.7,565.3,2820.9,2879.1 -0.17092313912133847,0.6709684027762346,1.832595714594046,73.7,34.3,161.9,624.6,2739.6,2359.8 -0.17094255891091276,0.6709821146653945,1.9634954084936205,32.2,32.4,253.2,771.6,1885.6,1666.5 -0.17093311861268717,0.6709741300648693,2.0943951023931953,21.2,51.1,431.1,1114.4,1499.8,1372.0 -0.17090662261859588,0.6709238294620148,2.2252947962927703,25.8,426.8,588.0,2252.0,1305.2,1246.3 -0.17090445695524809,0.6709144924838177,2.356194490192345,41.5,593.0,593.5,2720.2,1228.7,1229.3 -0.17090280119511495,0.6709141046176315,2.4870941840919194,68.5,587.9,647.0,2800.6,969.9,149.9 -0.170915017688422,0.6708782271300437,2.6179938779914944,114.3,637.5,765.2,2656.4,430.8,51.5 -0.17091631939920607,0.6708724230262795,2.748893571891069,191.5,769.1,989.0,1830.6,251.7,31.6 -0.1709431005556399,0.6708495899855089,2.8797932657906435,483.2,1091.4,1470.8,1453.0,161.3,33.8 -0.17095379278392261,0.6708451533367954,3.010692959690218,565.5,2167.7,2822.5,1267.8,106.4,47.5 -0.1710065627911223,0.7711449639948946,0.0,662.9,2750.4,2751.2,1099.3,71.0,70.9 -0.17097349334194442,0.770670022653207,0.1308996938995747,712.8,2823.3,2882.1,824.0,47.4,106.7 -0.17102392928688545,0.7706851999631019,0.2617993877991494,832.7,2542.2,2162.3,349.2,33.8,161.3 -0.17105204078082295,0.7707034065891192,0.39269908169872414,1073.4,1745.3,1525.8,191.2,31.8,252.4 -0.1710801078214442,0.7707359041951929,0.5235987755982988,1587.7,1384.7,1257.0,113.9,50.6,507.6 -0.1711087416024622,0.7707867476071577,0.6544984694978736,2800.7,1202.2,1143.2,68.5,530.6,691.5 -0.17111471587362034,0.7708183620099622,0.7853981633974483,2721.5,1129.2,1128.5,40.8,693.5,693.0 -0.17111386668608858,0.7708823865740007,0.916297857297023,2842.6,973.7,149.9,25.4,691.4,750.2 -0.17110642913941534,0.7709111360871848,1.0471975511965976,2186.6,431.8,51.4,21.3,752.3,879.6 -0.17109832245935166,0.7709233821285111,1.1780972450961724,1531.5,252.2,31.2,31.0,909.3,1128.5 -0.1710504491901688,0.7709691091799371,1.3089969389957472,1244.7,161.1,33.4,72.0,1289.9,1669.3 -0.1710142371364203,0.7709903361917345,1.4398966328953218,1120.7,106.5,48.0,491.6,2573.5,2926.0 -0.1710347434439813,0.7709864444000292,1.5707963267948966,1099.1,70.9,70.6,662.9,2751.5,2750.3 -0.170978773828495,0.7709851780530386,1.7016960206944713,233.9,47.4,105.7,669.0,2820.8,2879.1 -0.17093083133823897,0.7709711556402405,1.832595714594046,73.7,34.3,161.9,740.3,2539.5,2160.2 -0.1709492664802234,0.7709842945008598,1.9634954084936205,32.2,32.4,253.2,913.4,1744.4,1525.1 -0.17093906885461174,0.7709755895113954,2.0943951023931953,21.2,51.1,506.8,1314.3,1384.1,1256.7 -0.17091208328483998,0.7709244467359673,2.2252947962927703,25.8,530.3,691.5,2639.4,1201.8,1142.8 -0.17090967038486554,0.7709142279970482,2.356194490192345,41.5,692.9,693.5,2720.3,1128.7,1129.1 -0.1709079786150995,0.770913001852364,2.4870941840919194,68.5,691.5,750.3,2800.1,969.7,149.9 -0.17092039430463812,0.7708763517633102,2.6179938779914944,114.3,753.3,880.6,2456.5,430.8,51.5 -0.1709220275199289,0.7708699128501464,2.748893571891069,191.6,910.9,1130.7,1688.9,251.7,31.7 -0.17094929130209555,0.7708465900512249,2.8797932657906435,494.2,1291.2,1670.7,1337.4,161.3,33.8 -0.17096053464636904,0.7708418361557807,3.010692959690218,669.0,2555.0,2905.5,1164.3,106.4,47.5 -0.17101399555936245,0.8711421810075657,0.0,762.9,2751.0,2751.4,999.1,71.0,70.9 -0.1709801000150172,0.8706701506775822,0.1308996938995747,816.3,2822.5,2882.8,823.8,47.4,106.7 -0.17101406317715104,0.8706812003788778,0.2617993877991494,948.3,2343.0,1962.6,349.2,33.9,161.3 -0.17105159587280666,0.8707053659050388,0.39269908169872414,1215.0,1604.0,1384.6,191.2,31.8,252.4 -0.17108118387323515,0.8707395529087192,0.5235987755982988,1786.7,1269.1,1141.4,113.9,50.6,597.9 -0.17110953463821021,0.8707899768795575,0.6544984694978736,2800.6,1098.6,1039.5,68.5,149.3,795.1 -0.171115178324453,0.8708203284934997,0.7853981633974483,2721.0,1029.0,1028.5,40.8,793.4,792.8 -0.1711143219558175,0.8708828600041136,0.916297857297023,2842.6,973.6,149.9,25.4,794.9,853.7 -0.17110726927476677,0.8709101720887547,1.0471975511965976,1987.0,431.7,51.4,21.3,867.8,995.1 -0.17109988349448702,0.8709212214347914,1.1780972450961724,1390.0,252.3,31.3,31.0,1050.4,1269.4 -0.17105293354806314,0.8709660349635076,1.3089969389957472,1128.9,161.1,33.4,72.0,1489.4,1868.1 -0.17101777800702414,0.8709866446126076,1.4398966328953218,1017.0,106.5,48.0,572.5,2879.1,2820.9 -0.17103939934823256,0.8709825039009071,1.5707963267948966,999.1,70.9,70.7,763.0,2751.3,2751.4 -0.17096131568526376,0.8709836071773962,1.7016960206944713,234.0,47.4,105.7,772.6,2820.6,2879.9 -0.17092893872277903,0.8709743017516081,1.832595714594046,73.7,59.8,161.9,855.8,2340.0,1960.9 -0.1709505766159811,0.870989483762987,1.9634954084936205,32.2,32.4,253.3,1054.9,1603.3,1384.0 -0.1709402374253904,0.8709806972322482,2.0943951023931953,21.2,51.1,596.9,1513.9,1268.6,1141.1 -0.17091260338168632,0.8709283927551386,2.2252947962927703,25.8,633.8,795.0,2843.1,1098.4,1039.4 -0.1709097921144575,0.8709165878413301,2.356194490192345,41.6,792.9,793.7,2719.9,1028.7,1029.0 -0.17090810777792442,0.870913728661711,2.4870941840919194,68.5,795.1,854.0,2799.6,969.6,150.0 -0.17092095173167715,0.8708755781292918,2.6179938779914944,114.3,868.9,996.5,2257.7,430.7,51.5 -0.1709233112751342,0.870867890327756,2.748893571891069,191.6,1052.0,1272.2,1547.7,251.8,31.7 -0.17095154665774245,0.8708436222981435,2.8797932657906435,348.9,1490.5,1870.1,1221.5,161.3,33.8 -0.1709638872761619,0.8708382567015036,3.010692959690218,772.5,2857.7,2822.0,1060.5,106.4,47.5 -0.27096757824663725,0.17074778603630092,0.0,63.0,2651.4,2650.8,1699.0,171.0,171.0 -0.27099230008439323,0.1710478450546744,0.1308996938995747,91.5,2719.9,2778.7,1207.6,151.0,148.9 -0.2709922897563243,0.17104780938996966,0.2617993877991494,139.4,3015.7,3143.0,548.6,231.4,95.1 -0.27121318523899113,0.17075281719453073,0.39269908169872414,223.5,2592.3,2373.0,332.4,173.5,62.8 -0.27121599965135,0.17075828056013242,0.5235987755982988,392.8,2078.2,1950.8,229.6,187.4,59.6 -0.271241378389102,0.1708040880024193,0.6544984694978736,911.4,1823.3,1764.3,172.1,129.4,70.2 -0.2712476404667339,0.1708394187858835,0.7853981633974483,2621.4,1728.9,1728.4,140.9,93.6,93.0 -0.27124590820729405,0.17090963181684926,0.916297857297023,2738.9,1361.0,537.6,129.0,70.4,129.2 -0.2712358448398395,0.17094457483736125,1.0471975511965976,3093.8,631.5,251.2,136.9,59.1,186.4 -0.27122377584159746,0.1709619743017512,1.1780972450961724,2381.8,394.1,173.1,172.3,62.9,282.0 -0.27117116682119197,0.17101130870075565,1.3089969389957472,1938.4,276.8,149.1,139.5,94.9,474.1 -0.27112989504389845,0.17103461878100878,1.4398966328953218,1741.1,210.0,151.6,90.7,236.9,1065.4 -0.2711453964173816,0.17103156995806268,1.5707963267948966,1699.3,171.0,170.8,62.9,2651.8,2651.8 -0.27108486883515087,0.17102997996755986,1.7016960206944713,624.0,150.9,151.4,48.3,2717.5,2775.5 -0.27103292641870563,0.1710146755507267,1.832595714594046,273.1,231.1,94.9,46.7,3016.0,3143.3 -0.27108709515534984,0.17104653352819765,1.9634954084936205,173.5,174.2,62.8,63.2,2591.0,2371.9 -0.2710541217395336,0.17101365468158702,2.0943951023931953,136.8,186.4,59.1,116.7,2077.3,1949.9 -0.2710223562612211,0.1709544453853009,2.2252947962927703,129.4,129.2,70.4,318.1,1822.8,1764.0 -0.2710190138634685,0.17094266688075743,2.356194490192345,141.6,93.0,93.5,2620.2,1728.5,1728.9 -0.27101662213261,0.17094204565390814,2.4870941840919194,172.2,70.2,129.3,2696.8,1355.4,536.0 -0.27102807093287856,0.1709063309532899,2.6179938779914944,117.2,59.6,187.2,3003.8,629.9,251.0 -0.2710284218188722,0.1709006506527857,2.748893571891069,62.4,62.4,282.3,2537.3,393.2,173.2 -0.2710544376515309,0.17087769545160447,2.8797932657906435,46.3,94.5,474.2,2030.8,276.9,149.5 -0.2709767944084801,0.17078253793775255,3.010692959690218,48.0,234.9,1059.4,1784.6,209.8,151.1 -0.2710379121587441,0.27108559182662084,0.0,162.9,2650.6,2650.8,1599.2,171.0,171.1 -0.2710275102767989,0.27108560480636323,0.1308996938995747,194.9,2719.4,2779.2,1205.3,151.0,210.4 -0.270991162963948,0.2710752806795571,0.2617993877991494,254.9,3016.7,3144.2,548.1,149.5,250.1 -0.27095355127338877,0.2710525592245179,0.39269908169872414,365.3,2450.3,2231.0,332.3,250.7,203.7 -0.2709227274898176,0.2710221121809253,0.5235987755982988,592.6,1961.7,1834.4,229.4,250.3,175.1 -0.27091134921421645,0.27099907021243075,0.6544984694978736,1299.5,1719.6,1660.6,172.1,232.7,173.7 -0.2708989927929438,0.270952829258692,0.7853981633974483,2621.0,1629.1,1628.3,140.9,193.4,193.0 -0.2708999704568858,0.27094246595105553,0.916297857297023,2739.5,1358.4,536.6,129.0,173.9,232.8 -0.27089794048097965,0.2709508165145118,1.0471975511965976,3095.5,630.9,251.1,137.0,174.7,302.2 -0.2709416437282022,0.2708800710798609,1.1780972450961724,2238.9,393.8,173.1,172.4,204.2,423.4 -0.2709106535257941,0.2709079083623813,1.3089969389957472,1822.0,276.6,149.1,255.0,294.5,674.2 -0.27091988120998195,0.27090517607753273,1.4398966328953218,1637.8,209.9,151.6,194.2,628.2,1458.1 -0.27119656943746523,0.2708444146343352,1.5707963267948966,1599.3,170.9,170.7,163.0,2651.8,2651.1 -0.2710611300991792,0.27084000597966273,1.7016960206944713,622.4,150.9,209.3,151.8,2717.8,2776.1 -0.27102128934848796,0.27082777412101633,1.832595714594046,272.7,150.0,250.3,162.4,3017.3,3144.7 -0.27106917638255407,0.2708593051782342,1.9634954084936205,173.2,250.7,204.0,205.1,2448.3,2229.4 -0.27108634322495617,0.27088037699856793,2.0943951023931953,136.7,251.1,174.7,316.8,1960.7,1833.8 -0.271078051218004,0.2708641751924712,2.2252947962927703,129.3,232.6,174.0,707.0,1718.7,1660.0 -0.2710840782827424,0.2708909319651127,2.356194490192345,141.6,192.9,193.6,2620.4,1628.3,1628.9 -0.27108065498268663,0.2709253857395808,2.4870941840919194,217.7,173.7,232.9,2697.3,1352.2,534.3 -0.27106801849490875,0.2709696474058849,2.6179938779914944,230.1,175.2,303.0,3004.6,629.2,250.5 -0.27107206709941106,0.2709589375388255,2.748893571891069,203.7,203.8,424.0,2394.9,392.8,173.0 -0.2709052116860873,0.27079307436496247,2.8797932657906435,161.9,294.3,674.5,1914.3,276.7,149.4 -0.27092629371989707,0.2707827441324213,3.010692959690218,151.5,622.7,1447.5,1681.1,209.8,151.1 -0.2710027760307061,0.37110208879057827,0.0,262.9,2651.0,2651.5,1498.9,170.9,171.1 -0.2709938870285197,0.3711022373443118,0.1308996938995747,298.5,2720.4,2779.0,1204.9,151.0,210.4 -0.27095421530383,0.3710908813014584,0.2617993877991494,370.5,3016.7,2957.6,548.0,149.5,277.1 -0.27091260385452415,0.37106556713434724,0.39269908169872414,507.1,2308.6,2089.6,332.1,232.9,344.9 -0.2708785376508575,0.37103145195516296,0.5235987755982988,792.0,1846.7,1719.2,229.4,250.3,290.7 -0.27086510418508863,0.37100423455586706,0.6544984694978736,1685.8,1616.2,1557.1,172.1,336.2,277.2 -0.2708519515887738,0.3709536850334667,0.7853981633974483,2621.1,1529.0,1528.5,140.8,293.5,293.0 -0.2708532577482178,0.3709392896692705,0.916297857297023,2739.4,1357.9,536.4,129.0,277.4,336.3 -0.27086688502146244,0.37074819500208256,1.0471975511965976,2982.2,630.8,251.0,137.0,290.2,417.7 -0.2711776007509465,0.3710287994041104,1.1780972450961724,2098.4,394.1,173.2,203.3,345.2,564.3 -0.2709959571243477,0.37119616693829993,1.3089969389957472,1707.0,276.9,149.2,271.5,493.4,872.5 -0.2710734024972219,0.37115596792237016,1.4398966328953218,1534.4,210.0,151.6,297.8,1016.1,1844.0 -0.27112831157053097,0.3711432930647218,1.5707963267948966,1498.6,171.0,170.8,263.1,2651.1,2651.1 -0.2710785451721227,0.37114144045319963,1.7016960206944713,624.1,150.9,209.3,255.2,2717.6,2775.4 -0.27102803142422915,0.3711259621872989,1.832595714594046,273.1,150.1,277.6,278.0,3016.4,2957.2 -0.271042023582457,0.37113587454328556,1.9634954084936205,173.5,233.5,345.3,346.7,2309.1,2089.5 -0.2710278995696049,0.37112281528287916,2.0943951023931953,136.8,250.9,290.3,516.1,1845.9,1718.6 -0.2709981307255737,0.37106676391413984,2.2252947962927703,129.4,336.4,277.5,1092.7,1615.5,1557.0 -0.27099411020456554,0.3710514170032335,2.356194490192345,141.7,293.1,293.6,2620.7,1528.5,1528.8 -0.27099192832132646,0.3710451551121887,2.4870941840919194,172.2,277.4,336.4,2696.9,1356.1,536.1 -0.27100491695842427,0.37100377574418064,2.6179938779914944,230.1,290.9,418.6,3003.7,630.3,251.1 -0.27100805581531445,0.3709930618348469,2.748893571891069,314.3,345.3,565.2,2254.3,393.3,173.2 -0.2710376699779519,0.37096611801134927,2.8797932657906435,277.6,493.6,873.2,1799.5,276.9,149.5 -0.27105194151738987,0.37095856747496647,3.010692959690218,255.1,1008.4,1830.5,1578.0,210.0,151.1 -0.2711097922350668,0.4712622159603548,0.0,363.1,2650.2,2651.2,1399.2,171.1,171.1 -0.2710471651759053,0.4707089534933877,0.1308996938995747,402.2,2719.7,2778.8,1206.5,151.1,210.4 -0.27107097788749335,0.47071688452658256,0.2617993877991494,486.3,3016.1,2758.9,548.3,149.5,443.6 -0.2711029033190606,0.4707376796610414,0.39269908169872414,648.6,2168.0,1949.4,332.4,173.6,394.4 -0.27112902727239574,0.4707684176322642,0.5235987755982988,991.3,1730.9,1603.3,229.5,393.0,406.4 -0.27115502193169383,0.47081519108717074,0.6544984694978736,2070.2,1512.6,1453.7,172.0,440.0,380.9 -0.2711595418147747,0.4708419256293961,0.7853981633974483,2621.1,1429.1,1428.5,140.8,393.5,393.0 -0.2711583363766995,0.47090081718097365,0.916297857297023,2739.3,1359.1,536.8,128.9,380.9,439.8 -0.27115183969100876,0.4709247214041259,1.0471975511965976,2784.0,631.1,251.1,136.9,405.8,533.2 -0.2711458711581184,0.4709330158669003,1.1780972450961724,1955.9,393.9,173.0,172.3,486.3,705.6 -0.27110079786416513,0.47097555485239306,1.3089969389957472,1591.0,276.6,149.0,271.5,692.9,1072.5 -0.2710679109691281,0.47099440575350005,1.4398966328953218,1431.0,209.9,151.6,401.1,1407.4,2236.5 -0.2710920778233259,0.4709896320061644,1.5707963267948966,1399.0,170.9,170.8,363.0,2650.8,2650.8 -0.27103957029907744,0.4709883928402636,1.7016960206944713,623.0,150.8,209.3,358.6,2717.6,2775.9 -0.2709947816714656,0.4709750679468534,1.832595714594046,272.8,150.0,444.2,393.5,3016.4,2756.4 -0.27101575872957745,0.47098993615936613,1.9634954084936205,173.4,174.2,395.3,488.5,2167.1,1948.0 -0.27100726424820204,0.47098355750742993,2.0943951023931953,136.7,392.0,405.7,715.9,1730.2,1602.8 -0.2709813125650756,0.4709347096632759,2.2252947962927703,129.4,439.7,380.9,1481.6,1512.0,1453.2 -0.2709791637948346,0.47092681465261865,2.356194490192345,141.6,392.9,393.5,2620.2,1428.4,1429.2 -0.2709769037774639,0.47081938537293744,2.4870941840919194,172.2,380.8,440.0,2697.2,1353.8,535.0 -0.2709921133119345,0.4708760770172915,2.6179938779914944,230.1,406.5,534.2,3004.7,629.5,250.7 -0.2709861616577885,0.47088091466390747,2.748893571891069,333.2,486.6,706.8,2113.0,393.0,173.1 -0.2710103675083457,0.47085998061467604,2.8797932657906435,393.0,693.2,1073.2,1683.2,276.8,149.4 -0.27102071461679633,0.4708553716134376,3.010692959690218,358.5,1396.9,2220.4,1474.6,209.9,151.1 -0.27107443950792903,0.5711563976521672,0.0,462.9,2650.9,2650.9,1299.1,171.0,171.0 -0.27103100602019664,0.5706751647827102,0.1308996938995747,505.6,2720.0,2779.1,1206.7,151.1,210.4 -0.2710623344941203,0.5706854818121014,0.2617993877991494,601.8,2939.1,2559.5,548.4,149.5,277.0 -0.2710987710881346,0.5707091513375826,0.39269908169872414,790.3,2027.0,1807.4,332.3,173.6,394.3 -0.27112781851145806,0.5707430518976642,0.5235987755982988,1190.3,1615.2,1487.8,229.5,404.0,522.0 -0.2711556079505959,0.5707931326608489,0.6544984694978736,2456.1,1409.2,1350.0,172.0,520.6,484.4 -0.27116094054256784,0.5708232088640113,0.7853981633974483,2621.2,1328.9,1328.4,140.8,493.5,493.0 -0.27115971000794903,0.5708852636972856,0.916297857297023,2739.3,1349.5,536.8,128.9,484.4,543.3 -0.2711524442644924,0.5709120196707242,1.0471975511965976,2584.2,630.9,251.0,136.9,521.3,648.6 -0.27114510550257254,0.5709226777808722,1.1780972450961724,1814.2,393.9,173.0,172.3,627.5,846.6 -0.2710982767644531,0.5709670198846468,1.3089969389957472,1475.6,276.6,149.0,356.2,892.4,1271.6 -0.27106337394133423,0.5709870989978387,1.4398966328953218,1327.4,209.9,151.5,504.5,1797.1,2626.1 -0.2710854009485308,0.5709829082970639,1.5707963267948966,1299.1,171.0,170.8,462.9,2650.8,2651.2 -0.27103086169216223,0.5709816918882333,1.7016960206944713,623.1,150.9,209.3,462.1,2717.9,2775.9 -0.27098423467350063,0.5709679092614486,1.832595714594046,272.9,150.0,277.6,509.1,2936.2,2557.0 -0.27100366860476977,0.5709818658687447,1.9634954084936205,173.3,174.3,395.2,630.2,2025.6,1807.0 -0.2709940385129937,0.5709742797160853,2.0943951023931953,136.8,402.9,521.1,915.6,1614.6,1487.5 -0.27096737028882684,0.5709240977753931,2.2252947962927703,129.4,520.4,484.3,1868.6,1408.4,1350.0 -0.2709649289211724,0.5709148157678303,2.356194490192345,141.6,492.9,493.6,2620.7,1328.5,1329.2 -0.2709627858659884,0.5709145111718161,2.4870941840919194,172.2,484.3,543.3,2697.2,1350.3,535.1 -0.2709747875870485,0.570878429046564,2.6179938779914944,230.1,522.0,649.8,2853.1,629.7,250.8 -0.27097565872003526,0.5708724743997471,2.748893571891069,455.4,628.2,848.4,1971.1,393.0,173.1 -0.2710023776942438,0.5708493574130029,2.8797932657906435,508.5,892.7,1272.6,1567.9,276.8,149.4 -0.2710130949935346,0.5708446786657955,3.010692959690218,462.0,1784.0,2607.2,1370.9,209.9,151.1 -0.2710661043192735,0.6711447446866989,0.0,562.9,2650.5,2650.8,1199.0,171.0,171.0 -0.27102409078314416,0.6706704889354584,0.1308996938995747,609.2,2719.4,2778.8,1206.9,151.1,210.4 -0.27105623628125675,0.6706810564741128,0.2617993877991494,717.3,2740.1,2360.2,548.3,149.5,277.0 -0.2710932727761339,0.6707050860555759,0.39269908169872414,932.0,1885.8,1666.5,332.3,173.5,437.6 -0.271122747262168,0.6707394156300273,0.5235987755982988,1389.6,1500.0,1372.5,229.5,250.0,612.3 -0.27115083970426873,0.6707899780599174,0.6544984694978736,2696.8,1305.5,1246.5,172.0,535.3,587.9 -0.27115631685006003,0.6708205428442473,0.7853981633974483,2620.9,1229.1,1228.4,140.8,593.5,593.1 -0.2708256695155592,0.6709531148914836,0.916297857297023,2740.0,1246.2,535.5,128.9,588.1,647.0 -0.27083454278897867,0.6709274000629024,1.0471975511965976,2382.1,630.1,250.7,136.9,637.1,764.6 -0.2708576010568526,0.6708903904674406,1.1780972450961724,1671.4,393.4,172.9,172.4,769.0,988.8 -0.27084990137874343,0.6708981977393755,1.3089969389957472,1359.2,276.4,149.0,446.1,1092.7,1472.7 -0.2708593544642835,0.6708942145964787,1.4398966328953218,1223.7,209.7,151.5,608.0,2192.2,2716.0 -0.2709275836276006,0.6708794640635283,1.5707963267948966,1199.0,170.8,170.7,563.0,2651.1,2651.5 -0.2709162529253375,0.6708793583942507,1.7016960206944713,621.1,150.8,209.3,565.7,2717.9,2776.3 -0.2709082309991131,0.6708764238533171,1.832595714594046,272.3,149.9,277.7,625.1,2734.2,2355.7 -0.27095997454706094,0.670909941486749,1.9634954084936205,173.0,174.1,437.4,772.5,1883.4,1664.6 -0.2709744270623457,0.6709275111526496,2.0943951023931953,136.6,251.0,611.2,1116.8,1498.6,1371.3 -0.2709635105746915,0.670905027405382,2.2252947962927703,129.2,540.1,587.9,2261.6,1304.6,1246.0 -0.2709685513294956,0.6709246526124906,2.356194490192345,141.5,593.0,593.7,2620.7,1228.3,1229.2 -0.2709658696552883,0.6709523466794551,2.4870941840919194,172.1,588.1,647.3,2697.4,1246.8,533.3 -0.27097102266897527,0.6709408595988886,2.6179938779914944,230.1,637.9,765.9,2651.2,628.6,250.2 -0.27095922866850597,0.6709555338204096,2.748893571891069,333.4,770.0,990.5,1828.7,392.5,172.8 -0.27085931060954954,0.6708120182798514,2.8797932657906435,548.9,1092.7,1472.3,1452.1,276.7,149.4 -0.27088745048036733,0.6707979430146704,3.010692959690218,565.6,2172.4,2718.3,1267.1,209.8,151.1 -0.2709679226223854,0.7711190695318471,0.0,663.0,2650.9,2650.9,1099.2,170.9,171.0 -0.2709610181349534,0.7711191410689155,0.1308996938995747,712.8,2719.7,2779.6,1121.6,151.0,210.4 -0.27092245547663363,0.7711079527434885,0.2617993877991494,832.9,2540.4,2160.7,548.3,149.4,277.1 -0.2708816425652645,0.771082908426838,0.39269908169872414,1073.4,1775.9,1556.5,332.1,173.6,394.4 -0.2708481608993416,0.7710491321402966,0.5235987755982988,1588.5,1384.5,1256.7,229.4,250.1,629.4 -0.2708352893644602,0.7710224117577644,0.6544984694978736,2757.5,1202.0,1142.9,172.0,535.8,691.5 -0.27082242579768634,0.7709723716485375,0.7853981633974483,2620.6,1128.9,1128.4,140.8,693.6,693.0 -0.27082394711679797,0.7709586166549249,0.916297857297023,2739.3,1143.0,536.8,129.0,691.5,750.4 -0.27083757203685177,0.7709176538713771,1.0471975511965976,2184.8,631.0,251.0,136.9,752.5,879.9 -0.2708652002516503,0.7708727189827753,1.1780972450961724,1530.8,393.8,173.0,172.3,910.0,1129.1 -0.27086506331209526,0.7708744636600862,1.3089969389957472,1244.3,276.6,149.0,271.5,1291.5,1671.0 -0.2708773086547368,0.7708691515441557,1.4398966328953218,1120.3,209.9,151.5,711.6,2577.9,2716.2 -0.2709497818910085,0.7708532050293564,1.5707963267948966,1099.0,170.9,170.7,663.0,2651.1,2651.1 -0.27094283409638686,0.7708532491653599,1.7016960206944713,622.6,150.8,209.3,669.3,2717.5,2776.0 -0.27093872887862214,0.7708518793071202,1.832595714594046,272.7,149.9,277.6,740.6,2537.4,2158.3 -0.270993757676217,0.7708875816901659,1.9634954084936205,173.2,174.1,395.1,913.8,1743.8,1524.6 -0.2710106511705861,0.77090776047371,2.0943951023931953,136.6,250.8,631.2,1315.5,1383.6,1256.5 -0.2710010583201959,0.770888394343614,2.2252947962927703,129.2,539.0,691.4,2644.8,1201.3,1142.8 -0.2710065444447476,0.7709111308424474,2.356194490192345,141.5,693.0,693.6,2620.7,1128.4,1129.0 -0.27100423187906675,0.7709511761584398,2.4870941840919194,172.1,691.4,750.7,2697.4,1143.2,534.6 -0.271010196847637,0.7709360881352507,2.6179938779914944,230.0,753.4,881.3,2454.9,629.4,250.5 -0.27099794091752616,0.770951572928213,2.748893571891069,333.1,911.2,1131.2,1688.2,392.8,172.9 -0.27086395052363643,0.7708127777656311,2.8797932657906435,548.8,1292.1,1672.1,1336.7,276.8,149.4 -0.2708865693214248,0.7708016057007288,3.010692959690218,669.1,2559.2,2844.4,1163.8,209.9,151.1 -0.27096536701194246,0.8711232117906855,0.0,763.0,2651.1,2651.1,999.0,170.9,171.0 -0.2709581648974426,0.8711232317480766,0.1308996938995747,816.3,2720.2,2779.5,1017.9,151.0,210.3 -0.2709197310372415,0.8711120474969025,0.2617993877991494,948.3,2341.2,1961.7,548.3,149.4,277.0 -0.27087914683644737,0.871087107825852,0.39269908169872414,1215.2,1603.9,1384.6,332.2,173.5,394.3 -0.27084585575775405,0.871053501129891,0.5235987755982988,1788.0,1268.9,1141.2,229.5,250.0,727.6 -0.2708331577527525,0.871027017259042,0.6544984694978736,2696.9,1098.6,1039.5,172.0,620.5,795.0 -0.27082035219274975,0.8709772075799265,0.7853981633974483,2621.2,1029.1,1028.5,140.9,793.7,793.0 -0.27082189658006095,0.8709637108683581,0.916297857297023,2739.0,1039.3,537.0,129.0,795.0,853.8 -0.27083546796474983,0.8709229878914804,1.0471975511965976,1985.9,631.2,251.1,136.9,868.0,995.1 -0.27086296170209356,0.870878205543397,1.1780972450961724,1389.1,393.9,173.0,172.3,1051.3,1270.3 -0.27085984203145325,0.8708816167507432,1.3089969389957472,1128.6,276.6,149.0,271.4,1490.6,1869.7 -0.2708739964058639,0.8708753659057678,1.4398966328953218,1016.9,209.9,151.5,626.5,2775.1,2716.9 -0.2709468539797384,0.870859266501359,1.5707963267948966,999.2,170.9,170.7,763.1,2651.2,2651.1 -0.2709398436850266,0.8708592682515586,1.7016960206944713,623.0,150.8,209.3,772.7,2717.9,2776.2 -0.2709355405939678,0.8708578475694737,1.832595714594046,272.7,149.9,277.6,856.1,2338.5,1959.5 -0.27099038530738356,0.8708933838104052,1.9634954084936205,173.2,174.1,395.1,1055.7,1602.5,1383.4 -0.2710071608974541,0.8709133385670829,2.0943951023931953,136.6,250.8,719.1,1514.9,1268.0,1140.8 -0.2709974822113027,0.8708937853979193,2.2252947962927703,129.2,623.9,794.9,2738.4,1098.0,1039.0 -0.27100293824405264,0.8709163340661024,2.356194490192345,141.5,792.9,793.5,2620.7,1028.3,1029.1 -0.2710001607420459,0.8709465487221004,2.4870941840919194,172.1,795.0,854.2,2697.2,1039.6,534.7 -0.27100432462152946,0.8709374095685369,2.6179938779914944,229.9,869.1,996.8,2255.9,629.3,250.6 -0.27099151216959616,0.8709537989367837,2.748893571891069,333.1,1052.5,1272.8,1546.7,392.9,173.0 -0.2708603687790678,0.8708163383755341,2.8797932657906435,592.7,1491.7,1871.2,1221.3,276.8,149.4 -0.2708831635555941,0.8708050657245117,3.010692959690218,772.5,2776.7,2718.3,1060.4,209.9,151.1 -0.3708903480115708,0.17078183672449043,0.0,63.1,2551.2,2551.0,1699.0,270.9,271.0 -0.3709621379651206,0.17107119863620857,0.1308996938995747,91.5,2616.1,2675.0,1591.5,254.6,233.4 -0.37096221121868284,0.1710710696102249,0.2617993877991494,139.5,2900.3,3027.8,748.0,265.0,95.1 -0.37116961010062677,0.1706965401977798,0.39269908169872414,223.6,2592.2,2372.4,473.6,282.1,62.8 -0.3711963456338694,0.17072790892540302,0.5235987755982988,392.9,2078.2,1950.5,345.2,187.3,59.6 -0.3712266445637576,0.17078299650832607,0.6544984694978736,911.9,1823.3,1764.3,275.6,129.3,70.2 -0.3712335483894961,0.17082091998092408,0.7853981633974483,2521.2,1728.9,1728.5,240.9,93.5,93.0 -0.3712318466243414,0.17089127708173635,0.916297857297023,2636.1,1747.8,924.7,359.1,70.4,129.2 -0.37122202810284205,0.17092565469735588,1.0471975511965976,2978.8,831.0,450.9,252.4,59.1,186.4 -0.3712104855799749,0.1709424816587799,1.1780972450961724,2381.3,535.8,314.8,223.9,62.9,281.9 -0.37115852364897917,0.17099136612751287,1.3089969389957472,1938.6,392.3,264.7,139.5,94.9,474.0 -0.3711179528651653,0.17101438572830063,1.4398966328953218,1741.2,313.5,255.0,90.7,237.0,1065.6 -0.3711728249667402,0.17100022220251154,1.5707963267948966,1699.1,271.0,270.8,62.9,2550.8,2550.7 -0.3710857742305219,0.17099776554384527,1.7016960206944713,1013.4,254.3,237.0,48.2,2613.9,2672.5 -0.3710289473713663,0.1709809788342247,1.832595714594046,472.3,265.7,94.9,46.7,2900.1,3028.3 -0.37104533475164225,0.17099310815145574,1.9634954084936205,314.6,281.9,62.8,63.2,2590.8,2371.6 -0.3710347694887603,0.17098464674455527,2.0943951023931953,252.3,186.4,59.1,116.7,2076.4,1949.6 -0.3710076515215464,0.17093413965590631,2.2252947962927703,232.9,129.2,70.4,318.2,1822.8,1764.0 -0.371004885490765,0.17092465457414807,2.356194490192345,241.7,93.0,93.5,2520.1,1728.7,1728.9 -0.37100253105557346,0.17092407759997852,2.4870941840919194,230.9,70.2,129.3,2593.3,1740.3,921.2 -0.3710142922715815,0.17088773550070635,2.6179938779914944,117.1,59.6,187.2,2888.5,829.3,450.2 -0.3710151420173323,0.17088142082388136,2.748893571891069,62.3,62.3,282.3,2536.8,534.6,314.6 -0.3710418635956523,0.17085798416209474,2.8797932657906435,46.3,94.4,474.3,2030.6,392.4,265.0 -0.37105271492779013,0.1708530344778585,3.010692959690218,48.0,234.2,1057.2,1785.0,313.5,254.6 -0.37110603820592397,0.27115335335300017,0.0,162.9,2550.8,2551.0,1599.3,271.0,271.1 -0.37104644460209846,0.2706734562205728,0.1308996938995747,195.0,2616.1,2675.4,1590.2,254.6,314.0 -0.3710747076271304,0.27068284585997304,0.2617993877991494,255.0,2900.7,3028.0,747.7,430.5,294.3 -0.37111069611726294,0.2707062776868294,0.39269908169872414,365.3,2449.9,2231.3,473.4,315.3,203.9 -0.3711399391447886,0.27074045814617875,0.5235987755982988,592.3,1962.6,1834.4,345.1,302.9,175.2 -0.37116791882541456,0.27079104307279755,0.6544984694978736,1298.4,1719.5,1660.5,275.6,232.8,173.8 -0.3711733327523811,0.2708217211776516,0.7853981633974483,2521.2,1628.9,1628.6,240.8,193.5,193.0 -0.37117200610954154,0.2708843286580094,0.916297857297023,2670.8,1660.5,923.5,232.5,173.9,232.7 -0.3711645198784396,0.2709115597347438,1.0471975511965976,2980.1,830.6,450.6,349.1,174.6,302.0 -0.3711568866994686,0.2709226154838149,1.1780972450961724,2239.0,535.5,314.7,313.4,204.0,423.2 -0.3711097056860378,0.27096722141893115,1.3089969389957472,1822.3,392.2,264.6,255.0,294.3,673.7 -0.37107443058687806,0.2709874354987889,1.4398966328953218,1638.0,313.3,255.0,194.2,627.2,1456.4 -0.3710960966007611,0.27098333591530155,1.5707963267948966,1598.8,271.0,270.8,162.9,2551.1,2551.2 -0.37104122142663176,0.2709821157383556,1.7016960206944713,1012.1,254.4,312.8,151.7,2614.5,2672.3 -0.37099429886123986,0.27096823493534705,1.832595714594046,472.0,430.0,294.1,162.3,2901.2,3028.4 -0.37101346774548244,0.27098206995623864,1.9634954084936205,314.5,316.0,203.9,205.0,2448.7,2229.9 -0.37102659931063664,0.27100456502232384,2.0943951023931953,252.2,301.8,174.6,316.5,1961.1,1833.9 -0.37098737298879325,0.27093076536963356,2.2252947962927703,232.9,232.6,173.8,706.0,1719.1,1660.4 -0.37098338088125876,0.27091487029173766,2.356194490192345,241.6,192.9,193.5,2520.3,1628.5,1629.0 -0.3709811924862277,0.27091405920983735,2.4870941840919194,275.7,173.7,232.9,2593.0,1660.9,920.4 -0.3709927600427267,0.2708792475378816,2.6179938779914944,316.1,175.2,302.9,2888.5,828.8,449.9 -0.37099257939049735,0.27087485266757816,2.748893571891069,203.6,203.8,424.0,2395.1,534.4,314.6 -0.3710178931884426,0.27085299767034354,2.8797932657906435,161.8,294.0,674.1,1914.8,392.3,265.0 -0.37102700184181053,0.2708491477905217,3.010692959690218,151.4,621.8,1445.5,1681.3,313.3,254.6 -0.37107807192426645,0.37114774414051954,0.0,262.9,2551.3,2551.0,1499.0,271.0,271.1 -0.3710325875942798,0.3706689236472478,0.1308996938995747,298.6,2616.2,2675.7,1535.9,254.6,447.9 -0.3710641614859279,0.3706793306195302,0.2617993877991494,370.6,2900.6,2958.7,747.7,265.1,392.6 -0.37110121645535965,0.37070340585215433,0.39269908169872414,507.0,2309.3,2090.0,473.4,392.0,345.1 -0.371130829424033,0.3707379348804971,0.5235987755982988,791.6,1846.9,1719.0,345.1,418.4,290.8 -0.3711589951779986,0.37078874716189514,0.6544984694978736,1684.0,1616.4,1557.0,275.5,336.4,277.3 -0.3711644978423238,0.37081959318888513,0.7853981633974483,2521.4,1529.5,1528.7,240.8,293.5,293.0 -0.37116323776265897,0.3708823753675876,0.916297857297023,2635.9,1556.9,924.0,232.4,277.4,336.2 -0.37115577218703943,0.3709097817114777,1.0471975511965976,2978.8,830.8,450.6,252.4,290.2,417.6 -0.37114810251376723,0.37092097875319374,1.1780972450961724,2097.9,535.5,314.7,313.4,345.2,564.4 -0.37110085716010116,0.3709657217388027,1.3089969389957472,1706.6,392.2,264.7,370.6,493.6,872.9 -0.37106548473582596,0.3709860625543473,1.4398966328953218,1534.3,313.4,255.0,297.5,1017.1,1846.5 -0.37108702233689,0.3709820010568099,1.5707963267948966,1499.1,271.0,270.8,262.9,2551.2,2551.0 -0.3710320208710703,0.37098078642483223,1.7016960206944713,1012.5,254.3,454.8,255.2,2613.8,2672.2 -0.3709849779976173,0.37096689374917413,1.832595714594046,472.1,265.6,393.2,277.9,2901.0,2955.8 -0.37100405891195976,0.370980649774868,1.9634954084936205,314.4,391.9,345.0,346.7,2308.5,2089.2 -0.37099416110019234,0.370972801518334,2.0943951023931953,252.3,417.4,290.1,516.2,1845.8,1718.5 -0.37096731904895797,0.37092232041425865,2.2252947962927703,232.9,336.2,277.4,1093.5,1615.5,1557.0 -0.37096479542154215,0.3709127238746319,2.356194490192345,241.6,292.9,293.5,2520.4,1528.5,1529.3 -0.370962656174946,0.37091211723651507,2.4870941840919194,275.7,277.3,336.4,2593.5,1557.3,920.5 -0.3709747387947141,0.37087576738116756,2.6179938779914944,345.8,290.7,418.5,2888.8,828.7,449.9 -0.3709757486649186,0.37086959425857,2.748893571891069,345.1,345.2,565.4,2254.0,534.5,314.5 -0.37100264750886086,0.37084631887745,2.8797932657906435,277.4,493.6,873.7,1799.0,392.4,265.0 -0.3710135647218577,0.37084154526006063,3.010692959690218,255.0,1009.0,1832.6,1577.9,313.4,254.6 -0.3710668110328006,0.47114179322428873,0.0,362.9,2551.1,2551.0,1399.0,271.0,271.0 -0.3710247288811195,0.4706699815358599,0.1308996938995747,402.2,2616.2,2675.3,1432.2,254.6,313.9 -0.3710569271015543,0.4706805678546164,0.2617993877991494,486.3,2900.1,2759.3,747.8,265.1,443.4 -0.3710940195245283,0.4707046363558871,0.39269908169872414,648.6,2168.3,1948.9,473.5,374.4,486.2 -0.3711235387492028,0.4707390192112113,0.5235987755982988,990.7,1731.1,1603.6,345.0,449.3,406.5 -0.37115165631892566,0.4707896394366302,0.6544984694978736,2069.8,1512.9,1453.8,275.5,439.9,380.8 -0.371157143999451,0.47082026483212824,0.7853981633974483,2521.5,1429.1,1428.6,240.8,393.5,393.0 -0.37115594354232856,0.4708828641302911,0.916297857297023,2635.9,1453.3,924.1,232.5,380.9,439.8 -0.3711485744006698,0.470910123514771,1.0471975511965976,2784.2,830.9,450.6,252.4,405.8,533.1 -0.37114101192054777,0.47092119070618743,1.1780972450961724,1956.3,535.6,314.7,344.4,486.3,705.4 -0.37109389245712865,0.47096586084733216,1.3089969389957472,1591.2,392.3,264.6,460.8,692.8,1072.2 -0.3710586461134776,0.47098618317046426,1.4398966328953218,1430.7,313.4,255.0,401.0,1406.9,2235.7 -0.3710802961401667,0.4709820864176528,1.5707963267948966,1399.2,271.0,270.7,363.0,2551.6,2551.1 -0.37102539963043857,0.47098087046896864,1.7016960206944713,1012.7,254.3,312.8,358.6,2655.4,2672.5 -0.3709784463412067,0.4709670179272816,1.832595714594046,472.1,265.6,444.1,393.6,2900.3,2756.4 -0.37099761487783456,0.47098080039261503,1.9634954084936205,314.5,374.3,486.1,488.4,2166.9,1948.1 -0.37098780364503037,0.470972978599155,2.0943951023931953,252.3,450.8,405.7,716.0,1755.4,1602.9 -0.37096102347199206,0.47092256061407833,2.2252947962927703,232.9,439.7,380.9,1480.8,1512.1,1453.4 -0.3709585494256367,0.4709130376157453,2.356194490192345,241.6,393.0,393.5,2520.7,1428.5,1428.9 -0.37095645916431125,0.47091249927815215,2.4870941840919194,275.7,380.7,439.9,2593.6,1454.1,920.5 -0.37096854463144147,0.4708762380831506,2.6179938779914944,427.7,406.4,534.0,2888.6,828.8,450.0 -0.3709695634387215,0.4708701366738026,2.748893571891069,455.4,486.7,706.8,2112.7,534.4,314.5 -0.37099642398123167,0.4708469313561938,2.8797932657906435,393.0,693.0,1073.1,1683.7,392.4,265.0 -0.37100728834501917,0.47084220770435636,3.010692959690218,358.5,1396.4,2219.7,1474.7,313.4,254.6 -0.37106044973825086,0.5711423828328002,0.0,462.8,2551.0,2550.9,1299.2,271.0,271.0 -0.3710193741563741,0.5706700121439365,0.1308996938995747,505.7,2615.9,2674.8,1328.3,254.6,314.0 -0.37105178951520823,0.5706806556715052,0.2617993877991494,601.7,2900.1,2560.1,747.8,265.0,392.6 -0.3710889361321533,0.5707047366084219,0.39269908169872414,790.2,2027.4,1808.2,473.5,315.2,535.9 -0.37111846389648423,0.5707390961733341,0.5235987755982988,1190.0,1616.1,1488.1,345.1,449.2,522.0 -0.3711466094113318,0.5707896927700808,0.6544984694978736,2455.0,1409.1,1350.0,275.6,543.5,484.4 -0.37115211580671253,0.5708202851805373,0.7853981633974483,2521.0,1329.2,1328.5,240.8,493.4,492.9 -0.3711509565887725,0.57088287614104,0.916297857297023,2635.9,1349.6,924.2,232.5,484.5,543.3 -0.3711436254012368,0.5709101416395919,1.0471975511965976,2584.6,830.9,450.7,252.4,521.2,648.6 -0.3711360841762973,0.5709212065509133,1.1780972450961724,1814.8,535.6,314.7,313.3,627.3,846.5 -0.3710889851124214,0.5709658937187787,1.3089969389957472,1475.5,392.2,264.7,470.8,892.1,1271.5 -0.3710537497466442,0.5709862502953689,1.4398966328953218,1327.5,313.3,254.9,504.6,1796.6,2590.5 -0.371075396464702,0.5709821481992763,1.5707963267948966,1299.0,270.9,270.7,462.9,2550.8,2551.0 -0.37102049638223683,0.570980930437665,1.7016960206944713,1012.9,254.3,312.7,462.1,2614.2,2672.0 -0.3709735361597975,0.5709670890748413,1.832595714594046,472.2,265.6,393.3,509.1,2900.9,2557.9 -0.3709927082666493,0.5709808544857367,1.9634954084936205,314.4,315.9,536.9,630.1,2025.9,1806.9 -0.3709829158643275,0.5709730041169085,2.0943951023931953,252.2,450.7,521.2,915.5,1614.5,1487.6 -0.3709561517989563,0.5709225806127758,2.2252947962927703,232.8,543.1,484.4,1868.1,1408.5,1349.9 -0.37095370092664953,0.5709130574053469,2.356194490192345,241.6,492.9,493.5,2520.3,1328.6,1329.0 -0.3709516497052244,0.5709125163574129,2.4870941840919194,275.7,484.3,543.4,2593.6,1350.1,920.7 -0.3709637512076984,0.5708762751251475,2.6179938779914944,345.7,522.0,649.9,2888.5,829.0,450.0 -0.3709648027123925,0.5708701885930751,2.748893571891069,474.7,628.1,848.2,1971.3,534.5,314.5 -0.3709916657742145,0.5708470080485808,2.8797932657906435,508.5,892.6,1272.5,1568.2,392.4,265.0 -0.37100252544840034,0.5708423049373301,3.010692959690218,462.0,1783.5,2606.6,1371.1,313.4,254.6 -0.3710556645090491,0.6711424568895925,0.0,562.8,2551.3,2551.5,1199.1,271.0,271.0 -0.3710153006117561,0.6706699863641545,0.1308996938995747,609.1,2616.0,2675.8,1225.1,254.6,314.0 -0.3710478769316351,0.670680672189131,0.2617993877991494,717.3,2739.9,2360.6,747.9,265.1,392.5 -0.3710850684877336,0.6707047649468074,0.39269908169872414,931.8,1885.8,1667.0,473.5,315.2,535.9 -0.3711146073300622,0.6707391117382528,0.5235987755982988,1389.1,1500.3,1372.5,345.1,519.6,637.7 -0.3711427775266418,0.6707896966140816,0.6544984694978736,2593.8,1305.6,1246.6,275.6,647.0,587.9 -0.3711482997510619,0.6708202706198523,0.7853981633974483,2521.1,1229.1,1228.4,240.8,593.5,593.0 -0.37114717184562357,0.6708828617364935,0.916297857297023,2635.6,1246.2,924.2,232.4,588.0,646.7 -0.37113986791357173,0.6709101377798157,1.0471975511965976,2385.0,830.9,450.7,252.4,636.7,764.1 -0.3711323399609808,0.6709212057801266,1.1780972450961724,1672.9,535.5,314.7,313.3,768.5,987.7 -0.3710852527552551,0.6709659095906746,1.3089969389957472,1360.1,392.3,264.7,576.4,1091.4,1470.6 -0.37105002156092426,0.6709862947656504,1.4398966328953218,1224.0,313.4,255.0,607.9,2186.2,2613.1 -0.37107166132971425,0.6709821897108759,1.5707963267948966,1199.0,270.9,270.7,563.0,2551.0,2551.8 -0.3710167543493921,0.6709809705649661,1.7016960206944713,1012.8,254.3,312.8,565.5,2613.8,2672.7 -0.3709697850692421,0.6709671367902501,1.832595714594046,472.2,265.6,393.3,624.8,2737.9,2358.4 -0.3709889567309436,0.670980887331891,1.9634954084936205,314.4,315.9,536.9,771.8,1884.6,1666.0 -0.37097917634004374,0.6709730127095712,2.0943951023931953,252.3,494.6,636.8,1115.0,1499.3,1372.0 -0.37095242302695,0.670922582298682,2.2252947962927703,232.8,646.6,587.8,2255.6,1304.8,1246.4 -0.3709499891392149,0.6709130561056096,2.356194490192345,241.6,593.0,593.4,2520.2,1228.4,1229.0 -0.37094796784147777,0.6709125102472573,2.4870941840919194,275.7,587.9,646.9,2593.7,1246.9,920.8 -0.3709600823222721,0.6708762818850464,2.6179938779914944,345.7,637.7,765.4,2654.9,829.1,450.0 -0.3709611601215201,0.6708702047507844,2.748893571891069,596.9,769.4,989.4,1830.2,534.5,314.5 -0.3709880267217666,0.6708470417294581,2.8797932657906435,624.0,1092.0,1472.3,1452.5,392.4,265.0 -0.37099888460757896,0.6708423534718608,3.010692959690218,565.6,2170.2,2614.3,1267.5,313.4,254.6 -0.37105200870623606,0.7711424892979639,0.0,662.9,2550.7,2550.8,1099.2,271.0,271.0 -0.371012187017648,0.7706699626737024,0.1308996938995747,712.9,2615.9,2676.0,1121.5,254.6,314.0 -0.3710448868640249,0.7706806809768443,0.2617993877991494,832.9,2540.6,2161.5,748.0,265.0,392.5 -0.37108211332242147,0.7707047831166602,0.39269908169872414,1073.6,1745.2,1525.5,473.5,315.1,578.8 -0.37111166108092464,0.7707391206288516,0.5235987755982988,1588.1,1384.4,1256.7,345.1,609.7,753.3 -0.3711398504355057,0.7707896970951489,0.6544984694978736,2719.8,1202.2,1143.0,275.5,750.5,691.4 -0.37114538489268806,0.770820257607415,0.7853981633974483,2521.5,1129.0,1128.5,240.8,693.6,693.0 -0.37114428090560725,0.7708828493872464,0.916297857297023,2636.1,1142.7,924.3,232.4,691.4,750.3 -0.37113699766129876,0.7709101339785822,1.0471975511965976,2185.7,831.0,450.7,252.4,752.3,879.7 -0.3711294796080963,0.7709212047447693,1.1780972450961724,1531.4,535.6,314.7,313.4,909.7,1128.7 -0.3710824011556747,0.7709659215784204,1.3089969389957472,1244.4,392.3,264.6,561.9,1290.6,1669.5 -0.3710471727972511,0.7709863288100902,1.4398966328953218,1120.6,313.4,255.0,711.3,2575.3,2613.6 -0.37106880688506416,0.7709822215887081,1.5707963267948966,1099.1,270.9,270.7,662.9,2551.1,2551.1 -0.3710138942845837,0.7709810013844809,1.7016960206944713,1013.0,254.3,312.7,669.1,2614.4,2672.1 -0.3709669177687928,0.7709671733249817,1.832595714594046,472.1,265.6,393.2,740.4,2538.5,2159.5 -0.3709860888257826,0.7709809123460267,1.9634954084936205,314.5,315.9,578.7,913.6,1744.1,1524.9 -0.37097631741617565,0.7709730189847304,2.0943951023931953,252.3,608.6,752.3,1314.9,1384.0,1256.5 -0.37094957219258723,0.7709225830684168,2.2252947962927703,232.8,750.2,691.5,2612.0,1201.5,1142.9 -0.3709471512277746,0.7709130543553073,2.356194490192345,241.6,692.9,693.5,2520.4,1128.4,1129.2 -0.37094515280806184,0.7709125045911389,2.4870941840919194,275.7,691.4,750.5,2593.0,1143.1,920.8 -0.370957277269915,0.7708762858645739,2.6179938779914944,345.6,753.3,880.9,2455.6,828.9,450.0 -0.3709583752739729,0.7708702157479097,2.748893571891069,474.6,910.9,1131.1,1688.9,534.5,314.6 -0.37098524471374944,0.7708470659999016,2.8797932657906435,739.7,1291.6,1671.3,1337.1,392.4,265.0 -0.37099610138322436,0.7708423890223342,3.010692959690218,669.1,2558.0,2614.7,1163.9,313.5,254.6 -0.3710492142136098,0.8711425126228203,0.0,762.9,2550.6,2550.9,999.0,271.0,271.0 -0.37100980669321676,0.8706699443570858,0.1308996938995747,816.4,2615.7,2675.2,1017.8,254.6,314.0 -0.3710426013035434,0.870680687580818,0.2617993877991494,948.6,2341.5,1961.5,747.9,265.0,392.5 -0.37107985462614534,0.8707047970006325,0.39269908169872414,1215.1,1603.6,1384.5,473.5,315.1,535.8 -0.37110940931498865,0.8707391275357392,0.5235987755982988,1787.7,1268.7,1141.4,345.0,449.2,868.9 -0.3711376133811954,0.8707896976936442,0.6544984694978736,2593.8,1098.9,1039.7,275.6,854.0,794.9 -0.3711431572206296,0.8708202480146308,0.7853981633974483,2521.6,1029.1,1028.5,240.8,793.5,793.1 -0.37114207151376266,0.87088284041642,0.916297857297023,2635.4,1039.2,924.4,255.2,795.0,853.8 -0.37113480405127686,0.870910131644747,1.0471975511965976,1986.5,830.8,450.7,252.4,867.8,995.1 -0.3711272935123712,0.8709212046114758,1.1780972450961724,1389.8,535.7,314.8,313.3,1050.5,1270.0 -0.37108022168362875,0.8709659314624931,1.3089969389957472,1128.9,392.2,264.6,470.7,1490.1,1869.0 -0.3710449954162029,0.8709863555916624,1.4398966328953218,1017.1,313.4,255.0,814.9,2671.6,2613.8 -0.3710666250820556,0.8709822467320201,1.5707963267948966,999.4,271.0,270.7,762.7,2551.7,2550.7 -0.3710117081120257,0.8709810257164572,1.7016960206944713,1013.0,254.3,312.8,772.6,2613.8,2672.5 -0.37096472600071173,0.8709672020034016,1.832595714594046,472.2,265.6,393.2,855.9,2339.1,1960.1 -0.3709838965407667,0.8709809321830202,1.9634954084936205,314.5,315.9,536.8,1055.1,1603.0,1383.7 -0.37097413195429435,0.8709730244555678,2.0943951023931953,252.3,450.5,867.7,1514.2,1268.4,1141.0 -0.3709473928873542,0.8709225842829003,2.2252947962927703,232.8,853.6,795.0,2635.7,1098.1,1039.0 -0.3709449817881191,0.8709130535926548,2.356194490192345,241.6,793.0,793.4,2520.8,1028.5,1029.1 -0.3709430008551846,0.8709125007942728,2.4870941840919194,275.7,795.0,854.2,2593.0,1039.7,920.8 -0.37095513295727717,0.8708762893885442,2.6179938779914944,345.7,869.0,996.4,2256.0,829.1,450.0 -0.3709562464252162,0.8708702245986988,2.748893571891069,474.6,1052.4,1272.5,1547.3,534.6,314.5 -0.37098311806250445,0.8708470849669618,2.8797932657906435,748.4,1491.0,1870.8,1221.6,392.3,265.0 -0.37099397383396193,0.8708424165915072,3.010692959690218,772.6,2673.7,2614.9,1060.4,313.4,254.6 -0.4709978394287316,0.17074780700128067,0.0,63.0,2451.0,2451.4,1699.1,371.1,371.0 -0.4710107743136577,0.17145616089920934,0.1308996938995747,91.5,2512.5,2572.0,1742.7,496.5,233.7 -0.470959004498093,0.1714393607365261,0.2617993877991494,139.5,2784.8,2912.6,947.5,380.6,95.3 -0.4709060129727335,0.17140516053451837,0.39269908169872414,223.8,2592.4,2372.6,614.9,282.3,63.0 -0.47086323097186095,0.1713600191226703,0.5235987755982988,393.3,2077.9,1950.5,460.9,187.5,59.8 -0.4708445689287058,0.17132119645989397,0.6544984694978736,912.6,1823.3,1764.2,379.2,129.5,70.4 -0.4708289051141425,0.17125881620993577,0.7853981633974483,2421.0,1729.0,1728.3,341.0,93.8,93.2 -0.47083051468067777,0.17123353850340517,0.916297857297023,2531.9,1763.7,1312.2,381.6,70.7,129.5 -0.4708465788708595,0.17118207934707064,1.0471975511965976,2863.8,1030.8,650.5,350.0,59.5,186.8 -0.47087851854356744,0.17112791823572215,1.1780972450961724,2381.2,677.4,456.6,224.3,63.3,282.4 -0.4708813652097422,0.17112379047280668,1.3089969389957472,1937.7,508.1,380.3,139.9,95.6,474.8 -0.47090268789226736,0.17111196156336272,1.4398966328953218,1740.9,416.9,358.5,91.1,238.5,1067.0 -0.470983528229072,0.17109219616507132,1.5707963267948966,1698.8,370.9,370.7,63.3,2451.3,2450.9 -0.47098458388923814,0.1710907652157725,1.7016960206944713,1402.8,506.1,238.5,48.6,2510.2,2568.9 -0.47098799984197776,0.1710901713765698,1.832595714594046,671.6,381.2,95.6,47.1,2784.7,2913.2 -0.47104976349093547,0.17112851002886065,1.9634954084936205,455.6,282.4,63.3,63.7,2590.4,2371.1 -0.47107198730333466,0.17115282403535703,2.0943951023931953,367.8,186.8,59.5,117.4,2076.6,1949.8 -0.47106583009127,0.17113875731319306,2.2252947962927703,336.3,129.5,70.7,319.4,1822.4,1763.7 -0.4710727749699996,0.17116730074340647,2.356194490192345,341.6,93.3,93.8,2420.4,1728.1,1729.0 -0.4710695244188695,0.1712032344365384,2.4870941840919194,317.0,70.5,129.6,2490.2,1764.1,1306.3 -0.47107140625127014,0.17119896934191003,2.6179938779914944,117.7,59.9,187.6,2773.1,1028.2,649.2 -0.47105515845594115,0.17121888608051616,2.748893571891069,62.7,62.7,282.7,2537.3,676.1,456.0 -0.47082349133254636,0.1709362926297595,2.8797932657906435,46.5,94.6,473.9,2056.7,508.1,380.6 -0.47084643088316985,0.17092460093928752,3.010692959690218,48.1,234.1,1055.0,1785.4,417.0,358.0 -0.47091764633282196,0.2712360599767314,0.0,163.0,2451.2,2450.7,1598.9,371.0,370.8 -0.47090192429535627,0.2708292277096642,0.1308996938995747,194.9,2512.0,2571.0,1638.9,358.1,417.2 -0.47092708999552524,0.2708371422630773,0.2617993877991494,254.8,2783.3,2911.2,948.4,431.2,294.8 -0.470948223679745,0.27085042262775416,0.39269908169872414,364.9,2452.7,2233.5,615.2,423.6,204.1 -0.4709632819976326,0.2708682448487434,0.5235987755982988,591.3,1963.3,1835.6,460.9,303.1,175.3 -0.4709596061140753,0.27085612172415807,0.6544984694978736,1294.3,1720.4,1661.1,379.3,233.0,173.8 -0.47096873348346313,0.27089966044021074,0.7853981633974483,2421.2,1628.8,1628.4,340.7,193.7,193.0 -0.47096866261886877,0.2709514461639446,0.916297857297023,2531.6,1659.9,1314.6,335.8,174.0,232.6 -0.47096710567678296,0.2709618367575066,1.0471975511965976,2862.8,1031.7,650.9,367.7,174.7,301.8 -0.4709698187979689,0.27095669368098285,1.1780972450961724,2241.3,677.8,456.6,366.0,203.9,422.8 -0.47093612233145976,0.2709890967200528,1.3089969389957472,1848.8,508.1,380.3,255.3,293.9,672.6 -0.4709160348079949,0.2710017066010153,1.4398966328953218,1638.0,416.9,358.4,194.4,625.3,1452.3 -0.4709533024209396,0.2709934758556771,1.5707963267948966,1598.8,370.9,370.6,163.0,2451.6,2451.0 -0.4709131446818403,0.27099227626038735,1.7016960206944713,1406.0,357.7,415.9,151.7,2510.2,2613.4 -0.4708793599629798,0.2709822327902722,1.832595714594046,672.0,380.9,294.7,162.3,2783.7,2912.1 -0.47090982243238755,0.271002238693552,1.9634954084936205,455.8,423.5,204.2,204.8,2451.1,2231.8 -0.4709088057338687,0.27100238652956565,2.0943951023931953,367.9,302.2,174.7,316.1,1988.0,1834.4 -0.4708606197977085,0.27090800497109724,2.2252947962927703,336.4,232.9,173.9,704.0,1719.1,1660.3 -0.47087024986638076,0.27094863149935366,2.356194490192345,341.4,193.1,193.5,2420.4,1628.6,1628.9 -0.47086829998063034,0.27096701160016723,2.4870941840919194,379.0,173.8,232.8,2489.7,1660.6,1309.0 -0.47087824368845327,0.2709390026498588,2.6179938779914944,316.8,175.2,302.7,2772.2,1029.3,649.8 -0.47087732309784897,0.27093705317778727,2.748893571891069,204.0,203.7,423.5,2396.9,676.3,456.0 -0.47090165982668447,0.2709164198736935,2.8797932657906435,162.0,293.7,673.1,1915.7,508.2,380.5 -0.4709098836933281,0.27091311500302595,3.010692959690218,151.5,620.1,1440.9,1681.8,417.0,358.0 -0.4709598057770217,0.3712107122378485,0.0,262.9,2451.1,2451.0,1499.1,371.0,370.9 -0.47089646747216946,0.3707061935086273,0.1308996938995747,298.5,2512.3,2571.5,1535.4,358.1,462.9 -0.4709459606932886,0.37072186379346683,0.2617993877991494,370.3,2783.8,2911.3,948.1,380.5,494.3 -0.470983229171652,0.3707455804717439,0.39269908169872414,506.5,2311.1,2090.9,615.0,456.5,345.3 -0.47100929021248084,0.3707755606489309,0.5235987755982988,790.6,1847.1,1719.9,460.8,418.7,291.0 -0.47103492621474147,0.3708200981846699,0.6544984694978736,1680.0,1616.7,1557.4,379.0,336.5,277.3 -0.47103935317882184,0.37084386891531174,0.7853981633974483,2421.3,1528.7,1528.6,340.8,293.6,292.9 -0.47103908628488594,0.37090023575945064,0.916297857297023,2532.0,1556.7,1313.7,335.8,277.5,336.0 -0.4710340472298578,0.3709221187917566,1.0471975511965976,2863.0,1031.3,650.9,534.1,290.1,417.3 -0.4710296723256485,0.37092865494072047,1.1780972450961724,2099.1,677.5,456.6,454.1,344.9,564.0 -0.4709864258480292,0.3709702594111757,1.3089969389957472,1707.2,508.0,380.2,370.8,493.0,871.8 -0.47095532759953807,0.3709711466565595,1.4398966328953218,1534.6,416.9,358.4,297.7,1014.6,1841.8 -0.4709890292498794,0.37098206563629166,1.5707963267948966,1499.0,370.9,370.6,262.9,2451.6,2451.0 -0.47088325902962136,0.3709816478048584,1.7016960206944713,1405.2,357.8,461.5,255.1,2510.4,2568.6 -0.4708701608097715,0.3709781609468652,1.832595714594046,671.9,381.1,493.7,277.8,2784.4,2912.2 -0.4708983012496469,0.37099712291236187,1.9634954084936205,455.7,457.3,345.3,346.5,2309.3,2090.1 -0.47089047712630794,0.3709904810018836,2.0943951023931953,367.8,417.6,290.2,515.5,1846.5,1718.9 -0.4708639855971195,0.3709397553321838,2.2252947962927703,336.3,336.3,277.4,1091.1,1615.7,1556.9 -0.47086178837244724,0.3709293000033298,2.356194490192345,341.5,293.0,293.4,2420.4,1528.7,1528.6 -0.47086044951294403,0.3709276358170521,2.4870941840919194,379.0,277.3,336.3,2489.8,1557.1,1308.3 -0.4708731731080693,0.3708906894241837,2.6179938779914944,461.0,290.8,418.2,2772.7,1028.9,649.6 -0.47087527057835443,0.3708839926318752,2.748893571891069,345.3,345.0,564.9,2255.3,676.1,456.0 -0.47090285311757196,0.3708605489301886,2.8797932657906435,277.5,493.0,872.6,1800.1,508.1,380.5 -0.4709143850706951,0.37085571882302903,3.010692959690218,255.0,1006.7,1828.2,1578.0,416.9,358.1 -0.47096808704958404,0.47115618194950093,0.0,362.9,2451.2,2451.0,1399.1,370.9,370.9 -0.47094432738991227,0.4706740915293266,0.1308996938995747,402.0,2512.2,2571.5,1431.9,358.1,417.4 -0.4709800287065134,0.4706856043530976,0.2617993877991494,486.0,2784.2,2761.8,948.1,380.5,507.9 -0.47101763839397237,0.4707096706129692,0.39269908169872414,648.3,2169.6,1950.4,614.9,533.8,486.5 -0.47104693875647624,0.47074332988180356,0.5235987755982988,989.8,1732.0,1603.9,460.8,534.3,406.5 -0.47107521967323324,0.4707931271887029,0.6544984694978736,2065.4,1513.0,1453.7,379.1,440.0,380.8 -0.471080869212048,0.47082275786222416,0.7853981633974483,2421.2,1429.1,1428.5,340.8,393.6,392.9 -0.4710802928560173,0.4708847473774267,0.916297857297023,2531.8,1453.2,1313.4,335.8,380.9,439.6 -0.4710736147370522,0.4709116595230125,1.0471975511965976,2786.7,1031.5,650.7,367.7,405.6,532.9 -0.47106658768123566,0.47092233313908105,1.1780972450961724,1957.4,677.6,456.5,454.2,486.1,704.9 -0.4710200478641045,0.4709669846999147,1.3089969389957472,1591.8,508.0,380.2,486.5,692.2,1071.1 -0.47098527808916474,0.47098763335511107,1.4398966328953218,1431.1,416.9,358.4,401.2,1403.8,2231.4 -0.4710072082220481,0.4709833745120593,1.5707963267948966,1399.2,371.0,370.7,363.0,2451.4,2451.3 -0.4709525688794435,0.4709821324031882,1.7016960206944713,1404.8,357.8,416.0,358.7,2636.2,2569.0 -0.4709057924213419,0.47096851672720663,1.832595714594046,671.9,381.1,508.7,393.4,2784.8,2758.9 -0.47092524903187805,0.4709821839899484,1.9634954084936205,455.6,533.4,486.3,488.1,2168.2,1949.5 -0.47091589218844565,0.4709741195093917,2.0943951023931953,367.9,533.2,405.8,715.2,1730.9,1603.4 -0.4708894652495516,0.4709238196044512,2.2252947962927703,336.3,439.8,380.9,1478.0,1512.3,1453.4 -0.4708873872951969,0.4709145029718331,2.356194490192345,341.5,393.0,393.5,2420.4,1428.6,1429.0 -0.47088586743371313,0.47091412740649585,2.4870941840919194,379.1,380.8,439.8,2489.5,1453.6,1308.3 -0.4708981365037294,0.47087833801294643,2.6179938779914944,461.1,406.3,533.9,2772.4,1028.9,649.5 -0.4708995421846188,0.4707207632582866,2.748893571891069,486.7,486.5,706.3,2114.2,676.2,456.0 -0.4708727981328779,0.4708139739819992,2.8797932657906435,393.1,693.1,1072.8,1683.5,507.9,380.5 -0.4708870371003543,0.4708072367180365,3.010692959690218,358.5,1396.0,2218.8,1474.5,416.9,358.1 -0.4709631405292979,0.5711300456808188,0.0,463.0,2451.0,2451.2,1299.2,370.9,371.0 -0.47095516656711084,0.5711299856506198,0.1308996938995747,505.6,2512.1,2572.2,1328.8,358.2,417.3 -0.4709165751364065,0.5711187081876541,0.2617993877991494,601.6,2784.6,2560.0,947.4,380.6,605.3 -0.47087602676033047,0.5710937431516971,0.39269908169872414,790.1,2027.0,1808.3,614.6,515.6,627.4 -0.4708427861423123,0.5710601506357333,0.5235987755982988,1189.8,1615.9,1488.0,460.7,624.2,522.0 -0.4708301915822292,0.5710337494906732,0.6544984694978736,2454.3,1409.5,1350.1,379.1,543.5,484.4 -0.4708173996726452,0.570984001674445,0.7853981633974483,2421.0,1328.9,1328.3,340.8,493.6,493.0 -0.470818979043596,0.570970619030599,0.916297857297023,2531.8,1349.5,1311.8,336.0,484.5,543.2 -0.4708325386051598,0.5709300087721834,1.0471975511965976,2584.7,1030.6,650.4,368.0,521.2,648.7 -0.47085995463720653,0.5708852537839189,1.1780972450961724,1814.8,677.4,456.5,485.5,627.5,846.6 -0.47085676951702315,0.5708887086900023,1.3089969389957472,1475.4,507.9,380.2,602.1,892.4,1271.6 -0.470870855951887,0.5708825276697682,1.4398966328953218,1327.2,416.8,358.5,504.7,1796.4,2509.7 -0.4709436321862767,0.5708663510579046,1.5707963267948966,1298.9,370.9,370.8,463.0,2451.3,2450.8 -0.47093657016428225,0.5708662935795183,1.7016960206944713,1369.9,357.7,416.2,462.2,2510.6,2568.9 -0.4709322217907329,0.5708648755357402,1.832595714594046,671.2,381.1,605.2,509.2,2785.1,2558.2 -0.47098705932804735,0.570900339584018,1.9634954084936205,455.4,515.6,627.4,630.2,2026.0,1807.1 -0.47100386809270933,0.570920198194766,2.0943951023931953,367.7,648.6,521.3,915.6,1614.8,1487.5 -0.4709941943449482,0.5709006304586564,2.2252947962927703,336.3,543.3,484.5,1868.1,1408.5,1349.6 -0.47099966082485506,0.5709231714790752,2.356194490192345,341.5,493.0,493.6,2420.4,1328.6,1329.3 -0.47099693788806096,0.5709533471614194,2.4870941840919194,379.2,484.4,543.6,2489.9,1350.2,1306.1 -0.47100108211904745,0.5709442188430078,2.6179938779914944,486.6,522.1,649.8,2772.8,1028.1,649.1 -0.4709883266669304,0.5709605769178046,2.748893571891069,596.9,628.1,848.3,1971.5,675.8,455.8 -0.47099751132155193,0.5709540028096656,2.8797932657906435,508.5,892.6,1272.4,1568.1,507.9,380.4 -0.47098852073732594,0.5709598286029001,3.010692959690218,462.0,1783.1,2511.5,1371.0,416.9,358.0 -0.4710175962708651,0.6712416592986408,0.0,563.0,2450.6,2451.3,1199.2,371.0,370.9 -0.4709803003063699,0.6706668426776794,0.1308996938995747,609.3,2512.5,2571.4,1224.9,358.1,417.4 -0.4710135841247162,0.670677671508509,0.2617993877991494,717.0,2784.3,2361.4,947.6,380.6,508.0 -0.4710513578740833,0.6707019844265527,0.39269908169872414,931.5,1886.6,1667.0,614.8,456.7,677.3 -0.4710813306378826,0.6707365783938863,0.5235987755982988,1388.5,1500.4,1372.6,460.8,648.2,637.8 -0.47110998235561835,0.670787542840549,0.6544984694978736,2490.2,1305.9,1246.7,379.1,647.1,588.0 -0.47111576857864573,0.6708184804858177,0.7853981633974483,2421.8,1229.3,1228.3,340.8,593.7,592.9 -0.4711149090275536,0.6708815852758523,0.916297857297023,2532.2,1246.3,1304.9,335.9,587.9,646.6 -0.4711077139138896,0.6709094183442308,1.0471975511965976,2386.3,1030.9,650.5,367.9,636.8,764.0 -0.4711000708201602,0.6708885576457866,1.1780972450961724,1673.3,677.4,456.4,454.2,768.4,987.4 -0.4708451350376315,0.6708579787019096,1.3089969389957472,1359.6,507.7,380.2,670.5,1092.3,1471.7 -0.4708596091048001,0.6708511873572909,1.4398966328953218,1223.7,416.7,358.4,608.1,2189.2,2543.2 -0.470938802869709,0.6708336871641121,1.5707963267948966,1198.9,370.9,370.8,563.1,2451.2,2451.2 -0.4709393549558635,0.6708339231469549,1.7016960206944713,1266.7,357.7,416.3,565.7,2510.8,2569.3 -0.4709423439127596,0.6708345649145682,1.832595714594046,670.8,381.1,508.8,625.0,2779.4,2357.0 -0.4710033995289338,0.670873986728395,1.9634954084936205,455.3,457.6,678.8,772.1,1884.3,1665.1 -0.47102477077188126,0.6708989731707655,2.0943951023931953,367.6,650.4,636.8,1116.0,1498.8,1371.8 -0.471018066212785,0.6708848795523965,2.2252947962927703,336.3,646.8,588.0,2258.4,1304.9,1246.1 -0.47102485782246195,0.6709130905173055,2.356194490192345,341.5,593.0,593.6,2420.6,1228.1,1229.0 -0.4710218105949732,0.6709487754570886,2.4870941840919194,379.2,588.0,647.2,2490.0,1246.9,1304.3 -0.47102455195260523,0.6709443623213331,2.6179938779914944,461.3,637.9,765.8,2653.3,1027.2,648.6 -0.4710091554525794,0.6709647103672971,2.748893571891069,616.2,769.8,990.0,1829.3,675.5,455.7 -0.47086730741203237,0.6708103598335813,2.8797932657906435,624.2,1092.4,1472.5,1477.8,507.7,380.4 -0.47089081735361654,0.6707987209142237,3.010692959690218,565.5,2172.1,2511.4,1267.4,416.9,358.1 -0.4709696904129492,0.7711198901965635,0.0,662.9,2451.0,2451.6,1099.0,371.0,371.0 -0.4709623990433355,0.771119935242119,0.1308996938995747,712.9,2512.8,2571.6,1121.5,358.2,417.5 -0.4709238504429446,0.7711087453753187,0.2617993877991494,832.7,2540.4,2161.1,947.1,380.7,508.2 -0.4708831506214055,0.771083769932196,0.39269908169872414,1073.6,1744.5,1525.5,614.6,457.0,677.8 -0.47084976836868275,0.7710501074360903,0.5235987755982988,1588.9,1384.3,1256.5,460.8,736.5,753.2 -0.4708369783111892,0.7710235354484183,0.6544984694978736,2489.9,1202.1,1143.0,379.2,750.5,691.4 -0.4708241321767964,0.7709736379984238,0.7853981633974483,2420.9,1129.0,1128.4,340.8,693.5,692.9 -0.47082564676144634,0.770960030796978,0.916297857297023,2532.0,1142.8,1201.8,336.0,691.4,750.3 -0.4708392258734041,0.7709191987937136,1.0471975511965976,2184.7,1030.2,650.3,368.0,752.4,880.0 -0.4708667711112742,0.7708743469692898,1.1780972450961724,1530.7,677.2,456.4,454.7,909.9,1128.9 -0.47086371316443426,0.7708776957806909,1.3089969389957472,1244.4,507.8,380.3,670.3,1291.4,1670.4 -0.470877940713734,0.7708713894292467,1.4398966328953218,1120.5,416.8,358.4,711.6,2544.9,2509.9 -0.47095088108693706,0.770855309236196,1.5707963267948966,1098.9,370.9,370.6,663.1,2451.4,2450.8 -0.4709439385522877,0.7708553419459145,1.7016960206944713,1163.1,357.8,416.2,669.2,2511.0,2569.1 -0.4709396919211735,0.7708539441308473,1.832595714594046,671.1,381.1,508.8,740.4,2537.4,2158.3 -0.47099456593461747,0.7708895421682571,1.9634954084936205,455.4,457.5,678.7,913.9,1743.7,1524.5 -0.4710113405202635,0.7709095718599792,2.0943951023931953,367.7,738.3,752.3,1315.6,1383.5,1256.0 -0.47100165769640684,0.7708900609653511,2.2252947962927703,336.2,750.2,691.4,2531.4,1201.4,1142.7 -0.47100709703267024,0.7709126432813864,2.356194490192345,341.5,692.9,693.6,2420.3,1128.4,1129.1 -0.4710042800085438,0.7709428948416306,2.4870941840919194,379.2,691.5,750.6,2490.1,1143.0,1202.3 -0.47100843073479515,0.7709337650613413,2.6179938779914944,461.2,753.4,881.1,2455.0,1027.6,648.8 -0.4709955783197187,0.7709501729144281,2.748893571891069,738.3,911.1,1131.2,1688.0,675.6,455.7 -0.4710047687160371,0.7709436159213856,2.8797932657906435,739.6,1292.2,1672.2,1336.9,507.8,380.4 -0.47099577171339924,0.7709494736714795,3.010692959690218,669.1,2559.4,2511.1,1163.9,416.8,358.1 -0.47102484319836374,0.8712313149866413,0.0,762.9,2451.2,2451.0,999.0,370.9,371.0 -0.4709892442677241,0.8706640092217812,0.1308996938995747,816.5,2512.3,2571.7,1017.7,358.2,417.5 -0.4710231401154431,0.8706750524238758,0.2617993877991494,948.3,2342.0,1962.3,947.6,380.6,508.1 -0.47106125619410805,0.8706996281394166,0.39269908169872414,1214.9,1603.8,1384.8,614.8,456.7,720.2 -0.4710914424386596,0.8707345194686211,0.5235987755982988,1787.0,1268.8,1141.3,460.8,725.7,869.0 -0.47112016136718626,0.8707857623665121,0.6544984694978736,2489.9,1098.6,1039.5,379.0,854.2,795.1 -0.47112596448310085,0.8708169894420392,0.7853981633974483,2421.2,1029.1,1028.8,340.8,793.3,792.8 -0.47112501938684515,0.8708803167079708,0.916297857297023,2532.4,1039.3,1098.2,335.9,794.9,853.6 -0.47111769791183017,0.8709083215462916,1.0471975511965976,1986.9,1030.8,650.5,367.9,867.8,995.1 -0.4711099247935237,0.8709199554229701,1.1780972450961724,1389.6,677.5,456.4,454.4,1050.7,1269.6 -0.4710624955425695,0.8709651762077801,1.3089969389957472,1129.0,507.9,380.3,807.8,1489.6,1868.5 -0.47102681677252517,0.8709860172489692,1.4398966328953218,1017.0,416.9,358.4,815.1,2568.0,2509.6 -0.47104791442065963,0.8709820207828791,1.5707963267948966,999.0,371.0,370.7,762.9,2451.5,2450.9 -0.4709924939102929,0.8709807914113756,1.7016960206944713,1059.4,357.8,416.2,772.4,2510.4,2569.0 -0.4709450444556431,0.8709668946852542,1.832595714594046,671.7,381.1,508.8,855.9,2339.9,1960.5 -0.47096385846324085,0.8709803401126603,1.9634954084936205,455.6,457.5,719.8,1055.0,1603.0,1384.0 -0.47095389110074304,0.8709720359496729,2.0943951023931953,367.8,724.3,867.9,1514.1,1268.1,1141.1 -0.47092703731528474,0.8709212564383111,2.2252947962927703,336.3,853.8,795.0,2555.7,1098.1,1039.4 -0.47092463693893455,0.8709113931657493,2.356194490192345,341.6,792.9,793.5,2420.8,1028.5,1029.0 -0.47092282220889625,0.870910511316187,2.4870941840919194,379.1,795.0,854.0,2490.2,1039.6,1098.6 -0.4709351058862784,0.8708741007603946,2.6179938779914944,461.2,868.8,996.4,2257.3,1028.5,649.2 -0.470936499743842,0.8708678673764001,2.748893571891069,615.8,1052.1,1272.0,1547.6,675.9,456.0 -0.4709635700397322,0.8708446625134711,2.8797932657906435,855.3,1490.6,1870.5,1221.4,508.0,380.5 -0.47097461578753885,0.8708399773937956,3.010692959690218,772.5,2570.5,2511.1,1060.6,417.0,358.1 -0.5709784603585101,0.17074567345937974,0.0,63.0,2351.0,2351.0,1698.8,470.9,471.0 -0.571001667921719,0.17145558904580138,0.1308996938995747,91.5,2408.9,2468.4,1742.6,507.2,233.7 -0.5709520102485877,0.17143943192205446,0.2617993877991494,139.5,2669.0,2796.6,1146.8,474.8,95.3 -0.5708994852461204,0.17140550238877061,0.39269908169872414,223.8,2592.2,2372.6,756.0,282.3,63.0 -0.5708567396333584,0.17136035647922387,0.5235987755982988,393.3,2077.8,1950.4,576.4,187.5,59.8 -0.5708380346885137,0.1713213916348375,0.6544984694978736,912.7,1823.1,1763.9,482.7,129.5,70.5 -0.5708223743020134,0.17125883518588392,0.7853981633974483,2321.5,1728.7,1728.2,440.9,93.8,93.2 -0.570824023237267,0.17123337802977212,0.916297857297023,2428.0,1763.4,1699.2,439.5,70.7,129.4 -0.5708401691656022,0.17118176594614054,1.0471975511965976,2748.2,1230.6,850.4,393.8,59.5,186.8 -0.5708722231424795,0.17112750421868284,1.1780972450961724,2380.7,819.2,598.3,224.3,63.4,282.4 -0.5708751859257072,0.1711233040688085,1.3089969389957472,1937.8,623.5,496.0,139.9,95.6,474.8 -0.5708966231354445,0.1711114218858656,1.4398966328953218,1741.0,520.3,462.0,91.1,238.5,1067.1 -0.5709775759679953,0.17109165475528365,1.5707963267948966,1698.8,471.0,470.8,63.3,2351.0,2350.9 -0.5709787300535317,0.1710902316031091,1.7016960206944713,1783.6,506.8,238.4,48.6,2407.4,2465.6 -0.5709822384468274,0.17108964248262448,1.832595714594046,870.8,474.8,95.6,47.1,2669.3,2797.0 -0.571044083483175,0.17112801422409185,1.9634954084936205,596.7,282.5,63.3,63.7,2590.4,2371.2 -0.5710663752542009,0.1711523792084464,2.0943951023931953,483.3,186.8,59.5,117.4,2076.5,1949.2 -0.5710602851454936,0.17113835902780594,2.2252947962927703,439.8,129.5,70.7,319.5,1822.4,1763.5 -0.5710672841977411,0.17116696287701005,2.356194490192345,441.5,93.3,93.8,2320.8,1728.0,1728.9 -0.5710640598396672,0.17120297639858673,2.4870941840919194,317.0,70.5,129.6,2386.3,1764.2,1691.6 -0.5710659616737296,0.17119878541085365,2.6179938779914944,117.7,59.9,187.6,2657.5,1227.3,848.1 -0.5710496910080923,0.17121878388274614,2.748893571891069,62.7,62.7,282.7,2537.1,817.2,597.2 -0.5708190197851167,0.17093657628890302,2.8797932657906435,46.5,94.6,473.9,2031.3,623.7,496.1 -0.5708422460610186,0.17092473784634366,3.010692959690218,48.1,234.1,1054.8,1785.5,520.4,461.5 -0.5709137931899618,0.2712364840063817,0.0,163.0,2351.5,2351.3,1598.9,471.0,470.8 -0.5709006798566961,0.27123562975450866,0.1308996938995747,194.9,2408.8,2468.4,1638.9,461.6,520.8 -0.5708576026550252,0.27122235839092257,0.2617993877991494,254.7,2668.2,2795.3,1148.3,496.0,294.8 -0.5708136190464768,0.2711945294882858,0.39269908169872414,364.9,2452.1,2233.4,756.5,423.6,204.1 -0.5707779107042293,0.27115750223671675,0.5235987755982988,591.4,1963.4,1835.5,576.5,303.2,175.3 -0.5707642382202026,0.27112773488144737,0.6544984694978736,1294.3,1720.5,1660.8,482.8,233.0,173.8 -0.5707509570603377,0.271074505183317,0.7853981633974483,2321.3,1629.1,1628.4,440.7,193.7,193.0 -0.5707530695555709,0.27105822629463017,0.916297857297023,2428.7,1660.1,1702.8,439.4,174.0,232.7 -0.5707676514357937,0.27101515163321177,1.0471975511965976,2747.3,1231.6,850.9,483.2,174.8,301.9 -0.5707962794856581,0.2709680443155531,1.1780972450961724,2240.8,819.7,598.5,366.2,204.1,423.0 -0.5707946897643247,0.2709698329677448,1.3089969389957472,1823.1,623.8,496.0,255.5,294.2,672.9 -0.5708105657451588,0.27096268761600295,1.4398966328953218,1638.0,520.4,461.9,194.4,625.8,1452.7 -0.5708851699833172,0.27094533959083167,1.5707963267948966,1598.7,471.0,470.6,163.1,2351.2,2351.2 -0.570880024007049,0.27094472463884256,1.7016960206944713,1679.9,461.2,519.3,151.9,2406.5,2590.9 -0.5708775079317213,0.2709435538685325,1.832595714594046,871.4,496.5,294.9,162.4,2668.6,2795.7 -0.5709341831934552,0.2709793466241903,1.9634954084936205,597.1,423.6,204.3,205.0,2451.0,2231.5 -0.5709527137988617,0.2709997872025911,2.0943951023931953,483.4,302.3,174.8,316.3,1962.1,1834.8 -0.5709442124943682,0.2709815002601834,2.2252947962927703,439.7,233.0,174.0,704.3,1719.4,1660.5 -0.5709504200496127,0.27100555643308755,2.356194490192345,441.4,193.2,193.6,2320.4,1628.1,1629.0 -0.5709481653076127,0.27103713194676327,2.4870941840919194,482.5,173.9,232.8,2386.7,1660.5,1695.1 -0.5709519199359836,0.2710295340622184,2.6179938779914944,317.0,175.3,302.8,2656.8,1228.6,849.0 -0.5709387501014566,0.2710469623847134,2.748893571891069,204.1,203.8,423.5,2397.3,817.9,597.6 -0.5709468626910238,0.27104119877793886,2.8797932657906435,162.0,293.9,673.2,1915.5,623.6,496.1 -0.5709367081136589,0.27104735888409626,3.010692959690218,151.6,620.2,1441.2,1681.8,520.5,461.5 -0.5709644086227187,0.3713280465621578,0.0,263.0,2350.9,2351.1,1499.0,471.0,470.8 -0.5709255766726107,0.37068862340543207,0.1308996938995747,298.4,2408.5,2467.6,1535.4,461.6,520.9 -0.5709563324410106,0.37069851489327776,0.2617993877991494,370.3,2668.4,2795.2,1148.0,587.1,494.4 -0.5710330995390984,0.3707432844034426,0.39269908169872414,506.4,2311.4,2092.1,756.5,564.9,345.3 -0.5710399412396308,0.3707524694747415,0.5235987755982988,790.3,1847.5,1719.8,576.5,418.8,290.9 -0.5710647986743125,0.3707954294269722,0.6544984694978736,1678.4,1616.4,1557.6,482.7,336.5,277.3 -0.571070648924486,0.3708252812159718,0.7853981633974483,2321.7,1529.1,1528.5,440.8,293.6,292.9 -0.5710702021613454,0.37088998142474927,0.916297857297023,2428.3,1556.9,1615.4,439.3,277.4,336.0 -0.571062735676623,0.37092013126727164,1.0471975511965976,2747.0,1231.4,850.9,534.0,290.1,417.2 -0.5710540194314191,0.37093362277725705,1.1780972450961724,2099.2,819.6,598.3,507.8,344.9,563.6 -0.5710052712313531,0.37098049598686766,1.3089969389957472,1732.7,623.8,496.0,370.9,492.8,871.6 -0.5709679426029218,0.3710026936178348,1.4398966328953218,1534.8,520.4,461.9,297.7,1013.9,1840.6 -0.5709871453562182,0.3709989867033585,1.5707963267948966,1498.9,471.0,470.7,263.0,2351.5,2350.8 -0.5709299684821532,0.37099761748740034,1.7016960206944713,1576.6,461.0,519.3,255.1,2406.3,2464.9 -0.5708809290357522,0.370983363793443,1.832595714594046,871.5,586.4,494.0,277.7,2668.8,2796.0 -0.5709385342222004,0.37101692966282074,1.9634954084936205,596.9,564.6,345.2,346.4,2309.9,2090.7 -0.5709073679271743,0.37098496040162887,2.0943951023931953,483.4,417.7,290.2,515.4,1846.6,1744.8 -0.570877275523253,0.3709275529672209,2.2252947962927703,439.9,336.3,277.4,1090.2,1615.8,1556.9 -0.5708752647328339,0.3709179686158872,2.356194490192345,441.5,293.0,293.4,2320.6,1528.7,1529.3 -0.5708738743041658,0.37091962312943383,2.4870941840919194,533.0,277.3,336.2,2386.2,1557.1,1616.0 -0.570885445829797,0.3708864301261656,2.6179938779914944,516.1,290.7,418.2,2656.1,1228.5,849.1 -0.570885590567253,0.37088301971894366,2.748893571891069,345.5,345.0,564.8,2255.7,817.9,597.5 -0.5709105141290011,0.370862117424275,2.8797932657906435,277.5,492.9,872.2,1800.1,623.7,496.1 -0.5709190539774354,0.3708589499792898,3.010692959690218,255.0,1006.1,1827.0,1578.5,520.5,461.6 -0.570969083563015,0.4711566242642886,0.0,362.8,2351.1,2351.3,1399.2,470.9,470.9 -0.5709379051192305,0.47066965295712926,0.1308996938995747,402.0,2408.5,2467.8,1431.8,461.7,520.8 -0.5709725937487928,0.47068084293606116,0.2617993877991494,485.9,2668.5,2795.9,1148.0,496.0,623.4 -0.57101045494928,0.4707050363569778,0.39269908169872414,648.1,2169.7,1950.3,756.4,598.1,486.6 -0.5710402193175148,0.47073914641612835,0.5235987755982988,989.7,1732.0,1604.0,576.5,534.4,406.7 -0.5710689123138742,0.4707895843693719,0.6544984694978736,2064.5,1512.9,1453.8,482.7,440.1,380.8 -0.5710747653635704,0.4708199076991535,0.7853981633974483,2321.4,1429.0,1428.5,440.8,393.6,392.9 -0.5710742421347176,0.47088261160215006,0.916297857297023,2428.1,1453.2,1511.6,439.4,380.9,439.6 -0.5710506104765765,0.47096487270280574,1.0471975511965976,2747.7,1231.2,850.6,483.3,405.7,532.7 -0.5710641429193555,0.4709428662202704,1.1780972450961724,1957.1,819.5,598.4,595.2,486.0,704.9 -0.5709870019483247,0.4710147980072561,1.3089969389957472,1591.6,623.7,496.0,486.5,692.0,1070.8 -0.5709484120995145,0.4710388895651383,1.4398966328953218,1431.1,520.4,461.9,401.2,1403.6,2230.5 -0.5709984961976071,0.47102821438308173,1.5707963267948966,1399.1,470.9,470.6,362.9,2351.3,2350.7 -0.570944066363113,0.47102703029606174,1.7016960206944713,1473.0,461.1,519.5,358.6,2406.7,2465.2 -0.5708892547054368,0.47101105770838814,1.832595714594046,871.4,496.6,624.2,393.3,2668.6,2796.3 -0.5708996467179308,0.47101905365691055,1.9634954084936205,596.9,599.0,486.5,488.0,2169.0,1948.8 -0.570883010717843,0.4710031248728763,2.0943951023931953,483.3,533.1,405.7,715.0,1730.9,1603.1 -0.5708518331904132,0.47094392838403687,2.2252947962927703,439.9,439.9,380.9,1477.2,1512.1,1453.7 -0.570847628582231,0.47092533490393684,2.356194490192345,441.5,392.9,393.4,2320.5,1428.6,1429.0 -0.5708464848494726,0.47091607417986125,2.4870941840919194,482.5,380.7,439.7,2386.1,1453.8,1512.5 -0.5708472629957819,0.47091772105128715,2.6179938779914944,576.6,406.3,533.9,2656.8,1228.7,848.9 -0.5708700910815483,0.4708782722402529,2.748893571891069,486.9,486.4,706.2,2114.2,817.8,597.5 -0.570907245714777,0.4708459045714226,2.8797932657906435,393.0,692.3,1071.7,1684.3,623.7,496.1 -0.5709229934350738,0.4708388748638064,3.010692959690218,358.4,1393.0,2214.6,1474.8,520.5,461.6 -0.5709788245711132,0.5711397329290375,0.0,462.8,2351.5,2350.7,1299.1,471.0,470.8 -0.5709510006608456,0.5706709119177682,0.1308996938995747,505.6,2408.3,2467.9,1328.4,461.7,520.8 -0.5709862817343075,0.5706823133545884,0.2617993877991494,601.5,2669.1,2562.0,1147.6,496.1,623.5 -0.5710240842780311,0.5707065303961314,0.39269908169872414,789.8,2028.2,1808.8,756.2,674.9,627.7 -0.5710536651494447,0.5707405334817182,0.5235987755982988,1189.0,1616.1,1488.4,576.4,650.0,522.2 -0.5710821236510388,0.5707907501866103,0.6544984694978736,2386.7,1409.5,1350.4,482.7,543.6,484.4 -0.5710878482170859,0.5708208368140988,0.7853981633974483,2321.0,1329.2,1328.2,440.7,493.6,493.0 -0.5710872157949352,0.5708832383417484,0.916297857297023,2428.3,1349.6,1408.8,439.3,484.3,543.2 -0.5710803896682085,0.5709105064841398,1.0471975511965976,2586.9,1231.0,850.4,483.3,521.1,648.3 -0.5710731570185456,0.5709214808864627,1.1780972450961724,1815.7,819.4,598.3,595.3,627.2,846.1 -0.5710263654464607,0.5709663385886272,1.3089969389957472,1476.2,623.6,496.0,602.1,891.4,1270.3 -0.5709913238475138,0.5709871003958957,1.4398966328953218,1327.7,520.3,461.8,504.7,1793.3,2406.8 -0.5710129848755648,0.5709829169703882,1.5707963267948966,1299.0,471.0,470.6,462.9,2351.7,2351.5 -0.5709580921989443,0.5709816771017531,1.7016960206944713,1369.7,461.2,519.5,462.1,2407.0,2465.1 -0.5709110911331122,0.5709679907327974,1.832595714594046,871.3,496.7,624.2,509.0,2669.1,2560.0 -0.5709303481156117,0.5709815630757094,1.9634954084936205,597.0,674.7,627.7,629.8,2027.2,1807.6 -0.5709208243973022,0.5709733801577968,2.0943951023931953,483.4,648.6,521.3,914.8,1615.3,1487.8 -0.5708942841894195,0.5709229202828434,2.2252947962927703,439.9,543.3,484.4,1864.8,1408.7,1349.8 -0.5708921367707637,0.5709134296142995,2.356194490192345,441.6,493.0,493.5,2320.7,1328.4,1329.3 -0.5708905807398367,0.5709128880923282,2.4870941840919194,482.7,484.3,543.2,2385.8,1349.8,1409.4 -0.5709028773801517,0.5708769302989545,2.6179938779914944,671.4,521.9,649.5,2656.8,1228.2,848.9 -0.5709043287220598,0.570871057560788,2.748893571891069,628.2,627.9,847.7,1972.3,817.6,597.4 -0.570931204231781,0.570848209922638,2.8797932657906435,508.6,892.0,1271.2,1568.7,623.7,496.1 -0.5709419823145487,0.5708437791498566,3.010692959690218,462.1,1780.5,2407.9,1371.2,520.6,461.5 -0.5709948106321077,0.6711436163424349,0.0,562.8,2351.5,2351.1,1199.2,471.0,470.9 -0.570963505076709,0.6706696726251806,0.1308996938995747,609.2,2408.7,2467.9,1224.8,461.7,520.9 -0.570998129274647,0.6706808953141865,0.2617993877991494,717.1,2668.8,2362.6,1147.5,496.1,623.5 -0.5710358907378351,0.6707051371116586,0.39269908169872414,931.5,1886.7,1667.3,756.1,657.2,768.9 -0.5710655685886881,0.6707393195229032,0.5235987755982988,1388.2,1500.5,1372.9,576.5,765.4,637.7 -0.5710940511742579,0.6707897528682052,0.6544984694978736,2386.4,1305.8,1246.9,482.7,647.1,588.0 -0.5710997740100382,0.6708200902110424,0.7853981633974483,2320.9,1229.0,1228.5,440.8,593.5,592.9 -0.5710990442981719,0.6708826806763692,0.916297857297023,2428.7,1246.1,1305.1,439.5,587.8,646.7 -0.5710920876582556,0.6709100884474899,1.0471975511965976,2386.6,1230.9,850.4,483.3,636.6,763.7 -0.5710847297529067,0.670921193938046,1.1780972450961724,1673.6,819.3,598.3,626.4,768.3,987.2 -0.5710377949135875,0.6709661080806608,1.3089969389957472,1360.7,623.7,495.8,717.6,1090.7,1469.5 -0.5710026184778837,0.6709868561012489,1.4398966328953218,1224.1,520.3,461.8,608.1,2183.0,2532.8 -0.5710241715353545,0.6709827133349437,1.5707963267948966,1199.2,471.0,470.6,563.0,2351.1,2351.0 -0.5709691782986571,0.6709814768990112,1.7016960206944713,1266.2,461.2,519.5,565.5,2406.6,2465.7 -0.5709220950525911,0.6709677401356919,1.832595714594046,871.0,496.7,624.3,624.6,2668.6,2360.3 -0.5709412618808257,0.6709813024098803,1.9634954084936205,596.8,656.9,768.7,771.5,1885.8,1666.5 -0.5709316346829604,0.6709731203080724,2.0943951023931953,483.3,764.1,637.0,1114.4,1499.7,1372.2 -0.5709050183580547,0.6709226028833037,2.2252947962927703,439.9,646.8,587.9,2252.6,1305.0,1246.5 -0.5709028004970667,0.6709130394495606,2.356194490192345,441.5,593.0,593.5,2320.5,1228.4,1229.0 -0.5709011595301916,0.6709124330780099,2.4870941840919194,482.7,587.9,646.9,2385.8,1246.6,1305.8 -0.5709134388764614,0.670876368878869,2.6179938779914944,576.8,637.5,765.3,2656.8,1228.2,848.7 -0.570914850695073,0.6708704116907507,2.748893571891069,738.6,769.2,989.2,1830.8,817.5,597.4 -0.570941762003451,0.6708474718508504,2.8797932657906435,624.2,1091.6,1471.4,1453.0,623.6,496.1 -0.5709525968128042,0.6708429727682037,3.010692959690218,565.6,2167.5,2517.6,1267.7,520.5,461.6 -0.5710055299104649,0.771142903014169,0.0,662.9,2351.3,2350.6,1099.1,471.0,470.8 -0.5709725969283587,0.7706696484117819,0.1308996938995747,712.9,2409.0,2468.2,1121.3,461.7,520.9 -0.5710068691522727,0.7706807794708324,0.2617993877991494,832.6,2542.1,2161.6,1147.2,496.1,623.5 -0.5710445402641984,0.77070500128786,0.39269908169872414,1073.0,1745.5,1525.9,756.1,598.3,818.9 -0.571074201852702,0.7707392213373678,0.5235987755982988,1587.6,1384.7,1257.0,576.5,881.4,753.4 -0.5711026350005707,0.7707896913550405,0.6544984694978736,2386.7,1202.3,1143.2,482.6,750.6,691.5 -0.5711083251072453,0.7708200807914758,0.7853981633974483,2321.5,1129.1,1128.5,440.8,693.5,692.8 -0.5711075252487041,0.7708826814122802,0.916297857297023,2428.3,1142.7,1201.4,439.4,691.4,750.2 -0.5711005049961637,0.7709100750840403,1.0471975511965976,2186.5,1230.7,850.3,483.3,752.2,879.6 -0.5710931127210253,0.7709211814542116,1.1780972450961724,1531.6,819.2,598.2,595.4,909.4,1128.6 -0.5710461454100935,0.77096606426085,1.3089969389957472,1244.7,623.6,495.9,833.2,1289.7,1669.2 -0.5710109528609731,0.7709867522568197,1.4398966328953218,1120.5,520.3,462.0,711.5,2465.3,2406.7 -0.5710325143432372,0.770982617830229,1.5707963267948966,1099.1,470.9,470.6,663.0,2351.1,2351.1 -0.5709775298517614,0.770981384406497,1.7016960206944713,1162.8,461.2,519.6,668.9,2407.0,2465.2 -0.5709304608677033,0.7709676290663174,1.832595714594046,871.0,496.7,624.3,740.3,2539.6,2160.6 -0.5709496237134983,0.7709812215265275,1.9634954084936205,596.8,599.1,820.0,913.2,1744.6,1525.3 -0.5709399660038574,0.7709730896980009,2.0943951023931953,483.4,879.7,752.5,1314.1,1383.8,1256.6 -0.5709133232868296,0.7709225834151017,2.2252947962927703,439.8,750.3,691.5,2428.2,1201.6,1142.9 -0.5709110664363135,0.7709130221864273,2.356194490192345,441.6,693.0,693.5,2320.4,1128.5,1129.0 -0.5709093588445321,0.7709124222685146,2.4870941840919194,482.6,691.3,750.5,2386.4,1143.1,1202.3 -0.5709216103596808,0.7708763255967956,2.6179938779914944,576.7,753.1,880.7,2456.9,1228.0,848.7 -0.5709229655071625,0.7708703443462324,2.748893571891069,757.0,910.6,1130.6,1688.7,817.6,597.4 -0.5709498714152387,0.7708473631397315,2.8797932657906435,739.7,1291.1,1670.8,1362.5,623.6,496.2 -0.570960713010642,0.770842829509452,3.010692959690218,669.1,2466.5,2408.0,1164.2,520.5,461.6 -0.571013682766943,0.8711427977211685,0.0,763.0,2351.2,2350.8,999.1,470.9,470.9 -0.5709795366801871,0.8706696953878963,0.1308996938995747,816.4,2408.8,2467.8,1017.9,461.8,521.0 -0.5710135384862689,0.8706807557534113,0.2617993877991494,948.4,2342.5,1962.5,1128.6,496.1,623.6 -0.571051134540344,0.8707049583672732,0.39269908169872414,1214.8,1604.5,1384.8,756.1,598.3,818.9 -0.5710807780044336,0.870739200896878,0.5235987755982988,1786.9,1269.1,1141.3,576.5,847.3,869.1 -0.5711091694800232,0.8707896915279498,0.6544984694978736,2386.6,1098.7,1039.6,482.7,854.1,795.1 -0.5711148328004805,0.870820112965063,0.7853981633974483,2321.4,1029.2,1028.5,440.8,793.4,792.9 -0.5711139795523769,0.8708827139066186,0.916297857297023,2428.5,1039.3,1098.1,439.5,795.0,853.7 -0.5711069126549112,0.8709100901200049,1.0471975511965976,1987.2,1140.9,850.1,483.4,867.7,994.9 -0.571099497462565,0.870921191644012,1.1780972450961724,1389.7,819.3,598.2,595.4,1050.6,1269.8 -0.5710525095633672,0.8709660463542441,1.3089969389957472,1128.9,623.5,495.9,868.8,1489.3,1868.3 -0.5710173094879663,0.8709866857129414,1.4398966328953218,1017.2,520.3,461.8,815.0,2488.1,2406.6 -0.5710388824282023,0.8709825563423992,1.5707963267948966,998.9,470.9,470.7,762.9,2351.5,2351.3 -0.5709839093646476,0.8709813251980689,1.7016960206944713,1059.3,461.2,519.6,772.4,2406.7,2465.5 -0.5709368555612242,0.8709675567495385,1.832595714594046,870.9,496.7,624.4,855.7,2339.9,1960.6 -0.5709560189786103,0.870981174358157,1.9634954084936205,596.8,599.1,820.0,1054.9,1603.3,1384.2 -0.5709463406607284,0.8709730836892071,2.0943951023931953,483.3,849.5,867.9,1513.9,1268.2,1140.9 -0.5709196795332573,0.8709225889915793,2.2252947962927703,439.8,853.9,795.0,2554.7,1098.4,1039.2 -0.5709173936926355,0.8709130326674592,2.356194490192345,441.5,793.0,793.5,2320.8,1028.7,1029.1 -0.5709156350704339,0.870912440783695,2.4870941840919194,482.7,794.9,854.0,2386.7,1039.7,1098.6 -0.5709278644618704,0.8708763219994626,2.6179938779914944,576.7,868.8,996.4,2257.4,1141.3,848.8 -0.5709291748094687,0.8708703245720566,2.748893571891069,879.9,1052.1,1271.9,1547.5,817.5,597.4 -0.5709560747422011,0.8708473133263863,2.8797932657906435,855.3,1490.6,1870.3,1221.4,623.6,496.1 -0.570966919482447,0.8708427542242454,3.010692959690218,772.6,2466.7,2408.2,1060.6,520.4,461.6 -0.6709707873668148,0.17074776384330548,0.0,63.0,2250.8,2250.9,1699.2,571.0,570.9 -0.6709979698961717,0.17145597964966441,0.1308996938995747,91.6,2305.2,2341.4,1743.0,565.4,233.6 -0.6709490218697263,0.17144003594531476,0.2617993877991494,139.5,2553.6,2680.7,1346.3,474.9,95.3 -0.6708966047087308,0.1714061628905399,0.39269908169872414,223.8,2591.8,2372.3,897.2,282.3,63.0 -0.6708538243927383,0.1713609591137495,0.5235987755982988,393.3,2078.0,1950.3,692.0,187.5,59.8 -0.6708350728244493,0.17132187913370678,0.6544984694978736,912.6,1823.1,1763.9,586.3,129.5,70.4 -0.6708194023298641,0.1712591945551225,0.7853981633974483,2220.5,1729.0,1728.5,541.0,93.8,93.2 -0.6708210694371309,0.17123361141297555,0.916297857297023,2324.7,1763.4,1822.4,543.1,70.7,129.5 -0.6708372629972753,0.1711818900135853,1.0471975511965976,2632.6,1430.0,1049.7,393.8,59.5,186.8 -0.670869387635832,0.17112754938706098,1.1780972450961724,2380.8,960.9,739.9,224.4,63.3,282.5 -0.6708724273271532,0.17112329087891043,1.3089969389957472,1937.7,739.1,611.7,139.9,95.6,474.9 -0.6708939444565025,0.1711113669490223,1.4398966328953218,1740.8,623.7,565.4,91.1,238.5,1067.1 -0.6709749781815344,0.17109159022501474,1.5707963267948966,1698.7,571.1,570.6,63.3,2251.3,2251.4 -0.6709762055020054,0.17109016973506597,1.7016960206944713,1783.6,564.6,238.4,48.6,2303.4,2361.7 -0.6709797818777351,0.1710895888049122,1.832595714594046,1070.1,474.8,95.6,47.1,2553.8,2681.2 -0.671041685885715,0.17112798804400065,1.9634954084936205,737.8,282.4,63.3,63.7,2590.3,2371.2 -0.6710640248445349,0.1711523929881873,2.0943951023931953,598.9,186.8,59.5,117.4,2076.7,1949.2 -0.6710579754978108,0.1711384128289566,2.2252947962927703,543.3,129.5,70.7,319.5,1822.1,1763.5 -0.6710650033438126,0.17116706383664648,2.356194490192345,541.4,93.3,93.8,2220.7,1728.3,1728.7 -0.671061789193975,0.1712031324000085,2.4870941840919194,316.9,70.5,129.6,2282.7,1763.9,1823.2 -0.6710636938963184,0.17119899102083247,2.6179938779914944,117.6,59.9,187.6,2541.3,1426.3,1047.6 -0.6710474028551073,0.17121903923744153,2.748893571891069,62.7,62.7,282.7,2536.4,958.5,738.6 -0.6710523899302073,0.1712145784789918,2.8797932657906435,46.6,95.0,474.8,2030.3,738.9,611.6 -0.6710391175898099,0.17122097567519234,3.010692959690218,48.2,235.2,1058.2,1784.9,623.8,565.1 -0.6710639347547702,0.27149942504227065,0.0,163.2,2251.0,2251.2,1598.7,571.0,571.0 -0.6710102610980251,0.2707322127004115,0.1308996938995747,195.0,2305.4,2364.5,1639.0,565.3,617.3 -0.6710329491393144,0.27073965843381287,0.2617993877991494,254.9,2553.1,2680.8,1346.5,611.8,294.5 -0.671062752770731,0.270758916142706,0.39269908169872414,365.2,2450.8,2232.1,897.1,423.3,204.0 -0.6710869987160331,0.2707873509257679,0.5235987755982988,592.1,1962.8,1835.2,692.1,303.0,175.2 -0.6711119472119327,0.27068608122418003,0.6544984694978736,1297.3,1720.0,1661.0,586.1,232.9,173.8 -0.6711194567575319,0.27086623946375754,0.7853981633974483,2221.3,1629.0,1628.4,540.8,193.6,193.0 -0.67111881064989,0.27091544520131716,0.916297857297023,2325.1,1660.3,1719.3,542.9,173.9,232.7 -0.6711136185623773,0.27093591358981395,1.0471975511965976,2631.9,1430.1,1049.9,593.1,174.7,302.0 -0.6711086401012372,0.270942783176793,1.1780972450961724,2239.5,960.9,739.9,365.7,204.0,423.1 -0.6710643729242055,0.2709847538948911,1.3089969389957472,1822.7,739.1,611.5,255.1,294.2,673.3 -0.6710321621782097,0.2710034580531615,1.4398966328953218,1638.0,623.8,565.4,194.2,626.7,1455.3 -0.6710568890600811,0.2709984458710404,1.5707963267948966,1599.1,571.0,570.8,162.9,2251.6,2251.0 -0.6710049054329307,0.2709971449375983,1.7016960206944713,1680.5,564.7,541.1,151.7,2303.1,2361.9 -0.6709605735160531,0.2709839839750394,1.832595714594046,1069.9,612.4,294.2,162.3,2553.6,2681.2 -0.6709820160308821,0.27099894036837413,1.9634954084936205,737.9,423.1,204.0,204.9,2449.5,2230.3 -0.6709739951883716,0.27099265916156545,2.0943951023931953,599.0,302.0,174.7,316.4,1961.5,1834.3 -0.6709483832777293,0.2709441264645229,2.2252947962927703,543.4,232.7,173.9,705.4,1718.9,1660.1 -0.6709465034068646,0.2709366124767265,2.356194490192345,541.6,193.0,193.5,2220.1,1628.6,1628.7 -0.670944504302299,0.27093798505268096,2.4870941840919194,586.3,173.7,232.8,2282.5,1660.9,1720.0 -0.67095608509768,0.27090348946393883,2.6179938779914944,316.4,175.2,302.8,2541.3,1426.7,1048.0 -0.67095629919388,0.27089879557230545,2.748893571891069,203.8,203.8,423.7,2395.9,958.7,738.9 -0.6709819840746899,0.270876633969094,2.8797932657906435,161.9,294.0,673.7,1915.2,739.0,611.6 -0.6709915399682957,0.2708725198050701,3.010692959690218,151.5,621.3,1444.2,1681.6,623.9,565.2 -0.6710431318837219,0.37117145600200474,0.0,262.8,2251.4,2250.7,1499.3,571.1,571.0 -0.6710031329348032,0.3706759214310187,0.1308996938995747,298.6,2305.5,2364.9,1535.6,565.3,624.6 -0.6710351802153933,0.3706864045997349,0.2617993877991494,370.5,2553.6,2680.4,1346.4,611.8,493.9 -0.6710717820076381,0.37071006046262567,0.39269908169872414,506.8,2309.4,2090.7,897.1,564.4,345.3 -0.6711008438068673,0.3707438015024891,0.5235987755982988,791.2,1846.9,1719.4,692.1,418.5,290.9 -0.6711287770944263,0.3707937440473139,0.6544984694978736,1682.7,1616.5,1557.4,586.2,336.4,277.2 -0.6711342083138586,0.3708236405438228,0.7853981633974483,2221.2,1528.8,1528.8,540.7,293.5,293.0 -0.6711331978277715,0.37088565131388096,0.916297857297023,2324.9,1556.6,1615.4,543.0,277.4,336.2 -0.6711261335278206,0.37091244114074695,1.0471975511965976,2632.5,1429.9,1049.7,599.0,290.2,417.5 -0.671118905835343,0.3709230866418458,1.1780972450961724,2098.3,960.8,739.9,507.3,345.1,564.2 -0.6710721841078654,0.37096751920388393,1.3089969389957472,1706.7,739.3,611.5,370.7,493.4,872.6 -0.6710373383057773,0.37098778099383756,1.4398966328953218,1534.2,623.7,565.3,297.6,1016.2,1844.7 -0.6710988681734135,0.37097221721376683,1.5707963267948966,1499.2,570.9,570.7,262.9,2251.4,2250.9 -0.6710165742829449,0.37096996348885236,1.7016960206944713,1576.8,564.8,623.0,255.2,2303.4,2361.8 -0.6709643885835652,0.3709545311687177,1.832595714594046,1070.1,612.4,493.3,277.9,2553.4,2680.8 -0.6709848282091789,0.3709689962132525,1.9634954084936205,737.9,564.2,345.1,346.6,2308.5,2089.5 -0.6709774253984013,0.3709635280974448,2.0943951023931953,598.9,417.4,290.1,516.1,1845.7,1718.7 -0.6709525014413436,0.3708263380424188,2.2252947962927703,543.4,336.2,277.4,1092.8,1615.7,1556.8 -0.6709490743749899,0.37090583556851,2.356194490192345,541.5,293.0,293.5,2220.9,1528.6,1529.1 -0.6709469523063922,0.37091230565614985,2.4870941840919194,586.3,277.2,336.4,2282.3,1557.2,1616.3 -0.6709579536418664,0.3708798617662048,2.6179938779914944,515.6,290.8,418.5,2541.7,1426.9,1047.8 -0.6709576052148793,0.37087621476367527,2.748893571891069,345.2,345.2,565.1,2254.3,959.0,738.8 -0.6709827634272552,0.3708546998250364,2.8797932657906435,277.4,493.5,873.3,1799.4,739.1,611.7 -0.6709917716746067,0.3708510296137877,3.010692959690218,255.0,1008.3,1830.8,1578.0,623.9,565.1 -0.6710426588103247,0.4711494644143983,0.0,362.8,2251.5,2250.6,1399.1,570.9,571.0 -0.6710029316995928,0.47066903846716124,0.1308996938995747,402.2,2305.3,2364.6,1432.4,565.2,624.6 -0.6710357815070599,0.47067978519088727,0.2617993877991494,486.1,2553.8,2680.7,1346.2,611.7,693.1 -0.6710731599144769,0.4707039441082199,0.39269908169872414,648.5,2168.6,1949.5,897.0,705.7,486.4 -0.6711028281088212,0.47073835288910915,0.5235987755982988,990.4,1731.6,1603.6,692.0,534.2,406.5 -0.6711311508068792,0.4707890396412968,0.6544984694978736,2067.7,1513.0,1453.7,586.2,439.9,380.8 -0.6711367579451173,0.47081970743392865,0.7853981633974483,2220.9,1429.2,1428.5,540.8,393.6,393.0 -0.6711357253897193,0.4708824465522361,0.916297857297023,2325.3,1453.3,1512.1,543.0,380.9,439.7 -0.6711284684958287,0.4709098891638568,1.0471975511965976,2632.3,1430.1,1049.6,704.7,405.8,533.0 -0.6711209150045154,0.4709210760218847,1.1780972450961724,1956.2,960.6,740.0,649.1,486.2,705.4 -0.6710737806215241,0.4709659146093512,1.3089969389957472,1591.5,739.0,611.5,486.4,692.5,1071.9 -0.6710384668362082,0.47098644520961264,1.4398966328953218,1430.9,623.8,565.4,401.2,1405.9,2234.6 -0.671059984179038,0.47098235499594576,1.5707963267948966,1398.9,570.9,570.7,362.9,2251.1,2251.3 -0.671004961095448,0.4709811305116318,1.7016960206944713,1473.4,564.7,623.1,358.6,2303.8,2361.8 -0.6709578783091585,0.47096729880077004,1.832595714594046,1070.0,612.4,692.8,393.5,2553.6,2681.0 -0.6709769774024168,0.47098095987905797,1.9634954084936205,737.9,705.4,486.2,488.3,2166.9,1948.3 -0.6709899511596116,0.47100291845056264,2.0943951023931953,598.8,533.0,405.7,715.7,1730.2,1603.1 -0.6709508941644708,0.47092921090498163,2.2252947962927703,543.4,439.7,380.9,1479.9,1511.9,1453.3 -0.6709470626762162,0.47091327941445904,2.356194490192345,541.6,392.9,393.5,2220.4,1428.5,1429.1 -0.6709451610638145,0.47091236558592464,2.4870941840919194,586.2,380.8,439.8,2282.5,1453.8,1512.6 -0.6709568852409615,0.4708776064450131,2.6179938779914944,671.0,406.4,534.2,2541.3,1427.3,1047.6 -0.6709569944661467,0.47087324762552196,2.748893571891069,486.7,486.5,706.6,2113.3,958.8,738.8 -0.6709824007732276,0.4708515205875028,2.8797932657906435,392.9,692.8,1072.7,1683.9,739.0,611.7 -0.6709915528330682,0.47084779271812116,3.010692959690218,358.5,1395.5,2218.1,1474.5,624.0,565.0 -0.6710425455270338,0.5711462864251957,0.0,462.9,2251.2,2251.1,1299.1,571.1,571.0 -0.6710028830033294,0.570668271779593,0.1308996938995747,505.7,2305.2,2364.6,1328.6,565.3,624.6 -0.6710358337032091,0.5706790514848963,0.2617993877991494,601.6,2553.8,2559.9,1346.4,611.7,739.2 -0.6710733008185531,0.5707032677905206,0.39269908169872414,790.0,2027.4,1808.3,897.2,739.9,627.6 -0.6711030363371255,0.5707377506532711,0.5235987755982988,1189.6,1615.4,1488.3,692.0,649.7,522.0 -0.6708355620251141,0.5710393369964062,0.6544984694978736,2282.8,1408.8,1350.1,586.0,543.4,484.4 -0.6708289377112878,0.5710134027819744,0.7853981633974483,2221.2,1328.7,1328.5,540.8,493.5,493.1 -0.6708301184811877,0.5710170412946904,0.916297857297023,2325.5,1349.9,1408.7,543.0,484.5,543.4 -0.6708396923401458,0.5709898601844721,1.0471975511965976,2626.4,1428.2,1048.6,599.2,521.6,649.0 -0.6708606491173709,0.5709559061117806,1.1780972450961724,1813.5,960.0,739.4,737.1,627.9,847.4 -0.670849199130205,0.5709670087478631,1.3089969389957472,1474.8,738.7,611.3,601.8,893.0,1272.9 -0.6708539906583213,0.5709653390030056,1.4398966328953218,1327.0,623.7,565.3,504.6,1800.3,2302.5 -0.6709172618430049,0.5709513168710065,1.5707963267948966,1298.9,570.9,570.6,463.1,2251.0,2250.9 -0.6709013738684967,0.5709506901142445,1.7016960206944713,1370.3,564.7,623.2,462.4,2304.4,2362.8 -0.6708893957777358,0.5709462807301651,1.832595714594046,1068.7,612.4,740.4,509.4,2554.9,2555.3 -0.6709379982106444,0.5709773949977301,1.9634954084936205,737.4,741.3,627.3,630.6,2024.9,1805.8 -0.6709502840030125,0.5709920657574108,2.0943951023931953,598.6,648.3,521.2,916.5,1639.6,1486.8 -0.6709380460867433,0.5709666429333435,2.2252947962927703,543.2,543.2,484.5,1871.7,1408.1,1349.6 -0.670942573205523,0.5709833398081072,2.356194490192345,541.5,493.0,493.7,2220.4,1328.4,1329.1 -0.6709401453623053,0.5710082480923493,2.4870941840919194,586.3,484.4,543.6,2260.6,1350.4,1409.4 -0.6709459893212076,0.5709943953680732,2.6179938779914944,692.7,522.4,650.2,2542.3,1425.2,1046.3 -0.6709354455868467,0.5710070160407434,2.748893571891069,627.8,628.5,848.7,1969.9,958.0,738.2 -0.6709476599286721,0.5709975260008668,2.8797932657906435,508.5,893.5,1273.9,1567.5,738.6,611.3 -0.6709419710606214,0.5710013624641737,3.010692959690218,462.0,1786.8,2304.6,1370.8,623.7,565.0 -0.6709751140428286,0.6712862129483368,0.0,563.0,2250.8,2251.4,1198.7,570.8,571.0 -0.6709665124070229,0.6706837695620391,0.1308996938995747,609.3,2305.0,2364.6,1224.6,565.3,624.5 -0.6710037319811374,0.6706957713554316,0.2617993877991494,717.1,2553.5,2362.0,1346.6,611.7,805.3 -0.6710407176130506,0.6707195384584472,0.39269908169872414,931.7,1886.7,1667.2,897.4,816.0,769.0 -0.6710690789382441,0.6707523316897361,0.5235987755982988,1388.7,1500.2,1372.8,692.1,765.5,637.6 -0.6710964932711485,0.6708008932487746,0.6544984694978736,2367.4,1305.8,1246.5,586.2,647.1,587.9 -0.6711017100115341,0.6708292070302155,0.7853981633974483,2221.0,1229.1,1228.4,540.7,593.6,593.0 -0.6711009560808728,0.6708897930845039,0.916297857297023,2325.1,1245.9,1304.8,542.9,587.9,646.7 -0.6710944626823481,0.6709153661942857,1.0471975511965976,2385.9,1371.8,1049.7,598.8,636.7,764.1 -0.6710879851603009,0.6709249825552066,1.1780972450961724,1673.4,960.8,739.9,736.6,768.4,987.4 -0.671042165794398,0.6709687362730044,1.3089969389957472,1360.3,739.0,611.4,717.5,1090.9,1469.7 -0.6710082740630715,0.6709886581641831,1.4398966328953218,1224.1,623.8,565.3,608.1,2184.0,2303.4 -0.6710312049113275,0.6709841836586803,1.5707963267948966,1199.1,571.0,570.6,562.9,2251.5,2251.2 -0.6709775102269108,0.670982953007154,1.7016960206944713,1266.3,564.7,623.1,565.5,2303.8,2361.5 -0.670931607025852,0.670969484008803,1.832595714594046,1070.4,612.3,804.6,624.7,2553.8,2359.8 -0.6709517489619368,0.6709836508967106,1.9634954084936205,737.8,815.6,768.7,771.6,1885.3,1666.6 -0.6709428173382257,0.6709762794573313,2.0943951023931953,598.9,764.2,636.8,1114.8,1499.8,1371.8 -0.6709166518278565,0.6709266034719505,2.2252947962927703,543.4,646.7,587.8,2253.4,1305.2,1246.5 -0.6709146131376724,0.6709179131641403,2.356194490192345,541.5,592.9,593.5,2220.6,1228.5,1229.1 -0.6709128626052203,0.670918162234762,2.4870941840919194,586.2,587.9,646.9,2283.1,1246.6,1305.8 -0.6709248891554528,0.6708827940713982,2.6179938779914944,858.9,637.7,765.4,2541.5,1372.2,1048.1 -0.6709258260587891,0.6708774194859384,2.748893571891069,769.6,769.4,989.0,1830.4,958.9,738.8 -0.6709522351358973,0.670854865792825,2.8797932657906435,624.2,1091.6,1471.2,1452.8,739.2,611.7 -0.670962524602492,0.6708505873452058,3.010692959690218,565.6,2168.8,2304.3,1267.7,623.9,565.2 -0.6710148477940632,0.7711500631460613,0.0,662.8,2250.8,2251.0,1099.1,571.0,570.9 -0.6709811598813938,0.770670872050454,0.1308996938995747,712.7,2305.3,2364.6,1121.3,565.2,624.7 -0.6710151153638411,0.7706819183898934,0.2617993877991494,832.7,2553.0,2162.1,1243.9,611.7,739.2 -0.6710525946339537,0.7707060524533567,0.39269908169872414,1073.3,1745.5,1526.2,897.2,798.3,910.0 -0.6710821314330521,0.7707401885336549,0.5235987755982988,1587.7,1384.7,1257.1,691.9,881.2,753.3 -0.6711104403155906,0.7707905485884274,0.6544984694978736,2283.0,1202.4,1143.1,586.2,750.5,691.4 -0.6711160638370481,0.770820834217514,0.7853981633974483,2221.2,1129.1,1128.7,540.8,693.5,692.9 -0.6711152003209173,0.7708832972569697,0.916297857297023,2325.1,1142.8,1201.3,543.0,691.4,750.1 -0.6711081574725304,0.7709105447404092,1.0471975511965976,2186.4,1256.4,1049.9,598.9,752.3,879.4 -0.6711007984034932,0.7709215426944727,1.1780972450961724,1531.6,960.9,740.0,767.7,909.4,1128.4 -0.6710538834493905,0.7709663128685438,1.3089969389957472,1244.5,739.1,611.4,833.3,1290.2,1669.0 -0.671018770197189,0.7709868876805002,1.4398966328953218,1120.7,623.8,565.4,711.5,2361.2,2303.0 -0.6710404394279247,0.770982735349339,1.5707963267948966,1099.0,570.9,570.8,662.9,2251.3,2250.9 -0.6709855575389565,0.7709815044121617,1.7016960206944713,1163.0,564.7,623.1,669.0,2303.2,2362.3 -0.6709385873765007,0.7709677524581386,1.832595714594046,1070.2,612.3,739.9,740.3,2553.2,2160.1 -0.6709578181359191,0.7709814154346362,1.9634954084936205,738.0,797.9,909.6,913.3,1744.2,1525.0 -0.6709481846338041,0.7709733868148987,2.0943951023931953,598.9,879.6,752.3,1314.4,1384.2,1256.5 -0.6709215513616443,0.7709229522291208,2.2252947962927703,543.4,750.3,691.5,2324.9,1201.5,1142.9 -0.6709192728312499,0.7709134570341694,2.356194490192345,541.5,692.9,693.5,2220.5,1128.6,1129.1 -0.67091749835376,0.7709129250904303,2.4870941840919194,586.3,691.5,750.3,2282.5,1143.1,1202.3 -0.670929706020832,0.7708768506347567,2.6179938779914944,692.5,753.1,880.8,2456.7,1257.0,1047.7 -0.6709309764919109,0.7708708901169197,2.748893571891069,879.8,910.7,1130.7,1689.1,959.0,738.7 -0.6709578404628115,0.7708479000856054,2.8797932657906435,739.6,1291.3,1671.1,1337.3,739.1,611.7 -0.6709686480728968,0.7708433514303863,3.010692959690218,669.1,2363.2,2304.2,1164.0,624.0,565.2 -0.6710216056383358,0.8711433191103313,0.0,762.9,2250.9,2251.0,999.1,571.0,570.9 -0.670986279923958,0.8706698528665244,0.1308996938995747,816.5,2305.2,2364.3,1017.7,565.3,624.6 -0.6709365884725776,0.8711464418620409,0.2617993877991494,948.6,2340.9,1961.1,1128.8,611.7,739.2 -0.6709209604015242,0.8711362694340947,0.39269908169872414,1215.4,1603.3,1384.3,896.9,740.2,960.9 -0.6709056439638702,0.8711209989186515,0.5235987755982988,1788.3,1268.5,1140.8,691.9,996.6,869.0 -0.6709042770229022,0.8711147714972498,0.6544984694978736,2282.8,1098.3,1039.5,586.1,854.3,795.2 -0.6708965994951576,0.8710860335952788,0.7853981633974483,2221.4,1028.9,1028.3,540.8,793.6,793.1 -0.6708974963676224,0.8710924783974143,0.916297857297023,2325.6,1039.1,1097.8,543.0,795.1,854.0 -0.6709054112105999,0.8710695128099375,1.0471975511965976,1985.7,1141.0,1049.5,599.1,868.1,995.3 -0.6709233807276243,0.871039147766663,1.1780972450961724,1389.0,960.5,739.8,736.8,1051.2,1270.5 -0.6709083381897978,0.8710528894886171,1.3089969389957472,1128.6,739.0,611.4,948.7,1490.8,1870.0 -0.6709092579262316,0.8710528511853193,1.4398966328953218,1016.9,623.6,565.3,815.2,2487.6,2303.0 -0.6709686602136401,0.8710389983859186,1.5707963267948966,999.1,571.0,570.7,763.2,2251.1,2251.3 -0.670949376414833,0.8710377462279453,1.7016960206944713,1059.6,564.7,623.2,772.8,2304.0,2362.3 -0.6709344881014313,0.871032256269507,1.832595714594046,1069.4,612.4,740.1,856.5,2338.2,1959.0 -0.6709807973286166,0.8710615971132345,1.9634954084936205,737.6,741.0,962.1,1055.7,1602.5,1383.3 -0.6709914631487347,0.8710741566153073,2.0943951023931953,598.7,995.3,867.9,1515.2,1267.7,1140.5 -0.6709780365618052,0.8710467379595455,2.2252947962927703,543.3,853.7,795.1,2324.5,1097.7,1039.1 -0.6709818577257911,0.8710613828180735,2.356194490192345,541.5,793.0,793.8,2220.5,1028.2,1029.1 -0.6709793028850519,0.8710841524654385,2.4870941840919194,586.3,795.2,854.3,2282.8,1039.2,1098.5 -0.670985217417694,0.8710684082598443,2.6179938779914944,692.6,869.3,996.7,2255.7,1141.2,1047.2 -0.6709753851652238,0.8710791570834062,2.748893571891069,899.0,1052.7,1272.7,1546.5,958.4,738.6 -0.6709884569566065,0.8710681112832641,2.8797932657906435,855.2,1491.7,1871.9,1221.2,738.9,611.5 -0.6709839705977533,0.8710706926475418,3.010692959690218,772.7,2474.6,2304.5,1060.1,623.7,565.0 -0.1709092685104756,0.17096520315023578,0.0,63.2,2750.9,2750.9,1699.1,71.0,71.0 -0.17089403529843938,0.17147378025398985,0.1308996938995747,91.6,2823.2,2882.7,823.1,47.4,106.7 -0.17088346034299,0.17146960154974877,0.2617993877991494,139.5,3130.6,3258.8,349.0,187.7,95.3 -0.17083684705663324,0.17143920738366925,0.39269908169872414,223.8,2592.0,2373.0,191.2,110.0,63.0 -0.17079180869301336,0.17139127923636743,0.5235987755982988,393.2,2077.8,1950.3,113.9,50.8,59.8 -0.17077027892494348,0.1713464945841343,0.6544984694978736,912.8,1823.2,1763.8,68.5,129.5,70.5 -0.1707532883198432,0.17127698041928863,0.7853981633974483,2721.5,1728.9,1727.9,40.9,93.8,93.2 -0.1707554242213235,0.1712447106950128,0.916297857297023,2842.6,973.2,150.1,25.5,70.7,129.5 -0.17077368437427257,0.17118700135006448,1.0471975511965976,3210.6,431.7,51.5,106.4,59.5,186.8 -0.1708090867148418,0.17112778303816034,1.1780972450961724,2380.8,252.3,31.4,31.1,63.4,282.5 -0.1708161335440786,0.17111996097236815,1.3089969389957472,1937.3,161.1,33.4,72.1,95.6,474.8 -0.17084206841207317,0.17110576281174716,1.4398966328953218,1740.8,106.5,93.6,91.1,238.6,1067.2 -0.17092762964215824,0.1710849577829361,1.5707963267948966,1698.6,70.9,70.7,63.3,2751.6,2750.9 -0.17089092972691944,0.1710846225336431,1.7016960206944713,233.7,47.4,105.8,48.6,2821.0,2995.2 -0.17092536981601678,0.17109342161400654,1.832595714594046,73.6,187.8,95.6,47.1,3132.6,3259.6 -0.17099543081908053,0.17113676103327546,1.9634954084936205,32.1,110.2,63.3,63.7,2590.6,2371.2 -0.1710194227283933,0.17116263067749138,2.0943951023931953,21.1,51.0,59.5,117.4,2102.1,1949.2 -0.17101355578216024,0.17114846420930774,2.2252947962927703,25.7,129.5,70.7,319.5,1821.7,1763.5 -0.17102067251823855,0.1711763287575323,2.356194490192345,41.5,93.3,93.8,2720.4,1728.3,1728.4 -0.17101774807006256,0.17121152078013724,2.4870941840919194,68.5,70.5,129.6,2800.5,968.4,149.5 -0.17102012875112743,0.17120663033957206,2.6179938779914944,73.8,59.9,187.6,3119.7,430.4,51.4 -0.17100442263749796,0.1712261138288509,2.748893571891069,62.7,62.8,282.8,2536.9,251.5,31.6 -0.171010025717319,0.17122127558145683,2.8797932657906435,46.6,95.0,474.9,2030.2,161.1,33.7 -0.17099735384824766,0.17122744606389384,3.010692959690218,48.2,235.2,1058.1,1784.8,106.3,93.0 -0.17098106774252683,0.17123209408627327,0.0,63.3,2751.3,2750.9,1698.5,71.0,70.9 -0.1709190085791207,0.17123079374565897,0.1308996938995747,91.6,2823.1,2882.7,823.3,47.4,106.8 -0.17093462810328441,0.171234484485705,0.2617993877991494,139.6,3131.7,3259.0,349.0,187.9,95.4 -0.1709304716066916,0.17123059537945462,0.39269908169872414,223.9,2591.3,2372.5,191.1,110.1,63.1 -0.17092249760665326,0.17122238750266905,0.5235987755982988,393.4,2078.0,1950.4,113.9,50.7,59.9 -0.17092571228016795,0.1712237405745305,0.6544984694978736,912.8,1823.1,1764.0,68.5,129.6,70.5 -0.17092006147274905,0.17120282408314624,0.7853981633974483,2721.0,1728.9,1728.3,40.8,93.8,93.3 -0.17092077881858342,0.17121674142223853,0.916297857297023,2842.2,972.9,149.9,25.4,70.7,129.5 -0.17092650592067582,0.17120041002440067,1.0471975511965976,3209.9,431.5,51.4,106.3,59.5,186.8 -0.17094070696467015,0.17117525335973816,1.1780972450961724,2381.1,252.2,31.3,31.1,63.3,282.4 -0.17092101986649744,0.1711926099834873,1.3089969389957472,1937.7,161.1,33.4,72.0,95.5,474.8 -0.17091686695149474,0.17119459867183662,1.4398966328953218,1740.7,106.4,93.6,91.1,238.3,1067.1 -0.17097121617594205,0.17118104967056125,1.5707963267948966,1698.7,70.9,70.7,63.3,2750.9,2751.0 -0.17090198467026915,0.17117990725414667,1.7016960206944713,233.6,47.4,105.8,48.6,2820.7,2995.5 -0.1709126709234959,0.17118160071284705,1.832595714594046,73.6,187.8,95.6,47.0,3131.6,3259.9 -0.1709615444869056,0.17121175887709605,1.9634954084936205,32.1,110.2,63.3,63.7,2589.8,2371.0 -0.17096949868132671,0.17122050593064597,2.0943951023931953,21.1,51.1,59.5,117.3,2076.4,1949.0 -0.17095336897845426,0.17118724858339274,2.2252947962927703,25.8,129.5,70.7,319.4,1822.2,1763.8 -0.17095586708318994,0.17119532778295143,2.356194490192345,41.5,93.2,93.8,2720.3,1728.0,1728.7 -0.17095359593868328,0.17121163317696286,2.4870941840919194,68.5,70.5,129.6,2800.7,968.5,149.6 -0.17096102606783192,0.17119015087457368,2.6179938779914944,73.8,59.9,187.6,3120.2,430.5,51.4 -0.17095390246180428,0.17119592817004348,2.748893571891069,62.7,62.8,282.8,2536.4,251.6,31.6 -0.17097036265128257,0.17118095579777304,2.8797932657906435,46.6,95.0,474.8,2030.5,161.2,33.8 -0.17096982717367643,0.17118066322177383,3.010692959690218,48.2,235.3,1058.3,1784.7,106.3,93.1 -0.7711077925466276,0.3712211487664774,0.0,263.3,2151.1,2151.4,1498.5,670.8,670.9 -0.7710473919188671,0.3709689725647414,0.1308996938995747,298.6,2201.4,2261.3,1535.7,669.0,728.3 -0.7710472667179987,0.3709690939151913,0.2617993877991494,370.6,2438.0,2565.4,1545.7,727.4,494.0 -0.7710383103295009,0.3709635793639332,0.39269908169872414,506.9,2309.6,2090.1,1038.4,564.6,345.3 -0.7710392062090761,0.3709666148571289,0.5235987755982988,791.4,1846.9,1719.1,807.5,418.6,290.9 -0.77105057501103,0.3709851126395918,0.6544984694978736,1683.3,1616.5,1557.3,689.9,336.5,277.4 -0.7710487122192451,0.3709834776541092,0.7853981633974483,2121.4,1528.7,1528.5,640.8,293.6,293.0 -0.7710484777473008,0.37101599806488283,0.916297857297023,2221.6,1556.7,1615.6,646.4,277.5,336.2 -0.7710490732599822,0.3710164226986663,1.0471975511965976,2517.0,1629.5,1249.5,714.5,290.3,417.6 -0.7710548966773118,0.3710052167434166,1.1780972450961724,2098.5,1102.6,881.8,507.5,345.3,564.4 -0.7710247435238091,0.37103322708071174,1.3089969389957472,1732.3,854.8,727.2,370.9,493.8,872.8 -0.7710087280791635,0.3710425797268402,1.4398966328953218,1534.3,727.2,668.9,297.8,1017.0,1845.4 -0.771050513994863,0.37103302491015167,1.5707963267948966,1498.8,671.0,670.8,263.1,2151.4,2150.8 -0.7710146886546742,0.3710316468420316,1.7016960206944713,1576.7,668.1,726.6,255.3,2200.3,2258.3 -0.7709849188011401,0.37102229374285445,1.832595714594046,1269.3,728.0,493.6,278.1,2438.0,2566.2 -0.7710186491654623,0.37104439773011855,1.9634954084936205,879.0,564.4,345.3,346.8,2308.3,2089.0 -0.7710198162548135,0.3710474859761965,2.0943951023931953,714.4,417.6,290.3,516.4,1845.8,1718.4 -0.7710000801643225,0.37100948947670376,2.2252947962927703,646.9,336.3,277.5,1093.0,1615.5,1556.5 -0.7710008080773307,0.3710129810427487,2.356194490192345,641.5,293.0,293.6,2120.5,1528.3,1529.1 -0.7709983213944464,0.3710248799584299,2.4870941840919194,689.9,277.4,336.5,2179.3,1557.1,1616.3 -0.7710068556584355,0.37099954579099736,2.6179938779914944,515.9,290.9,418.6,2426.0,1625.8,1246.9 -0.7710019680546566,0.37100227688863363,2.748893571891069,345.4,345.3,565.4,2254.0,1100.3,880.1 -0.7710213253981524,0.37098538024282934,2.8797932657906435,277.5,493.6,873.6,1799.1,854.6,727.1 -0.7710239527866745,0.37098435143058617,3.010692959690218,255.0,1008.7,1831.8,1577.8,727.5,668.7 -0.7710674969456309,0.4712771323266325,0.0,363.0,2151.5,2151.1,1399.0,671.0,671.0 -0.7710175777190351,0.47069485056482696,0.1308996938995747,402.2,2201.7,2261.0,1432.1,668.9,832.1 -0.7710454063931423,0.47070400015473,0.2617993877991494,486.0,2438.2,2565.4,1545.5,785.8,693.2 -0.7710794892501488,0.47072607366747965,0.39269908169872414,648.5,2168.4,1949.6,1038.3,705.6,486.4 -0.7711069241851509,0.47075808843385936,0.5235987755982988,990.7,1756.7,1603.6,807.6,534.1,406.5 -0.7711122523714428,0.4707644875835477,0.6544984694978736,2068.8,1512.4,1453.7,689.8,439.9,380.8 -0.7711244879570811,0.47082390089414594,0.7853981633974483,2121.2,1429.0,1428.6,640.9,393.5,393.0 -0.7711231685387023,0.4708914624622469,0.916297857297023,2221.6,1453.1,1512.2,646.4,380.9,439.7 -0.7711166404237942,0.47091611047323245,1.0471975511965976,2517.3,1603.3,1249.2,714.7,405.8,533.0 -0.7711116745443269,0.47088864950353826,1.1780972450961724,1956.5,1102.6,881.6,648.9,486.2,705.3 -0.7708650438789505,0.4708494108148915,1.3089969389957472,1590.9,854.4,727.0,486.1,693.4,1073.2 -0.7708791382546208,0.4708427616206532,1.4398966328953218,1430.6,727.3,668.8,401.0,1409.3,2176.7 -0.770957387761328,0.47082560325668044,1.5707963267948966,1399.0,670.9,670.7,363.0,2151.3,2150.8 -0.7709568571746359,0.4708259015838252,1.7016960206944713,1473.4,668.2,843.4,358.8,2200.3,2259.1 -0.7709588176038374,0.4708262571076749,1.832595714594046,1268.1,784.3,692.1,393.7,2439.4,2566.8 -0.7710189380426672,0.4708652522518333,1.9634954084936205,878.5,705.0,486.0,488.9,2165.8,1946.9 -0.7710395307228842,0.47088968087802163,2.0943951023931953,714.1,532.8,405.8,716.5,1729.5,1602.4 -0.771006846757127,0.4708247512917323,2.2252947962927703,646.8,439.6,381.0,1483.6,1511.7,1452.9 -0.7710218527691558,0.470889730196965,2.356194490192345,641.5,392.9,393.6,2120.8,1428.4,1429.4 -0.7710183334104717,0.47093336785253803,2.4870941840919194,689.9,380.8,440.1,2179.4,1453.9,1513.0 -0.7710214133197284,0.4709275995057449,2.6179938779914944,714.1,406.6,534.4,2426.9,1604.3,1245.8 -0.7710080801094376,0.4709444524943218,2.748893571891069,486.3,486.9,707.0,2111.7,1099.3,879.5 -0.7710175817633309,0.47093753694030305,2.8797932657906435,392.8,693.6,1073.8,1683.0,854.3,727.0 -0.7710091903893327,0.47094301928451787,3.010692959690218,358.5,1398.4,2177.7,1474.5,727.2,668.6 -0.7710391733880472,0.5712256128014241,0.0,463.0,2150.9,2151.2,1299.0,670.9,671.1 -0.7709703207207006,0.5706856290751312,0.1308996938995747,505.8,2201.7,2261.4,1328.6,669.0,728.3 -0.7710206146918591,0.5707017363676719,0.2617993877991494,601.7,2437.9,2565.4,1475.4,727.5,848.7 -0.7710597206636702,0.5707269603546403,0.39269908169872414,790.2,2026.7,1807.7,1038.2,846.9,627.3 -0.7710874544065719,0.5707592415530098,0.5235987755982988,1190.0,1615.9,1487.9,807.6,649.6,522.0 -0.7711137870602547,0.570806210251767,0.6544984694978736,2179.5,1409.2,1350.2,689.8,543.4,484.4 -0.771118440701887,0.570832592755786,0.7853981633974483,2121.1,1329.1,1328.6,640.8,493.4,493.1 -0.771117523285382,0.5708910843292567,0.916297857297023,2221.9,1349.9,1408.7,646.4,484.5,543.2 -0.7711114127143124,0.5709146738332775,1.0471975511965976,2517.3,1487.9,1249.0,714.7,521.3,648.5 -0.7711058431246655,0.5709227371191321,1.1780972450961724,1814.6,1102.4,881.4,790.6,627.5,846.6 -0.7710611716184061,0.5709652155912681,1.3089969389957472,1475.5,854.8,727.2,601.9,892.0,1271.7 -0.771028629894593,0.5709841464990875,1.4398966328953218,1327.6,727.2,668.8,504.5,1796.6,2199.7 -0.7710530528382993,0.5709793984924885,1.5707963267948966,1299.1,670.9,670.8,463.0,2151.0,2151.2 -0.7709501251426856,0.5709792191423868,1.7016960206944713,1370.0,668.2,726.6,462.2,2266.4,2259.0 -0.7709380712637691,0.5709759373230276,1.832595714594046,1269.0,728.0,847.8,509.1,2438.3,2565.6 -0.7709652189447034,0.5709946204927607,1.9634954084936205,879.0,846.4,627.1,630.1,2026.0,1807.4 -0.7709559939292691,0.5709872388902286,2.0943951023931953,714.4,648.5,521.2,915.4,1614.5,1487.4 -0.7709284584750519,0.5709351187253793,2.2252947962927703,646.9,543.1,484.5,1868.6,1431.4,1349.8 -0.7709255493546234,0.5709230684637634,2.356194490192345,641.7,492.9,493.6,2120.4,1328.5,1329.1 -0.7709237044590995,0.5709198992575271,2.4870941840919194,689.9,484.3,543.5,2179.3,1350.3,1409.6 -0.7709366322314479,0.5707556122454573,2.6179938779914944,808.2,522.1,649.8,2426.3,1488.4,1246.6 -0.7711732651979953,0.5710385253440537,2.748893571891069,628.4,627.7,847.6,1972.3,1100.8,880.7 -0.7711704712895568,0.5710418947954392,2.8797932657906435,508.6,891.8,1271.1,1568.6,855.1,727.5 -0.7711492309004062,0.5710534842264514,3.010692959690218,462.1,1779.4,2201.3,1371.3,727.6,668.7 -0.7709820656234009,0.6710979592945427,0.0,563.2,2151.3,2151.1,1198.9,671.1,671.1 -0.7709906358778925,0.6710976144240732,0.1308996938995747,609.3,2201.7,2261.2,1224.8,668.9,728.1 -0.7709826480754004,0.6710949583867662,0.2617993877991494,717.4,2437.7,2360.9,1359.9,727.4,855.0 -0.7709717485087454,0.6710878996192484,0.39269908169872414,932.0,1886.2,1666.7,1038.4,881.8,768.9 -0.7709618125375458,0.6710787738099728,0.5235987755982988,1389.3,1499.9,1372.3,807.5,765.6,637.8 -0.7709642630046402,0.6710801100655064,0.6544984694978736,2305.4,1305.3,1246.5,689.9,647.1,588.1 -0.7709581801084413,0.6710593796718174,0.7853981633974483,2121.2,1228.8,1228.4,641.0,593.7,593.1 -0.7709586504538047,0.6710734566083243,0.916297857297023,2221.6,1246.1,1305.0,646.6,588.1,646.9 -0.7709643357217422,0.671057279649588,1.0471975511965976,2385.5,1371.9,1249.1,714.6,636.9,764.4 -0.7709786747655782,0.6710323855115969,1.1780972450961724,1672.8,1102.3,881.6,878.0,768.7,988.0 -0.7709592012319563,0.6710501909205993,1.3089969389957472,1359.7,854.7,727.1,717.7,1091.6,1470.9 -0.7709552057123167,0.6710528442400767,1.4398966328953218,1223.7,727.2,668.9,608.3,2186.8,2199.6 -0.7710095169104519,0.6710401462440096,1.5707963267948966,1198.9,670.9,670.7,563.2,2151.1,2151.1 -0.7709854775517185,0.6710388310109028,1.7016960206944713,1266.4,668.1,726.6,565.8,2200.4,2258.6 -0.7709662997599411,0.6710322864583063,1.832595714594046,1269.2,728.2,855.6,625.0,2438.1,2358.6 -0.7710089746618622,0.6710595755616062,1.9634954084936205,878.8,882.8,768.6,772.1,1884.8,1665.8 -0.7710168768910608,0.671069427261966,2.0943951023931953,714.4,764.1,637.0,1115.6,1499.1,1371.8 -0.7710015440441734,0.6710390213551336,2.2252947962927703,647.0,646.9,588.2,2198.4,1305.0,1245.9 -0.7710043623812552,0.6710504810761142,2.356194490192345,641.6,593.1,593.8,2120.3,1228.4,1229.0 -0.7710017421063624,0.6710700785591805,2.4870941840919194,689.8,588.1,647.1,2178.8,1246.3,1305.7 -0.771008292294447,0.6710515246044451,2.6179938779914944,859.0,637.7,765.6,2426.1,1372.4,1246.6 -0.7709998578911195,0.6710598586155401,2.748893571891069,769.6,769.7,989.8,1829.8,1100.0,880.0 -0.7710147087165656,0.6710470321377848,2.8797932657906435,624.4,1092.3,1472.3,1452.3,854.5,727.1 -0.7710122912320077,0.6710484883923646,3.010692959690218,565.6,2170.8,2201.3,1267.4,727.5,668.6 -0.7710498058654142,0.7713366495729506,0.0,663.1,2150.8,2151.0,1099.1,670.9,671.1 -0.7710051573831442,0.7707034819262508,0.1308996938995747,712.9,2201.7,2260.5,1121.5,668.8,728.2 -0.7710330300609829,0.770712601243188,0.2617993877991494,832.8,2438.2,2161.6,1244.2,727.3,1004.5 -0.7710663884623817,0.7707341536222876,0.39269908169872414,1073.5,1745.1,1525.7,1038.2,944.0,909.9 -0.7710930919154185,0.770765290453741,0.5235987755982988,1588.2,1384.8,1256.9,807.6,881.3,753.4 -0.771119552921839,0.7708124044424267,0.6544984694978736,2179.0,1202.1,1143.1,689.8,750.6,691.5 -0.7711243232133315,0.7708393928302917,0.7853981633974483,2121.5,1129.0,1128.5,640.8,693.6,692.9 -0.7711234001527026,0.7708986703545868,0.916297857297023,2221.3,1142.9,1201.4,646.5,691.3,750.3 -0.7711170599748617,0.7709230141787333,1.0471975511965976,2186.1,1256.3,1249.3,714.5,752.4,879.6 -0.7711110509726983,0.7709316265875255,1.1780972450961724,1531.3,1102.6,881.6,877.8,909.6,1128.8 -0.7710658748397283,0.7709745357482687,1.3089969389957472,1244.5,854.6,727.0,833.1,1290.4,1669.5 -0.7710327822445718,0.7709937913868323,1.4398966328953218,1120.7,727.2,668.9,711.5,2258.2,2199.8 -0.7710566277539649,0.7709890659924363,1.5707963267948966,1099.2,670.8,670.7,663.0,2151.1,2151.0 -0.7710038114387334,0.7709878176294902,1.7016960206944713,1162.9,668.2,726.5,669.0,2199.8,2258.6 -0.7709587194044597,0.7709744999472528,1.832595714594046,1269.3,728.0,1003.6,740.3,2438.5,2159.3 -0.7709795067474977,0.770989121032009,1.9634954084936205,878.9,945.2,909.6,913.5,1744.0,1525.0 -0.7709709848234211,0.7709823766824135,2.0943951023931953,714.5,879.6,752.4,1314.5,1383.9,1256.5 -0.7709450494416585,0.7709333010185007,2.2252947962927703,646.9,750.3,691.4,2221.0,1201.8,1142.7 -0.7709430257170952,0.7709252092152625,2.356194490192345,641.6,693.0,693.6,2120.2,1128.5,1129.1 -0.7709410543098626,0.7709260284872834,2.4870941840919194,689.8,691.4,750.5,2178.9,1143.2,1202.1 -0.7709528134381102,0.7708910528225474,2.6179938779914944,808.1,753.3,880.8,2426.3,1256.5,1246.9 -0.7709533155038991,0.770885983550402,2.748893571891069,910.8,910.9,1130.9,1688.6,1100.4,880.1 -0.7709793573333499,0.770863571946119,2.8797932657906435,739.7,1291.5,1671.2,1337.0,854.5,727.2 -0.7709892933545825,0.7708593348794959,3.010692959690218,669.0,2259.5,2200.9,1164.2,727.5,668.8 -0.7710413029118193,0.8711585952298249,0.0,763.0,2150.8,2151.0,999.2,671.1,671.0 -0.7710021681572121,0.8706729252688201,0.1308996938995747,816.4,2201.7,2260.8,1017.9,668.9,728.3 -0.7710347416581104,0.8706835769583445,0.2617993877991494,948.3,2342.0,1961.9,1128.4,727.2,854.8 -0.7710717196996879,0.870707473184958,0.39269908169872414,1215.0,1604.0,1384.7,1038.4,939.5,1051.2 -0.7711010464932314,0.8707415019170504,0.5235987755982988,1787.3,1268.7,1141.1,807.5,996.7,869.0 -0.7711291469412302,0.8707917552380953,0.6544984694978736,2179.6,1098.8,1039.5,689.8,854.2,794.9 -0.7711346540334162,0.8708219696822064,0.7853981633974483,2121.2,1029.0,1028.4,640.8,793.5,792.9 -0.7711336391176838,0.8708842818340972,0.916297857297023,2221.6,1039.2,1098.1,646.5,795.0,853.7 -0.7711264993985119,0.870911343050295,1.0471975511965976,1986.4,1141.1,1249.6,714.5,867.8,995.2 -0.7711191394621797,0.8709222133060548,1.1780972450961724,1389.6,1102.6,881.6,908.8,1050.8,1269.6 -0.7710722491482401,0.8709668163709199,1.3089969389957472,1128.9,854.6,727.1,948.8,1489.7,1868.6 -0.7710372105654071,0.8709871933222226,1.4398966328953218,1017.1,727.3,668.9,815.0,2257.9,2199.3 -0.7710590146722174,0.8709830260547995,1.5707963267948966,999.0,671.0,670.7,762.8,2151.1,2150.8 -0.7710042629301752,0.8709817995955413,1.7016960206944713,1059.7,668.1,726.6,772.5,2200.1,2258.9 -0.7709574244530824,0.8709680322165443,1.832595714594046,1221.8,728.1,855.8,855.9,2339.6,1960.4 -0.7709767312098764,0.8709818102873623,1.9634954084936205,879.0,939.0,1050.7,1055.1,1603.1,1383.8 -0.7709670938481037,0.8709739566577528,2.0943951023931953,714.5,995.4,867.8,1514.4,1268.2,1140.8 -0.7709404422866557,0.870923619655843,2.2252947962927703,646.9,853.9,795.0,2221.3,1097.9,1039.4 -0.7709356591566155,0.8709079034556915,2.356194490192345,641.5,793.0,793.4,2120.5,1028.5,1029.1 -0.7709336191695183,0.8709120510898072,2.4870941840919194,689.8,795.0,854.0,2179.2,1039.5,1098.5 -0.7709454862160919,0.8708767730091598,2.6179938779914944,808.1,868.9,996.6,2256.5,1141.2,1246.9 -0.7709467544637177,0.8708705521753284,2.748893571891069,1021.2,1052.2,1272.4,1547.2,1100.3,880.2 -0.7709740170341968,0.8708470763680274,2.8797932657906435,855.2,1490.9,1870.5,1221.7,854.6,727.2 -0.7709854012092205,0.870842142150358,3.010692959690218,772.5,2259.8,2200.9,1060.5,727.5,668.7 -0.17094299331062845,0.17079401417442486,0.0,63.0,2750.8,2750.7,1698.8,71.0,71.0 -0.17092331870826427,0.1714322778391859,0.1308996938995747,91.5,2822.7,2882.2,824.0,47.5,106.7 -0.1709159688307552,0.1714292415661416,0.2617993877991494,139.5,3131.4,3259.0,349.2,187.8,95.3 -0.1708736047011646,0.17140173288949034,0.39269908169872414,223.7,2592.6,2372.4,191.3,110.1,63.0 -0.17083202666570407,0.17135785857675323,0.5235987755982988,393.1,2078.0,1950.9,114.0,50.8,59.8 -0.1708127676475407,0.17131771327016532,0.6544984694978736,911.9,1823.5,1764.2,68.6,129.6,70.4 -0.17079661540327096,0.1712529105477194,0.7853981633974483,2721.1,1729.0,1728.2,40.9,93.8,93.2 -0.1707984642750512,0.1712251120207493,0.916297857297023,2842.2,974.1,150.4,25.5,70.7,129.5 -0.1708153988983482,0.17117135634478275,1.0471975511965976,3209.8,432.0,51.6,106.4,59.5,186.7 -0.1708486533578171,0.1711152539425831,1.1780972450961724,2381.7,252.4,31.4,31.2,63.3,282.3 -0.17085313944250546,0.17110978364700302,1.3089969389957472,1938.0,161.1,33.5,72.1,95.6,474.6 -0.17087625005716703,0.1710972160731996,1.4398966328953218,1741.1,106.5,93.6,91.1,238.2,1066.1 -0.17095886697855872,0.17107705906653403,1.5707963267948966,1698.6,71.0,70.7,63.3,2751.5,2750.6 -0.17091882053602644,0.17107671567060478,1.7016960206944713,234.0,47.4,105.8,48.6,2821.2,2997.2 -0.1709511370874667,0.1710851255513579,1.832595714594046,73.7,187.9,95.6,47.1,3130.8,3259.2 -0.1710191285320595,0.17112736392380135,1.9634954084936205,32.2,110.3,63.3,63.6,2591.0,2371.6 -0.17104147407516065,0.171151653191828,2.0943951023931953,21.1,51.1,59.5,117.3,2076.6,1949.2 -0.171034398966939,0.17113575960544458,2.2252947962927703,25.8,129.5,70.7,319.1,1822.3,1763.6 -0.1710408467395284,0.17116173663309886,2.356194490192345,41.5,93.3,93.8,2720.4,1728.0,1728.7 -0.17103787482310778,0.17119498381232234,2.4870941840919194,68.5,70.5,129.5,2801.2,969.4,149.8 -0.17104058910453068,0.17118839653024698,2.6179938779914944,73.9,59.9,187.5,3119.0,430.7,51.5 -0.17102578043302552,0.17120638352281725,2.748893571891069,62.7,62.7,282.6,2537.1,251.6,31.6 -0.17103246681430445,0.17120047070457467,2.8797932657906435,46.6,94.9,474.6,2030.6,161.3,33.8 -0.17102107264245758,0.17120598160588774,3.010692959690218,48.2,235.0,1057.2,1784.9,106.4,93.1 -0.17100604945890474,0.1712103973693,0.0,63.2,2751.2,2751.5,1698.9,71.0,71.0 -0.17094509195392515,0.1712092350674166,0.1308996938995747,91.6,2823.1,2882.6,824.0,47.5,106.7 -0.17096185951503967,0.17121342178498544,0.2617993877991494,139.6,3130.6,3258.8,349.3,188.0,95.4 -0.1709585096622749,0.17121024830264808,0.39269908169872414,223.8,2592.6,2373.1,191.3,110.2,63.1 -0.170950988571967,0.17140905730090283,0.5235987755982988,393.2,2078.1,1950.2,113.9,50.7,59.9 -0.17095504798791117,0.17120338096588683,0.6544984694978736,912.0,1823.3,1764.4,68.5,129.6,70.5 -0.17094955992983882,0.171184001680595,0.7853981633974483,2721.1,1728.9,1728.0,40.9,93.8,93.2 -0.1709501042162217,0.1711990254715643,0.916297857297023,2842.6,973.8,150.1,25.4,70.7,129.4 -0.17095547187338578,0.17118351362873718,1.0471975511965976,3209.4,431.8,51.5,106.4,59.5,186.7 -0.17096916889242733,0.17115887356338622,1.1780972450961724,2381.7,252.3,31.3,31.1,63.3,282.3 -0.17094898928130114,0.171176654248957,1.3089969389957472,1938.0,161.1,33.4,72.1,95.5,474.6 -0.17094433603131462,0.1711790312366095,1.4398966328953218,1741.1,106.5,93.6,91.1,238.1,1066.0 -0.17099814971282393,0.17116558813765437,1.5707963267948966,1698.8,71.0,70.7,63.3,2751.4,2751.0 -0.17092808246653146,0.17116450873330935,1.7016960206944713,234.0,47.4,105.8,48.6,2820.8,2998.0 -0.17093847158840497,0.17116635842938344,1.832595714594046,73.7,187.8,95.5,47.0,3131.3,3259.9 -0.17098690438181524,0.17119643535567564,1.9634954084936205,32.2,110.2,63.3,63.6,2590.8,2371.5 -0.17099444323438936,0.17120492721912406,2.0943951023931953,21.2,51.1,59.4,117.3,2077.1,1949.3 -0.17097789713487657,0.1711714111803484,2.2252947962927703,25.8,129.5,70.7,319.0,1822.5,1763.2 -0.17098008411442495,0.17117912540632596,2.356194490192345,41.5,93.3,93.8,2720.3,1728.5,1728.8 -0.17097771263016032,0.1711949444135794,2.4870941840919194,68.5,70.5,129.5,2800.7,969.5,149.8 -0.17098509182951718,0.1711730429915166,2.6179938779914944,73.9,59.9,187.5,3119.4,430.6,51.5 -0.17097819892362495,0.17117838409559227,2.748893571891069,62.7,62.7,282.6,2536.9,251.7,31.6 -0.17099490634240097,0.17116311921627214,2.8797932657906435,46.6,94.9,474.6,2030.2,161.3,33.8 -0.1709947115817902,0.17116266553297144,3.010692959690218,48.2,235.0,1057.4,1785.3,106.4,93.1 -0.8711051172753922,0.37119483681523313,0.0,263.2,2051.3,2051.0,1498.9,771.0,771.0 -0.8710450687612221,0.37097778503217826,0.1308996938995747,298.6,2098.5,2157.3,1535.6,772.5,831.8 -0.8710449441415642,0.3709778959560781,0.2617993877991494,370.6,2322.3,2449.7,1706.3,829.8,494.0 -0.8710351634168318,0.37097184116648485,0.39269908169872414,506.8,2309.4,2090.5,1179.4,564.6,345.3 -0.8710352238911304,0.3709739539210215,0.5235987755982988,791.6,1846.9,1719.3,923.3,418.7,291.0 -0.8710460175748415,0.3709913479226541,0.6544984694978736,1683.1,1616.3,1557.1,793.2,336.5,277.4 -0.8710438917940372,0.3709885418110226,0.7853981633974483,2021.1,1529.0,1528.4,741.1,293.6,293.0 -0.8710436967704133,0.3710199487640511,0.916297857297023,2118.0,1556.8,1615.3,750.0,277.5,336.3 -0.8710445942025389,0.37101937514307104,1.0471975511965976,2401.6,1718.7,1449.0,792.7,290.3,417.6 -0.8710509237619753,0.371007343703184,1.1780972450961724,2098.0,1244.3,1023.2,507.5,345.4,564.3 -0.8710214084339466,0.3710347381144812,1.3089969389957472,1706.9,970.4,842.7,370.9,493.7,872.7 -0.8710061129177569,0.37104368648865416,1.4398966328953218,1534.3,830.8,772.3,297.7,1017.1,1845.4 -0.8710486502301348,0.3710339372306295,1.5707963267948966,1499.0,771.0,770.7,263.1,2051.7,2051.0 -0.871013533745181,0.3710325595467019,1.7016960206944713,1576.8,771.6,830.1,255.3,2096.9,2217.5 -0.8709844012723252,0.3710233756820782,1.832595714594046,1468.8,829.1,493.7,278.0,2322.6,2450.3 -0.8710186703788656,0.37104579092396306,1.9634954084936205,1020.1,564.3,345.3,346.8,2308.4,2089.2 -0.8710202431867801,0.37104928549064975,2.0943951023931953,829.9,417.7,290.3,516.3,1845.7,1718.3 -0.8710007699364535,0.3710117477994397,2.2252947962927703,750.4,336.3,277.5,1093.2,1615.3,1556.6 -0.8710016202332262,0.3710157202503268,2.356194490192345,741.5,293.1,293.6,2020.6,1528.5,1528.8 -0.8709991227092253,0.37102808128344167,2.4870941840919194,793.5,277.4,336.5,2053.2,1557.3,1615.9 -0.8710075323515152,0.3710031538923628,2.6179938779914944,515.8,290.9,418.6,2310.4,1719.4,1446.1 -0.8710024295522245,0.37100621798465094,2.748893571891069,345.3,345.4,565.3,2254.2,1241.6,1021.7 -0.8710215131177409,0.3709895619159853,2.8797932657906435,277.5,493.6,873.4,1799.4,970.3,842.8 -0.8710238365523144,0.3709886779101037,3.010692959690218,255.1,1009.0,1831.6,1577.9,831.0,772.2 -0.8710670204780503,0.4712811818704159,0.0,363.0,2050.7,2051.2,1398.9,771.0,771.0 -0.8710171144819376,0.47069549993263116,0.1308996938995747,402.2,2098.4,2157.4,1432.1,772.4,916.7 -0.8710448784986359,0.47070462678400116,0.2617993877991494,486.1,2322.5,2449.7,1590.8,842.9,693.2 -0.8710788954374172,0.4707266552046485,0.39269908169872414,648.4,2168.3,1949.3,1179.4,705.5,486.3 -0.8711062782612559,0.47075860916092305,0.5235987755982988,990.6,1731.4,1603.8,923.1,534.0,406.5 -0.8711331504601169,0.4708066678034375,0.6544984694978736,2069.1,1512.9,1453.7,793.3,439.9,380.9 -0.8711380951442415,0.4708346651366768,0.7853981633974483,2021.0,1428.9,1428.5,740.9,393.6,393.1 -0.8711370594516142,0.47089485373640816,0.916297857297023,2118.4,1453.7,1512.0,750.1,380.9,439.7 -0.8711304033905117,0.47091998717496764,1.0471975511965976,2401.5,1603.3,1449.0,830.1,405.7,533.1 -0.8711239482122486,0.47092926760988174,1.1780972450961724,1956.4,1244.1,1023.3,648.8,486.1,705.4 -0.8710782221283341,0.4709726396649698,1.3089969389957472,1591.4,970.3,842.7,486.3,692.8,1072.0 -0.871044531665898,0.4709921555923604,1.4398966328953218,1431.2,830.7,772.2,401.1,1406.5,2096.0 -0.871067780941755,0.4709876006874094,1.5707963267948966,1398.7,770.9,770.7,362.9,2051.1,2051.2 -0.8710144017961483,0.47098635965090097,1.7016960206944713,1473.3,771.6,875.5,358.7,2096.5,2155.4 -0.870968809554752,0.4709728876465451,1.832595714594046,1468.2,843.6,692.7,393.5,2322.7,2449.9 -0.870989154156942,0.4709872945713358,1.9634954084936205,1020.0,705.1,486.2,488.3,2167.4,1948.3 -0.8709802660587259,0.47098028089795174,2.0943951023931953,829.9,532.9,405.7,715.8,1730.3,1603.2 -0.8709540850789151,0.4709308470835092,2.2252947962927703,750.5,439.7,380.9,1480.3,1512.0,1453.3 -0.8709519157897369,0.4709223677426486,2.356194490192345,741.6,393.0,393.5,2020.6,1428.7,1429.4 -0.870949876174783,0.4709228189830559,2.4870941840919194,917.0,380.8,439.9,2075.7,1453.9,1512.6 -0.870961705125548,0.4708874756285002,2.6179938779914944,714.6,406.4,534.1,2310.2,1603.6,1445.8 -0.8709623182655947,0.47088210888163506,2.748893571891069,486.6,486.7,706.6,2113.0,1241.4,1021.6 -0.8709885779261868,0.47085945606106927,2.8797932657906435,393.0,693.1,1072.9,1684.0,970.4,842.7 -0.8709987699544428,0.4708550644681242,3.010692959690218,358.5,1395.9,2097.2,1474.3,831.1,772.2 -0.8710511139710737,0.5711545929380148,0.0,463.0,2051.1,2050.6,1299.1,771.1,771.0 -0.8710105444069631,0.5706722871428922,0.1308996938995747,505.8,2098.3,2157.2,1328.6,772.4,831.7 -0.8710428818350076,0.5706828829802628,0.2617993877991494,601.6,2322.2,2450.0,1475.3,985.1,892.6 -0.8711209404891458,0.5707288098256098,0.39269908169872414,790.0,2027.3,1808.0,1179.5,846.7,627.5 -0.8708504978435092,0.5710726377251041,0.5235987755982988,1190.9,1615.2,1487.9,923.0,649.6,522.0 -0.8708517633839861,0.5710719504034087,0.6544984694978736,2075.5,1408.8,1349.9,793.1,543.4,484.4 -0.8708442091019829,0.5710427190866334,0.7853981633974483,2020.9,1328.9,1328.5,740.6,493.6,493.0 -0.8708453961454803,0.57104680665096,0.916297857297023,2118.2,1349.6,1408.6,750.0,484.5,543.5 -0.8708544173874166,0.5710212242572978,1.0471975511965976,2401.9,1487.7,1447.9,903.8,521.5,648.9 -0.870874201578852,0.5709887780663556,1.1780972450961724,1813.8,1243.6,1023.0,790.5,627.8,847.0 -0.8708612763273195,0.5710010516395507,1.3089969389957472,1475.2,970.0,842.4,601.9,893.0,1272.4 -0.8708644319889437,0.5710001438417551,1.4398966328953218,1327.0,830.6,772.2,504.7,1799.2,2152.6 -0.8709260340948852,0.5709862275666053,1.5707963267948966,1299.1,770.8,770.7,463.0,2051.4,2051.4 -0.8709086667116859,0.5709853474206497,1.7016960206944713,1369.9,771.6,830.3,462.4,2222.9,2155.0 -0.870895415340549,0.5709804719775036,1.832595714594046,1467.5,983.8,891.7,509.4,2322.7,2450.5 -0.8709866309135815,0.5710340123633901,1.9634954084936205,1019.5,846.3,627.3,630.3,2025.3,1806.4 -0.8709758046429266,0.5710233957530959,2.0943951023931953,829.7,648.6,521.3,916.3,1614.3,1487.1 -0.8709599436224095,0.5709910862279084,2.2252947962927703,750.3,543.3,484.5,1870.9,1408.3,1349.5 -0.8709646018901669,0.5710083860474131,2.356194490192345,741.5,493.0,493.7,2020.5,1328.3,1329.1 -0.8709620726007496,0.5710363300645538,2.4870941840919194,793.4,484.5,543.6,2076.1,1350.0,1409.4 -0.870966732056554,0.5710259371247293,2.6179938779914944,913.7,522.3,650.0,2310.5,1488.4,1444.9 -0.8709542335985561,0.5710415320466375,2.748893571891069,627.8,628.5,848.6,1970.4,1241.0,1020.9 -0.8709638394480144,0.5710342576012701,2.8797932657906435,508.4,893.3,1273.2,1567.7,970.0,842.4 -0.8709552813578157,0.5710394336733138,3.010692959690218,462.1,1785.8,2136.7,1370.7,830.8,772.0 -0.870985042242532,0.6713216963391466,0.0,563.1,2051.0,2051.6,1198.9,770.8,770.8 -0.8709676290948469,0.6706893024377794,0.1308996938995747,609.1,2098.2,2157.5,1225.0,772.3,831.8 -0.8710024552086618,0.6707005453470969,0.2617993877991494,717.1,2321.9,2361.6,1359.7,842.7,970.1 -0.8710385103039638,0.6707237049682264,0.39269908169872414,931.6,1886.6,1667.3,1179.7,988.3,768.8 -0.871066445346867,0.6707560141729716,0.5235987755982988,1388.3,1525.8,1372.7,923.4,765.5,637.7 -0.8710936668420465,0.6708041665407858,0.6544984694978736,2076.2,1305.6,1246.7,793.3,647.0,588.0 -0.8710988041069027,0.6708320940521182,0.7853981633974483,2021.4,1228.9,1228.4,740.8,593.6,592.9 -0.8710980785857314,0.6708923440975187,0.916297857297023,2117.9,1246.2,1304.7,749.9,587.9,646.6 -0.8710749269579361,0.6709719988984149,1.0471975511965976,2401.2,1371.8,1449.4,830.0,636.7,764.0 -0.8710893677061647,0.6709483414842676,1.1780972450961724,1673.6,1244.4,1023.5,932.6,768.5,987.3 -0.8710136893136644,0.6710185739159735,1.3089969389957472,1360.3,970.5,843.0,717.6,1090.8,1469.7 -0.870976626474456,0.6710415069551996,1.4398966328953218,1224.1,830.9,772.4,608.0,2131.4,2095.9 -0.8710282933386498,0.6710304799650824,1.5707963267948966,1198.9,771.1,770.6,562.8,2051.3,2051.3 -0.8709754868301472,0.6710293045813847,1.7016960206944713,1266.2,771.7,830.0,565.5,2096.6,2155.2 -0.8709222099655679,0.6710136308332786,1.832595714594046,1453.1,843.4,971.0,624.7,2322.3,2359.3 -0.870933848636017,0.6710302596269526,1.9634954084936205,1020.2,987.5,768.7,771.4,1885.4,1666.3 -0.8711176108311833,0.6708252353817357,2.0943951023931953,830.1,764.5,637.0,1114.0,1499.7,1372.3 -0.8711178383571566,0.6708254446664428,2.2252947962927703,750.5,647.0,588.1,2118.1,1305.3,1246.4 -0.871127508186272,0.6708683369703567,2.356194490192345,741.5,593.0,593.5,2020.5,1228.6,1229.1 -0.8711239298844206,0.6709175029241399,2.4870941840919194,793.0,587.9,646.7,2075.3,1246.5,1305.4 -0.8711066930027449,0.6709766235513945,2.6179938779914944,923.3,637.5,764.9,2309.7,1371.9,1447.7 -0.8711051565092238,0.6709754491669921,2.748893571891069,770.0,768.9,988.8,1831.4,1242.3,1022.3 -0.8708823250123312,0.6708094991277747,2.8797932657906435,624.2,1092.2,1472.4,1452.3,970.2,842.6 -0.8708963879506009,0.670802829511205,3.010692959690218,565.6,2132.8,2097.4,1267.5,831.0,772.1 -0.8709718352275775,0.7711238045312196,0.0,662.9,2051.0,2050.9,1099.0,771.1,771.1 -0.870963643334784,0.7711237780619133,0.1308996938995747,712.8,2098.1,2157.6,1121.7,772.3,831.8 -0.870925046998205,0.7711125471652645,0.2617993877991494,832.9,2322.7,2160.8,1244.5,843.0,1047.9 -0.870884527003358,0.7710876630695227,0.39269908169872414,1073.4,1744.8,1525.5,1179.4,1023.5,909.6 -0.870851313564622,0.7710541765047014,0.5235987755982988,1588.4,1409.9,1256.7,923.2,880.9,753.2 -0.8708386811582868,0.7710278562350179,0.6544984694978736,2075.4,1202.2,1143.1,793.3,750.6,691.5 -0.8708258674359889,0.7709781973384264,0.7853981633974483,2021.3,1129.0,1128.5,740.9,693.6,693.0 -0.8708273820179264,0.7709648522979824,0.916297857297023,2118.4,1142.6,1201.5,750.1,691.6,750.4 -0.8708408859292142,0.7709242556658544,1.0471975511965976,2185.0,1256.6,1384.0,830.2,752.4,879.8 -0.8708682785351577,0.7708795400519295,1.1780972450961724,1531.0,1244.0,1023.3,1019.2,909.9,1129.2 -0.8708650646886045,0.7708830034235146,1.3089969389957472,1244.4,970.2,842.6,833.2,1291.0,1670.2 -0.8708791292197825,0.7708768012699434,1.4398966328953218,1120.4,830.8,772.2,711.6,2154.2,2096.1 -0.8709518968634827,0.7708606833915408,1.5707963267948966,1099.0,771.0,770.7,663.1,2051.3,2051.0 -0.8709448131603763,0.7708606698528386,1.7016960206944713,1163.0,771.7,830.1,669.1,2097.1,2155.5 -0.8709404394470571,0.7708592554328655,1.832595714594046,1337.3,843.5,1047.4,740.5,2323.1,2158.8 -0.8709952259280697,0.770894761804022,1.9634954084936205,1019.9,1024.6,909.5,913.8,1743.5,1524.6 -0.8710119575815962,0.7709146682642096,2.0943951023931953,829.8,879.6,752.3,1315.2,1383.6,1256.4 -0.8710022245147587,0.7708950877551168,2.2252947962927703,750.3,750.1,691.5,2170.6,1201.5,1142.7 -0.8710076343533796,0.7709175968224984,2.356194490192345,741.4,693.1,693.5,2020.3,1128.5,1129.3 -0.8710048411701574,0.7709477459931002,2.4870941840919194,793.3,691.5,750.7,2075.8,1143.3,1202.1 -0.8710089773457537,0.7709385541523279,2.6179938779914944,1025.4,753.3,880.9,2311.3,1256.9,1384.6 -0.8709961900917277,0.7709548730238258,2.748893571891069,910.9,911.1,1131.1,1688.3,1241.4,1021.3 -0.8710054058219142,0.7709482560346974,2.8797932657906435,739.7,1292.2,1671.6,1337.0,970.0,842.6 -0.8709964553526129,0.7709540619586175,3.010692959690218,669.0,2156.2,2097.5,1163.9,830.8,772.1 -0.8710255929592209,0.8712359462130568,0.0,762.8,2051.1,2051.3,999.0,771.0,770.9 -0.8709873557055191,0.8706653452383946,0.1308996938995747,816.4,2097.7,2157.2,1017.7,772.4,831.7 -0.8710206328872473,0.8706761880456431,0.2617993877991494,948.1,2322.2,1962.4,1128.6,842.9,970.5 -0.8710585316031482,0.8707006111941795,0.39269908169872414,1214.7,1604.3,1384.7,1179.7,1085.5,1051.3 -0.8710886308865284,0.8707353875306703,0.5235987755982988,1787.0,1269.0,1141.2,923.3,996.9,869.2 -0.8711173295514933,0.8707865454633601,0.6544984694978736,2076.0,1098.6,1039.5,793.4,854.2,795.1 -0.8711231286893206,0.870817693372409,0.7853981633974483,2021.3,1029.1,1028.5,740.8,793.6,793.0 -0.8711222084448456,0.8708809647548141,0.916297857297023,2118.2,1039.1,1098.0,749.9,795.0,853.7 -0.8711149206008681,0.8709089285197826,1.0471975511965976,1986.4,1141.1,1268.1,829.9,867.9,995.2 -0.8711071792732715,0.8709205220035015,1.1780972450961724,1390.0,1244.4,1023.6,1018.8,1050.7,1269.7 -0.8710597883594576,0.8709657231265258,1.3089969389957472,1129.0,970.5,842.7,948.7,1489.3,1868.2 -0.8710241469789877,0.8709865646995973,1.4398966328953218,1017.2,830.7,772.3,815.1,2154.4,2095.8 -0.871045275657571,0.8709825520641958,1.5707963267948966,998.8,771.0,770.7,762.9,2051.1,2050.8 -0.8709898856852876,0.8709813188730835,1.7016960206944713,1059.7,771.5,830.0,772.6,2097.1,2155.2 -0.8709424619300111,0.8709674362005742,1.832595714594046,1221.4,843.6,971.3,855.9,2322.2,1960.8 -0.8709613036815269,0.8709808848688505,1.9634954084936205,1020.1,1086.5,1050.9,1054.9,1603.1,1383.9 -0.8709513669684441,0.8709725818878611,2.0943951023931953,830.0,995.1,867.9,1514.2,1268.5,1141.1 -0.8709245338847496,0.8709218217903181,2.2252947962927703,750.4,853.8,794.9,2118.1,1098.1,1039.4 -0.870922150924354,0.870911981713798,2.356194490192345,741.5,793.0,793.5,2020.4,1028.4,1029.0 -0.8709203570282389,0.8709111190239747,2.4870941840919194,793.3,794.8,854.0,2075.9,1039.5,1098.6 -0.8709326406780492,0.870874738457907,2.6179938779914944,923.6,868.7,996.4,2301.4,1141.2,1268.8 -0.8709340424759736,0.8708685264491571,2.748893571891069,1052.3,1052.1,1272.2,1547.2,1242.0,1021.6 -0.8709610993921179,0.8708453441817197,2.8797932657906435,855.3,1490.4,1870.2,1247.0,970.1,842.9 -0.8709721277278065,0.8708406742055284,3.010692959690218,772.6,2156.4,2097.5,1060.6,831.0,772.2 -0.17092821699833122,0.17079889610385668,0.0,63.0,2751.2,2750.9,1699.1,71.0,71.0 -0.17091618662125754,0.17143227731027877,0.1308996938995747,91.5,2823.5,2882.2,823.9,47.5,106.7 -0.1709105638962032,0.17142976736183035,0.2617993877991494,139.5,3130.6,3258.2,349.2,187.8,95.3 -0.17086853013345432,0.1714024494591746,0.39269908169872414,223.7,2592.7,2372.9,191.3,110.1,63.0 -0.17082692894279336,0.17135851762385546,0.5235987755982988,393.0,2078.2,1950.5,114.0,50.8,59.8 -0.1708075985134846,0.17131819156586015,0.6544984694978736,912.0,1823.3,1764.1,68.6,129.5,70.4 -0.17079142934117544,0.17125317416176467,0.7853981633974483,2721.2,1728.8,1728.2,40.9,93.8,93.2 -0.1707933103468458,0.17122516185058778,0.916297857297023,2842.6,974.0,150.4,25.5,70.7,129.4 -0.170810327798885,0.1711712201434925,1.0471975511965976,3209.7,431.9,51.6,106.4,59.5,186.7 -0.1708437040281063,0.17111498252383006,1.1780972450961724,2381.5,252.4,31.4,31.2,63.3,282.4 -0.17084832325699875,0.17110941383326517,1.3089969389957472,1938.1,161.1,33.5,72.1,95.6,474.6 -0.1708715718315037,0.1710967782855104,1.4398966328953218,1740.9,106.5,93.6,91.1,238.2,1066.4 -0.17095432711776093,0.17107660595300755,1.5707963267948966,1699.0,71.0,70.7,63.3,2750.7,2751.3 -0.1709113100008543,0.17107888512209612,1.7016960206944713,234.0,47.4,105.8,48.6,2820.5,2997.7 -0.17094521770671256,0.17108781196987466,1.832595714594046,73.6,187.9,95.6,47.1,3130.9,3258.6 -0.17101313976118324,0.17113000191998973,1.9634954084936205,32.2,110.3,63.3,63.6,2590.7,2371.5 -0.17103505434439628,0.17115381544051078,2.0943951023931953,21.1,51.0,59.5,117.3,2077.1,1949.4 -0.17102763774815324,0.17113722827064848,2.2252947962927703,25.7,129.5,70.7,319.1,1822.2,1763.3 -0.17103393700143585,0.1711624398285987,2.356194490192345,41.5,93.3,93.8,2720.1,1728.3,1728.8 -0.17103101253188935,0.17119495442859467,2.4870941840919194,68.5,70.5,129.5,2800.9,969.5,149.7 -0.17103395495127643,0.17118772136132,2.6179938779914944,73.8,59.9,187.5,3119.4,430.7,51.4 -0.17101949312353354,0.17120518819380748,2.748893571891069,62.7,62.7,282.7,2537.5,251.6,31.6 -0.17102661714177897,0.17119889354838946,2.8797932657906435,46.6,94.9,474.6,2030.4,161.2,33.8 -0.1710156996924198,0.17120416481476886,3.010692959690218,48.2,235.0,1057.1,1784.7,106.4,93.1 -0.171001167897074,0.1712084755652845,0.0,63.2,2750.9,2751.0,1698.9,71.0,71.0 -0.1709407383498361,0.17120733026365764,0.1308996938995747,91.6,2823.1,2882.2,823.8,47.4,106.7 -0.1709578645261787,0.17121162166274018,0.2617993877991494,139.5,3130.6,3258.8,349.2,188.0,95.5 -0.17095484385606743,0.17120863953319754,0.39269908169872414,223.8,2592.2,2372.9,191.3,110.2,63.1 -0.1709475888984463,0.17120148781700406,0.5235987755982988,393.2,2078.0,1950.3,114.0,50.7,59.9 -0.1709512435180066,0.1712039841156967,0.6544984694978736,912.2,1823.3,1764.1,68.5,129.6,70.5 -0.17094563086795292,0.17118411735103378,0.7853981633974483,2721.3,1728.8,1728.2,40.9,93.8,93.2 -0.17094620862298535,0.17119902783253682,0.916297857297023,2842.3,973.7,150.1,25.4,70.7,129.5 -0.17095159155200546,0.17118354809869984,1.0471975511965976,3209.2,431.8,51.5,106.4,59.5,186.7 -0.17096527581169083,0.1711589841248855,1.1780972450961724,2381.8,252.3,31.3,31.1,63.3,282.4 -0.17094505263681514,0.17117683030299502,1.3089969389957472,1938.0,161.1,33.4,72.1,95.5,474.6 -0.1709403358920697,0.17117924640354332,1.4398966328953218,1740.8,106.5,93.6,91.1,238.1,1066.2 -0.17099407821366758,0.17116583483035575,1.5707963267948966,1698.9,70.9,70.7,63.3,2751.3,2751.2 -0.17092395321983989,0.17116475673010112,1.7016960206944713,234.0,47.4,105.8,48.6,2820.7,2997.7 -0.1709342730071557,0.17116656945991537,1.832595714594046,73.7,187.9,95.5,47.0,3131.5,3259.2 -0.17098265797395706,0.1711966023613367,1.9634954084936205,32.2,110.2,63.3,63.6,2591.4,2371.7 -0.17099016908308912,0.1712050462607302,2.0943951023931953,21.1,51.1,59.4,117.3,2076.7,1949.4 -0.17097362285299042,0.1711714721431763,2.2252947962927703,25.8,129.5,70.7,319.0,1822.3,1763.5 -0.17097582740761388,0.17117913567211307,2.356194490192345,41.5,93.3,93.8,2720.6,1728.3,1728.7 -0.17097347886741773,0.17119492203305464,2.4870941840919194,68.5,70.5,129.5,2800.6,969.4,149.8 -0.1709808962021019,0.1711729955154051,2.6179938779914944,73.8,59.9,187.5,3119.2,430.7,51.5 -0.17097402828583994,0.17117833005250227,2.748893571891069,62.7,62.7,282.7,2537.6,251.7,31.6 -0.17099076518448586,0.17116306360610856,2.8797932657906435,46.6,94.9,474.7,2030.2,161.3,33.8 -0.1709905912405167,0.17116261286489887,3.010692959690218,48.2,235.0,1057.2,1784.9,106.3,93.1 -0.9710877493256871,0.37118694860654244,0.0,263.2,1951.1,1951.3,1498.8,870.9,871.0 -0.9710382827863379,0.37098405946387336,0.1308996938995747,298.5,1994.3,2053.9,1535.6,875.9,917.0 -0.9710381757749312,0.370984149929791,0.2617993877991494,370.6,2206.6,2334.6,1706.2,873.6,494.0 -0.9710293635896402,0.3709786820478571,0.39269908169872414,507.0,2309.7,2090.3,1320.7,564.5,345.2 -0.9710290077614445,0.37098031827005906,0.5235987755982988,791.4,1847.1,1719.4,1038.8,418.6,290.9 -0.9710392944039812,0.3709967219266379,0.6544984694978736,1682.9,1616.5,1557.0,897.0,336.5,277.4 -0.9710369112884967,0.3709927255185279,0.7853981633974483,1921.4,1528.9,1528.3,840.9,293.7,293.0 -0.9710367690704876,0.3710229590838243,0.916297857297023,2014.4,1556.9,1615.5,853.6,277.5,336.3 -0.9710380009198466,0.37102132405601185,1.0471975511965976,2286.0,1718.2,1648.8,792.8,290.3,417.6 -0.9710448839876867,0.37100841688373043,1.1780972450961724,2097.9,1386.0,1165.0,507.5,345.3,564.3 -0.9710160603251473,0.3710351619393031,1.3089969389957472,1706.8,1085.9,958.4,370.8,493.6,872.8 -0.9710015399095143,0.37104368839557544,1.4398966328953218,1534.2,934.2,875.8,297.8,1016.7,1845.4 -0.9710448812658378,0.3710337420863865,1.5707963267948966,1498.8,871.2,870.8,263.1,1951.8,1951.0 -0.9710105195776133,0.3710323723406108,1.7016960206944713,1577.1,875.1,931.1,255.3,1993.4,2177.8 -0.9709820639263782,0.3710233718380396,1.832595714594046,1667.6,872.9,493.8,278.0,2207.3,2334.1 -0.9710169049839095,0.3710461183107918,1.9634954084936205,1161.0,564.3,345.2,346.8,2308.4,2089.1 -0.9710189104573761,0.37105004267359365,2.0943951023931953,945.5,417.6,290.3,516.3,1845.7,1718.3 -0.9709997219399025,0.37101298896938184,2.2252947962927703,853.9,336.3,277.5,1093.2,1615.3,1556.7 -0.9710007112979953,0.37101747021236253,2.356194490192345,841.5,293.1,293.7,1920.2,1528.5,1529.1 -0.9709982132371676,0.37103032379725787,2.4870941840919194,896.9,277.4,336.5,1972.1,1557.2,1616.7 -0.9710065024733938,0.37100583401905163,2.6179938779914944,515.7,290.9,418.6,2195.2,1719.2,1645.3 -0.9710011801597245,0.37100926196492856,2.748893571891069,345.3,345.3,565.3,2254.0,1383.3,1162.9 -0.9710199786622724,0.37099287403960224,2.8797932657906435,277.5,493.6,873.7,1799.1,1085.7,958.5 -0.9710219797863664,0.37099215700681176,3.010692959690218,255.1,1008.9,1831.8,1578.0,934.4,875.7 -0.9710647724864025,0.4712843599225447,0.0,363.1,1951.1,1951.0,1399.0,871.1,871.0 -0.9710154888631561,0.47069585729519026,0.1308996938995747,402.2,1994.7,2053.9,1432.0,876.2,935.3 -0.9710433455297134,0.4707050089612146,0.2617993877991494,486.1,2206.5,2334.1,1590.8,958.5,693.3 -0.9710773551758243,0.4707270258262448,0.39269908169872414,648.5,2168.9,1949.6,1320.8,705.6,486.4 -0.9711047113552953,0.47075894092070936,0.5235987755982988,990.8,1731.4,1603.8,1038.9,534.1,406.4 -0.9711315701919132,0.47080695228128944,0.6544984694978736,1972.2,1512.9,1453.6,896.9,440.0,380.9 -0.971136510428923,0.4708348968010918,0.7853981633974483,1921.2,1429.2,1428.5,840.9,393.5,393.0 -0.9711354876233573,0.4708950412710162,0.916297857297023,2014.6,1453.1,1512.0,853.5,380.9,439.7 -0.971128853350764,0.4709201388582498,1.0471975511965976,2285.7,1603.2,1648.6,945.8,405.8,533.1 -0.9711224230591912,0.47092938774011484,1.1780972450961724,1956.5,1385.8,1164.8,649.1,486.2,705.5 -0.971076726501363,0.47097274125443267,1.3089969389957472,1591.4,1085.9,958.2,486.4,692.8,1072.0 -0.9708911953557793,0.47082556738965287,1.4398966328953218,1430.7,934.0,875.8,401.1,1408.7,1992.3 -0.9711381391559077,0.47077140334707646,1.5707963267948966,1399.2,870.7,870.7,363.1,1950.8,1951.3 -0.9710166148739435,0.4707672307077948,1.7016960206944713,1473.5,875.1,933.5,358.9,1993.2,2051.8 -0.970996163580897,0.47076068192634013,1.832595714594046,1666.5,959.3,692.4,393.8,2207.6,2335.6 -0.971062323988798,0.47080338263191757,1.9634954084936205,1160.8,705.0,486.2,488.7,2166.5,1947.1 -0.9710936293838698,0.4708392338575418,2.0943951023931953,945.1,532.9,405.7,716.5,1730.0,1602.7 -0.9710945314769056,0.47083968562838496,2.2252947962927703,853.7,439.7,381.0,1482.7,1511.7,1453.1 -0.9711048430530379,0.47088380956463416,2.356194490192345,841.7,392.9,393.6,1920.4,1428.2,1429.1 -0.9711010784381738,0.47093492069862886,2.4870941840919194,942.5,380.9,440.0,1972.9,1453.9,1513.2 -0.9710995388666309,0.47094408361567486,2.6179938779914944,714.4,406.5,534.3,2195.0,1603.9,1644.2 -0.9710769860310215,0.47097564262815816,2.748893571891069,486.4,486.8,707.0,2111.6,1382.1,1162.4 -0.9708849260929544,0.4707941645578002,2.8797932657906435,392.9,693.5,1073.5,1683.5,1085.4,958.1 -0.9709051707730544,0.470784273951087,3.010692959690218,358.5,1397.7,1993.4,1474.1,934.3,875.5 -0.9709831327268359,0.5711054371949382,0.0,462.9,1951.0,1951.1,1299.1,870.8,871.0 -0.9709758132714968,0.5711055716021953,0.1308996938995747,505.6,1994.8,2054.4,1328.9,876.0,935.4 -0.9709375091454555,0.5710945566041614,0.2617993877991494,601.7,2206.9,2334.7,1475.8,1009.5,892.0 -0.9708970470605356,0.5710698540631818,0.39269908169872414,790.3,2026.8,1807.5,1320.2,846.3,627.3 -0.9708638413452612,0.571036528495559,0.5235987755982988,1190.2,1615.4,1487.7,1038.9,649.4,522.0 -0.9708510756803362,0.5710102646563457,0.6544984694978736,1972.3,1409.1,1350.0,896.6,543.3,484.3 -0.9708382270593409,0.5709606843999928,0.7853981633974483,1921.2,1329.0,1328.7,840.8,493.5,493.0 -0.9708396347187379,0.5709473041936706,0.916297857297023,2014.9,1349.9,1409.1,853.7,484.5,543.4 -0.9708530865447936,0.5709066447873132,1.0471975511965976,2286.4,1488.0,1615.1,945.9,521.4,648.6 -0.9708805258398792,0.5708619790867546,1.1780972450961724,1813.8,1385.6,1164.4,790.6,627.6,846.9 -0.9708773371046793,0.5708654429957192,1.3089969389957472,1475.3,1085.8,958.2,601.8,892.4,1272.3 -0.9708914303950092,0.5708591833675216,1.4398966328953218,1327.4,934.1,875.6,504.5,1798.4,2119.1 -0.9710095935457502,0.5708302509611389,1.5707963267948966,1298.7,871.0,870.8,463.0,1951.1,1951.2 -0.9709706872180477,0.5708292078274941,1.7016960206944713,1370.1,875.1,933.6,462.3,1993.2,2051.7 -0.9709599526671933,0.5708258491758933,1.832595714594046,1568.8,1027.5,891.6,509.3,2207.4,2335.3 -0.971015773991931,0.5708621623499184,1.9634954084936205,1160.9,846.2,627.2,630.3,2025.3,1806.5 -0.9710347836641537,0.5708848074220751,2.0943951023931953,945.3,648.5,521.2,916.0,1614.6,1487.1 -0.9710268504672206,0.5708687487191295,2.2252947962927703,853.7,543.2,484.4,1869.7,1408.5,1349.6 -0.9710330786753293,0.5708951040284702,2.356194490192345,841.5,492.9,493.5,1920.4,1328.7,1329.2 -0.9710300203632743,0.5709290319897831,2.4870941840919194,897.1,484.3,543.5,1972.3,1350.2,1409.5 -0.9710331582656284,0.5709230950712774,2.6179938779914944,913.5,522.2,649.8,2195.4,1488.4,1615.7 -0.9710185640552547,0.5708789108288461,2.748893571891069,627.9,628.3,848.4,1970.9,1382.3,1162.3 -0.9708903171247601,0.5708132346504888,2.8797932657906435,508.6,893.0,1273.1,1567.9,1085.7,958.2 -0.9709086747949257,0.5708042943568967,3.010692959690218,462.0,1785.0,2120.0,1370.8,934.4,875.8 -0.9709837263772103,0.6711225643608882,0.0,562.9,1951.2,1951.1,1199.1,870.9,871.0 -0.9709743856984587,0.6711225480043443,0.1308996938995747,609.2,1994.9,2054.1,1225.3,876.1,935.5 -0.9709346202273815,0.671111010002124,0.2617993877991494,717.4,2207.2,2334.6,1360.4,958.6,1047.6 -0.9708930779048748,0.6710855535568001,0.39269908169872414,932.0,1885.8,1666.5,1320.3,987.5,768.5 -0.9708590979386499,0.6710513216207752,0.5235987755982988,1389.6,1500.0,1372.3,1038.5,765.1,637.5 -0.9708458878197564,0.6710241122731466,0.6544984694978736,1972.1,1305.6,1246.7,896.7,646.9,587.9 -0.9708328276257702,0.6709735555964838,0.7853981633974483,1921.0,1229.0,1228.8,840.8,593.5,593.0 -0.9708342859223654,0.6709592881132251,0.916297857297023,2014.8,1246.2,1305.3,853.6,588.0,646.8 -0.9708479781916207,0.6709178396655142,1.0471975511965976,2286.3,1372.4,1499.3,1103.5,636.9,764.3 -0.9708757909826639,0.6708724816538867,1.1780972450961724,1672.6,1385.5,1164.8,932.2,768.8,987.9 -0.9708730923231208,0.6708754297979089,1.3089969389957472,1359.9,1085.6,958.0,717.6,1091.9,1471.4 -0.9708877483524412,0.670868837946551,1.4398966328953218,1223.8,934.0,875.8,608.1,2050.9,1992.6 -0.9709611558722108,0.6708526584237158,1.5707963267948966,1199.1,870.7,870.6,562.9,1951.3,1951.2 -0.9709546505187918,0.6708527166426463,1.7016960206944713,1266.5,875.1,933.6,565.6,1993.2,2051.8 -0.970950791625147,0.6708514382640569,1.832595714594046,1453.3,959.4,1047.0,625.0,2207.3,2335.0 -0.9710059673843373,0.6708872765694791,1.9634954084936205,1160.8,987.3,768.3,772.1,1884.7,1665.8 -0.9710487747808042,0.6709417640069155,2.0943951023931953,945.2,764.0,636.6,1115.8,1499.1,1371.7 -0.9710251766948816,0.6708961627906669,2.2252947962927703,853.7,646.8,587.9,2013.9,1304.9,1246.2 -0.971028981309013,0.670911806095694,2.356194490192345,841.4,593.0,593.7,1920.6,1228.6,1229.1 -0.9710261010303426,0.6709419681951738,2.4870941840919194,896.9,587.9,647.1,1972.2,1246.6,1305.9 -0.9710296304435647,0.6709346985143747,2.6179938779914944,1039.5,637.8,765.5,2195.3,1372.9,1500.5 -0.9710153813323252,0.6709532141089392,2.748893571891069,769.2,769.7,989.8,1829.5,1382.6,1162.7 -0.9710227096022186,0.6709483420003874,2.8797932657906435,624.1,1092.6,1472.7,1452.6,1085.5,958.0 -0.9710115890815969,0.6709553025920485,3.010692959690218,565.5,2052.5,1993.6,1267.3,934.5,875.7 -0.9710380967443356,0.7712351940184805,0.0,663.0,1951.0,1951.0,1099.1,871.0,870.9 -0.9709980964977942,0.7706618625543835,0.1308996938995747,712.8,1995.0,2053.8,1121.4,876.0,935.4 -0.9710313283236548,0.7706727172609109,0.2617993877991494,832.7,2206.3,2161.7,1244.2,958.4,1085.9 -0.9710695101509427,0.7706973689663832,0.39269908169872414,1073.3,1745.5,1525.8,1320.7,1129.3,910.0 -0.9710999018546085,0.7707325326019687,0.5235987755982988,1588.1,1384.3,1257.0,1039.0,881.0,753.3 -0.9711287436072178,0.7707841189885449,0.6544984694978736,1972.3,1202.2,1143.2,896.9,750.7,691.4 -0.9711345952531055,0.770815728722875,0.7853981633974483,1921.4,1128.9,1128.5,840.8,693.4,692.9 -0.9711335803597756,0.7708793903277942,0.916297857297023,2014.5,1142.6,1201.5,853.4,691.5,750.2 -0.9711261168903168,0.7708269867236708,1.0471975511965976,2186.3,1256.5,1383.8,945.6,752.3,879.6 -0.9711150909567503,0.770926698007752,1.1780972450961724,1531.5,1386.1,1165.1,1074.3,909.6,1128.6 -0.9710710479303744,0.7709686706040022,1.3089969389957472,1269.9,1086.0,958.4,833.1,1290.1,1669.6 -0.971035947789392,0.7709891457716802,1.4398966328953218,1120.4,934.2,875.7,711.5,2099.1,1992.5 -0.9710564976283261,0.7709852885323158,1.5707963267948966,1098.9,871.0,870.7,662.9,1951.1,1951.0 -0.971000186337328,0.7709840377310191,1.7016960206944713,1163.0,875.2,933.4,669.0,1993.0,2051.7 -0.9709518301804401,0.770969854512833,1.832595714594046,1337.5,959.1,1086.8,740.2,2206.9,2159.5 -0.9709698398566936,0.7709828296357508,1.9634954084936205,1161.3,1128.8,909.7,913.6,1743.8,1525.1 -0.9709592446447523,0.770973927271307,2.0943951023931953,945.5,879.6,752.3,1314.4,1384.0,1256.6 -0.9709319826238565,0.7709224455883696,2.2252947962927703,854.0,750.3,691.6,2140.3,1201.5,1142.8 -0.9709293745586107,0.7709118459947573,2.356194490192345,841.6,692.9,693.5,1920.6,1128.4,1129.1 -0.9709275271859442,0.7709102633406195,2.4870941840919194,896.9,691.5,750.5,1972.3,1143.1,1202.1 -0.970939974172641,0.7708732055594549,2.6179938779914944,1039.2,753.2,880.9,2195.0,1257.0,1384.6 -0.970941641851482,0.7708664387121178,2.748893571891069,911.1,910.7,1130.8,1688.6,1383.0,1162.9 -0.9709691132004735,0.7708428202206468,2.8797932657906435,739.6,1291.5,1671.1,1336.9,1085.8,958.4 -0.9709806188122355,0.7708378648947394,3.010692959690218,669.1,2084.3,1993.7,1164.1,934.5,875.7 -0.9710344584872107,0.8711385178090081,0.0,762.8,1950.9,1951.4,999.2,870.9,871.2 -0.9709965291040207,0.8706642161135982,0.1308996938995747,816.4,1994.7,2053.9,1017.9,876.0,935.3 -0.9710303835064764,0.8706752736871872,0.2617993877991494,948.4,2206.8,1962.4,1128.7,958.6,1204.0 -0.9710684282074308,0.8706998369081307,0.39269908169872414,1215.0,1604.0,1384.6,1320.8,1164.7,1051.1 -0.9710985507831114,0.8707347079407222,0.5235987755982988,1787.3,1294.4,1141.2,1038.7,996.6,868.9 -0.9711271835484222,0.8707859008173575,0.6544984694978736,1972.4,1098.7,1039.6,896.9,854.1,795.1 -0.9711329376672106,0.8708170808529021,0.7853981633974483,1921.3,1029.2,1028.4,840.9,793.4,793.0 -0.9711319351064369,0.8708803270529419,0.916297857297023,2014.7,1039.1,1098.1,853.4,795.0,853.7 -0.9711245835899383,0.8709082388363236,1.0471975511965976,1986.8,1141.0,1268.1,945.5,867.9,995.1 -0.9711168230089855,0.8709198075810547,1.1780972450961724,1389.8,1383.6,1165.2,1160.0,1050.5,1269.7 -0.9710694184732062,0.8709649524225409,1.3089969389957472,1129.4,1085.8,958.4,948.8,1489.5,1868.8 -0.971033784718321,0.8709857098276017,1.4398966328953218,1017.2,934.3,875.9,815.0,2051.1,1992.5 -0.9710549505218671,0.8709817073054469,1.5707963267948966,999.2,871.0,870.5,763.0,1951.6,1951.1 -0.9709995944178281,0.8709804827878487,1.7016960206944713,1059.4,874.9,933.4,772.5,1993.2,2051.6 -0.9709522078422322,0.8709665847682901,1.832595714594046,1221.7,959.2,1202.9,856.0,2206.6,1960.4 -0.9709710601837915,0.870980082367963,1.9634954084936205,1161.4,1166.1,1050.7,1055.1,1602.9,1383.8 -0.9709610971882279,0.8709718550660168,2.0943951023931953,945.4,995.1,867.9,1514.1,1268.3,1141.0 -0.9709342405249138,0.8709211215983206,2.2252947962927703,854.1,853.8,794.8,2014.1,1098.1,1039.1 -0.9709318157069381,0.870911297738941,2.356194490192345,841.7,792.9,793.4,1920.4,1028.7,1029.1 -0.9709299422834797,0.8709104575997335,2.4870941840919194,896.8,794.9,854.1,1972.4,1039.8,1098.7 -0.9709421928897831,0.8708740505860721,2.6179938779914944,1039.2,868.9,996.5,2194.3,1141.4,1269.0 -0.9709435214526703,0.8708678229581948,2.748893571891069,1052.4,1052.3,1272.3,1547.4,1383.0,1163.2 -0.9709705667426651,0.8708446019872658,2.8797932657906435,855.3,1490.8,1870.7,1221.6,1085.9,958.3 -0.9709815954246027,0.8708398997390001,3.010692959690218,772.6,2052.5,1993.7,1060.6,934.3,875.7 -0.17093882008905698,0.17080486442859621,0.0,63.0,2750.6,2750.8,1698.9,71.0,71.0 -0.1709196375910661,0.17143219469348137,0.1308996938995747,91.5,2822.8,2882.4,823.9,47.5,106.7 -0.17091343903417147,0.17142951034574905,0.2617993877991494,139.4,3130.8,3258.1,349.3,187.8,95.3 -0.1708712956474166,0.1714021341857095,0.39269908169872414,223.7,2592.0,2373.0,191.3,110.1,63.0 -0.17082969868641795,0.17135822731937367,0.5235987755982988,393.1,2077.8,1950.0,114.0,50.8,59.8 -0.17081038958186354,0.1713179686683559,0.6544984694978736,912.0,1823.3,1764.3,68.6,129.5,70.4 -0.17079421753264898,0.17125302528061392,0.7853981633974483,2720.8,1728.8,1728.3,40.9,93.8,93.2 -0.1707960818753344,0.1712250867696452,0.916297857297023,2842.5,974.2,150.3,25.5,70.7,129.4 -0.1708130656101091,0.17117120717774026,1.0471975511965976,3209.5,431.9,51.6,106.4,59.5,186.7 -0.17084639470606872,0.1711150086551465,1.1780972450961724,2381.2,252.4,31.4,31.2,63.3,282.3 -0.17085096732681151,0.17110946881872557,1.3089969389957472,1937.8,161.1,33.5,72.1,95.5,474.6 -0.1708741703543489,0.17109685611183933,1.4398966328953218,1741.1,106.5,93.6,91.1,238.2,1066.3 -0.17095688053662658,0.17107668354259897,1.5707963267948966,1698.6,71.0,70.7,63.3,2751.0,2751.1 -0.1709169370047475,0.17107634440417208,1.7016960206944713,234.0,47.4,105.8,48.6,2820.1,2998.0 -0.17094931888107373,0.17108476874749923,1.832595714594046,73.7,187.9,95.6,47.1,3131.5,3258.8 -0.17101737392167374,0.17112704085992902,1.9634954084936205,32.2,110.3,63.3,63.6,2591.0,2371.6 -0.17103977140940582,0.17115137684687842,2.0943951023931953,21.1,51.1,59.5,117.3,2076.7,1949.6 -0.17103273639345773,0.17113553467047793,2.2252947962927703,25.7,129.5,70.7,319.1,1822.4,1763.5 -0.17103920972799833,0.17116156865371535,2.356194490192345,41.5,93.3,93.8,2720.1,1728.2,1728.7 -0.17103624604423723,0.17119487602563055,2.4870941840919194,68.5,70.5,129.5,2800.1,969.7,149.7 -0.1710389563945245,0.17118834418110307,2.6179938779914944,73.9,59.9,187.5,3119.4,430.7,51.5 -0.17102412612622034,0.17120638244650777,2.748893571891069,62.7,62.7,282.6,2537.0,251.7,31.6 -0.171030782313652,0.17120050971513767,2.8797932657906435,46.6,94.9,474.7,2030.5,161.3,33.8 -0.17101934927180046,0.17120604823024954,3.010692959690218,48.2,235.0,1057.2,1785.0,106.4,93.1 -0.1710042845009696,0.17121047729393313,0.0,63.3,2751.1,2751.1,1698.7,71.0,70.9 -0.17094328748098275,0.171209314721662,0.1308996938995747,91.6,2823.2,2881.8,824.1,47.5,106.7 -0.17096001566935354,0.17121348689383709,0.2617993877991494,139.6,3131.1,3258.4,349.2,188.0,95.4 -0.17095663735003697,0.17121028924573367,0.39269908169872414,223.8,2592.4,2373.0,191.2,110.1,63.1 -0.17094910043003375,0.17120285206290808,0.5235987755982988,393.2,2078.1,1950.4,113.9,50.7,59.9 -0.17095257276880008,0.17120503127098163,0.6544984694978736,912.2,1823.3,1764.3,68.5,129.6,70.5 -0.17094686320201677,0.17118482596330797,0.7853981633974483,2721.7,1728.8,1728.4,40.9,93.8,93.2 -0.1709474379839391,0.17138345797185472,0.916297857297023,2842.5,973.8,150.2,25.5,70.7,129.4 -0.1709553953382194,0.17117367135706463,1.0471975511965976,3209.6,431.9,51.5,106.4,59.5,186.7 -0.17096567710812305,0.17115458440105158,1.1780972450961724,2381.9,252.3,31.3,31.1,63.3,282.4 -0.17094458376873992,0.17117322586690276,1.3089969389957472,1937.7,161.1,33.4,72.0,95.5,474.6 -0.17094029040914163,0.17117541014925686,1.4398966328953218,1741.1,106.5,93.6,91.1,238.1,1066.2 -0.17099497671595862,0.1711617698638297,1.5707963267948966,1698.8,71.0,70.7,63.3,2751.4,2751.2 -0.1709259986974376,0.17116072008222627,1.7016960206944713,234.0,47.4,105.8,48.6,2820.9,2998.1 -0.17093722550367763,0.1711628169322177,1.832595714594046,73.7,187.8,95.5,47.0,3131.5,3259.0 -0.17098642104685666,0.1711933642734349,1.9634954084936205,32.2,110.2,63.3,63.6,2591.1,2371.5 -0.17099454304762915,0.171202471895201,2.0943951023931953,21.2,51.1,59.4,117.3,2076.7,1949.6 -0.17097837684476194,0.1711696423073008,2.2252947962927703,25.8,129.5,70.7,319.0,1822.2,1763.8 -0.17098074185559003,0.1711780713782698,2.356194490192345,41.5,93.2,93.8,2720.8,1728.2,1728.8 -0.17097835636997627,0.17119457814830397,2.4870941840919194,68.5,70.5,129.5,2799.9,969.4,149.8 -0.17098556355198288,0.17117328348894834,2.6179938779914944,73.8,59.9,187.5,3119.2,430.7,51.5 -0.17097836430824004,0.17117913130669127,2.748893571891069,62.7,62.7,282.6,2537.4,251.7,31.6 -0.17099468129556097,0.1711642437356724,2.8797932657906435,46.6,95.0,474.6,2029.6,161.3,33.8 -0.17099404498455972,0.17116403341775066,3.010692959690218,48.2,235.1,1057.4,1784.7,106.4,93.1 -1.071078824454931,0.3711826384075627,0.0,263.3,1851.1,1850.8,1498.8,970.8,971.0 -1.0710344464853938,0.3709882249929306,0.1308996938995747,298.6,1890.9,1950.3,1535.6,979.5,1001.7 -1.0710343488770022,0.37098830338580124,0.2617993877991494,370.5,2091.2,2218.7,1706.5,873.6,494.0 -1.071025982797285,0.37098310219376285,0.39269908169872414,507.0,2309.9,2090.3,1461.8,564.5,345.2 -1.0710253285524702,0.37098439985963094,0.5235987755982988,791.6,1847.0,1719.3,1154.8,418.6,291.0 -1.0710352913410228,0.37100017285529496,0.6544984694978736,1683.2,1616.2,1557.5,1000.5,336.4,277.4 -1.0710327464178186,0.3709954323857654,0.7853981633974483,1821.0,1529.0,1528.3,940.8,293.6,293.1 -1.07103263599082,0.37102493610205234,0.916297857297023,1911.1,1556.5,1615.4,957.1,277.5,336.4 -1.0710340743624354,0.371022641639392,1.0471975511965976,2170.1,1718.7,1846.0,792.9,290.3,417.6 -1.071041299935311,0.37100919020419276,1.1780972450961724,2098.0,1527.6,1306.7,507.4,345.3,564.3 -1.0710129047833126,0.3710355313059823,1.3089969389957472,1706.9,1201.4,1074.0,370.9,493.8,872.9 -1.0709988650658402,0.37104379487182193,1.4398966328953218,1534.3,1037.6,979.2,297.8,1017.0,1845.8 -1.0710427055310094,0.3710337252768512,1.5707963267948966,1499.3,970.8,971.1,263.1,1851.0,1850.9 -1.0710088127043782,0.3710323598142513,1.7016960206944713,1576.7,978.6,1016.9,255.3,1889.6,1948.3 -1.0709807776432696,0.37102347292751214,1.832595714594046,1800.0,873.0,493.7,278.1,2091.6,2218.9 -1.0710159741209453,0.3710464251988055,1.9634954084936205,1302.4,564.3,345.3,346.8,2308.5,2089.3 -1.071018248244338,0.3710506168435217,2.0943951023931953,1061.1,417.6,290.3,516.4,1846.1,1718.7 -1.0709992361010745,0.3710138641947769,2.2252947962927703,957.4,336.3,277.5,1093.2,1615.6,1556.6 -1.0710003110023238,0.371018661762367,2.356194490192345,941.5,293.1,293.6,1820.3,1528.4,1529.1 -1.0709978115535737,0.3710318212383943,2.4870941840919194,1000.4,277.3,336.4,1868.6,1557.2,1616.1 -1.071006024855015,0.37100760282794454,2.6179938779914944,515.7,290.9,418.6,2078.9,1719.1,1844.8 -1.0710005652911792,0.37101125589964257,2.748893571891069,345.3,345.4,565.4,2254.2,1524.4,1304.2 -1.0710191861543483,0.370995033390942,2.8797932657906435,277.5,493.6,873.5,1799.4,1201.4,1074.0 -1.0710209869860687,0.3709944188777399,3.010692959690218,255.1,1008.9,1831.4,1577.7,1038.0,979.2 -1.0710635373202997,0.4712864350314985,0.0,363.0,1851.2,1850.8,1398.8,971.0,971.0 -1.0710145795006887,0.4706960972865799,0.1308996938995747,402.1,1890.9,1949.9,1432.2,979.7,1039.0 -1.071042482832652,0.4707052610726743,0.2617993877991494,486.2,2091.0,2218.6,1591.1,1073.0,693.4 -1.071076484321747,0.47072726873950743,0.39269908169872414,648.6,2168.7,1949.3,1461.7,705.6,486.3 -1.0711038226354173,0.4707591587133402,0.5235987755982988,990.6,1731.4,1603.4,1154.6,534.2,406.5 -1.0711306721753868,0.4708071399849707,0.6544984694978736,1868.5,1512.8,1453.8,1000.2,439.9,380.8 -1.0711356091330966,0.47083505123853153,0.7853981633974483,1821.5,1428.9,1428.6,940.8,393.5,393.0 -1.0711345936913639,0.4708951675543076,0.916297857297023,1911.3,1453.3,1512.1,957.0,380.9,439.8 -1.0711279725484586,0.47092024199788707,1.0471975511965976,2170.2,1603.1,1730.3,992.0,405.8,533.1 -1.0711215577367594,0.4709294706678657,1.1780972450961724,1956.4,1527.5,1306.6,649.0,486.4,705.4 -1.0710758796549937,0.47097281190289797,1.3089969389957472,1591.7,1201.4,1073.8,486.2,692.6,1071.8 -1.071042238140971,0.47099231714485645,1.4398966328953218,1431.1,1037.7,979.3,401.1,1406.4,1889.1 -1.0710655322203781,0.47098774777427255,1.5707963267948966,1399.1,970.8,970.7,362.9,1851.1,1851.1 -1.0710121953196134,0.47098650565834177,1.7016960206944713,1473.4,978.5,1037.0,358.7,1889.9,1948.5 -1.0709666396662105,0.4709730483115451,1.832595714594046,1684.1,1071.9,692.6,393.5,2091.5,2219.2 -1.0709870192791586,0.4709874667790219,1.9634954084936205,1302.5,705.3,486.2,488.4,2167.4,1948.0 -1.070978164536782,0.4709804658537651,2.0943951023931953,1061.0,532.9,405.7,715.7,1730.3,1603.0 -1.070952007067081,0.4709310579205943,2.2252947962927703,957.3,439.7,380.9,1480.1,1512.1,1453.6 -1.0709498555846908,0.47092260818238185,2.356194490192345,941.7,392.9,393.5,1820.2,1428.5,1429.0 -1.0709478320907244,0.4709230869700416,2.4870941840919194,1000.3,380.8,439.9,1868.7,1453.9,1513.0 -1.0709596602699571,0.4708877773828075,2.6179938779914944,714.7,406.4,534.1,2079.1,1604.1,1731.3 -1.0709602738891928,0.4708824376958256,2.748893571891069,486.6,486.5,706.6,2113.1,1524.4,1304.3 -1.0709865175375717,0.47085981027495816,2.8797932657906435,392.9,693.0,1072.8,1683.6,1201.3,1073.8 -1.0709966886073492,0.470855436217434,3.010692959690218,358.5,1395.8,1890.2,1474.4,1038.0,979.2 -1.071049000270197,0.5711549356092747,0.0,462.8,1851.6,1851.1,1299.0,971.0,970.9 -1.0710094969617507,0.5706660802242132,0.1308996938995747,505.7,1891.0,1950.5,1328.6,979.5,1038.8 -1.0710427847251232,0.5706769815142034,0.2617993877991494,601.6,2091.2,2218.8,1475.3,1074.2,892.8 -1.0710805229963718,0.5707014009437441,0.39269908169872414,790.1,2027.3,1808.2,1461.7,846.8,627.6 -1.0711104582893878,0.5707361459176057,0.5235987755982988,1189.9,1615.5,1488.1,1154.6,649.8,522.1 -1.0711389093740311,0.5707871808357301,0.6544984694978736,1984.1,1409.2,1350.0,1000.3,543.5,484.4 -1.0711445650250035,0.5708182133567663,0.7853981633974483,1821.1,1329.2,1328.3,940.7,493.6,493.0 -1.0711434676310978,0.5708812630145901,0.916297857297023,1910.8,1349.8,1408.5,956.8,484.4,543.2 -1.0711360802353518,0.5709089647885897,1.0471975511965976,2170.5,1487.9,1615.1,1061.3,521.3,648.5 -1.0711283645204848,0.5709203768382043,1.1780972450961724,1814.9,1527.6,1306.8,790.5,627.5,846.4 -1.0710810332509282,0.5709653582101764,1.3089969389957472,1475.8,1201.8,1074.0,601.9,892.2,1271.1 -1.071045512573746,0.5709859512087228,1.4398966328953218,1327.5,1037.7,979.2,504.6,1795.8,1889.1 -1.0710668332854079,0.5709819218853609,1.5707963267948966,1299.1,971.0,970.7,462.9,1851.3,1851.2 -1.0710116250725619,0.5709807006150343,1.7016960206944713,1370.0,978.7,1036.9,462.0,1889.6,1948.0 -1.0709643808850324,0.5709668079696613,1.832595714594046,1568.8,1074.9,891.8,509.1,2091.3,2218.9 -1.0709833305871683,0.5709804082958885,1.9634954084936205,1302.5,846.2,627.3,630.0,2026.3,1807.3 -1.070973401197781,0.5709723309852552,2.0943951023931953,1061.1,648.5,521.2,915.7,1614.9,1487.5 -1.0709465560531128,0.5709217018264523,2.2252947962927703,957.3,543.2,484.3,1867.6,1408.7,1349.8 -1.0709440973036723,0.57091197342902,2.356194490192345,941.5,492.9,493.5,1820.1,1328.7,1329.0 -1.0709421246844253,0.5709112305721726,2.4870941840919194,1000.4,484.4,543.4,1868.8,1350.3,1409.5 -1.0709543096794296,0.5708748539790638,2.6179938779914944,913.9,522.1,649.8,2079.2,1488.0,1616.1 -1.0709555146227694,0.5708686539299459,2.748893571891069,628.0,627.9,848.2,1971.6,1524.2,1304.5 -1.0709929323143468,0.5708353448111307,2.8797932657906435,508.5,892.6,1272.5,1568.2,1201.3,1073.7 -1.0709950948744882,0.5708352665906924,3.010692959690218,462.0,1782.8,1890.4,1371.3,1038.0,979.1 -1.0710463105233834,0.6711362516225701,0.0,562.8,1851.0,1851.2,1199.2,971.0,971.2 -1.0710187378758267,0.6711359687593146,0.1308996938995747,609.1,1890.9,1950.5,1225.4,979.7,1038.8 -1.0709646542596551,0.671120404991397,0.2617993877991494,717.0,2091.3,2218.2,1360.1,1184.4,1091.9 -1.0709118226116479,0.6710883145201068,0.39269908169872414,931.5,1886.6,1667.2,1461.9,987.8,768.5 -1.0708693826648756,0.6710455760114953,0.5235987755982988,1388.7,1500.2,1398.1,1154.5,765.2,637.5 -1.0708236620356706,0.6709561319772386,0.6544984694978736,1868.6,1305.8,1246.6,1000.5,646.9,587.8 -1.0708171752506337,0.6709352357790361,0.7853981633974483,1820.9,1229.1,1228.8,941.0,593.5,592.9 -1.0708183777265259,0.670920837378141,0.916297857297023,1911.1,1246.4,1305.0,957.1,587.9,646.8 -1.070834672693237,0.670870275295971,1.0471975511965976,2170.1,1371.9,1499.5,1147.9,636.8,764.3 -1.070868619679821,0.6708147520472747,1.1780972450961724,1673.0,1527.9,1306.8,932.4,768.6,987.8 -1.0708745188995397,0.6708096381333133,1.3089969389957472,1360.1,1201.4,1073.9,717.6,1091.5,1470.5 -1.0708991778508643,0.6707979126868915,1.4398966328953218,1224.0,1037.7,979.3,608.1,1947.4,1889.1 -1.0709830114339955,0.6707793991971085,1.5707963267948966,1198.9,971.2,970.7,563.1,1851.1,1850.9 -1.070986237390567,0.6707799834316344,1.7016960206944713,1266.4,978.7,1037.0,565.5,1889.7,1948.0 -1.0709908987642462,0.6707817049896851,1.832595714594046,1453.0,1183.7,1091.2,624.9,2091.5,2219.2 -1.0710788511707487,0.6708362402732357,1.9634954084936205,1302.4,987.6,768.5,771.9,1885.3,1666.2 -1.0710876088412753,0.670847963431539,2.0943951023931953,1060.9,764.2,636.9,1115.2,1499.2,1372.0 -1.0710537829700335,0.6707815934071455,2.2252947962927703,957.2,646.6,588.0,1910.7,1304.7,1246.1 -1.0710691572487132,0.6708493499273653,2.356194490192345,941.7,592.9,593.5,1820.2,1228.6,1229.2 -1.0710654579782222,0.6708969232287258,2.4870941840919194,1000.5,587.9,647.0,1868.7,1246.7,1305.9 -1.071067074402336,0.670895189856233,2.6179938779914944,1113.1,637.6,765.4,2079.0,1372.7,1500.5 -1.0710517928922625,0.6709153390710116,2.748893571891069,769.4,769.4,989.5,1829.9,1524.1,1304.4 -1.071058541953661,0.6709110209037168,2.8797932657906435,624.0,1091.9,1471.7,1452.4,1201.3,1073.9 -1.0710471457412327,0.6709182524345105,3.010692959690218,565.5,1948.9,1890.3,1267.6,1038.1,979.3 -1.0710734412340859,0.7711980884116165,0.0,662.8,1851.3,1851.0,1099.2,971.1,970.9 -1.070975579341894,0.7706756645897765,0.1308996938995747,712.9,1891.1,1950.7,1121.3,979.7,1038.9 -1.0710234233637081,0.7706910310989554,0.2617993877991494,833.0,2091.1,2205.1,1244.3,1074.0,1201.5 -1.071062982300769,0.7707165553601514,0.39269908169872414,1073.5,1744.9,1525.3,1462.1,1129.1,909.9 -1.0710916809315119,0.770749894429307,0.5235987755982988,1588.5,1384.5,1256.7,1154.3,880.8,753.3 -1.0711187769532575,0.7707982960664403,0.6544984694978736,1868.8,1202.1,1165.9,1000.3,750.6,691.5 -1.0711237855410363,0.7708262426649115,0.7853981633974483,1821.3,1128.9,1128.5,940.9,693.5,693.0 -1.071122830137463,0.7708862525088753,0.916297857297023,1910.8,1142.8,1201.6,957.2,691.4,750.3 -1.071116318447247,0.7709112133022311,1.0471975511965976,2169.8,1256.5,1384.0,1061.2,752.4,879.8 -1.0711100558798041,0.7709203983506161,1.1780972450961724,1531.0,1524.9,1306.6,1074.1,909.6,1128.6 -1.0710645159841268,0.7709637244257912,1.3089969389957472,1244.5,1201.5,1073.8,833.0,1290.6,1669.6 -1.0710309918246246,0.7709832274987147,1.4398966328953218,1120.7,1037.5,979.2,711.4,2073.2,1888.9 -1.071054382521723,0.7709787321716193,1.5707963267948966,1099.4,970.9,970.8,663.0,1851.4,1851.1 -1.0709503361433297,0.7709785474335544,1.7016960206944713,1163.1,978.6,1037.1,668.9,1889.7,1948.4 -1.0709375029271,0.7709750721147712,1.832595714594046,1337.3,1074.7,1202.8,740.3,2091.5,2193.3 -1.0709639345502178,0.7709933329790997,1.9634954084936205,1302.1,1128.8,909.3,913.5,1744.0,1525.1 -1.0709541624569971,0.7709853780051823,2.0943951023931953,1060.9,879.6,752.2,1314.8,1383.7,1256.3 -1.0709262638971182,0.7709326252760449,2.2252947962927703,957.3,750.2,691.4,1910.4,1201.4,1165.6 -1.0709231872607112,0.7709199094599692,2.356194490192345,941.6,692.9,693.6,1820.3,1128.8,1128.9 -1.070921372394145,0.7709160910355379,2.4870941840919194,1000.4,691.4,750.6,1868.9,1143.3,1202.1 -1.0709344699569496,0.7708769366834056,2.6179938779914944,1155.1,753.3,881.0,2079.2,1256.9,1384.5 -1.0709371385231687,0.7708684479279819,2.748893571891069,910.9,910.9,1130.9,1688.2,1524.4,1304.3 -1.0709659821054227,0.7708435098831374,2.8797932657906435,739.6,1291.6,1671.5,1336.9,1201.3,1073.7 -1.0709790189056407,0.7708376923046492,3.010692959690218,669.0,2075.2,1890.4,1163.8,1038.1,979.2 -1.0710347392245128,0.8712798133863642,0.0,763.0,1850.7,1851.0,999.1,971.0,971.0 -1.0709889095045226,0.8707951109541303,0.1308996938995747,816.3,1891.2,1950.2,1017.9,979.5,1038.9 -1.0710163198610465,0.8708039481063674,0.2617993877991494,948.6,2091.0,1962.1,1128.4,1074.1,1201.7 -1.0710406855498915,0.8708196796752217,0.39269908169872414,1215.2,1603.9,1384.8,1389.0,1270.7,1050.8 -1.0710585069312073,0.8708410723654587,0.5235987755982988,1787.8,1268.7,1141.5,1154.5,996.7,869.1 -1.071078840097414,0.870876554030044,0.6544984694978736,1868.8,1098.4,1039.6,1000.5,854.1,795.0 -1.0710808099216655,0.8708912336577965,0.7853981633974483,1821.2,1029.1,1028.5,940.8,793.6,793.0 -1.0710802395265695,0.8709387731128528,0.916297857297023,1911.3,1039.4,1098.1,956.9,794.9,853.7 -1.0710770297676913,0.8709525742886284,1.0471975511965976,1986.3,1141.0,1268.0,1061.3,867.9,995.2 -1.0710763368907827,0.8709524914942846,1.1780972450961724,1389.6,1384.0,1306.7,1216.0,1050.8,1270.1 -1.071037861990386,0.8709888839930569,1.3089969389957472,1128.8,1201.5,1074.0,948.9,1490.0,1869.0 -1.071012348437756,0.8710038235384208,1.4398966328953218,1017.0,1037.7,979.1,815.1,1947.2,1889.4 -1.0710441266319484,0.8709970728073544,1.5707963267948966,999.1,971.0,970.8,762.9,1851.8,1851.2 -1.070998788790281,0.8709958423920057,1.7016960206944713,1059.4,978.7,1037.1,772.6,1889.7,1948.0 -1.070960425802444,0.8709842909943062,1.832595714594046,1221.8,1074.9,1202.4,856.1,2091.6,1960.2 -1.0709868828174915,0.87100222638484,1.9634954084936205,1302.0,1269.7,1050.7,1055.5,1602.7,1383.8 -1.0709826015804984,0.8709998171012845,2.0943951023931953,1060.9,995.0,867.9,1514.4,1268.2,1140.7 -1.070959411661202,0.8709555818345858,2.2252947962927703,957.4,853.9,795.1,1910.5,1097.9,1039.3 -1.070958644315705,0.8709525550355257,2.356194490192345,941.6,793.0,793.6,1820.3,1028.7,1029.1 -1.070956496826856,0.8709582516614933,2.4870941840919194,1000.5,794.9,854.1,1868.8,1039.7,1098.6 -1.0709669274008577,0.8709275304641135,2.6179938779914944,1224.9,869.1,996.6,2078.9,1141.3,1269.1 -1.070965109527464,0.8709259546088319,2.748893571891069,1052.6,1052.4,1272.4,1547.2,1387.4,1304.5 -1.070988269001399,0.8709060460010529,2.8797932657906435,855.3,1491.2,1871.0,1221.4,1201.2,1074.1 -1.0709950116724634,0.8709033117037583,3.010692959690218,772.5,1949.0,1890.1,1060.4,1038.0,979.1 -1.1709993584172729,0.17079676495160134,0.0,63.1,1751.0,1750.9,1699.1,1071.0,1070.8 -1.171009135050403,0.17146666556101198,0.1308996938995747,91.6,1787.5,1846.8,1742.5,1049.3,233.6 -1.170955016879531,0.17144910304989236,0.2617993877991494,139.5,1975.5,2103.1,1937.2,474.9,95.3 -1.1709006598104466,0.1714140021365802,0.39269908169872414,223.8,2411.6,2372.2,1603.1,282.3,63.0 -1.1708570273250003,0.17136788695954253,0.5235987755982988,393.3,2078.1,1950.3,1270.2,187.5,59.8 -1.1708378569871911,0.17132805174356402,0.6544984694978736,912.8,1823.1,1763.7,1104.0,129.5,70.5 -1.1708220005983572,0.171264673058513,0.7853981633974483,1721.0,1728.9,1728.4,1040.7,93.8,93.2 -1.1708236565353827,0.1712384563415026,0.916297857297023,1807.9,1763.5,1822.5,917.9,70.7,129.5 -1.1708399840012125,0.17118616512896545,1.0471975511965976,2055.0,1949.0,2048.1,393.9,59.5,186.8 -1.1708723602259383,0.1711313409769235,1.1780972450961724,2381.4,1669.4,1448.8,224.4,63.4,282.4 -1.1708757357447892,0.17112670897978144,1.3089969389957472,1937.7,1316.9,1189.6,139.9,95.6,474.9 -1.1708976481219602,0.17120686555654085,1.4398966328953218,1740.8,1141.2,1082.7,91.1,238.5,1067.2 -1.1710764660778705,0.17121927167752293,1.5707963267948966,1698.8,1070.9,1070.8,63.1,1751.2,1751.3 -1.171014936228905,0.17121644172123052,1.7016960206944713,1783.8,1064.8,237.5,48.4,1786.3,1844.8 -1.1709647323347565,0.1712000339868074,1.832595714594046,2031.1,474.2,95.2,46.9,1976.0,2103.7 -1.1709823205973184,0.17121132357635305,1.9634954084936205,1443.0,282.0,63.1,63.5,2413.1,2370.9 -1.1709718478155278,0.17120131340417788,2.0943951023931953,1176.2,186.6,59.3,117.2,2076.1,1948.9 -1.1709449898187572,0.1711489949467866,2.2252947962927703,1060.9,129.3,70.6,319.4,1822.1,1763.4 -1.1709426493036696,0.17113794624038103,2.356194490192345,1041.7,93.1,93.8,1720.4,1728.3,1729.0 -1.1709406332184584,0.17113620387132222,2.4870941840919194,316.1,70.4,129.6,1765.3,1764.1,1823.4 -1.170952805645403,0.17109877734736,2.6179938779914944,117.4,59.8,187.6,1963.7,1950.7,2042.9 -1.1709537459881956,0.1710914973638158,2.748893571891069,62.6,62.7,282.8,2408.8,1665.5,1445.5 -1.1709806979074777,0.1710669183683653,2.8797932657906435,46.5,94.9,474.9,2029.9,1316.4,1189.2 -1.1709918825098315,0.17106067438423067,3.010692959690218,48.2,235.3,1059.3,1784.6,1141.4,1082.5 -1.1710460835306584,0.2713614452678861,0.0,163.2,1750.9,1751.4,1599.1,1071.1,1071.1 -1.171019054817385,0.27135949705691487,0.1308996938995747,195.1,1787.7,1846.9,1639.0,1083.5,616.6 -1.1709651473671348,0.2713425097793336,0.2617993877991494,255.1,1975.9,2103.2,1822.5,673.8,294.3 -1.1709126834640176,0.27130918716012364,0.39269908169872414,365.5,2412.3,2230.7,1602.8,423.2,204.0 -1.1708708709862927,0.2712656144067691,0.5235987755982988,592.7,1961.9,1834.3,1269.8,302.9,175.3 -1.1708527617373976,0.27122849980962616,0.6544984694978736,1299.4,1719.6,1660.4,1103.8,232.9,173.9 -1.1708374420563483,0.2711679461879051,0.7853981633974483,1721.1,1628.9,1628.3,1041.0,193.7,193.2 -1.1708389464714606,0.2711442620558113,0.916297857297023,1784.6,1659.9,1719.1,1060.7,174.1,232.9 -1.1708546789471812,0.2710942491629409,1.0471975511965976,2055.1,1834.0,1961.3,592.8,175.0,302.3 -1.1708861628783236,0.27104154463800034,1.1780972450961724,2238.8,1668.8,1448.2,365.8,204.4,423.6 -1.170888300723852,0.27103860360127796,1.3089969389957472,1821.7,1316.9,1189.5,255.3,294.8,674.3 -1.1709087105920324,0.2710276525349742,1.4398966328953218,1637.5,1141.0,1082.7,194.4,628.6,1458.0 -1.1709884873342373,0.271008824150887,1.5707963267948966,1598.6,1071.2,1070.7,163.2,1751.4,1750.9 -1.1709883352558326,0.2710079493426454,1.7016960206944713,1680.1,1082.1,627.0,152.0,1786.5,1844.9 -1.1709905160077188,0.27100739468955015,1.832595714594046,1915.6,673.5,294.6,162.6,1976.1,2103.7 -1.1710510362919249,0.271045562728252,1.9634954084936205,1443.1,423.3,204.3,205.3,2412.7,2229.3 -1.1710721462725393,0.27106943543505335,2.0943951023931953,1176.3,302.1,174.9,317.1,1960.5,1833.5 -1.1710652646311817,0.27105449654163016,2.2252947962927703,1060.9,232.9,174.1,707.3,1718.7,1659.9 -1.1710718519967003,0.27108201151039024,2.356194490192345,1041.4,193.2,193.8,1720.4,1628.1,1628.9 -1.171068538191392,0.2711170030118675,2.4870941840919194,701.4,174.0,233.1,1765.5,1660.7,1720.1 -1.1710708840964197,0.2711118388167999,2.6179938779914944,316.5,175.4,303.2,1963.6,1835.0,1962.5 -1.1710551809812582,0.2711312124290697,2.748893571891069,204.0,204.1,424.2,2408.1,1665.3,1445.6 -1.1710610668939987,0.27112637734022416,2.8797932657906435,162.0,294.4,674.5,1914.2,1316.7,1189.1 -1.1709048926051249,0.27086425531161873,3.010692959690218,151.6,621.5,1444.2,1681.5,1141.6,1082.7 -1.1709714511404485,0.3711420636240872,0.0,263.0,1750.7,1751.1,1498.8,1071.0,1071.2 -1.1709617860978005,0.37114172065316664,0.1308996938995747,298.4,1787.6,1846.8,1535.6,1083.0,1001.4 -1.1709253793308465,0.37113094237661226,0.2617993877991494,370.5,1975.4,2103.3,1706.3,873.6,493.9 -1.170887690698982,0.3711076184960902,0.39269908169872414,506.7,2309.9,2090.4,1603.1,564.4,345.1 -1.1708568432040758,0.3710764771543795,0.5235987755982988,791.3,1846.9,1719.3,1270.2,418.5,290.8 -1.1708458796916974,0.37105298009965226,0.6544984694978736,1682.3,1616.6,1557.1,1104.0,336.5,277.3 -1.1708337741261805,0.3710062697766139,0.7853981633974483,1721.1,1529.1,1528.2,1040.8,293.6,293.0 -1.17083524301598,0.3709958142993659,0.916297857297023,1807.5,1556.4,1615.4,1134.3,277.5,336.2 -1.1708479425349012,0.3709578075351714,1.0471975511965976,2054.4,1718.4,1845.8,792.7,290.3,417.6 -1.1708739006811215,0.37091508856414634,1.1780972450961724,2098.4,1669.5,1448.5,507.5,345.2,564.3 -1.1708689478084173,0.3709200114661202,1.3089969389957472,1706.9,1317.4,1189.7,370.8,493.7,872.9 -1.1708810970850687,0.3709147447864196,1.4398966328953218,1534.6,1141.2,1082.8,297.8,1016.5,1763.0 -1.170951906506089,0.37089879320807406,1.5707963267948966,1499.1,1070.9,1070.8,263.1,1751.2,1751.0 -1.1709430781475267,0.3708985008392587,1.7016960206944713,1576.8,1082.1,1017.1,255.3,1786.3,1844.5 -1.1709372040052737,0.3708965271319822,1.832595714594046,1799.2,873.0,493.6,278.0,1975.5,2103.3 -1.1709908291871625,0.37093107653351387,1.9634954084936205,1443.6,564.5,345.3,346.8,2308.8,2089.3 -1.171006788902897,0.37094983244334534,2.0943951023931953,1176.5,417.7,290.3,516.3,1846.0,1718.6 -1.1709965548388392,0.370929168588809,2.2252947962927703,1061.0,336.3,277.5,1092.9,1615.6,1556.6 -1.1710017519324063,0.37095060071606567,2.356194490192345,1041.5,293.1,293.6,1720.3,1528.5,1528.8 -1.1709990602146794,0.37097968328428355,2.4870941840919194,1087.7,277.3,336.3,1765.2,1557.2,1616.2 -1.17100338586275,0.3709696100566997,2.6179938779914944,515.7,290.9,418.5,1963.4,1719.4,1847.0 -1.1709910739124711,0.37098510532691087,2.748893571891069,345.3,345.3,565.2,2254.3,1666.2,1446.0 -1.1710007781288252,0.3709778478224546,2.8797932657906435,277.5,493.5,873.4,1799.4,1317.0,1189.6 -1.1709924263993452,0.3709831566735782,3.010692959690218,255.0,1008.5,1763.9,1577.9,1141.6,1082.5 -1.171022364844802,0.47126561873994,0.0,362.9,1750.9,1751.2,1399.1,1071.0,1071.0 -1.1709809353577991,0.47067442552550776,0.1308996938995747,402.0,1764.5,1846.4,1432.4,1083.1,1142.5 -1.1710126500982654,0.47068475015706635,0.2617993877991494,485.9,1975.4,2102.6,1590.6,1073.3,693.4 -1.1710494590573481,0.4707084354378366,0.39269908169872414,648.4,2168.9,1949.9,1603.4,705.7,486.4 -1.1710787986718112,0.47074232545786243,0.5235987755982988,990.1,1731.6,1603.8,1270.2,534.2,406.5 -1.1711070760497921,0.4707925576454075,0.6544984694978736,1765.4,1513.0,1453.7,1103.9,440.0,380.8 -1.171112696369358,0.47082275189474165,0.7853981633974483,1721.0,1429.0,1428.3,1040.9,393.6,393.0 -1.1711118648285601,0.4708851660951465,0.916297857297023,1899.8,1453.4,1512.0,1060.5,380.9,439.7 -1.1711048567413034,0.47091238422641135,1.0471975511965976,2054.7,1602.6,1730.3,992.8,405.7,533.0 -1.1710975216173465,0.47089307398451963,1.1780972450961724,1957.1,1669.7,1448.7,649.2,486.2,705.1 -1.1708437810420018,0.47085992149047984,1.3089969389957472,1590.8,1316.9,1189.1,486.3,693.5,1072.9 -1.170858264594129,0.47085312931195267,1.4398966328953218,1430.8,1141.1,1082.7,401.2,1408.4,1785.5 -1.1709374146644953,0.47083562240355414,1.5707963267948966,1398.9,1071.0,1070.8,363.0,1751.0,1751.0 -1.1709379150007861,0.47083584356954633,1.7016960206944713,1473.6,1082.1,1140.5,358.8,1786.4,1844.9 -1.1709408553552918,0.47083646561553305,1.832595714594046,1684.5,1071.4,692.4,393.7,1976.1,2104.2 -1.1710018761467411,0.4708758469643979,1.9634954084936205,1442.8,705.1,486.2,488.8,2166.4,1947.5 -1.1710232300396963,0.470900784787867,2.0943951023931953,1176.1,532.9,405.8,716.4,1730.0,1602.6 -1.1710165160579569,0.4708866531565914,2.2252947962927703,1060.8,439.6,380.9,1482.6,1511.9,1453.1 -1.1710233090358417,0.4709148288487075,2.356194490192345,1041.5,393.0,393.6,1720.6,1428.4,1429.2 -1.1710202768790319,0.47095047859297146,2.4870941840919194,1104.0,380.8,440.0,1765.3,1453.7,1513.0 -1.1710230280191374,0.4709460428506995,2.6179938779914944,714.4,406.5,534.3,1963.8,1604.0,1731.9 -1.1710076549579929,0.47096636781328005,2.748893571891069,486.4,486.8,707.0,2112.1,1665.2,1445.1 -1.1710137510407346,0.4709626655093846,2.8797932657906435,393.0,693.4,1073.7,1683.3,1316.4,1189.1 -1.1710012837727883,0.47097032091099145,3.010692959690218,358.5,1397.6,1786.4,1474.1,1141.3,1082.6 -1.1710261864341358,0.5712489895944748,0.0,462.9,1751.2,1750.7,1298.9,1070.8,1071.0 -1.1709923175846386,0.5706635242149831,0.1308996938995747,505.7,1787.1,1846.4,1328.5,1083.0,1216.8 -1.1710265879198054,0.5706746879938864,0.2617993877991494,601.6,1975.5,2103.0,1475.1,1189.4,892.7 -1.1710648323279707,0.5706993596099972,0.39269908169872414,790.0,2027.4,1808.5,1603.3,846.9,627.7 -1.1710950688992336,0.5707343273177472,0.5235987755982988,1189.2,1615.7,1488.3,1270.2,649.7,522.1 -1.17112378692733,0.5707856237307336,0.6544984694978736,1765.2,1409.2,1350.2,1103.8,543.5,484.3 -1.1711295845549687,0.5708169034242938,0.7853981633974483,1721.3,1329.2,1328.5,1040.9,493.4,492.9 -1.1711286087744435,0.5708802593530868,0.916297857297023,1807.7,1349.8,1408.8,1060.5,484.4,543.1 -1.171121253912782,0.5709082790727777,1.0471975511965976,2054.3,1487.5,1615.0,1148.0,521.2,648.5 -1.171113456560235,0.5709199323362402,1.1780972450961724,1815.2,1669.3,1448.4,790.8,627.4,846.3 -1.1710660001818167,0.5709651529186341,1.3089969389957472,1475.9,1317.3,1189.6,601.9,891.8,1271.0 -1.1710302990086496,0.5709859752037625,1.4398966328953218,1327.7,1141.2,1082.7,504.5,1795.3,1785.6 -1.1710513842470802,0.570981987893262,1.5707963267948966,1299.0,1070.7,1070.6,462.9,1751.3,1751.1 -1.1709959523180893,0.5709807600780077,1.7016960206944713,1369.9,1081.9,1234.9,462.1,1785.9,1844.8 -1.170948495900706,0.5709668496629858,1.832595714594046,1568.5,1190.3,892.0,509.0,1975.5,2103.3 -1.1709672968154397,0.5709803009331185,1.9634954084936205,1443.7,846.4,627.2,630.0,2026.1,1807.3 -1.1709573074572686,0.5709720103013141,2.0943951023931953,1176.8,648.6,521.3,915.3,1615.2,1487.7 -1.1709304378328043,0.5709212248987845,2.2252947962927703,1061.1,543.2,484.3,1784.4,1408.5,1349.9 -1.170928019353275,0.5709113516368711,2.356194490192345,1041.5,492.9,493.4,1720.6,1328.4,1329.3 -1.1709261761830172,0.5709104633783331,2.4870941840919194,1103.9,484.3,543.3,1765.0,1350.4,1409.2 -1.1709384519250339,0.570874030054241,2.6179938779914944,914.2,521.9,649.7,1963.3,1488.2,1615.9 -1.1709398251121472,0.5708677802803128,2.748893571891069,628.0,628.0,848.0,1971.7,1665.9,1446.2 -1.1709668992996056,0.5708445528318757,2.8797932657906435,508.5,892.3,1271.8,1568.3,1316.9,1189.7 -1.1709779543906338,0.5708398500399563,3.010692959690218,462.0,1782.4,1786.6,1371.1,1141.5,1082.7 -1.1710312370304465,0.671140074799611,0.0,562.8,1751.0,1751.2,1199.1,1071.0,1071.0 -1.1710034420870146,0.6711398062754215,0.1308996938995747,609.1,1787.4,1846.6,1224.9,1083.1,1142.5 -1.1709484532385526,0.6711239574602912,0.2617993877991494,717.1,1975.9,2103.1,1359.9,1189.6,1092.2 -1.1708947035084702,0.671091254897618,0.39269908169872414,931.5,1886.7,1667.3,1603.3,987.8,768.6 -1.1708515336897733,0.6710476676702739,0.5235987755982988,1388.7,1500.3,1372.7,1270.1,765.1,637.7 -1.170832530036204,0.671010121853125,0.6544984694978736,1765.0,1305.4,1246.8,1104.1,647.1,587.8 -1.1708166232246735,0.6709486376301659,0.7853981633974483,1721.0,1229.0,1228.7,1040.7,593.4,592.9 -1.1708183081464871,0.6709240911603156,0.916297857297023,1807.4,1246.2,1305.0,1060.6,587.9,646.7 -1.1708347610935033,0.6708734314599978,1.0471975511965976,2054.7,1372.0,1499.2,1176.8,636.9,764.1 -1.1708672551267933,0.670820335795512,1.1780972450961724,1673.1,1665.9,1448.8,932.6,768.5,987.5 -1.1708706145556533,0.6708177148448962,1.3089969389957472,1360.1,1317.5,1189.6,717.6,1091.2,1469.9 -1.1708921058682407,0.6708078041078123,1.4398966328953218,1224.0,1141.3,1082.9,608.1,1844.0,1785.8 -1.1709725128784867,0.6707900632832957,1.5707963267948966,1199.1,1070.9,1070.6,563.1,1751.0,1751.0 -1.1709725052310296,0.670790538797174,1.7016960206944713,1266.3,1082.1,1140.4,565.6,1763.3,1844.8 -1.1709742750479712,0.6707914239953883,1.832595714594046,1452.6,1190.4,1091.3,624.7,1975.3,2103.2 -1.1710340595575832,0.6708304430651353,1.9634954084936205,1443.7,987.7,768.7,771.8,1885.4,1666.5 -1.1710543803617322,0.6708545876766103,2.0943951023931953,1176.2,764.2,636.9,1114.9,1499.2,1372.0 -1.1710467369814097,0.6708396613850374,2.2252947962927703,1060.8,646.8,587.9,1807.5,1304.9,1246.3 -1.171052931567382,0.6708668300942588,2.356194490192345,1041.6,593.1,593.4,1720.7,1228.5,1228.9 -1.1710498500838387,0.670901253894197,2.4870941840919194,1104.2,587.9,646.9,1765.1,1246.7,1305.6 -1.1710526848179892,0.6708958283177906,2.6179938779914944,1113.4,637.6,765.3,1963.5,1372.6,1500.1 -1.171038034046705,0.6709151968266489,2.748893571891069,769.6,769.4,989.4,1830.1,1665.9,1445.7 -1.1710448405318636,0.6709109247677583,2.8797932657906435,624.3,1091.8,1471.8,1452.8,1316.9,1189.7 -1.1710332370284444,0.6709183358470592,3.010692959690218,565.5,1845.7,1786.7,1267.5,1141.5,1082.6 -1.1710591089288702,0.7711977963820744,0.0,662.9,1751.2,1751.1,1099.1,1070.9,1071.0 -1.171003269811917,0.7706509844977567,0.1308996938995747,712.9,1787.3,1846.7,1121.2,1083.3,1142.5 -1.171034574531782,0.7706612669019204,0.2617993877991494,832.9,1975.9,2103.0,1244.0,1189.7,1291.8 -1.1711146003568524,0.7707084139246978,0.39269908169872414,1073.3,1745.0,1526.0,1530.9,1129.4,909.9 -1.1711247138181393,0.7707216056781405,0.5235987755982988,1588.1,1384.4,1256.9,1270.2,881.0,753.4 -1.1707935429953837,0.7710238620925369,0.6544984694978736,1764.6,1201.7,1142.9,1103.8,750.4,691.4 -1.1707894317460767,0.771008708001919,0.7853981633974483,1721.3,1129.1,1128.6,1040.9,693.6,693.2 -1.1707907285054129,0.7709917789501401,0.916297857297023,1807.8,1142.9,1201.6,1060.8,691.7,750.5 -1.170806393056907,0.77096357997287,1.0471975511965976,2055.3,1256.6,1384.3,1343.5,752.7,880.3 -1.1708238475429218,0.7709353967860506,1.1780972450961724,1530.5,1525.5,1447.6,1073.5,910.3,1129.6 -1.17081423500899,0.7709448881713654,1.3089969389957472,1243.8,1316.8,1189.1,833.1,1291.9,1672.0 -1.170823594502074,0.7709408668454094,1.4398966328953218,1120.5,1140.9,1082.5,711.4,1843.6,1785.7 -1.1708924789866515,0.7709256088947676,1.5707963267948966,1099.0,1070.7,1070.7,663.1,1751.7,1751.1 -1.170882101896472,0.7709251938907289,1.7016960206944713,1163.1,1082.0,1140.6,669.2,1786.4,1844.9 -1.1708750993252337,0.7709223006834556,1.832595714594046,1338.0,1190.6,1289.8,740.8,1976.4,2104.4 -1.1709718854339066,0.7709794293326777,1.9634954084936205,1442.5,1128.1,909.3,914.0,1742.7,1524.0 -1.170964657050032,0.7709728178241559,2.0943951023931953,1176.3,879.4,752.2,1316.3,1383.2,1256.2 -1.1709512595667564,0.7709449889297308,2.2252947962927703,1060.6,750.1,691.6,1807.0,1201.2,1142.5 -1.1709571222837503,0.7709669839609625,2.356194490192345,1041.4,693.0,693.7,1720.8,1128.4,1129.1 -1.1709545356219653,0.7709995116204249,2.4870941840919194,1104.2,691.6,750.8,1765.7,1143.1,1202.6 -1.1709582068416118,0.7709931617151813,2.6179938779914944,1267.5,753.6,881.4,1964.3,1257.2,1385.1 -1.1709437523810395,0.7710122443509366,2.748893571891069,910.5,911.4,1131.8,1687.6,1529.6,1445.1 -1.1709508948557268,0.7710076344970882,2.8797932657906435,739.6,1292.8,1673.2,1336.6,1316.2,1188.9 -1.1709394658498666,0.7710146371682804,3.010692959690218,669.0,1845.4,1786.4,1163.7,1141.1,1082.6 -1.170965578425194,0.8712941446008347,0.0,763.0,1750.7,1751.0,998.9,1070.8,1070.9 -1.1709573213531852,0.8706770053063309,0.1308996938995747,816.2,1787.6,1846.6,1017.9,1083.2,1142.2 -1.1709953127455597,0.870689237773062,0.2617993877991494,948.1,1975.7,1962.5,1128.3,1189.3,1316.9 -1.171033112108942,0.8707134897473863,0.39269908169872414,1214.9,1604.4,1384.8,1388.7,1270.7,1051.1 -1.1710621236639591,0.8707469369621952,0.5235987755982988,1786.6,1269.1,1141.4,1270.3,996.9,869.1 -1.1710900135935616,0.8707962633828696,0.6544984694978736,1765.1,1098.8,1039.7,1104.0,854.1,795.3 -1.1710954580008035,0.8708253650344255,0.7853981633974483,1721.5,1029.0,1028.3,1040.7,793.5,793.0 -1.1710947551079882,0.8708867411869465,0.916297857297023,1807.6,1039.3,1098.0,1060.3,795.0,853.6 -1.171071325097985,0.870967547068004,1.0471975511965976,2029.3,1140.7,1268.1,1176.7,867.5,995.0 -1.1710853343801177,0.8709446568647774,1.1780972450961724,1389.8,1383.7,1448.8,1216.1,1050.4,1269.5 -1.1710089842514053,0.8710156076213398,1.3089969389957472,1129.3,1317.2,1189.7,949.1,1489.0,1868.1 -1.1709711830523877,0.8710390206341789,1.4398966328953218,1017.2,1141.1,1082.7,815.0,1844.4,1785.4 -1.1710221529757012,0.87102817949017,1.5707963267948966,999.1,1070.8,1070.7,762.8,1751.4,1751.0 -1.170968620993208,0.871027011806794,1.7016960206944713,1059.5,1082.1,1140.2,772.4,1786.1,1844.2 -1.1709146644323936,0.8710111776349996,1.832595714594046,1221.7,1190.2,1317.7,855.8,1975.4,1961.5 -1.1709257330405112,0.8710196677793265,1.9634954084936205,1443.7,1270.0,1051.1,1054.7,1603.3,1384.3 -1.170909517246049,0.8710044282560749,2.0943951023931953,1176.6,995.3,867.9,1513.7,1268.4,1141.1 -1.170878602286313,0.8709458475743879,2.2252947962927703,1060.8,853.9,794.9,1807.1,1098.2,1039.2 -1.1708744411442773,0.8709278732675323,2.356194490192345,1041.5,793.0,793.4,1720.4,1028.6,1029.0 -1.1708730704652284,0.8709192345223191,2.4870941840919194,1103.7,794.8,854.0,1764.9,1039.6,1098.5 -1.1708735923041185,0.8709213204969948,2.6179938779914944,1270.2,868.8,996.5,1963.3,1141.2,1268.7 -1.1708959826327623,0.870882227376065,2.748893571891069,1052.5,1052.0,1272.1,1547.6,1387.2,1446.2 -1.1709327792333395,0.870850045396466,2.8797932657906435,855.4,1490.7,1869.9,1221.7,1317.0,1189.7 -1.1709481566438715,0.870843101565846,3.010692959690218,772.5,1845.6,1786.5,1060.5,1141.4,1082.9 -1.2709519207562627,0.1707509824300979,0.0,63.0,1650.8,1651.3,1698.9,1171.0,1170.9 -1.2709886831099968,0.17145774315217843,0.1308996938995747,91.6,1684.1,1743.2,1742.8,1049.2,233.6 -1.2709416424335351,0.17144237449395217,0.2617993877991494,139.5,1860.5,1987.7,1937.3,474.8,95.3 -1.2708894395965986,0.1714086085312725,0.39269908169872414,223.8,2270.4,2372.3,1744.4,282.3,63.0 -1.2708464873298206,0.17136317035862625,0.5235987755982988,393.3,2078.0,1950.2,1385.8,187.5,59.8 -1.2708275562003968,0.17132368679960308,0.6544984694978736,912.8,1823.3,1764.2,1207.4,129.5,70.4 -1.2708118278870257,0.1712605540055181,0.7853981633974483,1621.0,1728.8,1728.3,1140.9,93.8,93.2 -1.2708135424909137,0.17123453348298878,0.916297857297023,1704.0,1763.7,1822.4,917.5,70.7,129.5 -1.2708298863784293,0.17118242799165073,1.0471975511965976,1939.1,1949.4,2076.9,393.8,59.5,186.8 -1.2708622414925363,0.17112779591939664,1.1780972450961724,2412.1,1811.3,1590.0,224.3,63.3,282.5 -1.2708655438959124,0.17112332156721677,1.3089969389957472,1937.4,1432.8,1305.0,139.9,95.6,474.8 -1.270887341384647,0.17111124880264605,1.4398966328953218,1741.2,1244.5,1186.5,91.1,238.5,1067.3 -1.2709686613246856,0.1710914245284021,1.5707963267948966,1698.7,1170.9,1170.6,63.3,1650.8,1650.8 -1.2709701516132057,0.17109001091545206,1.7016960206944713,1783.4,1066.7,238.4,48.6,1682.8,1740.9 -1.2709739690477855,0.17108947235006355,1.832595714594046,2030.0,474.8,95.6,47.1,1860.2,1987.9 -1.271036080089994,0.1711279763617206,1.9634954084936205,1584.8,282.4,63.3,63.7,2270.8,2370.9 -1.2710585815287616,0.1711525270166987,2.0943951023931953,1292.1,186.8,59.5,117.4,2076.6,1949.1 -1.2710526608665844,0.17113870013972843,2.2252947962927703,1164.3,129.5,70.7,319.5,1822.2,1763.4 -1.2710597714976892,0.17116752354137588,2.356194490192345,1141.6,93.3,93.8,1620.3,1728.3,1728.9 -1.271056580289324,0.17120377991685554,2.4870941840919194,316.8,70.5,129.6,1661.6,1764.0,1823.4 -1.2710584755295102,0.17119980719839578,2.6179938779914944,117.6,59.9,187.6,1847.8,1950.2,2078.4 -1.271042110252201,0.1712200145863041,2.748893571891069,62.7,62.7,282.8,2266.7,1806.8,1587.1 -1.2710470027758722,0.17121567399955784,2.8797932657906435,46.6,95.0,474.8,2029.9,1432.1,1305.0 -1.2710336083427944,0.17122215126992124,3.010692959690218,48.2,235.2,1058.3,1784.8,1245.0,1186.1 -1.2710582612518868,0.27150046722057763,0.0,163.2,1651.4,1651.0,1599.0,1171.1,1171.1 -1.2710070536316849,0.2707320486222664,0.1308996938995747,195.0,1683.9,1720.3,1639.1,1186.7,617.3 -1.2710303202429092,0.27073966883746925,0.2617993877991494,254.9,1860.0,1987.4,1821.7,674.2,294.5 -1.271060266797694,0.27075900664382613,0.39269908169872414,365.3,2269.5,2232.1,1744.4,423.3,204.0 -1.2710845341473718,0.270787449082023,0.5235987755982988,592.0,1962.5,1834.8,1385.9,302.9,175.3 -1.2711094894724502,0.2708316584064445,0.6544984694978736,1297.1,1719.7,1661.0,1207.6,232.9,173.8 -1.2711135854708828,0.2708556662897945,0.7853981633974483,1621.1,1628.9,1628.5,1140.8,193.6,193.0 -1.2711127576210142,0.2709121490340882,0.916297857297023,1704.0,1660.3,1719.2,1163.8,173.9,232.7 -1.2708286688015717,0.27090977945516914,1.0471975511965976,1939.7,1834.5,1962.4,592.3,174.8,302.2 -1.2708470265537681,0.2708800170207306,1.1780972450961724,2238.7,1810.2,1589.3,365.4,204.2,423.5 -1.2708408476642372,0.2708862708710047,1.3089969389957472,1822.0,1432.5,1304.8,255.1,294.6,674.3 -1.2708551131029024,0.27087977243499184,1.4398966328953218,1637.6,1244.4,1186.0,194.2,628.4,1458.4 -1.2709294215335185,0.2708634317332501,1.5707963267948966,1599.0,1170.9,1170.7,163.0,1651.2,1651.4 -1.2709241600653456,0.2708634514516448,1.7016960206944713,1680.3,1185.5,625.9,151.8,1682.8,1741.4 -1.2709216088217181,0.27086230051198745,1.832595714594046,1915.9,672.9,294.1,162.5,1860.9,1988.3 -1.2709779619861437,0.27089867884032093,1.9634954084936205,1583.6,422.9,204.0,205.2,2271.8,2229.3 -1.2709958621705226,0.27091982927708247,2.0943951023931953,1291.8,301.9,174.7,316.9,1960.7,1833.7 -1.2709870326714294,0.27090147043905644,2.2252947962927703,1164.3,232.6,174.0,707.2,1718.8,1660.1 -1.2709929503677269,0.270925323189388,2.356194490192345,1141.6,193.0,193.6,1620.5,1628.3,1629.1 -1.2709901362291869,0.2709569275190158,2.4870941840919194,700.3,173.7,232.9,1661.6,1660.7,1720.3 -1.2709940857403361,0.2709489396010354,2.6179938779914944,316.1,175.3,303.1,1848.3,1835.4,1963.3 -1.270980560933264,0.2709663883218423,2.748893571891069,203.7,203.9,424.1,2267.9,1806.3,1586.5 -1.2709890117789957,0.2709605522620586,2.8797932657906435,161.8,294.3,674.5,1913.9,1432.0,1304.6 -1.270979132476876,0.2709668429091727,3.010692959690218,151.5,622.5,1447.1,1681.2,1244.8,1186.1 -1.2710071360114172,0.3712478472621532,0.0,263.0,1650.9,1650.9,1498.9,1171.0,1171.0 -1.2709834200565853,0.3706669620858023,0.1308996938995747,298.5,1683.8,1743.5,1535.5,1264.5,1001.7 -1.2710194070464649,0.3706786403709341,0.2617993877991494,370.5,1860.1,1987.1,1706.6,873.8,494.0 -1.2710576730182312,0.3707032964334316,0.39269908169872414,506.8,2269.7,2090.6,1744.3,564.6,345.2 -1.2710875709120177,0.37073785660640657,0.5235987755982988,791.2,1847.2,1719.7,1385.9,418.6,290.9 -1.271116022772081,0.37078857004897325,0.6544984694978736,1639.0,1616.4,1557.2,1207.4,336.3,277.3 -1.2711217015614529,0.37081919462024526,0.7853981633974483,1621.1,1528.8,1528.7,1140.8,293.6,293.0 -1.271120787051661,0.3708819367396856,0.916297857297023,1703.9,1556.7,1615.6,1209.6,277.4,336.1 -1.2711136351522503,0.37090941645217623,1.0471975511965976,1939.6,1718.3,1846.0,792.5,290.2,417.4 -1.2711061394626748,0.37092062123295566,1.1780972450961724,2098.5,1811.1,1590.4,507.3,345.1,564.1 -1.2710590531556827,0.37096552381944203,1.3089969389957472,1707.3,1432.8,1305.1,370.7,493.3,872.5 -1.2710237564793103,0.37098615648905575,1.4398966328953218,1534.6,1244.8,1186.2,297.7,1015.8,1682.1 -1.2710452497981184,0.3709820650393221,1.5707963267948966,1499.1,1171.1,1170.7,262.9,1651.3,1651.1 -1.2709902004427072,0.3709808391297731,1.7016960206944713,1576.9,1284.4,1017.0,255.1,1682.7,1741.3 -1.2709430849246932,0.37096702842925366,1.832595714594046,1799.9,872.9,493.5,277.8,1860.0,1987.4 -1.2709621818725425,0.3709806340121824,1.9634954084936205,1584.9,564.4,345.1,346.5,2270.3,2089.2 -1.2709524297332084,0.3709725398801744,2.0943951023931953,1292.3,417.5,290.2,515.8,1846.2,1718.6 -1.2709257209782023,0.37092199605762666,2.2252947962927703,1164.4,336.2,277.4,1092.3,1615.6,1556.8 -1.2709233946667167,0.3709123822795348,2.356194490192345,1141.6,292.9,293.5,1620.6,1528.5,1528.9 -1.2709215835758962,0.3709117450266406,2.4870941840919194,1087.2,277.3,336.3,1661.2,1557.5,1616.6 -1.2709338126871752,0.3708755522563363,2.6179938779914944,515.5,290.8,418.4,1847.7,1719.6,1846.9 -1.2709350990262958,0.37086950249721196,2.748893571891069,345.2,345.1,565.1,2266.1,1807.3,1587.6 -1.2709620294831585,0.3708464331729351,2.8797932657906435,277.4,493.3,873.0,1799.3,1432.4,1305.3 -1.2709729151190945,0.3708418328955274,3.010692959690218,255.0,1008.0,1682.9,1578.2,1245.1,1186.3 -1.2710259782339806,0.4711418834370158,0.0,362.9,1651.1,1650.9,1399.2,1170.9,1170.8 -1.2709980421266147,0.4711416009445777,0.1308996938995747,402.0,1684.0,1743.4,1432.5,1186.6,1246.1 -1.2709429470964178,0.47112570313472824,0.2617993877991494,485.9,1860.0,1987.2,1590.9,1072.9,693.2 -1.2708891267283198,0.47109292966999927,0.39269908169872414,648.1,2168.7,1949.7,1744.9,705.5,486.2 -1.2708459137253685,0.4710492575274905,0.5235987755982988,990.0,1731.4,1603.9,1385.9,534.1,406.4 -1.270826909400185,0.4710116341641659,0.6544984694978736,1661.7,1513.0,1453.9,1207.5,439.9,380.8 -1.270811013971714,0.47095007276635514,0.7853981633974483,1620.9,1429.0,1428.8,1140.9,393.5,392.9 -1.2708127379284184,0.47092547421165043,0.916297857297023,1704.1,1453.4,1512.1,1164.2,380.9,439.7 -1.2708292355192556,0.47087478079251266,1.0471975511965976,1939.1,1603.1,1730.1,992.5,405.7,533.1 -1.2708617671043752,0.4708216541643484,1.1780972450961724,1956.4,1811.6,1590.5,649.1,486.2,705.2 -1.270865164899042,0.47081902230309103,1.3089969389957472,1591.5,1432.8,1305.3,486.5,692.6,1071.7 -1.2708866887738168,0.470809117265379,1.4398966328953218,1430.8,1244.7,1186.2,401.3,1406.0,1758.8 -1.2709671195061865,0.47079135948447104,1.5707963267948966,1399.1,1171.1,1170.7,363.0,1651.2,1651.1 -1.2709671360130308,0.47079182403161424,1.7016960206944713,1473.6,1185.6,1243.9,358.7,1682.8,1741.3 -1.2709689291303388,0.4707927110081984,1.832595714594046,1684.2,1072.3,693.1,393.6,1860.0,1987.6 -1.27102874536212,0.47083171844312877,1.9634954084936205,1584.6,705.4,486.4,488.3,2167.3,1948.4 -1.2710491076875001,0.4708558501851987,2.0943951023931953,1292.2,533.1,405.7,715.6,1730.5,1603.4 -1.2710415014080882,0.47084093336171073,2.2252947962927703,1164.3,439.7,380.9,1479.8,1512.2,1453.4 -1.271047732732899,0.4708681219863524,2.356194490192345,1141.7,393.0,393.6,1620.5,1428.6,1428.8 -1.2710446907684743,0.4709025689367661,2.4870941840919194,1207.6,380.7,439.9,1661.8,1453.8,1512.7 -1.271047540175868,0.4708971831801183,2.6179938779914944,714.8,406.4,534.0,1847.9,1603.6,1731.3 -1.2710329054035294,0.47091658630416955,2.748893571891069,486.6,486.6,706.5,2113.3,1807.4,1587.5 -1.271039699480828,0.47091234974478935,2.8797932657906435,393.1,692.7,1072.6,1683.7,1432.4,1305.0 -1.2710280733151609,0.4709197851883449,3.010692959690218,358.5,1394.8,1745.4,1474.9,1245.4,1186.2 -1.2710539022931209,0.5711992080923678,0.0,462.9,1651.0,1651.2,1299.0,1171.0,1170.8 -1.2709991982598967,0.5706512839913251,0.1308996938995747,505.6,1683.8,1720.5,1328.3,1186.7,1291.9 -1.2710307194457588,0.5706616254483758,0.2617993877991494,601.6,1859.9,1987.1,1475.3,1272.5,892.9 -1.2710695580981253,0.5706866944185811,0.39269908169872414,790.0,2027.7,1808.5,1744.4,846.9,627.5 -1.2711009635605612,0.5707229493971484,0.5235987755982988,1189.7,1615.9,1488.2,1386.0,649.8,522.1 -1.271130592993403,0.57077597000153,0.6544984694978736,1661.7,1409.3,1350.2,1207.5,543.5,484.5 -1.271136813472536,0.5708091287476007,0.7853981633974483,1621.0,1329.1,1328.3,1140.9,493.6,493.0 -1.2711357854950294,0.5708743024545071,0.916297857297023,1704.1,1349.5,1408.6,1164.0,484.4,543.1 -1.2711279450858668,0.5709039612910374,1.0471975511965976,1939.2,1487.7,1615.0,1192.0,521.2,648.6 -1.2711193166547528,0.5709169579887894,1.1780972450961724,1814.7,1807.1,1590.1,790.9,627.2,846.3 -1.2710708188182174,0.5709631904200829,1.3089969389957472,1475.9,1432.9,1305.2,602.0,891.9,1271.0 -1.2710339410599607,0.570984691486057,1.4398966328953218,1327.6,1244.6,1186.1,504.6,1718.0,1682.2 -1.2710537925499734,0.5709810097167078,1.5707963267948966,1299.0,1170.8,1170.8,462.9,1651.4,1651.2 -1.2709971996135185,0.5709797770598481,1.7016960206944713,1369.8,1185.5,1289.3,462.0,1682.8,1741.2 -1.2709486960017646,0.5709656024945349,1.832595714594046,1568.6,1271.1,892.3,509.0,1859.8,1987.5 -1.2709666158354795,0.5709785387789432,1.9634954084936205,1584.6,846.5,627.3,630.0,2026.6,1807.2 -1.2709559694580936,0.5709695700243371,2.0943951023931953,1292.1,648.6,521.2,915.2,1614.7,1487.7 -1.270928667845084,0.5709180380082892,2.2252947962927703,1164.4,543.2,484.4,1703.8,1408.7,1349.7 -1.2709260482070441,0.5709073809918639,2.356194490192345,1141.5,493.0,493.5,1620.6,1328.3,1329.2 -1.270924233510727,0.5709057300968783,2.4870941840919194,1303.4,484.3,543.4,1661.6,1350.1,1409.4 -1.2709367071616682,0.570868636174618,2.6179938779914944,914.0,522.0,649.6,1847.8,1487.9,1615.6 -1.270938446569765,0.5708618365518221,2.748893571891069,628.1,627.9,848.0,1971.9,1807.6,1587.3 -1.2709659658251184,0.5708382168128432,2.8797932657906435,508.5,892.2,1272.0,1568.5,1432.4,1305.3 -1.2709775178236218,0.5708332770876936,3.010692959690218,462.0,1719.1,1683.3,1371.1,1244.7,1186.0 -1.2710313873342298,0.6711339484377128,0.0,562.8,1651.4,1651.0,1199.3,1170.9,1171.0 -1.271004003476857,0.6711337313151777,0.1308996938995747,609.1,1684.0,1743.1,1225.2,1186.8,1245.8 -1.270949307930513,0.6711180084864681,0.2617993877991494,717.1,1860.0,1987.3,1359.9,1305.3,1092.1 -1.2708957692459186,0.6710854758731131,0.39269908169872414,931.3,1886.5,1667.2,1672.4,988.1,768.7 -1.2708527352678272,0.671042078356646,0.5235987755982988,1388.3,1500.8,1372.5,1386.0,765.4,637.6 -1.2708338196188467,0.6710047340172642,0.6544984694978736,1661.5,1305.8,1246.8,1207.5,646.9,587.9 -1.2708179362227456,0.6709434376260774,0.7853981633974483,1620.9,1229.1,1228.5,1141.0,593.6,592.8 -1.2708196144113693,0.6709190725834591,0.916297857297023,1703.5,1246.2,1305.0,1164.1,587.9,646.8 -1.2708360243954375,0.6708685759010382,1.0471975511965976,1939.0,1371.9,1499.1,1292.2,636.9,764.1 -1.2708684417864826,0.6708156057117374,1.1780972450961724,1673.2,1665.7,1590.5,932.6,768.5,987.6 -1.270871713070681,0.6708130942621904,1.3089969389957472,1360.2,1433.1,1305.2,717.6,1091.2,1470.4 -1.2708931022594323,0.6708032801129487,1.4398966328953218,1224.1,1244.5,1186.2,608.1,1740.4,1682.2 -1.2709733915783674,0.670785583464234,1.5707963267948966,1199.1,1171.1,1170.4,563.0,1651.1,1650.9 -1.270973266514249,0.6707860832248693,1.7016960206944713,1266.3,1185.4,1244.0,565.6,1682.7,1741.1 -1.2709749172892726,0.6707869790853902,1.832595714594046,1453.0,1305.9,1091.7,624.7,1860.0,1987.6 -1.2710345943191301,0.6708259625614392,1.9634954084936205,1585.1,987.7,768.6,771.7,1885.1,1666.0 -1.271054830876299,0.6708500391008796,2.0943951023931953,1292.0,764.1,636.7,1115.0,1499.3,1372.2 -1.2710471202667817,0.6708350405938541,2.2252947962927703,1164.5,646.8,588.0,1781.4,1305.1,1246.1 -1.2710532783668642,0.6708621232463379,2.356194490192345,1141.6,593.0,593.5,1620.6,1228.3,1229.3 -1.271050203287338,0.6708964508854578,2.4870941840919194,1207.5,587.9,647.0,1661.6,1246.8,1305.9 -1.2710530597093619,0.6708909498146101,2.6179938779914944,1113.6,637.6,765.3,1847.8,1372.6,1500.5 -1.2710384729453994,0.6709102528751214,2.748893571891069,769.4,769.3,989.3,1830.4,1670.1,1587.5 -1.271045342741908,0.6709059468156009,2.8797932657906435,624.1,1091.8,1471.6,1452.9,1432.6,1305.3 -1.2710338087093112,0.6709133501015785,3.010692959690218,565.5,1742.3,1683.1,1267.6,1245.2,1186.4 -1.2710597496319074,0.7711928659118836,0.0,663.0,1651.2,1650.8,1099.0,1171.0,1171.0 -1.271003022272532,0.7706497112551056,0.1308996938995747,712.8,1683.7,1743.2,1121.3,1186.8,1246.1 -1.2710343081336737,0.770659989647243,0.2617993877991494,832.7,1860.0,1987.5,1244.1,1384.4,1292.3 -1.2710732352501204,0.7706851310899394,0.39269908169872414,1073.3,1745.3,1525.7,1530.6,1129.5,910.1 -1.2711047783240952,0.7707215583384084,0.5235987755982988,1588.2,1384.9,1257.0,1386.0,881.1,753.3 -1.2711344926924368,0.7707747888819474,0.6544984694978736,1661.8,1202.1,1143.1,1207.4,750.6,691.6 -1.271140748393161,0.7708081767319892,0.7853981633974483,1621.1,1128.9,1128.5,1140.8,693.6,693.0 -1.2711396884368094,0.7708735552776163,0.916297857297023,1704.1,1142.6,1201.4,1163.9,691.4,750.3 -1.2711317708728798,0.7709033897560549,1.0471975511965976,1939.2,1256.6,1383.9,1343.1,752.2,879.5 -1.2711230384786936,0.7709165356607628,1.1780972450961724,1531.2,1524.7,1590.3,1074.4,909.5,1128.6 -1.2710744138638055,0.7709628684323981,1.3089969389957472,1244.4,1432.9,1305.2,833.2,1290.4,1669.3 -1.2710374003336287,0.7709844219684496,1.4398966328953218,1120.3,1244.6,1186.0,711.4,1740.6,1682.1 -1.2710963641343125,0.770969514307017,1.5707963267948966,1098.9,1171.0,1170.7,662.9,1651.2,1651.1 -1.2710121034195383,0.7709672641982381,1.7016960206944713,1162.9,1185.4,1243.9,669.1,1682.8,1741.2 -1.2709580064746697,0.7709513566847197,1.832595714594046,1337.3,1383.0,1290.4,740.3,1860.0,1987.6 -1.2709768066720213,0.7709648441448655,1.9634954084936205,1584.7,1128.8,909.6,913.2,1744.2,1525.0 -1.2709681872494154,0.7709580752681431,2.0943951023931953,1292.3,879.7,752.3,1314.5,1383.8,1256.6 -1.2709424754097995,0.7709095366179897,2.2252947962927703,1164.5,750.3,691.3,1703.6,1201.6,1142.8 -1.270940606259206,0.770902178312,2.356194490192345,1141.6,692.9,693.6,1620.4,1128.4,1129.1 -1.27093865477296,0.7709037417969493,2.4870941840919194,1207.6,691.6,750.4,1661.5,1142.9,1202.2 -1.27095025424783,0.770869478308779,2.6179938779914944,1312.6,753.3,880.8,1847.8,1256.7,1384.4 -1.2709505041386449,0.77086502536393,2.748893571891069,911.1,910.6,1130.8,1689.2,1528.4,1587.5 -1.2709761605814969,0.7708431376222566,2.8797932657906435,739.8,1291.1,1671.2,1337.2,1432.6,1305.0 -1.270985632910451,0.770839305521196,3.010692959690218,669.0,1741.8,1683.3,1164.0,1245.3,1186.2 -1.2710369934522454,0.8711380803937372,0.0,762.8,1651.0,1651.1,999.3,1171.0,1171.0 -1.2710078352208847,0.871137813819479,0.1308996938995747,816.1,1683.5,1743.2,1018.1,1186.5,1246.2 -1.2709518200243728,0.8711216971438034,0.2617993877991494,948.2,1859.9,1987.2,1128.7,1305.1,1432.6 -1.2708972691957625,0.8710885466677332,0.39269908169872414,1214.8,1604.1,1385.2,1389.1,1270.2,1051.1 -1.2708534984153572,0.871044380229167,0.5235987755982988,1786.7,1269.2,1141.5,1385.9,996.5,868.9 -1.2708341017992077,0.8710061839973442,0.6544984694978736,1661.3,1098.9,1039.7,1207.5,854.1,794.9 -1.2708179980828944,0.8709440090398428,0.7853981633974483,1621.1,1029.2,1028.5,1140.9,793.4,793.0 -1.2708196798548808,0.8709188009338793,0.916297857297023,1703.8,1039.1,1097.8,1164.3,794.9,853.7 -1.2708362999620464,0.870867543190488,1.0471975511965976,1938.9,1141.0,1268.1,1292.3,867.9,995.1 -1.2708690960931242,0.8708139518127498,1.1780972450961724,1389.7,1383.7,1590.1,1216.1,1050.6,1269.8 -1.2708728481460343,0.8708109728831612,1.3089969389957472,1129.1,1433.1,1305.1,948.8,1489.2,1835.5 -1.2708947841838298,0.8708008481621368,1.4398966328953218,1017.2,1244.5,1186.2,815.1,1740.7,1682.4 -1.2709756473755773,0.870783027286407,1.5707963267948966,998.8,1170.9,1170.8,762.9,1651.2,1651.2 -1.2709760569944886,0.8707835503149126,1.7016960206944713,1059.5,1185.5,1244.0,772.6,1682.9,1741.4 -1.2709781825869724,0.8707845881351184,1.832595714594046,1221.5,1305.9,1433.7,856.0,1860.2,1987.7 -1.2710382475441901,0.8708238313729526,1.9634954084936205,1550.2,1270.2,1050.8,1055.2,1602.8,1383.7 -1.271085188990962,0.8708831271730384,2.0943951023931953,1292.2,995.4,867.9,1514.3,1268.3,1140.8 -1.271063318878043,0.8708415106229697,2.2252947962927703,1164.2,853.7,795.0,1703.9,1098.2,1039.2 -1.27106786540892,0.8708615652987586,2.356194490192345,1141.5,792.9,793.3,1620.4,1028.4,1029.1 -1.2710647806239104,0.8708958708528263,2.4870941840919194,1207.6,794.9,853.9,1661.2,1039.7,1098.8 -1.271067022610153,0.870892357324486,2.6179938779914944,1386.3,868.9,996.4,1848.0,1141.4,1269.0 -1.271051018050849,0.8709138949219872,2.748893571891069,1052.3,1052.3,1272.1,1547.3,1387.5,1587.4 -1.27105595460747,0.8709113867938003,2.8797932657906435,855.1,1491.1,1834.5,1221.6,1432.5,1305.2 -1.2710421995089978,0.870919973164666,3.010692959690218,772.5,1742.3,1683.1,1060.6,1245.0,1186.3 -0.17092442219204945,0.17085178464513673,0.0,63.0,2751.0,2751.2,1699.1,71.0,71.0 -0.17096836028368106,0.171006579221618,0.1308996938995747,91.5,2823.0,2882.2,823.4,47.4,106.8 -0.17096845368049826,0.17100650915612614,0.2617993877991494,139.4,3131.9,3259.1,349.1,187.6,95.1 -0.17097688618653284,0.1710117647554632,0.39269908169872414,223.6,2592.4,2372.8,191.2,109.9,62.9 -0.17097642469307142,0.1710130972766546,0.5235987755982988,393.0,2078.3,1950.7,113.9,50.7,59.7 -0.1709838652172814,0.17102384668659032,0.6544984694978736,912.0,1823.3,1764.2,68.5,129.4,70.3 -0.17097985228689158,0.1710120879650614,0.7853981633974483,2721.3,1728.9,1727.9,40.8,93.6,93.1 -0.17098012617568176,0.17103441622451587,0.916297857297023,2842.3,973.2,150.0,25.4,70.5,129.3 -0.17098370440145375,0.17102557390435358,1.0471975511965976,3210.5,431.7,51.5,106.0,59.3,186.6 -0.17099443469821132,0.1710067283506982,1.1780972450961724,2381.4,252.2,31.3,31.1,63.1,282.2 -0.17097039025315322,0.1710290989364951,1.3089969389957472,1938.0,161.1,33.4,72.1,95.2,474.4 -0.17096119423808556,0.17103481707094925,1.4398966328953218,1741.3,106.5,93.6,90.9,237.6,1066.3 -0.17101002749561858,0.17102359626653207,1.5707963267948966,1698.8,70.9,70.7,63.1,2751.5,2751.3 -0.1709335114578418,0.1710233428923471,1.7016960206944713,233.8,47.4,105.8,48.4,2820.5,2997.1 -0.17094005533892465,0.1710249452057484,1.832595714594046,73.6,187.5,95.2,46.8,3132.0,3259.4 -0.1709843463959923,0.1710534881595327,1.9634954084936205,32.2,109.9,63.0,63.4,2590.5,2371.4 -0.1709883864044327,0.17105937784481817,2.0943951023931953,21.2,51.1,59.3,117.0,2076.7,1949.7 -0.17096945951044867,0.1710224499527624,2.2252947962927703,25.8,129.3,70.5,318.6,1822.5,1763.5 -0.1709704997827157,0.17102635808869793,2.356194490192345,41.6,93.1,93.6,2720.7,1728.3,1728.8 -0.1709681998520755,0.1710384797133364,2.4870941840919194,68.6,70.3,129.4,2800.5,968.8,149.7 -0.17097685025649248,0.1710133295007561,2.6179938779914944,73.5,59.7,187.3,3119.6,430.6,51.5 -0.1709719999858038,0.17101623484932382,2.748893571891069,62.5,62.5,282.5,2536.9,251.6,31.6 -0.170991315940011,0.17099947949293748,2.8797932657906435,46.4,94.7,474.5,2030.2,161.3,33.8 -0.17099384107608578,0.17099852942885962,3.010692959690218,48.1,234.6,1057.2,1785.1,106.4,93.1 -0.1709929523817046,0.1710006876261292,0.0,63.1,2751.0,2750.9,1698.9,71.0,71.0 -0.1709455455722573,0.1710009093597742,0.1308996938995747,91.5,2823.3,2882.3,823.4,47.4,106.8 -0.17097312328438083,0.17100941592896945,0.2617993877991494,139.4,3131.4,3258.4,349.1,187.6,95.1 -0.17097852986046916,0.1710127753239965,0.39269908169872414,223.6,2591.8,2373.1,191.2,109.9,62.9 -0.17097736174173017,0.17101324376644178,0.5235987755982988,393.0,2077.9,1950.5,113.9,50.7,59.7 -0.17098465525204937,0.17102375017321658,0.6544984694978736,912.0,1823.3,1764.2,68.5,129.4,70.3 -0.17098063056542803,0.17101194831152133,0.7853981633974483,2720.8,1729.0,1728.3,40.8,93.6,93.1 -0.17098090005537467,0.17103430970896327,0.916297857297023,2843.0,973.2,150.0,25.4,70.5,129.3 -0.17098445953981123,0.1710255187337275,1.0471975511965976,3210.2,431.7,51.5,106.0,59.3,186.6 -0.17099515700383316,0.17100672096731473,1.1780972450961724,2381.1,252.3,31.3,31.1,63.1,282.2 -0.17097107106109952,0.17102912792335845,1.3089969389957472,1938.0,161.1,33.4,72.1,95.2,474.4 -0.17096182884491928,0.17103486957600644,1.4398966328953218,1741.5,106.5,93.6,90.9,237.5,1066.2 -0.1710106146488473,0.17102365942971898,1.5707963267948966,1698.9,70.9,70.7,63.1,2751.6,2750.6 -0.17093404713281848,0.17102340505821134,1.7016960206944713,233.8,47.4,105.8,48.4,2820.7,2996.7 -0.17094055603736977,0.17102499829905438,1.832595714594046,73.6,187.4,95.2,46.8,3131.4,3259.7 -0.17098481404269206,0.17105352316105837,1.9634954084936205,32.2,110.0,63.0,63.4,2590.8,2371.7 -0.170988827571457,0.1710593885028875,2.0943951023931953,21.2,51.1,59.3,117.0,2076.8,1949.8 -0.17096988206943023,0.17102243260209793,2.2252947962927703,25.8,129.3,70.5,318.6,1822.5,1763.8 -0.17097091189348723,0.17102631058844886,2.356194490192345,41.6,93.1,93.6,2720.8,1728.2,1728.8 -0.17096860973473602,0.17103840220316635,2.4870941840919194,68.6,70.3,129.4,2800.8,968.9,149.8 -0.17097726532414734,0.17101322450246914,2.6179938779914944,73.5,59.7,187.4,3119.9,430.6,51.5 -0.1709724268705697,0.17101610616828267,2.748893571891069,62.5,62.5,282.5,2537.2,251.6,31.6 -0.17099175940227576,0.1709993326743824,2.8797932657906435,46.4,94.7,474.4,2030.0,161.3,33.8 -0.1709943042426763,0.1709983707686198,3.010692959690218,48.1,234.6,1057.4,1784.8,106.4,93.1 -0.17099343656327193,0.1710005237939185,0.0,63.1,2751.0,2750.9,1698.9,71.0,71.0 -0.17094605000139385,0.17100074648252073,0.1308996938995747,91.5,2823.2,2882.3,823.6,47.5,106.8 -0.17097364516031702,0.17100925980031856,0.2617993877991494,139.4,3131.6,3258.9,349.1,187.6,95.1 -0.17097906516445927,0.1710126300813284,0.39269908169872414,223.6,2592.3,2373.1,191.2,109.9,62.9 -0.17097790579725514,0.17101311186561774,0.5235987755982988,393.0,2078.0,1950.5,113.9,50.7,59.7 -0.17098520331141895,0.17102363224512618,0.6544984694978736,911.9,1823.0,1764.2,68.5,129.4,70.3 -0.1709811783761046,0.17101184374757028,0.7853981633974483,2721.1,1728.8,1728.4,40.8,93.7,93.1 -0.17098144429814496,0.17103421664238216,0.916297857297023,2843.0,973.2,150.0,25.4,70.5,129.3 -0.17098499792824104,0.17102543480986232,1.0471975511965976,3210.2,431.6,51.5,106.0,59.3,186.5 -0.1709956883441877,0.17100664360613216,1.1780972450961724,2381.2,252.2,31.3,31.1,63.1,282.1 -0.170971595147564,0.17102905482984831,1.3089969389957472,1938.1,161.1,33.4,72.1,95.2,474.4 -0.1709623459276165,0.17103479901900287,1.4398966328953218,1741.0,106.5,93.6,90.9,237.6,1066.2 -0.17101112515373867,0.1710235900965369,1.5707963267948966,1698.9,70.9,70.7,63.1,2751.2,2750.6 -0.17093454887922557,0.1710233358425839,1.7016960206944713,233.9,47.4,105.8,48.4,2820.6,2996.6 -0.17094105393769315,0.17102492933541624,1.832595714594046,73.6,187.5,95.2,46.8,3131.9,3259.4 -0.17098530670534967,0.17105345337611744,1.9634954084936205,32.2,109.9,63.0,63.4,2590.7,2371.2 -0.17098931484803817,0.17105931680553277,2.0943951023931953,21.2,51.1,59.2,117.0,2077.0,1949.1 -0.1709703642888363,0.17102235791584497,2.2252947962927703,25.8,129.3,70.5,318.6,1822.5,1763.5 -0.17097138983744897,0.17102623171008657,2.356194490192345,41.6,93.1,93.6,2720.3,1728.6,1729.0 -0.17096908471682454,0.1710383181330306,2.4870941840919194,68.6,70.3,129.4,2800.9,969.0,149.7 -0.17097773897844248,0.17101313479265134,2.6179938779914944,73.5,59.7,187.4,3120.1,430.6,51.5 -0.17097290115972633,0.17101601087410634,2.748893571891069,62.5,62.5,282.5,2537.3,251.6,31.6 -0.1709922360553249,0.17099923266825634,2.8797932657906435,46.4,94.6,474.4,2030.6,161.2,33.8 -0.17099478465583776,0.1709982675214765,3.010692959690218,48.1,234.6,1057.5,1784.6,106.3,93.1 -0.17099392149937917,0.1710004192230683,0.0,63.1,2751.2,2751.0,1699.0,71.0,71.0 -0.17094653785887864,0.17100064236940304,0.1308996938995747,91.5,2823.2,2882.7,823.6,47.4,106.8 -0.1709741376824197,0.1710091584744815,0.2617993877991494,139.4,3131.5,3259.1,349.1,187.6,95.1 -0.17097955999038825,0.1710125325949179,0.39269908169872414,223.6,2592.1,2373.2,191.2,109.9,62.9 -0.17097840096474856,0.17101301855374573,0.5235987755982988,393.0,2078.0,1950.7,113.9,50.7,59.7 -0.17098569716425902,0.1710235427322082,0.6544984694978736,912.0,1823.5,1764.1,68.5,129.4,70.3 -0.17098166966150327,0.17101175708023653,0.7853981633974483,2721.1,1729.0,1728.3,40.8,93.6,93.1 -0.17098193245141363,0.17103413157047243,0.916297857297023,2842.5,973.2,150.0,25.4,70.5,129.3 -0.17098548302428815,0.17102535007162234,1.0471975511965976,3210.1,431.7,51.5,106.0,59.3,186.6 -0.17099617100460165,0.17100655822485855,1.1780972450961724,2381.3,252.2,31.3,31.1,63.1,282.2 -0.17097207630078082,0.17102896841821158,1.3089969389957472,1937.9,161.1,33.4,72.1,95.2,474.4 -0.170962826494913,0.17103471175049312,1.4398966328953218,1741.4,106.4,93.6,90.9,237.6,1066.1 -0.17101160577033206,0.17102350253327048,1.5707963267948966,1699.1,71.0,70.7,63.1,2751.1,2751.0 -0.17093502771547536,0.17102324856690698,1.7016960206944713,233.8,47.4,105.8,48.4,2821.4,2996.5 -0.17094153391898725,0.17102484375672966,1.832595714594046,73.6,187.4,95.2,46.8,3131.6,3259.2 -0.17098578597117986,0.17105336969882012,1.9634954084936205,32.2,109.9,63.0,63.4,2590.5,2371.7 -0.17098979220654223,0.17105923478186114,2.0943951023931953,21.2,51.2,59.3,117.0,2076.4,1949.6 -0.17097083888129058,0.17102227690988792,2.2252947962927703,25.8,129.3,70.5,318.7,1822.4,1763.6 -0.17097186126748942,0.1710261507073314,2.356194490192345,41.6,93.1,93.6,2720.6,1728.4,1729.0 -0.1709695531742022,0.1710382359917999,2.4870941840919194,68.6,70.3,129.4,2800.7,968.8,149.8 -0.1709782051393061,0.17101305061697425,2.6179938779914944,73.5,59.7,187.4,3119.8,430.6,51.5 -0.17097336618855524,0.17101592413305222,2.748893571891069,62.5,62.5,282.5,2537.4,251.7,31.6 -0.17099270114846715,0.1709991434744378,2.8797932657906435,46.4,94.7,474.5,2030.1,161.2,33.8 -0.17099525089039438,0.17099817654174676,3.010692959690218,48.1,234.6,1057.3,1785.0,106.4,93.1 -1.371059879892572,0.5710182592916091,0.0,463.1,1551.1,1550.8,1298.8,1271.0,1270.8 -1.371025690686266,0.5709786920768711,0.1308996938995747,505.7,1580.4,1616.8,1328.4,1290.3,1349.6 -1.3710256230368525,0.5709787689361316,0.2617993877991494,601.8,1744.1,1872.0,1475.2,1272.5,892.9 -1.3710214897730075,0.5709762468658177,0.39269908169872414,790.3,2027.1,1807.9,1814.0,846.9,627.7 -1.3710220259947588,0.5709788312536299,0.5235987755982988,1189.9,1615.6,1487.8,1501.6,649.8,522.1 -1.3710323184966022,0.5709952103857727,0.6544984694978736,1558.0,1409.2,1350.2,1311.1,543.6,484.5 -1.3710298651128723,0.57099080011326,0.7853981633974483,1521.3,1329.0,1328.4,1241.0,493.7,493.2 -1.371029769811534,0.5710205247408466,0.916297857297023,1600.5,1349.5,1408.3,1267.7,484.5,543.3 -1.371031184150413,0.5710184070759501,1.0471975511965976,1823.7,1487.4,1614.9,1192.0,521.4,648.7 -1.3710383550434488,0.5710051056587877,1.1780972450961724,1814.5,1806.8,1732.0,791.0,627.5,846.5 -1.371009879501983,0.5710315701412803,1.3089969389957472,1475.6,1548.7,1420.7,602.1,892.2,1271.5 -1.3709957362708742,0.5710399280883529,1.4398966328953218,1350.0,1393.8,1289.6,504.7,1637.2,1578.7 -1.3710394559683665,0.5710299191691799,1.5707963267948966,1298.9,1271.2,1270.9,463.1,1551.2,1551.2 -1.3710054391950222,0.571028576975936,1.7016960206944713,1369.9,1288.9,1347.3,462.3,1579.6,1637.8 -1.3709772856638018,0.5710196754844641,1.832595714594046,1568.3,1271.3,892.1,509.3,1744.3,1872.2 -1.3710123792220188,0.5710425779165895,1.9634954084936205,1725.8,846.6,627.5,630.3,2026.3,1807.0 -1.371014578002892,0.5710466942906258,2.0943951023931953,1407.6,648.6,521.5,915.6,1614.6,1487.5 -1.3709955240722784,0.5710098521167588,2.2252947962927703,1267.9,543.3,461.7,1600.3,1408.2,1349.7 -1.370996591876895,0.5710145564053686,2.356194490192345,1241.8,493.0,493.6,1520.5,1328.4,1329.2 -1.3709941170802746,0.5710276317832748,2.4870941840919194,1356.8,484.5,543.6,1557.9,1349.8,1409.2 -1.3710023792236383,0.5710033486490667,2.6179938779914944,914.2,522.3,649.9,1732.5,1487.9,1615.6 -1.3709969828807513,0.5710069609911765,2.748893571891069,628.2,628.3,848.2,1971.4,1811.4,1728.9 -1.3710156703426786,0.570990722815105,2.8797932657906435,508.6,892.7,1272.4,1567.9,1547.9,1420.8 -1.3710175322501883,0.5709901139820546,3.010692959690218,462.1,1638.4,1579.6,1370.9,1348.8,1289.7 -1.371060131591408,0.6712821654067707,0.0,562.9,1550.9,1550.8,1198.9,1270.8,1271.1 -1.3710124470964073,0.6706929535792316,0.1308996938995747,609.2,1580.2,1639.6,1224.9,1290.4,1349.7 -1.3710410029700073,0.6707023226022879,0.2617993877991494,717.3,1744.5,1872.1,1359.7,1421.0,1092.2 -1.371075429049404,0.6707245967253581,0.39269908169872414,932.0,1886.5,1667.0,1672.5,988.1,768.7 -1.3711030541372795,0.6707567912837846,0.5235987755982988,1389.0,1500.0,1372.3,1501.4,765.5,637.8 -1.3711300873071102,0.6708050990723617,0.6544984694978736,1558.0,1305.7,1246.8,1311.0,647.0,588.0 -1.3711351086093522,0.670833341741544,0.7853981633974483,1521.4,1229.2,1228.5,1241.0,593.6,592.9 -1.371134096358903,0.6708937762795741,0.916297857297023,1600.3,1246.1,1305.1,1267.5,587.9,646.7 -1.3711274023550162,0.6709191397205951,1.0471975511965976,1823.7,1371.9,1499.2,1391.4,636.9,764.1 -1.3711208512420416,0.6709286062933171,1.1780972450961724,1672.8,1665.9,1731.8,932.5,768.4,987.7 -1.3710749980666046,0.6709721314740142,1.3089969389957472,1359.9,1548.5,1420.8,717.5,1091.3,1470.3 -1.3710411539981011,0.6709917650031827,1.4398966328953218,1246.9,1348.0,1289.3,608.0,1710.1,1578.7 -1.371064231237009,0.6709872523435767,1.5707963267948966,1199.1,1271.0,1270.8,562.9,1551.3,1551.3 -1.3710106888825322,0.6709860113043891,1.7016960206944713,1266.5,1288.8,1347.6,565.5,1579.0,1637.8 -1.3709649470296306,0.6709725089781333,1.832595714594046,1452.8,1421.7,1091.1,624.7,1744.7,1872.1 -1.3709851719374269,0.670986832539801,1.9634954084936205,1725.6,987.6,768.6,771.7,1884.8,1665.7 -1.370976205739924,0.6709797055008122,2.0943951023931953,1407.6,764.0,636.8,1115.2,1499.5,1372.3 -1.3709499781921726,0.6709301626331632,2.2252947962927703,1267.9,646.6,587.8,1726.4,1305.2,1246.4 -1.3709478001390591,0.670921573327379,2.356194490192345,1241.5,592.9,593.5,1520.5,1228.5,1228.9 -1.3709457935765204,0.6709219180654167,2.4870941840919194,1311.0,588.0,647.1,1557.9,1246.6,1305.6 -1.3709576650754263,0.6708864978501516,2.6179938779914944,1113.1,637.6,765.3,1732.0,1372.5,1500.1 -1.370958352473283,0.670881068436628,2.748893571891069,769.5,769.4,989.5,1829.8,1670.0,1729.0 -1.370984677313867,0.6708583813912243,2.8797932657906435,624.0,1091.9,1471.6,1452.6,1548.1,1420.9 -1.3709949351139445,0.6708539743370083,3.010692959690218,542.7,1697.7,1579.8,1267.7,1348.5,1289.6 -1.3710473416813975,0.771153542084444,0.0,662.9,1551.1,1551.0,1098.9,1271.0,1270.8 -1.3710189047834673,0.7711531612791951,0.1308996938995747,712.5,1580.4,1639.6,1121.6,1290.4,1350.0 -1.370963476574228,0.7711371203898889,0.2617993877991494,832.7,1744.4,1871.5,1244.5,1420.8,1291.3 -1.3709093967839423,0.7711041830542966,0.39269908169872414,1073.2,1745.2,1525.7,1530.8,1129.0,909.6 -1.3708659966174743,0.7710603497934665,0.5235987755982988,1588.1,1384.8,1256.9,1501.3,880.9,753.1 -1.3708467812749114,0.7710225227437306,0.6544984694978736,1557.8,1202.2,1143.1,1310.9,750.4,691.2 -1.3708307626472052,0.7709607749436873,0.7853981633974483,1521.0,1129.1,1128.7,1240.8,693.3,693.0 -1.3708323489312038,0.7709359240347087,0.916297857297023,1600.5,1142.8,1201.6,1267.7,691.4,750.3 -1.370848771331776,0.7708849503579238,1.0471975511965976,1823.6,1256.4,1383.7,1408.1,752.4,879.6 -1.3708813270848998,0.7708315961232322,1.1780972450961724,1531.1,1524.9,1731.7,1074.4,909.8,1128.9 -1.3708847906397286,0.7708287105883878,1.3089969389957472,1244.5,1548.6,1420.8,833.4,1290.6,1669.9 -1.3709064466419212,0.7708185383837218,1.4398966328953218,1120.5,1348.1,1289.9,711.6,1637.0,1578.5 -1.3709870845987575,0.7708006894558999,1.5707963267948966,1098.9,1271.2,1270.6,663.0,1551.3,1551.0 -1.3709873182292174,0.7708011101530425,1.7016960206944713,1162.6,1288.9,1347.4,669.1,1579.3,1637.9 -1.3709893350900606,0.7708019741300653,1.832595714594046,1337.3,1421.5,1290.5,740.4,1744.4,1872.4 -1.3710493203355205,0.7708411093263776,1.9634954084936205,1692.1,1128.7,909.6,913.5,1743.8,1524.7 -1.371069759475292,0.7708654527651926,2.0943951023931953,1407.5,879.6,752.3,1315.0,1383.7,1256.5 -1.3710621819557502,0.770850703825747,2.2252947962927703,1268.0,750.3,691.4,1600.4,1201.5,1142.8 -1.3710683578921532,0.7708780543909532,2.356194490192345,1241.5,693.0,693.6,1520.8,1128.5,1129.1 -1.3710651508966558,0.7709126579234715,2.4870941840919194,1311.1,691.5,750.4,1557.9,1143.1,1201.9 -1.3710678611441431,0.7709073229135279,2.6179938779914944,1312.4,753.3,881.0,1732.5,1256.9,1384.5 -1.3710530050124263,0.7709267480074686,2.748893571891069,910.7,910.9,1130.9,1688.4,1528.7,1728.7 -1.371059665489547,0.770922452924806,2.8797932657906435,739.7,1291.5,1671.2,1337.0,1548.2,1420.6 -1.3710479392681865,0.7709297999643461,3.010692959690218,669.0,1638.4,1579.6,1164.2,1348.5,1289.5 -1.3710737534211963,0.8712092166356644,0.0,762.7,1551.0,1550.7,999.1,1270.9,1270.9 -1.3710151971723106,0.8706540532139757,0.1308996938995747,816.3,1580.2,1639.4,1017.7,1290.1,1349.6 -1.371045600911259,0.8706640707608944,0.2617993877991494,948.4,1744.3,1871.8,1128.6,1446.4,1491.2 -1.3710839344214287,0.8706888790627727,0.39269908169872414,1215.0,1603.8,1384.5,1389.3,1270.4,1051.1 -1.3711150705738915,0.8707249331234044,0.5235987755982988,1732.3,1268.9,1141.3,1501.1,996.5,868.9 -1.3711232015222792,0.8707365967422986,0.6544984694978736,1558.1,1098.6,1039.5,1311.0,854.3,795.2 -1.3711364741613024,0.8708004581972455,0.7853981633974483,1521.1,1029.1,1028.6,1240.7,793.5,793.0 -1.3711350599868044,0.8708725873461554,0.916297857297023,1600.6,1039.4,1098.1,1267.5,794.9,853.6 -1.3711273267269413,0.8709014482308126,1.0471975511965976,1823.5,1140.9,1268.2,1503.3,867.7,995.1 -1.3711202560254176,0.8709118332759835,1.1780972450961724,1389.7,1383.8,1602.9,1215.8,1050.8,1269.8 -1.3710742821258302,0.8709555760982712,1.3089969389957472,1128.9,1548.2,1420.9,948.8,1489.7,1745.5 -1.3710404962774319,0.8709752930776802,1.4398966328953218,1017.1,1348.3,1289.8,814.9,1637.2,1578.6 -1.3710636768682485,0.8709708508630403,1.5707963267948966,999.2,1271.1,1270.7,763.0,1551.2,1551.0 -1.3710102222313034,0.8709697138944144,1.7016960206944713,1059.6,1289.0,1347.6,772.6,1579.3,1637.4 -1.3709645265214305,0.8709563397906241,1.832595714594046,1222.0,1581.8,1489.8,856.0,1744.6,1872.1 -1.370984761068066,0.8709707707894727,1.9634954084936205,1550.3,1269.7,1050.5,1055.3,1602.5,1383.9 -1.3709757813483223,0.8709637216964583,2.0943951023931953,1407.5,995.2,867.6,1514.2,1268.1,1141.0 -1.3709219051773078,0.8708596188542159,2.2252947962927703,1267.9,853.8,795.0,1600.1,1098.1,1039.3 -1.3709290536001537,0.8708920116492818,2.356194490192345,1241.6,792.8,793.5,1520.3,1028.3,1029.0 -1.3709266845820645,0.870901935244969,2.4870941840919194,1311.0,795.1,854.0,1557.9,1039.5,1098.6 -1.3709387325624307,0.8708659536370624,2.6179938779914944,1467.7,868.7,996.6,1732.1,1141.4,1268.8 -1.370941400477494,0.8708574546656809,2.748893571891069,1052.2,1052.4,1272.5,1547.2,1387.3,1607.4 -1.3709709258347607,0.8708318659818581,2.8797932657906435,855.2,1490.9,1744.2,1221.5,1548.3,1420.5 -1.3709850272273147,0.8708254987579334,3.010692959690218,772.5,1638.4,1579.4,1060.6,1348.3,1289.8 diff --git a/tools/localisation_machine_learning/data/sector3.csv b/tools/localisation_machine_learning/data/sector3.csv deleted file mode 100644 index 68f0a3c2..00000000 --- a/tools/localisation_machine_learning/data/sector3.csv +++ /dev/null @@ -1,2496 +0,0 @@ -2.8290387010639457,0.1708039118782665,0.0,63.0,93.0,93.0,1699.1,2729.1,2729.2 -2.829091608705104,0.17142191775350013,0.1308996938995747,91.6,119.3,129.6,1742.7,964.3,233.5 -2.8290042807064815,0.17139418441362575,0.2617993877991494,116.8,59.3,186.8,1937.8,474.7,95.2 -2.8289478052728394,0.17135789193280337,0.39269908169872414,62.7,63.0,283.8,2380.4,282.3,63.0 -2.828909087029326,0.1713172609735607,0.5235987755982988,150.3,95.2,474.4,3186.6,187.4,59.8 -2.828894348375713,0.17128609040658938,0.6544984694978736,48.3,234.5,1054.2,2820.5,129.5,70.5 -2.828880667263091,0.1712326474405561,0.7853981633974483,63.1,1728.4,1728.6,2699.1,93.8,93.2 -2.828881862539084,0.17121603706104538,0.916297857297023,91.3,1763.5,1822.1,917.3,70.7,129.5 -2.8288954401360242,0.17117238179263228,1.0471975511965976,139.1,1949.5,2076.7,393.6,59.5,94.9 -2.828923320128915,0.1711247239608289,1.1780972450961724,222.6,2371.4,2590.9,224.3,63.3,110.3 -2.828921050202843,0.17112536307889026,1.3089969389957472,393.3,3234.5,3106.6,139.9,95.6,200.7 -2.828936639367103,0.1711165423559371,1.4398966328953218,836.7,2856.9,2798.3,91.1,128.5,70.1 -2.8290115646096057,0.17109826943435125,1.5707963267948966,1698.7,2729.1,2728.5,63.3,93.2,93.0 -2.829007063980042,0.1710967684592013,1.7016960206944713,1783.2,1066.2,238.2,48.6,122.6,129.2 -2.829005528623743,0.17109472199283493,1.832595714594046,2030.6,474.6,95.6,47.1,58.8,186.5 -2.8290631011878515,0.17113061984764455,1.9634954084936205,2542.0,282.3,63.3,63.7,62.5,283.5 -2.8290821344743167,0.17115181987255945,2.0943951023931953,3091.9,186.8,59.5,117.4,95.5,475.8 -2.8290739219599126,0.1711341660761876,2.2252947962927703,2776.8,129.5,70.7,91.0,235.4,1058.8 -2.829079871225673,0.17115895775339607,2.356194490192345,2699.6,93.2,93.8,62.4,1728.2,1728.8 -2.8290765783628,0.17119131622602435,2.4870941840919194,316.7,70.5,129.6,48.3,1764.2,1823.2 -2.8290793698725993,0.1711838207204448,2.6179938779914944,117.6,59.9,94.5,46.5,1950.4,2078.1 -2.8290646440487666,0.1712010923574605,2.748893571891069,62.7,62.7,110.2,63.1,2377.4,2596.8 -2.829071770632288,0.1711945402213284,2.8797932657906435,46.6,95.0,200.4,117.1,3232.3,3105.1 -2.8290609313829234,0.17119960978359372,3.010692959690218,48.2,129.2,70.4,318.3,2857.3,2798.8 -2.8290887502404676,0.2714803528140084,0.0,163.2,93.0,93.0,1598.7,2729.2,2728.9 -2.829030405093865,0.27073057850273363,0.1308996938995747,195.0,70.2,129.6,1639.5,1432.8,617.0 -2.829052406034923,0.2707378497150368,0.2617993877991494,116.8,59.3,186.8,1822.1,673.9,294.4 -2.8290821772477606,0.27075716815264506,0.39269908169872414,64.2,63.0,283.7,2239.2,423.1,204.0 -2.8291065363249635,0.2707858465512183,0.5235987755982988,47.0,95.4,474.7,3177.1,302.8,175.2 -2.829131476765533,0.27083034557527563,0.6544984694978736,48.4,234.8,1054.3,2820.1,232.8,173.8 -2.829135542431696,0.27085470109753995,0.7853981633974483,63.2,1629.0,1628.5,2698.4,193.6,193.0 -2.829134536855386,0.270911422245796,0.916297857297023,91.4,1660.5,1719.0,1303.9,173.9,232.8 -2.8291287288450198,0.27093342586609004,1.0471975511965976,139.2,1834.0,1961.6,592.7,174.7,161.1 -2.829123785255402,0.27094011955285824,1.1780972450961724,222.7,2231.0,2449.5,365.6,204.0,92.2 -2.8290799891015457,0.2709815163579061,1.3089969389957472,393.3,3156.4,3105.9,255.0,187.4,59.8 -2.8290485117421578,0.27099256513568903,1.4398966328953218,922.7,2856.9,2798.1,194.2,151.4,70.1 -2.8290817475422765,0.27099265128522076,1.5707963267948966,1598.8,2729.1,2728.7,162.9,93.3,93.1 -2.829025215208115,0.2709911744585165,1.7016960206944713,1680.4,1454.5,626.5,151.7,70.8,129.2 -2.8289805347143675,0.2709778531982334,1.832595714594046,1915.9,673.2,294.2,162.3,58.8,186.5 -2.8290027367997586,0.27099335753834497,1.9634954084936205,2400.6,423.0,204.0,204.9,62.5,283.5 -2.8289954839722204,0.2709880855448492,2.0943951023931953,3092.6,301.9,174.6,139.3,95.4,475.6 -2.828970401807111,0.2709406816249573,2.2252947962927703,2776.8,232.7,173.9,217.2,235.2,1058.7 -2.8289687080740697,0.27093435219477824,2.356194490192345,2699.9,192.9,193.5,62.4,1628.5,1629.0 -2.828966522078063,0.2709368756220272,2.4870941840919194,701.0,173.7,232.9,48.3,1661.0,1719.6 -2.8289777365460504,0.2709033113018997,2.6179938779914944,316.2,175.2,161.8,46.4,1834.9,1962.8 -2.8289773095669624,0.27089939447345746,2.748893571891069,203.8,203.8,92.2,63.1,2235.8,2455.5 -2.8290023280038703,0.2708777580963009,2.8797932657906435,161.9,186.8,59.4,117.1,3161.4,3105.0 -2.8290111664855098,0.2708739640355695,3.010692959690218,151.5,129.2,70.4,318.2,2857.8,2798.8 -2.829061949358878,0.37117230314197447,0.0,262.9,93.0,93.0,1499.0,2729.0,2729.4 -2.829032351494212,0.3711717647567616,0.1308996938995747,298.4,70.2,129.5,1535.9,1816.0,1000.3 -2.8289761039284844,0.37115538760829714,0.2617993877991494,124.8,59.3,186.8,1706.7,873.2,493.5 -2.8289214152897277,0.3711220093617318,0.39269908169872414,62.7,63.0,283.7,2097.4,564.1,344.9 -2.828877590086141,0.3710776851324409,0.5235987755982988,46.9,95.2,474.3,2977.7,418.4,290.7 -2.8288580562676895,0.3710393237310152,0.6544984694978736,48.3,234.4,1054.0,2820.8,336.3,277.2 -2.8288418824135086,0.37097705619047283,0.7853981633974483,63.1,1529.1,1528.4,2698.6,293.5,293.0 -2.8288433930712302,0.3709516711358063,0.916297857297023,91.3,1556.9,1615.5,1690.4,277.4,236.1 -2.8288598548212507,0.37090018257227886,1.0471975511965976,139.1,1718.6,1845.9,792.5,290.2,172.1 -2.828892573505865,0.37084639677923414,1.1780972450961724,222.5,2089.5,2308.6,507.3,284.4,63.5 -2.8288962680871435,0.37084311785304536,1.3089969389957472,393.2,2956.9,3105.8,370.7,250.5,59.7 -2.828918231375867,0.37083259926507983,1.4398966328953218,922.2,2856.2,2798.1,297.7,128.5,70.1 -2.8289992494373646,0.370814580876365,1.5707963267948966,1499.0,2729.2,2728.6,263.0,93.3,93.0 -2.8289998716754243,0.37081492569291497,1.7016960206944713,1577.0,1844.6,1016.3,255.3,70.8,129.2 -2.829002273888274,0.3708157897018809,1.832595714594046,1799.9,872.9,493.5,278.0,58.8,186.5 -2.829062587081387,0.3708550866526874,1.9634954084936205,2259.0,564.2,345.2,221.5,62.5,283.5 -2.8290832517356113,0.3708796971695123,2.0943951023931953,3091.4,417.5,290.2,272.6,95.5,475.7 -2.8290758144776045,0.3708652207062497,2.2252947962927703,2776.9,336.2,277.4,91.0,235.4,1058.9 -2.8290820143888613,0.37089286051951764,2.356194490192345,2699.6,293.0,293.5,62.4,1528.5,1529.0 -2.829078695591477,0.3709277485167206,2.4870941840919194,1001.7,277.2,234.4,48.3,1557.5,1616.4 -2.829081255409417,0.37092260414410494,2.6179938779914944,515.5,290.9,172.8,46.5,1719.5,1847.2 -2.8290661499456813,0.3709421636507064,2.748893571891069,345.2,283.1,63.1,63.1,2094.6,2315.1 -2.8290725945921795,0.3709379009584304,2.8797932657906435,277.4,250.1,59.4,117.1,2961.1,3105.1 -2.829060668261429,0.37094521077285236,3.010692959690218,255.0,129.2,70.4,318.3,2857.6,2798.9 -2.829086334743422,0.47122451247767927,0.0,362.9,93.0,93.0,1399.1,2729.1,2729.6 -2.8290254149835627,0.4706580791826471,0.1308996938995747,314.4,70.2,129.5,1432.1,2200.8,1384.8 -2.8290548714904955,0.4706678121267751,0.2617993877991494,240.6,59.3,186.8,1590.9,1072.8,693.1 -2.8290926336976496,0.47069229254226874,0.39269908169872414,62.8,63.0,283.8,1956.3,705.6,486.4 -2.82912339882296,0.47072799887439354,0.5235987755982988,47.0,95.4,474.5,2778.4,534.1,406.5 -2.829152518277156,0.4707804130414095,0.6544984694978736,48.4,234.8,1054.3,2820.9,439.9,380.8 -2.8291584795635676,0.47081298900094093,0.7853981633974483,63.2,1429.0,1428.3,2699.0,393.5,393.0 -2.8291572750206284,0.47087750556133035,0.916297857297023,91.4,1453.2,1512.0,2078.1,380.9,236.6 -2.8291494363812415,0.47090651078351353,1.0471975511965976,139.2,1603.0,1730.8,992.0,405.7,95.2 -2.829141016417826,0.4709189994620986,1.1780972450961724,222.6,1948.3,2167.5,648.8,284.5,63.6 -2.8290928147456254,0.4709647611269532,1.3089969389957472,393.4,2757.7,3106.3,486.2,187.4,59.8 -2.829056331496448,0.47098584057793014,1.4398966328953218,922.4,2856.6,2798.8,401.1,128.5,70.2 -2.8290766678089634,0.47098205592356357,1.5707963267948966,1398.8,2728.8,2728.5,362.9,93.3,93.1 -2.829020536674546,0.4709808268542879,1.7016960206944713,1473.6,2234.1,1405.7,358.6,70.8,129.2 -2.828972467523072,0.4709667020921795,1.832595714594046,1684.6,1071.9,692.7,391.7,58.8,186.5 -2.8289907105404284,0.4709799135011139,1.9634954084936205,2117.6,705.2,486.1,315.4,62.5,283.4 -2.828980230450889,0.4709713362147645,2.0943951023931953,3062.1,532.9,405.6,139.3,95.4,475.8 -2.8289530163975978,0.4709201203919806,2.2252947962927703,2777.2,439.6,380.9,90.9,235.2,1058.6 -2.8289503605202295,0.47090976816349106,2.356194490192345,2699.9,392.9,393.6,62.4,1428.6,1428.9 -2.828948348924173,0.4709084208094425,2.4870941840919194,1387.3,380.8,234.2,48.3,1453.8,1512.9 -2.828960662370225,0.47087148601653306,2.6179938779914944,714.7,406.4,94.5,46.5,1603.9,1731.4 -2.828962106229011,0.4708648209724655,2.748893571891069,486.6,283.0,63.1,63.1,1953.0,2173.3 -2.828989437760208,0.4708412289460848,2.8797932657906435,393.0,186.8,59.4,117.0,2762.3,3105.4 -2.8290008197054175,0.47083627604077294,3.010692959690218,358.5,129.2,70.4,318.2,2857.8,2798.8 -2.8290545714259108,0.571136883989485,0.0,462.9,93.0,93.0,1299.2,2728.9,2729.1 -2.8290270515003444,0.5711366367632869,0.1308996938995747,314.4,70.2,129.6,1328.8,2584.4,1768.4 -2.828972282877753,0.5711209008375193,0.2617993877991494,116.8,59.3,186.8,1475.9,1271.8,892.3 -2.8289186650344877,0.571088370452145,0.39269908169872414,62.7,63.0,283.7,1814.5,846.5,627.3 -2.828875569557041,0.571045000209286,0.5235987755982988,46.9,95.2,474.3,2578.9,649.7,521.9 -2.8288564906266878,0.5710076268071562,0.6544984694978736,48.3,234.4,1053.8,2820.9,543.3,484.3 -2.8288405120983957,0.5709463249640798,0.7853981633974483,63.1,1329.1,1328.7,2698.6,493.5,492.9 -2.828842027712273,0.5709218530550879,0.916297857297023,91.2,1349.7,1408.6,2465.6,484.4,323.2 -2.8288583186059792,0.570871201728351,1.0471975511965976,139.1,1487.6,1614.8,1191.8,475.1,94.9 -2.828890712890083,0.5706334288618409,1.1780972450961724,191.5,1807.2,2026.4,790.7,296.5,63.5 -2.8288992748541872,0.5708109852039742,1.3089969389957472,393.1,2558.4,2937.4,602.0,187.3,59.7 -2.8289163291447843,0.570803242803227,1.4398966328953218,922.1,2856.2,2798.1,504.6,128.5,70.1 -2.828995686757583,0.570785775988585,1.5707963267948966,1299.1,2729.1,2728.7,463.0,93.2,93.0 -2.8289957453614214,0.5707862806344939,1.7016960206944713,1370.0,2624.1,1795.3,462.1,70.8,129.2 -2.8289979161366507,0.5707872688186493,1.832595714594046,1568.5,1271.2,891.9,391.6,58.9,186.5 -2.8290580846786804,0.5708266414290251,1.9634954084936205,1975.2,846.6,627.4,221.5,62.5,283.5 -2.829078637055301,0.5708512727929806,2.0943951023931953,2862.1,648.6,521.3,139.4,95.4,431.8 -2.829071110274135,0.57083678519034,2.2252947962927703,2777.7,543.3,484.4,91.0,150.1,1058.7 -2.8290772739219263,0.5708643751189886,2.356194490192345,2699.6,493.0,493.5,62.4,1328.3,1329.0 -2.8290739956701,0.5708991958331138,2.4870941840919194,1857.3,484.4,323.4,48.4,1350.3,1409.1 -2.829076635479786,0.57089402409475,2.6179938779914944,913.9,473.5,94.6,46.5,1488.2,1615.9 -2.829061668668432,0.5709135983883495,2.748893571891069,627.9,296.4,63.1,63.1,1811.8,2031.5 -2.829068237037898,0.5709094222882545,2.8797932657906435,508.5,186.8,59.4,117.1,2562.1,2942.4 -2.8290564072481903,0.570916876022395,3.010692959690218,462.0,129.2,70.4,318.3,2857.5,2798.5 -2.829082084778633,0.6711962037043899,0.0,562.7,93.0,93.0,1199.1,2728.6,2729.5 -2.829021662837321,0.6706503408964266,0.1308996938995747,389.1,70.2,129.5,1225.0,2800.0,2153.6 -2.8290520877226837,0.6706603845964536,0.2617993877991494,116.9,59.3,186.8,1359.8,1471.5,1092.2 -2.8290907441907334,0.6706854292476112,0.39269908169872414,62.8,63.1,283.8,1672.5,988.0,768.6 -2.8291221981058867,0.670721871877477,0.5235987755982988,47.0,95.4,474.5,2379.8,765.3,637.5 -2.828791036889227,0.6710224511678151,0.6544984694978736,48.5,235.5,1056.6,2820.2,646.9,587.9 -2.828786998278443,0.6710076186492304,0.7853981633974483,63.3,1229.0,1228.7,2698.8,593.6,593.1 -2.8287883058066825,0.6710104159898624,0.916297857297023,91.5,1246.4,1305.2,2761.9,588.0,427.0 -2.8287992996089475,0.6709789694033663,1.0471975511965976,114.0,1372.5,1499.8,1390.2,474.8,95.1 -2.8288231878457766,0.6709405444910892,1.1780972450961724,222.9,1666.8,1886.0,932.0,284.4,63.7 -2.828815645496047,0.6709481336639567,1.3089969389957472,350.0,2360.9,2740.8,717.4,187.3,59.8 -2.8288248877210735,0.6709441911124103,1.4398966328953218,924.5,2856.5,2797.6,608.0,128.5,70.3 -2.828892767717422,0.6709291799739905,1.5707963267948966,1198.8,2728.7,2728.6,562.9,93.3,93.2 -2.8288811707239154,0.6709287350158855,1.7016960206944713,1266.5,2797.5,2181.4,565.8,70.9,129.4 -2.828872995982254,0.6709254891538527,1.832595714594046,1453.4,1469.0,1090.4,484.0,59.0,186.8 -2.8289247743674046,0.6709585658851964,1.9634954084936205,1834.5,987.0,768.4,221.4,62.7,283.8 -2.8289394378851798,0.6709757103708032,2.0943951023931953,2664.6,763.9,636.7,139.4,95.8,476.5 -2.8289287532728027,0.6709530276562625,2.2252947962927703,2776.2,646.7,588.0,91.0,236.3,1061.2 -2.8289340433633234,0.6709725752147995,2.356194490192345,2700.0,593.0,593.7,62.5,1228.4,1229.1 -2.8289316338139727,0.6710002346487598,2.4870941840919194,2239.3,588.0,427.3,48.4,1246.5,1305.8 -2.8289368549146925,0.6709888422118955,2.6179938779914944,1112.3,473.3,94.7,46.6,1372.9,1500.7 -2.828925155139292,0.6709983656951315,2.748893571891069,769.0,283.0,63.3,63.3,1670.7,1890.9 -2.828844705297987,0.6708558598142509,2.8797932657906435,624.2,186.9,59.4,117.1,2362.2,2742.0 -2.8288703676746128,0.6708429648925078,3.010692959690218,565.6,129.3,70.5,318.3,2857.7,2799.0 -2.8289472998016447,0.7711599731297527,0.0,663.0,93.1,93.1,1099.0,2729.0,2728.9 -2.828938219585628,0.771159714180419,0.1308996938995747,492.7,70.3,129.6,1121.5,2885.0,2538.5 -2.8288982216128393,0.7711478339531863,0.2617993877991494,117.0,59.4,186.9,1244.4,1671.7,1291.7 -2.8288564621333645,0.7711219074624704,0.39269908169872414,62.8,63.1,252.6,1530.7,1129.4,909.9 -2.828822332845041,0.7710871229405902,0.5235987755982988,47.0,51.6,474.4,2180.2,881.1,753.3 -2.828809279676403,0.7710594922731824,0.6544984694978736,48.4,234.6,1053.6,2820.7,750.5,691.5 -2.8287963136694976,0.7710084956733896,0.7853981633974483,63.2,1128.9,1128.6,2699.1,693.5,693.0 -2.8287980501518,0.7709940193359714,0.916297857297023,91.3,1142.6,1201.3,2776.5,691.5,530.2 -2.828811976083756,0.7709524666125049,1.0471975511965976,139.2,1256.4,1383.7,1591.4,507.0,95.1 -2.8288398818677876,0.7709068866210349,1.1780972450961724,222.6,1524.5,1743.9,1074.4,284.6,63.6 -2.828837304728912,0.7709097372992404,1.3089969389957472,393.2,2159.0,2538.1,833.3,187.4,59.8 -2.828852065199521,0.7709031682037348,1.4398966328953218,922.0,2857.1,2798.1,711.4,128.6,70.2 -2.8289255385323817,0.7708866644916781,1.5707963267948966,1098.9,2728.8,2729.0,663.1,93.4,93.1 -2.828919176324116,0.7708864720606576,1.7016960206944713,1162.9,2843.1,2576.2,669.2,70.9,129.3 -2.828915493310378,0.7708851358766586,1.832595714594046,1336.9,1670.3,1290.9,494.7,58.9,186.6 -2.828970964459724,0.7709207749679947,1.9634954084936205,1691.6,1128.9,909.7,221.6,62.6,283.5 -2.8289883325527057,0.7709409161913843,2.0943951023931953,2462.2,879.8,752.4,139.5,51.7,475.8 -2.828979057947819,0.770921796617204,2.2252947962927703,2777.1,750.4,691.6,91.1,235.5,1058.5 -2.828984773181219,0.7709448604007794,2.356194490192345,2700.0,693.1,693.7,62.5,1128.4,1129.2 -2.8289821669459303,0.7709755495099766,2.4870941840919194,2630.4,691.5,530.5,48.4,1142.8,1202.3 -2.8289862011955837,0.7709669366162542,2.6179938779914944,1312.9,507.6,94.8,46.6,1256.7,1384.4 -2.8289732574192077,0.7709836927368685,2.748893571891069,910.9,283.3,63.2,63.2,1528.4,1748.3 -2.8289820913519796,0.7709774099770923,2.8797932657906435,739.8,186.9,59.5,117.2,2162.4,2542.4 -2.828972705952065,0.7709833745250598,3.010692959690218,669.0,129.3,70.5,233.2,2858.1,2798.5 -2.82900130734336,0.8712648095495867,0.0,762.9,93.1,93.1,999.0,2728.6,2729.2 -2.8289666622721734,0.8706723502453793,0.1308996938995747,596.3,70.3,129.5,1017.6,2799.9,2840.2 -2.8290000154262755,0.8706831616484427,0.2617993877991494,117.1,59.4,186.8,1128.5,1871.6,1491.9 -2.8290373658307324,0.8707071404951032,0.39269908169872414,62.9,63.1,283.7,1388.7,1270.7,1051.6 -2.8290669019454695,0.8707411684230666,0.5235987755982988,47.0,95.5,474.3,1980.0,996.8,869.1 -2.829095325407649,0.8707914998957553,0.6544984694978736,48.4,149.9,1052.9,2820.7,854.1,795.1 -2.829101024106659,0.8708217580323361,0.7853981633974483,63.2,1029.0,1028.4,2698.7,793.4,792.9 -2.8291002861602514,0.8708842776945172,0.916297857297023,91.4,1039.1,1097.8,2776.7,794.9,633.7 -2.829093336002851,0.8709116205795058,1.0471975511965976,139.2,1140.9,1268.0,1791.6,622.2,95.3 -2.829085999014901,0.8709226708125368,1.1780972450961724,222.6,1383.5,1602.1,1216.3,284.7,63.7 -2.8290390947501676,0.8709675371243879,1.3089969389957472,393.1,1959.4,2338.5,949.0,187.5,59.8 -2.8290039578338844,0.870988245890659,1.4398966328953218,921.2,2856.8,2797.7,815.0,128.6,70.2 -2.8290255578233103,0.8709840820431651,1.5707963267948966,999.2,2729.2,2728.7,762.8,93.4,93.1 -2.828970612510751,0.870982837933937,1.7016960206944713,1059.7,2797.3,2855.4,772.4,70.9,129.2 -2.828923575487995,0.8709691049985651,1.832595714594046,1221.5,1870.1,1490.5,392.0,58.9,186.4 -2.828942781323954,0.8709826874553666,1.9634954084936205,1549.8,1270.4,1050.8,221.7,62.5,283.3 -2.8289331811220704,0.8709745368271142,2.0943951023931953,2261.6,995.3,867.9,139.5,95.4,475.3 -2.8289065802586446,0.8709240534116318,2.2252947962927703,2777.7,853.8,794.9,91.0,149.9,1057.4 -2.828904364538376,0.8709145249372172,2.356194490192345,2699.6,793.0,793.4,62.5,1028.7,1029.0 -2.8289027116926335,0.8709139511910196,2.4870941840919194,2820.9,794.9,634.1,48.4,1039.6,1098.4 -2.8289149726515923,0.8708779101447621,2.6179938779914944,1468.4,623.1,94.7,46.5,1141.0,1268.8 -2.828916357982934,0.8708719684385349,2.748893571891069,1052.7,283.3,63.2,63.1,1387.1,1607.0 -2.8289432444582587,0.8708490334403061,2.8797932657906435,855.3,186.9,59.4,117.0,1962.5,2342.0 -2.8289540566654936,0.87084453154658,3.010692959690218,772.5,129.3,70.4,317.8,2858.1,2799.2 -2.7289406606438824,0.17075472612858045,0.0,63.0,193.1,193.0,1699.1,2628.9,2629.1 -2.7289856876140037,0.17145980994769805,0.1308996938995747,91.6,173.8,233.1,1742.7,1049.2,233.6 -2.7289408131357837,0.17144511104134974,0.2617993877991494,139.5,174.9,302.3,1937.4,474.9,95.3 -2.728888816377063,0.17141147796704903,0.39269908169872414,203.9,204.7,425.3,2379.9,282.3,63.0 -2.7288456029596584,0.17136576763543054,0.5235987755982988,162.5,294.6,629.8,3071.5,187.5,59.8 -2.728826423551052,0.1713258217899727,0.6544984694978736,151.9,620.0,1439.2,2717.4,129.5,70.5 -2.7288105563661595,0.17126213896569586,0.7853981633974483,163.1,1728.7,1728.3,2599.0,93.8,93.2 -2.728812285622372,0.17123558574014175,0.916297857297023,194.8,1763.4,1822.4,917.8,70.7,129.5 -2.7288287721903486,0.1711829965762377,1.0471975511965976,254.7,1949.5,2077.0,393.8,59.5,186.8 -2.7288613665702375,0.17112794990623525,1.1780972450961724,363.7,2371.1,2590.3,224.3,63.3,205.2 -2.728864981849481,0.1711231723980966,1.3089969389957472,592.4,3118.3,2990.9,139.9,95.6,231.7 -2.7288497955827524,0.17112695842379155,1.4398966328953218,1311.8,2752.9,2694.5,91.1,209.2,173.6 -2.7291307249874848,0.17106349000743482,1.5707963267948966,1698.6,2628.8,2628.6,63.3,193.4,193.1 -2.729018956600095,0.17105775655239586,1.7016960206944713,1783.3,1067.0,238.5,48.6,174.3,232.7 -2.728997294268438,0.17104934559274398,1.832595714594046,2030.5,474.8,95.7,47.1,174.5,302.2 -2.7290599902797243,0.17108815029423696,1.9634954084936205,2542.0,282.4,63.4,63.7,204.3,425.1 -2.7290884392857597,0.17111903790608296,2.0943951023931953,2976.6,186.8,59.5,117.4,295.2,631.5 -2.7290875075312226,0.17111453084343187,2.2252947962927703,2673.6,129.5,70.7,194.5,622.9,1446.1 -2.729097042875914,0.1711538178250862,2.356194490192345,2599.9,93.3,93.8,162.5,1728.0,1728.8 -2.729093494585363,0.17120031431855742,2.4870941840919194,316.9,70.5,129.6,151.9,1764.0,1823.0 -2.7290926162025673,0.1712054243322476,2.6179938779914944,117.6,59.9,187.6,162.2,1950.1,2077.7 -2.7290715534474694,0.1712331517628698,2.748893571891069,62.7,62.7,204.6,204.6,2376.9,2597.4 -2.729070483976115,0.1712343871502846,2.8797932657906435,46.6,95.0,231.4,316.7,3117.0,2990.0 -2.729007482010391,0.17126263529518315,3.010692959690218,48.2,210.0,173.9,620.3,2754.3,2695.4 -2.7290523727635003,0.27150586020323875,0.0,163.2,193.0,193.0,1598.7,2628.9,2629.4 -2.729004328537034,0.2707344911790279,0.1308996938995747,195.0,173.8,233.2,1639.4,1433.3,617.4 -2.729028420864289,0.270742360304677,0.2617993877991494,254.9,174.9,302.4,1822.2,674.1,294.5 -2.7290961028576373,0.2707877992493024,0.39269908169872414,204.0,204.7,425.5,2238.8,423.3,204.0 -2.7290985843300923,0.27079262266852977,0.5235987755982988,162.6,294.6,673.7,3071.9,302.9,175.2 -2.72911985405535,0.27082989201616203,0.6544984694978736,152.0,535.4,1439.4,2716.8,232.9,173.8 -2.7291356820497388,0.2709084942975637,0.7853981633974483,163.2,1629.0,1628.5,2599.1,193.5,192.9 -2.729136015365871,0.27092860216947834,0.916297857297023,194.9,1660.2,1718.9,1304.3,173.9,232.7 -2.729132223866869,0.2709446429179081,1.0471975511965976,254.8,1834.1,1961.5,593.0,174.7,294.9 -2.7291257298149,0.2709539955119984,1.1780972450961724,363.8,2230.7,2449.1,365.6,204.0,251.0 -2.7290778664215645,0.27099937312243205,1.3089969389957472,548.7,3118.2,2990.8,255.1,294.1,175.4 -2.7290409337367043,0.27102062808978067,1.4398966328953218,1311.7,2753.1,2695.0,194.2,232.0,173.6 -2.7290605163030817,0.2710168010052578,1.5707963267948966,1599.3,2628.8,2628.5,162.9,193.3,193.1 -2.729003652143547,0.2710153415069265,1.7016960206944713,1680.2,1455.6,626.9,151.7,174.3,232.7 -2.728954963437165,0.2710008649348339,1.832595714594046,1915.1,673.4,294.2,162.3,174.5,302.1 -2.729007768140335,0.27103795206571957,1.9634954084936205,2400.2,423.1,203.9,204.9,204.2,425.1 -2.7290007602193165,0.2710322955031128,2.0943951023931953,2976.5,302.0,174.7,254.9,295.1,675.2 -2.72895911970959,0.2709535232728846,2.2252947962927703,2673.6,232.7,173.9,232.9,537.3,1445.4 -2.7289661996564316,0.2709876955978545,2.356194490192345,2599.7,192.9,193.5,162.4,1628.5,1629.2 -2.7289657349002185,0.27095386146712097,2.4870941840919194,701.5,173.7,232.8,151.9,1660.7,1719.7 -2.728979048796577,0.27091386810193807,2.6179938779914944,316.4,175.2,293.8,162.1,1835.0,1962.7 -2.728977477930131,0.2709121027526489,2.748893571891069,203.7,203.8,251.2,204.6,2235.6,2455.7 -2.728998843512417,0.2708940093437142,2.8797932657906435,161.9,293.9,175.0,316.5,3117.4,2990.0 -2.7290027619923145,0.27089292676935894,3.010692959690218,151.5,232.8,173.9,705.2,2754.6,2695.7 -2.7290471555607323,0.37118625138170946,0.0,262.9,193.0,193.0,1499.1,2629.1,2628.6 -2.7290130544197493,0.37118556917487533,0.1308996938995747,298.4,173.8,233.1,1536.0,1816.9,916.5 -2.7289534145771417,0.37116812372162444,0.2617993877991494,316.3,174.9,302.4,1706.7,873.3,493.7 -2.728896160726732,0.37113307087556313,0.39269908169872414,205.6,204.7,425.2,2097.3,564.3,345.0 -2.728850485373386,0.3710866532290733,0.5235987755982988,162.5,294.5,673.4,2977.0,418.4,290.8 -2.7288299017173014,0.3710460599655301,0.6544984694978736,151.9,619.8,1438.8,2716.7,336.3,277.2 -2.728813280966507,0.3709814752588674,0.7853981633974483,163.1,1529.0,1528.5,2598.8,293.5,292.9 -2.7288150065486176,0.3709539959642476,0.916297857297023,194.8,1556.8,1615.5,1691.8,277.5,336.2 -2.72883216402234,0.37090068831700984,1.0471975511965976,254.6,1718.7,1845.8,792.7,290.2,294.7 -2.7288658980751244,0.37084537621111635,1.1780972450961724,363.6,2089.3,2308.2,507.5,345.2,233.3 -2.728870850372664,0.3708410370021482,1.3089969389957472,592.3,2956.8,2990.9,370.8,303.0,175.3 -2.7288941850911113,0.3708299195776439,1.4398966328953218,1311.4,2753.1,2694.5,297.8,232.0,173.6 -2.7289765726377775,0.3708115429513601,1.5707963267948966,1498.9,2629.0,2628.9,263.0,193.3,193.0 -2.7289784777381016,0.3708119014538198,1.7016960206944713,1576.5,1845.6,931.0,255.3,174.3,232.7 -2.728982011773907,0.37081313407374905,1.832595714594046,1799.9,872.9,493.7,278.0,174.5,302.1 -2.729043311543399,0.370852945389043,1.9634954084936205,2258.8,564.3,345.2,346.7,204.3,425.2 -2.7290647774260344,0.37087819199254923,2.0943951023931953,2976.8,417.6,290.2,254.9,295.1,675.3 -2.7290578748530803,0.3708645273370488,2.2252947962927703,2673.6,336.2,277.4,194.5,622.5,1445.7 -2.7290643883516186,0.3708930352715296,2.356194490192345,2599.5,292.9,293.5,162.5,1528.7,1529.0 -2.729061209879026,0.37092874891663974,2.4870941840919194,1087.0,277.3,336.4,151.9,1557.3,1616.1 -2.7290636234192918,0.37092442140380455,2.6179938779914944,515.5,290.8,293.9,162.2,1719.6,1846.9 -2.7290482736384,0.37094465419021283,2.748893571891069,345.2,345.2,233.5,204.6,2094.4,2314.4 -2.729054251275593,0.37094094494860785,2.8797932657906435,277.4,302.4,175.0,316.7,2960.7,2990.3 -2.7290417685193358,0.37094862715846166,3.010692959690218,255.0,232.8,173.9,620.1,2754.0,2695.6 -2.72906668655181,0.4712273467569421,0.0,362.9,193.0,193.0,1399.1,2628.4,2628.7 -2.729008681616777,0.4706578202642786,0.1308996938995747,402.1,173.8,233.1,1431.8,2201.7,1301.2 -2.729038811196153,0.4706677314850418,0.2617993877991494,316.4,174.9,302.4,1590.8,1029.2,693.3 -2.729076776083534,0.47069227198453767,0.39269908169872414,204.1,204.7,425.4,1955.6,705.7,486.4 -2.7291076020996607,0.47072794211652,0.5235987755982988,162.6,294.6,629.8,2777.9,534.1,406.5 -2.728788433029909,0.47102459746461767,0.6544984694978736,152.0,536.8,1443.2,2716.4,439.8,380.9 -2.7287844258261966,0.4710099072744074,0.7853981633974483,163.2,1428.8,1428.6,2598.5,393.6,393.0 -2.72878574935086,0.4710123780671003,0.916297857297023,195.0,1453.3,1512.0,2074.1,381.0,439.9 -2.728796877471563,0.4709804961192181,1.0471975511965976,255.0,1603.4,1730.9,991.6,405.9,392.4 -2.7288210104019393,0.4709416632948549,1.1780972450961724,333.1,1949.5,2168.4,648.7,426.0,205.3 -2.7288137914798503,0.4709489417675272,1.3089969389957472,549.6,2760.1,2990.0,486.2,443.9,175.4 -2.728823403375779,0.47094479984114535,1.4398966328953218,1315.0,2752.7,2693.8,401.2,232.0,173.7 -2.7288916684146596,0.47092968268948043,1.5707963267948966,1399.1,2628.9,2628.8,363.0,193.3,193.2 -2.728880436385399,0.4709292364640809,1.7016960206944713,1473.5,2230.4,1403.6,358.8,174.4,232.9 -2.728872588120839,0.47092608475526454,1.832595714594046,1684.7,1071.1,692.3,393.8,174.6,302.4 -2.728924644108845,0.4709593201956934,1.9634954084936205,2118.6,705.1,486.1,362.5,204.6,425.7 -2.728939519324571,0.47097666857564535,2.0943951023931953,2975.3,532.9,405.8,254.9,295.7,676.2 -2.7289289683815667,0.470954224650741,2.2252947962927703,2672.9,439.7,381.0,194.5,624.4,1449.2 -2.728934320317277,0.4709740215359379,2.356194490192345,2599.3,393.0,393.7,162.5,1428.4,1429.1 -2.728931909794174,0.4710019157792624,2.4870941840919194,1469.9,381.0,440.0,152.0,1454.0,1513.1 -2.7289370637772126,0.4709907349457587,2.6179938779914944,714.4,406.6,393.3,162.3,1604.1,1732.1 -2.7289252601967884,0.4710056028067855,2.748893571891069,486.4,424.5,204.6,204.8,1954.2,2174.3 -2.728935804829318,0.47099781971515586,2.8797932657906435,393.0,443.3,175.1,317.2,2763.9,2989.3 -2.7289281995825383,0.4710027811269122,3.010692959690218,358.5,232.8,174.1,707.4,2753.2,2694.7 -2.728958943253834,0.5712857972956809,0.0,463.0,193.0,193.2,1299.0,2628.4,2628.2 -2.7289543416156485,0.5706804092628499,0.1308996938995747,505.7,173.9,233.1,1328.4,2587.8,1771.3 -2.728992805924213,0.5706927793330117,0.2617993877991494,356.0,174.9,276.9,1475.2,1273.4,893.3 -2.7290303852281323,0.5707168794148096,0.39269908169872414,204.1,204.7,425.3,1813.6,847.1,627.7 -2.729059077938721,0.5707499655829316,0.5235987755982988,162.6,294.6,673.4,2577.7,649.8,522.1 -2.7290867392457763,0.5707988343780448,0.6544984694978736,152.0,619.9,1353.4,2717.2,543.6,484.5 -2.7290920800130585,0.5708274411823506,0.7853981633974483,163.2,1328.9,1328.4,2598.6,493.6,493.0 -2.7290914036968457,0.5708883489533012,0.916297857297023,194.9,1349.7,1408.6,2468.4,484.3,543.0 -2.729084901572449,0.5709142386438986,1.0471975511965976,254.8,1487.4,1614.5,1192.4,521.2,402.9 -2.7290783186380208,0.5709241033510692,1.1780972450961724,363.6,1806.6,2025.8,790.9,426.6,205.5 -2.729032350910494,0.570968082442147,1.3089969389957472,592.3,2556.2,2936.2,602.1,303.1,175.5 -2.7289982644964956,0.5709882009967602,1.4398966328953218,1310.7,2753.4,2694.5,504.6,232.1,173.7 -2.7290209597905344,0.5709837776951454,1.5707963267948966,1299.3,2629.2,2628.3,462.9,193.4,193.1 -2.7289670411480205,0.5709825452500499,1.7016960206944713,1369.9,2626.7,1797.1,462.2,174.3,232.7 -2.7289209285233333,0.5709690479147864,1.832595714594046,1568.3,1271.7,892.3,509.1,174.5,276.6 -2.7289409129081528,0.57098308349917,1.9634954084936205,1975.1,846.6,627.5,457.1,204.2,425.1 -2.728931896726292,0.5709755274999229,2.0943951023931953,2860.8,648.6,521.2,255.0,295.0,675.1 -2.728905686200693,0.5709256983283597,2.2252947962927703,2674.1,543.3,484.4,194.5,622.1,1359.3 -2.7289036613836286,0.5709168593821352,2.356194490192345,2599.4,493.0,493.5,162.4,1328.6,1328.9 -2.7289019987735617,0.570916961670372,2.4870941840919194,1860.1,484.3,543.4,151.9,1350.0,1409.1 -2.728914100552314,0.5708815119024431,2.6179938779914944,914.5,522.0,404.0,162.1,1488.0,1615.4 -2.728915174029459,0.5708760692344879,2.748893571891069,628.2,424.7,204.6,204.5,1811.1,2030.9 -2.7289416739342074,0.5708534968543009,2.8797932657906435,508.7,302.5,175.0,272.6,2560.9,2940.9 -2.728952047050669,0.5708492203843678,3.010692959690218,462.1,232.8,173.9,704.8,2754.4,2695.1 -2.7290044294483984,0.671148721881554,0.0,562.8,193.1,193.0,1199.1,2629.1,2628.9 -2.728976072182122,0.6711483893520038,0.1308996938995747,609.0,173.9,233.1,1225.1,2696.4,2154.9 -2.728920655452634,0.6711323299109155,0.2617993877991494,471.4,174.9,302.3,1359.8,1472.5,1092.3 -2.728866630128217,0.6710993244374968,0.39269908169872414,204.0,204.6,394.0,1672.3,987.9,768.7 -2.7288232910573873,0.6710553701738822,0.5235987755982988,162.6,294.4,673.3,2378.4,765.3,637.7 -2.7288043277795464,0.671017508692471,0.6544984694978736,151.9,619.4,1246.8,2717.9,647.0,587.9 -2.7287884833904963,0.6708867199051785,0.7853981633974483,163.1,1228.9,1228.3,2598.9,593.5,592.9 -2.7287904120180513,0.6709150459669941,0.916297857297023,194.8,1246.1,1305.0,2673.0,587.8,624.3 -2.7288038319859758,0.670874737813139,1.0471975511965976,254.6,1371.8,1499.1,1348.3,636.8,294.8 -2.7288352532482,0.6708234686371317,1.1780972450961724,363.6,1665.7,1884.7,932.8,437.5,205.4 -2.728839030325713,0.6708205748458227,1.3089969389957472,592.2,2357.6,2736.9,717.7,303.1,175.4 -2.7288616655860762,0.6708101822775314,1.4398966328953218,1224.7,2753.5,2694.8,608.2,232.1,173.6 -2.7289434651687268,0.6707920428831164,1.5707963267948966,1199.0,2628.7,2629.1,563.0,193.3,193.0 -2.728944854976429,0.6707924974940913,1.7016960206944713,1266.1,2693.7,2187.6,565.6,174.3,232.7 -2.7289478970737546,0.6707937570449225,1.832595714594046,1452.7,1471.1,1091.8,591.3,174.5,302.1 -2.72900881435936,0.6708333203510022,1.9634954084936205,1833.3,987.9,768.7,362.8,204.2,425.1 -2.7290300720516534,0.6708581587641738,2.0943951023931953,2661.3,764.2,636.9,255.0,295.0,675.1 -2.7290230685350076,0.6708441406051706,2.2252947962927703,2673.5,646.9,588.0,194.6,622.3,1246.6 -2.7290296495043784,0.6708722961911968,2.356194490192345,2599.9,593.0,593.5,162.5,1228.3,1228.9 -2.72902674819359,0.6709076695542662,2.4870941840919194,2245.5,587.9,620.8,151.9,1246.6,1305.4 -2.7290294239934867,0.6709031878747316,2.6179938779914944,1113.6,637.6,294.0,162.2,1372.4,1500.0 -2.729014489380829,0.6709233341549479,2.748893571891069,769.7,437.7,204.7,204.5,1669.9,1889.7 -2.7290207489574447,0.6709196941119462,2.8797932657906435,624.1,302.5,175.0,316.5,2361.6,2740.8 -2.729008493297584,0.6709275182310814,3.010692959690218,565.5,232.9,174.0,704.8,2754.1,2696.0 -2.729033494928019,0.7712062946467577,0.0,662.8,193.1,193.0,1099.2,2628.9,2628.8 -2.7289820464412866,0.7706520483857822,0.1308996938995747,699.5,173.9,233.1,1121.3,2802.5,2540.0 -2.7290142185667214,0.7706625575055521,0.2617993877991494,316.6,174.9,302.3,1244.1,1671.9,1292.3 -2.7290531675587593,0.7706876245270009,0.39269908169872414,204.1,204.7,425.3,1530.3,1129.5,910.1 -2.729084546575737,0.7707237445910897,0.5235987755982988,162.7,294.6,673.5,2179.6,881.0,753.2 -2.7287820347539538,0.7710228151248333,0.6544984694978736,152.0,621.7,1142.7,2716.5,750.4,691.5 -2.728778411376997,0.7710097540684415,0.7853981633974483,163.2,1129.0,1128.4,2599.0,693.4,693.0 -2.7287797524535025,0.771012090371685,0.916297857297023,195.0,1142.6,1201.7,2762.4,691.6,622.6 -2.728791091638207,0.7709795662383718,1.0471975511965976,255.0,1256.8,1384.2,1590.1,674.4,294.6 -2.7288156606131135,0.7709400598620659,1.1780972450961724,364.1,1525.3,1744.8,1073.8,426.0,205.3 -2.7288090247230037,0.7709468083990165,1.3089969389957472,593.3,2161.6,2540.4,832.9,302.9,175.4 -2.7288193021609,0.7709423227301537,1.4398966328953218,1120.3,2752.5,2694.0,711.4,232.0,173.7 -2.7288882576888533,0.7709270514124877,1.5707963267948966,1099.0,2628.8,2628.6,663.1,193.3,193.2 -2.728877670354623,0.7709266277923961,1.7016960206944713,1163.1,2836.9,2570.4,669.2,174.4,232.9 -2.7288703946511865,0.7709236486437971,1.832595714594046,1337.7,1668.5,1289.8,590.5,174.6,302.4 -2.7289229300914903,0.7709571766939673,1.9634954084936205,1692.8,1128.2,909.4,362.6,204.5,425.7 -2.728938165158757,0.7709748954155276,2.0943951023931953,2464.7,879.5,752.1,254.9,295.6,676.2 -2.7289278484515136,0.7709528645175971,2.2252947962927703,2673.2,750.1,691.6,194.6,624.4,1142.7 -2.728933314486795,0.7709730915583166,2.356194490192345,2599.3,693.1,693.6,162.5,1128.4,1129.0 -2.7289309056343005,0.7710013998859524,2.4870941840919194,2623.8,691.7,619.2,152.0,1143.0,1202.3 -2.7289359624200027,0.7709905893070657,2.6179938779914944,1311.2,672.4,293.6,162.3,1257.4,1385.1 -2.7289239827836003,0.7710057676439164,2.748893571891069,910.4,424.4,204.6,204.9,1529.6,1749.5 -2.728934294480926,0.7709982194986829,2.8797932657906435,739.6,302.4,175.1,273.3,2164.7,2544.8 -2.728926422743345,0.7710033345883287,3.010692959690218,669.2,232.8,174.0,707.3,2753.8,2694.9 -2.7289568344709645,0.8712860974651049,0.0,763.1,193.1,193.2,999.2,2628.6,2629.0 -2.7289527400147318,0.8706800552085794,0.1308996938995747,699.7,173.9,233.1,1017.8,2697.5,2756.1 -2.7289913489390707,0.8706924676440881,0.2617993877991494,316.6,174.9,302.3,1128.5,1871.7,1491.8 -2.7290289934364496,0.8707166032538327,0.39269908169872414,204.1,204.7,425.3,1388.7,1271.0,1051.4 -2.729057720842733,0.8707497182096999,0.5235987755982988,162.7,250.7,673.5,1979.9,996.9,869.1 -2.729085409281125,0.8707986170542383,0.6544984694978736,152.0,619.7,1039.5,2717.1,854.4,795.0 -2.729090763956975,0.8708272517590345,0.7853981633974483,163.2,1028.9,1028.5,2598.5,793.5,793.0 -2.729090098273399,0.87088819194303,0.916297857297023,194.8,1039.1,1097.8,2672.8,795.0,633.6 -2.7290835977533447,0.8709141144505881,1.0471975511965976,254.7,1140.6,1268.2,1791.7,726.7,295.0 -2.729077005444745,0.8709240044532351,1.1780972450961724,363.7,1383.6,1602.1,1216.0,426.4,205.5 -2.7290310238773334,0.8709680077686037,1.3089969389957472,592.2,1959.4,2338.4,948.8,303.2,175.5 -2.7289969182665907,0.8709881487472282,1.4398966328953218,1017.3,2753.6,2694.5,815.0,232.1,173.6 -2.729019589243949,0.8709837304060324,1.5707963267948966,999.0,2629.2,2628.2,762.8,193.4,193.1 -2.7289656474107398,0.8709824977052478,1.7016960206944713,1059.4,2693.9,2752.1,772.4,174.3,232.7 -2.728919512848083,0.8709689982291118,1.832595714594046,1221.6,1869.8,1446.5,610.2,174.5,302.1 -2.728939481299458,0.870983019286075,1.9634954084936205,1550.0,1270.4,1051.0,362.8,204.2,425.1 -2.7289304576595512,0.8709754425202358,2.0943951023931953,2261.8,995.2,867.9,255.0,295.0,675.0 -2.728904243565503,0.8709255972615173,2.2252947962927703,2673.9,853.8,795.0,194.5,622.0,1039.3 -2.7289022216896974,0.8709167430523785,2.356194490192345,2599.8,792.8,793.4,162.5,1028.4,1029.1 -2.728900570655781,0.8709168301225099,2.4870941840919194,2717.2,794.9,633.9,151.9,1039.6,1098.6 -2.7289126812468187,0.8708813732945639,2.6179938779914944,1512.5,727.6,294.0,162.1,1141.2,1268.7 -2.728913770882191,0.870875924652404,2.748893571891069,1052.5,424.8,204.6,204.5,1387.1,1606.8 -2.728940280305211,0.8708533520217361,2.8797932657906435,855.1,302.5,175.0,316.5,1962.5,2341.8 -2.728950661705163,0.8708490771573991,3.010692959690218,772.7,232.8,174.0,704.8,2754.4,2695.2 -2.6289364777437774,0.17075788602082476,0.0,63.0,293.1,293.0,1699.0,2528.7,2528.8 -2.628982468357271,0.17146048642418354,0.1308996938995747,91.5,277.4,336.7,1742.6,1049.1,233.6 -2.6289376992334788,0.17144581211233323,0.2617993877991494,139.5,290.5,418.0,1937.6,474.8,95.3 -2.6288856717569873,0.1714121449817687,0.39269908169872414,223.8,346.3,567.1,2380.3,282.3,63.0 -2.62884241608385,0.17136636282705542,0.5235987755982988,278.1,493.7,873.0,2955.6,187.5,59.8 -2.628823203987605,0.17132632334957032,0.6544984694978736,381.7,1005.7,1786.9,2614.5,129.5,70.5 -2.628807341212647,0.1712625527362739,0.7853981633974483,263.1,1729.0,1728.2,2499.1,93.8,93.2 -2.628809088972813,0.17123591441624386,0.916297857297023,298.3,1763.5,1822.3,832.5,70.7,129.5 -2.62882561313107,0.1711832545288965,1.0471975511965976,370.2,1949.2,2076.4,393.9,59.5,186.8 -2.6288582610781988,0.17112816589580393,1.1780972450961724,504.9,2371.4,2590.4,224.3,63.3,282.5 -2.6288619277297838,0.17112335564241588,1.3089969389957472,791.7,3002.5,2875.1,139.9,95.6,291.0 -2.628884131255777,0.17111106735233617,1.4398966328953218,1701.6,2649.6,2591.1,91.1,238.5,277.1 -2.628965870279027,0.17109114106605183,1.5707963267948966,1699.0,2528.9,2529.1,63.3,293.2,293.0 -2.6289677535465596,0.17108973226259683,1.7016960206944713,1783.5,1066.7,238.4,48.6,277.8,336.1 -2.628934890433151,0.17107518522450937,1.832595714594046,2030.6,474.8,95.6,47.1,290.1,417.8 -2.629175009532567,0.17122763190919144,1.9634954084936205,2541.5,282.4,63.3,63.6,346.0,567.0 -2.6291165299901604,0.17116467606808938,2.0943951023931953,2860.8,186.8,59.5,117.4,494.9,875.4 -2.629097643780216,0.17112618661009904,2.2252947962927703,2569.8,129.5,70.7,275.3,925.1,1786.2 -2.6291049733978644,0.1711556505647016,2.356194490192345,2499.8,93.3,93.8,262.5,1728.1,1729.0 -2.629101489204859,0.17120108620101981,2.4870941840919194,316.8,70.5,129.6,255.5,1763.9,1823.1 -2.629100156560805,0.17120777764813488,2.6179938779914944,117.6,59.9,187.6,277.8,1950.5,2078.1 -2.629077822578443,0.17123755783401706,2.748893571891069,62.7,62.7,282.8,346.1,2376.7,2597.0 -2.629074948423755,0.17124049985815382,2.8797932657906435,46.6,95.0,290.6,516.3,3001.6,2874.7 -2.6290527838632163,0.1712516791112717,3.010692959690218,48.2,235.2,277.5,1092.8,2650.8,2591.8 -2.6290667797288902,0.27152191391435454,0.0,163.1,293.1,293.1,1599.0,2528.4,2529.1 -2.6290086985977634,0.27072445172192294,0.1308996938995747,195.0,277.4,336.6,1639.1,1433.6,617.3 -2.6290313199302293,0.2707318814016375,0.2617993877991494,255.0,290.5,417.9,1821.7,674.1,294.5 -2.6290618676743827,0.27075160752651195,0.39269908169872414,345.2,346.4,567.0,2238.7,423.3,204.0 -2.6290868708217294,0.27078085226529613,0.5235987755982988,349.0,493.9,872.6,2956.0,302.9,175.3 -2.62911236399336,0.2708260683231811,0.6544984694978736,255.5,1005.6,1660.7,2613.7,232.8,173.7 -2.6291167087371123,0.2708511543706662,0.7853981633974483,263.2,1628.9,1628.4,2498.6,193.5,193.0 -2.6291158570800963,0.27090867558503784,0.916297857297023,298.4,1660.2,1719.2,1304.4,173.9,232.7 -2.629109990414016,0.27093145762121384,1.0471975511965976,370.2,1834.1,1961.1,593.1,174.7,302.0 -2.629104759090542,0.2709387605352995,1.1780972450961724,504.8,2230.9,2449.4,365.7,204.0,347.1 -2.629029660938231,0.27101480213353835,1.3089969389957472,747.9,3002.7,2875.3,255.1,294.1,430.2 -2.6290247573292103,0.271018936739553,1.4398966328953218,1660.5,2649.5,2591.4,194.2,335.4,277.1 -2.6290557789029227,0.2710125215563519,1.5707963267948966,1599.1,2528.9,2528.7,162.9,293.3,293.1 -2.6290025793531933,0.2710112146853507,1.7016960206944713,1680.2,1455.9,626.9,151.7,277.7,336.2 -2.628954920639765,0.2709970890888629,1.832595714594046,1915.2,673.4,294.2,162.3,290.0,417.7 -2.6289729425532284,0.271009919279279,1.9634954084936205,2400.6,423.2,204.0,204.9,346.0,566.8 -2.62896223415824,0.27100074889095627,2.0943951023931953,2861.8,302.0,174.6,316.3,494.7,874.8 -2.6289348783084883,0.2709489671068934,2.2252947962927703,2569.8,232.7,173.9,298.0,1009.5,1660.5 -2.6289322186548234,0.27093806921295815,2.356194490192345,2499.8,193.0,193.5,262.4,1628.6,1628.9 -2.628930357463246,0.270936201119214,2.4870941840919194,701.6,173.7,232.8,255.4,1660.7,1720.0 -2.6289428152701095,0.27089887391398193,2.6179938779914944,316.4,175.2,302.9,277.7,1835.0,1962.6 -2.6289445300044965,0.2708918395683151,2.748893571891069,203.8,203.8,346.0,345.9,2235.4,2455.9 -2.628972083795344,0.2708679611491398,2.8797932657906435,161.9,293.9,430.3,516.1,3002.3,2874.9 -2.628983722988316,0.2708627602986502,3.010692959690218,151.5,336.2,277.4,1092.4,2650.7,2592.0 -2.6290378139678476,0.3711635794799697,0.0,262.8,293.0,293.0,1499.2,2529.3,2529.1 -2.629010596859251,0.37116313827181346,0.1308996938995747,298.4,277.4,336.7,1535.8,1817.1,1000.9 -2.6289560950219366,0.37114728591501756,0.2617993877991494,370.3,290.4,417.9,1706.7,873.3,493.6 -2.628902758926157,0.3711147065926361,0.39269908169872414,345.2,346.2,566.9,2097.4,564.2,345.0 -2.6288599157782366,0.37107135218743315,0.5235987755982988,278.1,493.6,872.6,2955.8,418.5,290.7 -2.628841115745949,0.371034108067992,0.6544984694978736,255.4,1005.3,1557.2,2614.0,336.4,277.2 -2.6288252873113693,0.37097296808629054,0.7853981633974483,263.1,1529.2,1528.7,2498.7,293.5,293.0 -2.6288269130607986,0.3709487421093438,0.916297857297023,298.2,1556.7,1615.5,1691.9,277.4,336.2 -2.628843194833964,0.37089834294608703,1.0471975511965976,370.2,1718.5,1846.1,792.9,290.2,417.6 -2.6288754460446433,0.37084541943360705,1.1780972450961724,473.7,2089.1,2308.6,507.5,345.2,392.1 -2.6288785329681534,0.37084285601104483,1.3089969389957472,791.7,2956.3,2874.9,370.8,418.6,290.9 -2.6288997658793476,0.3708328962661349,1.4398966328953218,1534.3,2649.4,2591.2,297.7,461.6,277.0 -2.6289799655004575,0.370815041691543,1.5707963267948966,1499.0,2528.8,2528.8,263.0,293.3,293.0 -2.6289798203874497,0.37081535822413514,1.7016960206944713,1576.8,1845.5,1017.0,255.3,277.7,336.2 -2.6289815232916043,0.37081607189900034,1.832595714594046,1799.8,872.8,493.7,278.0,290.1,417.7 -2.629041292014103,0.37085495146226033,1.9634954084936205,2258.7,564.3,345.2,346.7,346.1,566.8 -2.629061621350955,0.3708790003867357,2.0943951023931953,2861.0,417.6,290.2,370.5,494.7,874.8 -2.6290539891481632,0.37086401100806965,2.2252947962927703,2570.2,336.2,277.5,298.1,1009.8,1556.7 -2.629060171610094,0.370891142602656,2.356194490192345,2499.8,293.0,293.5,262.4,1528.8,1528.9 -2.6290570406833904,0.3709255356699863,2.4870941840919194,1087.1,277.3,336.3,255.4,1557.1,1616.5 -2.6290598061597144,0.37092005359791,2.6179938779914944,515.5,290.8,418.5,277.7,1719.2,1846.8 -2.629045069025472,0.370939331911186,2.748893571891069,345.2,345.1,392.6,345.9,2094.1,2313.6 -2.629051811638727,0.3709349262185142,2.8797932657906435,277.4,418.1,290.6,516.2,2960.6,2874.4 -2.6290401824601006,0.3709421736067826,3.010692959690218,255.0,462.6,277.4,1092.3,2650.7,2592.4 -2.629066122208695,0.4712216690449422,0.0,362.9,293.0,293.0,1399.3,2528.9,2528.9 -2.6290082803508312,0.4706575289565835,0.1308996938995747,402.1,277.3,336.7,1432.0,2201.8,1385.8 -2.6290385060397328,0.4706674705387528,0.2617993877991494,486.0,290.5,418.0,1590.6,1073.1,693.4 -2.629076515986033,0.4706920387538325,0.39269908169872414,347.4,346.3,566.9,1955.5,705.8,486.4 -2.629107366750211,0.47074029373713144,0.5235987755982988,278.3,493.8,872.9,2777.5,534.2,406.5 -2.6288125869137056,0.4710397956772481,0.6544984694978736,255.6,1007.8,1453.5,2613.1,439.8,380.9 -2.628804854314647,0.4710092488287634,0.7853981633974483,263.2,1428.9,1428.4,2498.7,393.5,393.1 -2.6288062598223694,0.4710096759598028,0.916297857297023,298.5,1453.4,1512.2,2074.9,381.0,439.9 -2.6288166804237503,0.4709800974120617,1.0471975511965976,370.6,1603.8,1731.2,947.5,405.9,494.1 -2.6288388924112467,0.4709443120096124,1.1780972450961724,505.3,1949.2,2168.4,648.8,486.7,374.8 -2.6288289517839014,0.4709541446304748,1.3089969389957472,792.8,2758.6,2874.2,486.2,450.4,291.0 -2.628835381912957,0.47095172487069714,1.4398966328953218,1430.7,2648.7,2636.2,401.1,335.5,277.1 -2.628900300136684,0.4709373845953604,1.5707963267948966,1398.9,2528.7,2528.7,363.1,293.4,293.2 -2.6288859250308527,0.4709368573020358,1.7016960206944713,1473.5,2230.4,1318.6,358.8,277.9,336.4 -2.6288752700293725,0.4709328977752809,1.832595714594046,1684.6,1027.1,692.4,393.7,290.3,418.0 -2.6289249785444246,0.4709647004762252,1.9634954084936205,2118.3,705.0,486.2,488.9,346.3,567.5 -2.6289381071362796,0.47098021429360926,2.0943951023931953,2860.2,532.8,405.8,472.9,495.4,876.2 -2.628926428354969,0.4709557418841912,2.2252947962927703,2569.2,439.7,380.9,298.0,1012.3,1453.1 -2.6289312572436923,0.47097342947951115,2.356194490192345,2499.2,393.0,393.7,262.5,1428.4,1428.8 -2.628928898842173,0.4709992951831927,2.4870941840919194,1469.9,380.9,440.0,255.6,1453.8,1513.1 -2.6289345722538138,0.47098633191890205,2.6179938779914944,714.2,406.7,492.8,277.9,1604.1,1731.7 -2.628923689945889,0.47099971732300383,2.748893571891069,486.5,487.0,375.4,346.3,1953.7,2174.3 -2.628935398085097,0.47099084192501794,2.8797932657906435,392.9,450.2,290.6,516.9,2763.7,2873.5 -2.6289291014555642,0.4709951113614699,3.010692959690218,358.5,336.3,277.5,1095.2,2650.4,2591.5 -2.6289614295068495,0.571279332172919,0.0,463.0,293.1,293.1,1298.9,2528.7,2529.1 -2.628956023602689,0.5706806222296554,0.1308996938995747,505.7,277.5,336.7,1328.5,2587.5,1771.1 -2.628994338533808,0.5706929493823372,0.2617993877991494,516.0,290.5,417.9,1475.4,1273.0,893.1 -2.6290318644172097,0.5707170217274886,0.39269908169872414,345.3,346.3,566.9,1813.3,847.1,627.8 -2.629060535178014,0.570750093350731,0.5235987755982988,278.3,493.7,872.7,2577.6,649.9,522.2 -2.629088178130573,0.5707989493370567,0.6544984694978736,255.5,1005.2,1350.3,2613.2,543.5,484.4 -2.6290935089593055,0.570827546643021,0.7853981633974483,263.2,1329.1,1328.5,2498.8,493.5,493.0 -2.6290928211616125,0.570888439414404,0.916297857297023,298.4,1349.6,1408.4,2467.8,484.4,543.1 -2.629086312472339,0.5709143118411608,1.0471975511965976,344.9,1487.6,1614.8,1192.4,521.2,494.8 -2.6290797308739546,0.5709241641407317,1.1780972450961724,504.8,1806.6,2025.5,790.9,568.3,347.2 -2.629033766941269,0.5709681285457222,1.3089969389957472,791.6,2557.5,2875.5,602.0,418.7,291.1 -2.628999688415135,0.570988230822046,1.4398966328953218,1327.5,2649.6,2591.7,504.7,335.6,277.1 -2.629022396275112,0.5709838056244232,1.5707963267948966,1299.2,2529.0,2528.6,462.9,293.4,293.0 -2.6289684897631385,0.5709825735399237,1.7016960206944713,1369.9,2540.8,1797.1,462.0,277.8,336.2 -2.6289223891148623,0.5709690757450259,1.832595714594046,1568.3,1271.6,892.3,509.0,290.1,417.7 -2.6289423809035704,0.5709831211149037,1.9634954084936205,1975.1,846.7,627.5,504.0,345.9,566.7 -2.628933365585663,0.570975579731253,2.0943951023931953,2861.0,648.6,521.3,370.6,494.7,874.6 -2.6289071542338185,0.5709257595548691,2.2252947962927703,2569.9,543.1,484.4,298.1,1009.0,1350.0 -2.628905124278379,0.570916928292559,2.356194490192345,2499.4,493.0,493.5,262.4,1328.2,1329.1 -2.628903449945296,0.5709170384336457,2.4870941840919194,1859.4,484.3,543.3,255.4,1350.2,1409.5 -2.6289155446514254,0.5708815890917578,2.6179938779914944,914.2,522.0,493.3,277.8,1488.0,1615.4 -2.6289166052164457,0.5708761469155443,2.748893571891069,628.1,566.2,346.1,345.9,1811.1,2031.4 -2.6289430999333767,0.570853570720876,2.8797932657906435,508.6,418.1,290.6,515.9,2561.1,2874.3 -2.6289534697000487,0.5708492901729525,3.010692959690218,462.0,336.4,277.5,1091.7,2651.1,2592.2 -2.629005852924435,0.6711487930173952,0.0,562.9,293.0,293.0,1199.1,2528.8,2528.6 -2.6289774933253507,0.6711484595582433,0.1308996938995747,609.1,277.4,313.9,1225.1,2593.1,2154.5 -2.628922076441097,0.6711324013596003,0.2617993877991494,575.9,290.5,417.9,1359.7,1472.2,1092.4 -2.6288680493349177,0.6710993987119056,0.39269908169872414,345.3,346.3,566.8,1672.1,988.1,768.8 -2.6288247084158223,0.6710554490512073,0.5235987755982988,278.2,493.6,872.5,2378.6,765.4,637.7 -2.6288057362952797,0.6710175888338346,0.6544984694978736,255.4,1004.6,1247.0,2613.8,647.0,587.9 -2.6287898863068873,0.6709557817001559,0.7853981633974483,263.1,1229.3,1228.6,2498.9,593.6,592.9 -2.6287917607678626,0.6709310410559757,0.916297857297023,298.3,1246.2,1304.8,2569.1,587.9,646.6 -2.628808414821088,0.6708802702933974,1.0471975511965976,370.1,1372.0,1499.2,1392.1,636.7,518.4 -2.628841057248888,0.6708270506642313,1.1780972450961724,504.6,1665.6,1884.7,932.8,568.1,347.1 -2.6288445714803084,0.670824403460655,1.3089969389957472,791.4,2357.9,2736.7,717.8,418.7,290.9 -2.62886618810908,0.6708145510322363,1.4398966328953218,1224.0,2649.9,2592.1,608.1,335.6,277.1 -2.6289466729618685,0.6707967195310294,1.5707963267948966,1198.8,2528.3,2528.7,562.9,293.3,293.1 -2.628946751345459,0.670797135486271,1.7016960206944713,1266.2,2590.3,2187.7,565.6,277.8,336.2 -2.6289486030651523,0.6707980350348235,1.832595714594046,1452.9,1471.0,1091.8,624.7,290.1,417.7 -2.629008518884294,0.6708369798706926,1.9634954084936205,1832.7,987.9,768.8,598.8,346.0,566.8 -2.629029029353579,0.6708610329556737,2.0943951023931953,2660.7,764.1,636.9,370.6,450.8,874.7 -2.629021549800878,0.6708461386788072,2.2252947962927703,2570.6,646.8,588.0,298.1,1009.1,1246.2 -2.629027912637349,0.6708733871315375,2.356194490192345,2499.6,592.9,593.6,262.5,1228.6,1229.0 -2.6290250304647085,0.6709078958728176,2.4870941840919194,2245.6,587.9,646.9,255.5,1246.6,1305.6 -2.6290279324418493,0.6709026488094443,2.6179938779914944,1069.8,637.5,519.6,277.8,1372.2,1499.9 -2.6290133813421313,0.6709221628071329,2.748893571891069,769.6,566.2,346.1,346.0,1669.9,1889.5 -2.629020136514409,0.6709180510671751,2.8797932657906435,624.2,418.2,290.6,515.8,2361.6,2741.1 -2.6290084372434603,0.6709255722653928,3.010692959690218,565.6,336.4,277.5,1091.6,2651.0,2591.9 -2.6290341170789944,0.7712048620058023,0.0,662.8,293.1,293.0,1099.2,2529.0,2529.3 -2.628982913700008,0.7706524899586247,0.1308996938995747,712.9,277.4,336.6,1121.3,2592.7,2539.4 -2.629015106062339,0.7706630065252549,0.2617993877991494,587.0,290.5,417.9,1244.1,1672.2,1292.2 -2.628883577704402,0.7711108777482509,0.39269908169872414,345.1,346.5,567.4,1530.9,1098.0,909.8 -2.6288733661272663,0.7711008560347299,0.5235987755982988,278.2,494.2,873.5,2181.4,881.0,753.3 -2.628872588385744,0.7710956943131002,0.6544984694978736,255.5,1007.2,1142.9,2613.6,750.6,691.6 -2.6288648994408943,0.7710662507028039,0.7853981633974483,263.2,1129.0,1128.4,2498.6,693.8,693.2 -2.6288659818800353,0.7710714552169691,0.916297857297023,298.5,1142.7,1201.3,2680.1,691.6,750.5 -2.6288744602764633,0.7710472584808112,1.0471975511965976,370.4,1256.4,1383.8,1590.7,752.5,634.5 -2.6288933023913965,0.7710159626073985,1.1780972450961724,505.1,1525.3,1744.5,1043.0,579.1,347.0 -2.6288792456142986,0.7710290631405972,1.3089969389957472,792.4,2160.1,2539.7,833.2,418.4,291.0 -2.6288811848821685,0.7710286486835716,1.4398966328953218,1120.4,2649.2,2590.9,711.6,335.4,277.2 -2.628941578179116,0.7710147898602413,1.5707963267948966,1098.9,2528.9,2528.6,663.1,293.3,293.1 -2.628923150581379,0.7710137093596756,1.7016960206944713,1162.9,2590.2,2572.8,669.3,277.8,336.3 -2.6289089972138457,0.7710084759532718,1.832595714594046,1337.5,1669.2,1290.1,740.6,290.2,417.9 -2.628955898941006,0.7710382333609149,1.9634954084936205,1692.4,1128.5,909.6,503.7,346.2,567.1 -2.6289670100826386,0.7710512900055071,2.0943951023931953,2463.2,879.7,752.5,370.4,495.1,875.5 -2.628953948503819,0.7710243421891687,2.2252947962927703,2569.4,750.3,691.5,298.0,1011.2,1142.4 -2.628958031957931,0.7710394938223337,2.356194490192345,2499.5,693.2,693.8,262.5,1128.2,1128.9 -2.628955595334258,0.7710628253960687,2.4870941840919194,2542.0,691.6,750.8,255.5,1142.9,1202.4 -2.628961572209182,0.771047607681876,2.6179938779914944,1311.9,753.5,635.6,277.9,1257.0,1384.7 -2.6289516090801746,0.7710589039503264,2.748893571891069,910.8,579.7,345.9,346.2,1529.1,1748.8 -2.6289644840346527,0.7710483313288612,2.8797932657906435,739.8,417.9,290.6,516.5,2163.6,2543.5 -2.628959678439059,0.7710513009557529,3.010692959690218,669.0,336.3,277.5,1094.1,2650.1,2591.5 -2.628994104735301,0.871337084119068,0.0,763.1,293.1,293.1,999.1,2528.9,2529.2 -2.628972817887502,0.8706988587740712,0.1308996938995747,816.4,277.4,336.7,1017.7,2593.0,2652.4 -2.6290059743349086,0.8707095734197712,0.2617993877991494,516.1,290.5,418.0,1128.5,1871.6,1491.6 -2.629040842293389,0.8707319824046946,0.39269908169872414,345.3,346.4,566.9,1389.2,1270.5,1051.2 -2.629067943498529,0.8707633983141647,0.5235987755982988,278.3,493.7,872.9,1980.6,996.7,869.1 -2.6290946270093873,0.8708105807993369,0.6544984694978736,255.6,1005.4,1039.6,2613.8,854.3,795.0 -2.629099517647752,0.8708375188694677,0.7853981633974483,263.3,1029.0,1028.5,2499.1,793.5,793.1 -2.6290987887599298,0.8708968207269439,0.916297857297023,298.4,1039.0,1098.0,2569.4,794.9,853.6 -2.62909261818722,0.8709212431656665,1.0471975511965976,370.2,1140.9,1268.2,1791.4,867.8,494.6 -2.6290866980064282,0.8709298994112404,1.1780972450961724,504.8,1383.8,1602.4,1216.2,568.1,347.2 -2.6290415932191324,0.8709729275536686,1.3089969389957472,791.6,1959.6,2338.4,948.8,418.7,291.0 -2.629008518878588,0.8709923640808073,1.4398966328953218,1017.2,2649.2,2591.4,815.0,335.6,277.1 -2.6290323124783184,0.8709876443183633,1.5707963267948966,999.1,2528.9,2528.4,763.0,293.4,293.0 -2.628979439317089,0.8709863989321238,1.7016960206944713,1059.4,2590.5,2648.6,772.4,277.8,336.2 -2.628916614575714,0.8709705586329268,1.832595714594046,1221.8,1869.8,1490.5,790.6,290.1,417.6 -2.628947326165623,0.8709913103331159,1.9634954084936205,1550.1,1270.0,1050.7,503.9,345.9,566.8 -2.6289403132637776,0.8709859795329915,2.0943951023931953,2262.6,995.2,867.9,370.6,494.6,874.7 -2.6289140479430015,0.8709361154385797,2.2252947962927703,2570.4,853.9,795.1,298.0,1009.1,1039.5 -2.6289117502672346,0.8709263396530327,2.356194490192345,2499.6,792.9,793.5,262.5,1028.8,1029.1 -2.628910030883976,0.8709252570720891,2.4870941840919194,2613.3,795.0,854.0,255.4,1039.4,1098.4 -2.628922414191412,0.8708886231751503,2.6179938779914944,1512.3,868.7,493.2,277.8,1141.3,1268.9 -2.628923990756339,0.8708821616112563,2.748893571891069,1052.5,566.2,346.1,345.9,1387.1,1606.9 -2.6289512255371226,0.8708587787775393,2.8797932657906435,855.4,418.0,290.6,515.8,1962.9,2342.6 -2.6289624556583124,0.8708539467874878,3.010692959690218,772.7,336.3,277.4,1083.3,2650.9,2592.3 -2.528949997546069,0.17076573757034885,0.0,63.0,393.0,393.0,1698.8,2429.0,2428.5 -2.5289896070912503,0.17146305770067305,0.1308996938995747,91.6,381.0,440.3,1742.9,1049.3,233.6 -2.5289432995521324,0.17144791198827858,0.2617993877991494,139.5,406.1,533.5,1937.0,474.9,95.3 -2.5288907341298703,0.17141392278966494,0.39269908169872414,223.8,488.0,708.7,2380.3,282.2,63.0 -2.528847250157483,0.17136793002377604,0.5235987755982988,393.4,693.1,1072.2,2840.5,187.5,59.8 -2.5288279310357633,0.17132773952881886,0.6544984694978736,442.3,1391.3,1764.2,2510.0,129.5,70.5 -2.528811995222536,0.17126382250703354,0.7853981633974483,363.1,1728.8,1728.3,2399.0,93.8,93.2 -2.5288137177710115,0.1712370541399546,0.916297857297023,401.8,1763.4,1822.5,917.9,70.7,129.5 -2.5288302474958395,0.17118426970682132,1.0471975511965976,485.7,1949.3,2076.4,393.8,59.5,186.8 -2.5288629249097125,0.1711290529152898,1.1780972450961724,645.9,2371.1,2590.5,224.3,63.4,282.5 -2.5288666551606274,0.17112414535249298,1.3089969389957472,991.1,2887.4,2759.7,139.9,95.6,406.6 -2.52888894562457,0.17111179982439162,1.4398966328953218,1741.1,2546.3,2487.4,91.1,238.5,506.7 -2.5289707813244084,0.1710918224375808,1.5707963267948966,1698.6,2429.1,2429.0,63.3,393.3,393.1 -2.5289727630549175,0.17109040657482444,1.7016960206944713,1783.5,1066.7,238.4,48.6,381.2,439.7 -2.5289770169302828,0.17109000683151865,1.832595714594046,2030.5,474.7,95.6,47.1,405.7,533.3 -2.529039495191414,0.1711287334925522,1.9634954084936205,2542.2,282.4,63.3,63.7,487.7,708.7 -2.529062270590021,0.1711535650428082,2.0943951023931953,2745.1,186.8,59.5,117.4,694.6,1074.6 -2.5290565092897,0.17114006893784217,2.2252947962927703,2466.6,129.5,70.7,319.5,1397.6,1763.6 -2.529063679559791,0.17116922981482174,2.356194490192345,2399.4,93.3,93.8,362.5,1728.2,1728.8 -2.5290604684918483,0.1712057921043395,2.4870941840919194,316.9,70.5,129.6,359.0,1764.0,1823.1 -2.529062253157685,0.1712020913473462,2.6179938779914944,117.6,59.9,187.6,393.4,1950.2,2078.0 -2.5290457439519285,0.17122250534420536,2.748893571891069,62.7,62.7,282.8,487.5,2377.2,2597.3 -2.529050444155986,0.17121831457608017,2.8797932657906435,46.6,95.0,406.2,715.6,2886.1,2758.5 -2.529036847394465,0.17122487941355957,3.010692959690218,48.2,235.2,507.2,1479.9,2547.5,2488.7 -2.52906126745084,0.27150301565443513,0.0,163.2,393.0,393.0,1598.8,2429.0,2428.3 -2.529008074802774,0.2707322730958923,0.1308996938995747,195.0,380.9,440.3,1639.3,1433.3,617.4 -2.5290309829497084,0.27073978212817407,0.2617993877991494,254.9,406.1,533.6,1822.0,674.1,294.5 -2.5290608483144563,0.27075906944477457,0.39269908169872414,365.2,488.0,708.6,2238.8,423.3,204.0 -2.529085110044038,0.27078750755076086,0.5235987755982988,393.9,693.0,1071.8,2840.6,302.9,175.3 -2.529110072377144,0.27083173464539567,0.6544984694978736,359.0,1391.4,1660.6,2510.1,232.9,173.8 -2.529114172037075,0.2708557690762212,0.7853981633974483,363.1,1629.2,1628.8,2398.6,193.6,193.0 -2.529113340150569,0.27091227838067167,0.916297857297023,401.9,1660.3,1719.1,1304.3,173.9,232.7 -2.529107734140564,0.2709341472058213,1.0471975511965976,485.8,1834.1,1961.6,592.9,174.7,302.0 -2.5291309950365406,0.270895495020274,1.1780972450961724,645.9,2230.4,2449.8,365.6,204.0,423.0 -2.528927272153483,0.2710842164723577,1.3089969389957472,991.0,2886.7,2760.0,255.1,294.1,406.6 -2.5289989622457694,0.27104813940776906,1.4398966328953218,1637.9,2591.7,2488.3,194.2,438.9,380.6 -2.529052281774251,0.27103667778011586,1.5707963267948966,1599.4,2428.8,2428.7,162.9,393.3,393.1 -2.5290022794181084,0.2710354899106715,1.7016960206944713,1680.4,1455.8,626.6,151.7,381.2,439.6 -2.528951844937111,0.2710205122230447,1.832595714594046,1915.2,673.4,294.2,162.3,405.7,533.3 -2.528965920724224,0.2710308653117266,1.9634954084936205,2400.7,423.1,204.0,204.9,487.6,708.5 -2.528951883238416,0.27101812385566504,2.0943951023931953,2745.2,302.0,174.6,316.3,650.4,1074.6 -2.5289223292980765,0.27096222095845124,2.2252947962927703,2466.6,232.7,173.9,401.5,1396.8,1660.5 -2.528918669285947,0.2709470088164896,2.356194490192345,2399.4,193.0,193.5,362.4,1628.5,1628.9 -2.5289169423856697,0.27094101333305587,2.4870941840919194,701.6,173.7,232.8,358.9,1661.0,1720.3 -2.5289304988330166,0.27090004682132585,2.6179938779914944,316.4,175.2,302.9,393.3,1835.1,1962.4 -2.528963502365458,0.2708433048048704,2.748893571891069,203.8,203.8,423.8,487.3,2235.8,2455.9 -2.5289657012387283,0.27084285070140557,2.8797932657906435,161.9,294.0,406.1,715.6,2886.2,2758.9 -2.528972525942428,0.27084014388210553,3.010692959690218,151.5,439.8,380.9,1479.4,2547.0,2487.8 -2.5290314387839428,0.37114859031130276,0.0,263.0,393.0,393.0,1499.3,2428.4,2429.0 -2.529063294176238,0.37115398819629486,0.1308996938995747,298.4,380.9,440.3,1535.8,1817.0,1000.8 -2.5289774705843664,0.37112832879999025,0.2617993877991494,370.3,406.0,533.4,1706.6,873.3,493.7 -2.528920245033538,0.3710932373184026,0.39269908169872414,486.4,487.9,708.6,2097.4,564.5,344.9 -2.528880169460783,0.3710528011901637,0.5235987755982988,534.7,692.9,1071.9,2840.2,418.5,290.7 -2.5288643684276892,0.3710211226310136,0.6544984694978736,359.0,1391.0,1557.4,2510.0,336.3,277.3 -2.5288500962639002,0.37096661359805916,0.7853981633974483,363.1,1529.1,1528.5,2398.8,293.5,292.9 -2.528851515691053,0.37094892523219625,0.916297857297023,401.8,1556.8,1615.4,1691.7,277.4,336.2 -2.5288659891234846,0.37090445479432343,1.0471975511965976,485.7,1718.3,1845.9,792.8,290.2,417.5 -2.528895176518611,0.37085643440369975,1.1780972450961724,645.9,2089.1,2308.4,507.4,345.2,488.7 -2.5288943932295265,0.37085748633246785,1.3089969389957472,990.9,2887.1,2759.7,370.8,493.5,406.5 -2.528911273918907,0.3708498317321145,1.4398966328953218,1534.3,2546.4,2487.6,297.7,541.2,380.5 -2.5289869690887063,0.37083300542515407,1.5707963267948966,1498.8,2428.9,2428.7,263.0,393.3,393.1 -2.529030445841739,0.37083876278941186,1.7016960206944713,1576.9,1845.7,1017.0,255.3,381.3,439.6 -2.528996327930246,0.37082850189663485,1.832595714594046,1800.0,872.7,493.7,278.0,405.8,533.3 -2.5290462496960595,0.3708611555333641,1.9634954084936205,2258.5,564.3,345.2,346.7,487.7,708.7 -2.5290642191314414,0.37088264824071393,2.0943951023931953,2745.6,417.5,290.3,486.0,694.4,1074.7 -2.529056187603222,0.3708668870138059,2.2252947962927703,2467.2,336.2,277.5,401.5,1396.8,1556.9 -2.529062363882069,0.3708939796939186,2.356194490192345,2399.5,293.0,293.5,362.4,1528.5,1529.0 -2.529059215085011,0.3709285882209139,2.4870941840919194,1087.3,277.3,336.4,358.9,1557.2,1616.0 -2.5290618943110292,0.37092336163518635,2.6179938779914944,515.6,290.8,418.4,393.4,1719.5,1846.9 -2.529046988731385,0.37094287161407635,2.748893571891069,345.2,345.2,487.4,487.4,2094.5,2314.5 -2.5290535275847144,0.37093863164048124,2.8797932657906435,277.4,493.4,406.2,715.6,2886.3,2758.9 -2.5290416727427982,0.3709459759406577,3.010692959690218,255.0,536.1,380.9,1479.3,2547.0,2488.6 -2.529067352191116,0.4712252714217675,0.0,362.9,393.1,393.0,1399.0,2429.1,2428.9 -2.5290093927472923,0.47065817211938854,0.1308996938995747,402.1,381.0,440.3,1432.3,2201.2,1385.8 -2.529039527941727,0.4706680860212964,0.2617993877991494,486.1,406.0,533.6,1590.9,1073.0,693.5 -2.5290774618140244,0.47069260946083236,0.39269908169872414,486.4,488.0,708.6,1955.6,705.8,486.4 -2.5291082557636413,0.4707282490766227,0.5235987755982988,393.9,693.1,1072.0,2777.5,534.2,406.4 -2.5287894490263216,0.4710249044698722,0.6544984694978736,359.1,1394.4,1453.6,2509.6,439.9,380.9 -2.5287854643181986,0.4710103267089518,0.7853981633974483,363.2,1428.8,1428.6,2398.8,393.5,393.1 -2.5287867808330557,0.4710129027698071,0.916297857297023,402.1,1453.5,1512.4,2074.2,381.0,439.9 -2.5287978760655223,0.47098111278894916,1.0471975511965976,486.1,1603.5,1730.6,991.3,406.0,533.4 -2.5288219560985423,0.47094235109171945,1.1780972450961724,646.4,1948.8,2168.4,648.8,486.7,533.8 -2.528814674521111,0.4709496808531868,1.3089969389957472,992.3,2759.8,2759.1,486.3,534.1,406.6 -2.528824218515778,0.4709455714574511,1.4398966328953218,1430.6,2545.8,2487.2,401.1,438.8,380.6 -2.52889241475596,0.47093046334712985,1.5707963267948966,1399.0,2428.7,2428.6,363.0,393.3,393.2 -2.528881120606225,0.470930011042336,1.7016960206944713,1473.4,2230.7,1403.5,358.8,381.3,439.9 -2.5288732177388167,0.4709268425962527,1.832595714594046,1684.6,1071.3,692.3,393.8,405.9,533.7 -2.5289252290064623,0.4709600484201173,1.9634954084936205,2118.0,705.1,486.1,488.9,488.2,709.3 -2.5289400712893633,0.4709773598855602,2.0943951023931953,2744.5,532.8,405.8,485.9,695.3,1076.2 -2.528929496944192,0.4709548782942563,2.2252947962927703,2465.9,439.7,381.0,401.6,1400.6,1452.9 -2.528934835858486,0.4709746356136375,2.356194490192345,2399.5,392.9,393.7,362.6,1428.3,1428.9 -2.528932423772065,0.47100248954952106,2.4870941840919194,1469.6,380.9,440.0,359.2,1453.7,1513.3 -2.5289375825621305,0.4709912730720478,2.6179938779914944,714.1,406.7,534.5,393.6,1603.9,1731.8 -2.5289257947640347,0.47100610809344245,2.748893571891069,486.4,486.9,534.8,487.8,1954.2,2174.2 -2.5289363589578446,0.47099829926076864,2.8797932657906435,392.9,533.4,406.2,716.5,2763.5,2758.2 -2.528867866028734,0.4708367015763497,3.010692959690218,358.6,439.8,381.0,1479.0,2547.5,2488.1 -2.528944678521581,0.5711263369275912,0.0,462.9,393.1,393.1,1299.1,2428.7,2429.3 -2.528939938843884,0.5711262302874223,0.1308996938995747,505.6,381.1,440.2,1328.5,2489.6,1770.4 -2.528905984465739,0.5711162321618086,0.2617993877991494,601.6,406.1,533.5,1475.4,1228.8,892.7 -2.528869772443791,0.5710938212049215,0.39269908169872414,488.9,488.0,708.6,1814.3,847.0,627.5 -2.5288398967254584,0.5710636641447508,0.5235987755982988,393.9,692.9,1071.7,2578.2,649.8,522.0 -2.5288295926524946,0.5710412142610406,0.6544984694978736,359.0,1390.4,1350.3,2510.2,543.5,484.4 -2.528817826838647,0.5709955640629587,0.7853981633974483,363.2,1329.1,1328.4,2399.1,493.6,493.1 -2.5288193977224087,0.5709861617216843,0.916297857297023,401.9,1349.5,1408.4,2381.8,484.4,543.3 -2.5288319456630366,0.5709491450802524,1.0471975511965976,485.6,1487.3,1614.6,1148.5,521.3,648.5 -2.5288575167741136,0.570907260288416,1.1780972450961724,645.9,1806.9,2025.4,790.9,627.4,515.6 -2.5288520272349944,0.5709128672037609,1.3089969389957472,990.7,2557.6,2759.9,602.0,648.9,406.7 -2.528863515325705,0.5709081154653037,1.4398966328953218,1327.5,2546.0,2487.7,504.8,439.0,380.6 -2.5289335798081316,0.5708923958849321,1.5707963267948966,1299.2,2428.8,2428.8,463.0,393.4,393.0 -2.5289240301520435,0.5708921313922164,1.7016960206944713,1369.9,2487.3,1797.1,462.2,381.3,439.6 -2.5289174933410217,0.5708900163600454,1.832595714594046,1568.0,1271.7,892.4,509.3,405.8,533.3 -2.5289705799742364,0.5709242088975326,1.9634954084936205,1975.1,846.7,627.6,630.0,487.7,708.5 -2.5289861804032623,0.5709424780419219,2.0943951023931953,2746.0,648.7,521.4,486.1,694.5,1074.4 -2.528975749906327,0.570921313946253,2.2252947962927703,2466.6,543.3,484.5,401.6,1396.4,1349.7 -2.528980926913807,0.5709422446996266,2.356194490192345,2399.7,493.0,493.6,362.5,1328.6,1328.9 -2.528978390652051,0.5709708636150732,2.4870941840919194,1859.1,484.3,543.5,359.0,1350.4,1409.2 -2.5289829450763297,0.5709604505468331,2.6179938779914944,914.3,522.1,649.8,393.4,1488.2,1615.6 -2.5289709677424006,0.5709756970875437,2.748893571891069,628.1,628.0,516.3,487.5,1811.1,2031.3 -2.5289809858228427,0.5709683166662394,2.8797932657906435,508.7,649.0,406.3,715.5,2560.7,2758.9 -2.5289729341930416,0.5709735927951463,3.010692959690218,462.0,439.8,381.0,1371.2,2547.3,2488.6 -2.5290031388533074,0.6712562444464387,0.0,562.9,393.1,393.1,1199.0,2428.6,2428.9 -2.5289665830056465,0.6706719866705599,0.1308996938995747,609.2,381.0,440.2,1224.8,2489.5,2156.0 -2.528999661214804,0.6706827132800453,0.2617993877991494,715.7,406.1,533.5,1359.7,1472.4,1092.7 -2.529036996943085,0.6707066805400381,0.39269908169872414,486.6,488.0,708.7,1671.5,988.5,768.7 -2.5290665761047633,0.6707407514488222,0.5235987755982988,393.9,692.8,1071.6,2378.3,765.6,637.7 -2.52909504348399,0.6707911553342816,0.6544984694978736,359.1,1305.7,1246.9,2511.1,647.1,587.9 -2.529100763783085,0.6708214952408356,0.7853981633974483,363.3,1229.1,1228.3,2398.5,593.6,592.9 -2.5291000287430596,0.670884098644821,0.916297857297023,402.0,1246.4,1305.1,2465.8,587.8,646.6 -2.5290930604693824,0.670911519151993,1.0471975511965976,485.8,1371.8,1498.9,1392.4,636.7,694.7 -2.529085686673618,0.6708917850900527,1.1780972450961724,645.7,1665.8,1884.5,932.8,709.9,488.9 -2.528835573623219,0.6708644430226722,1.3089969389957472,991.6,2359.8,2739.8,717.5,534.1,406.5 -2.528850201310648,0.6708576019277468,1.4398966328953218,1223.7,2545.5,2487.7,608.2,438.9,380.5 -2.52892965939211,0.6708399660863453,1.5707963267948966,1199.0,2429.0,2428.4,563.0,393.3,393.0 -2.5289305157275783,0.6708401535507291,1.7016960206944713,1266.7,2532.8,2183.6,565.6,381.3,439.8 -2.5289337954579034,0.6708408654003777,1.832595714594046,1453.4,1469.7,1047.0,625.0,405.9,533.6 -2.528995131936214,0.6708803727120991,1.9634954084936205,1834.4,987.2,768.5,644.8,487.9,709.0 -2.5290167570874873,0.6709054785663053,2.0943951023931953,2663.6,764.0,636.8,485.9,694.8,1075.5 -2.529010224008695,0.6708915959968134,2.2252947962927703,2466.1,646.7,588.1,401.5,1313.8,1245.9 -2.529017124873491,0.6709200461538529,2.356194490192345,2399.6,593.1,593.7,362.5,1228.4,1229.2 -2.529014148199865,0.6709559527826265,2.4870941840919194,2240.9,588.0,647.1,359.1,1246.8,1305.8 -2.52901684152053,0.6709517797537243,2.6179938779914944,1112.6,637.8,692.1,368.1,1372.6,1500.4 -2.529001391140148,0.6709723078050671,2.748893571891069,769.2,707.3,487.4,487.7,1670.5,1890.2 -2.529007323141665,0.6709687677479332,2.8797932657906435,624.0,533.5,406.1,716.2,2363.7,2744.0 -2.528994669065424,0.6709765188214738,3.010692959690218,565.6,439.7,381.0,1267.3,2547.0,2488.2 -2.529019332104719,0.7712549924929568,0.0,662.8,393.0,393.1,1099.2,2428.8,2429.3 -2.5289858778261505,0.7706647081713043,0.1308996938995747,712.8,381.0,440.3,1121.4,2489.2,2538.9 -2.529020193910363,0.7706758703206087,0.2617993877991494,715.4,406.1,533.5,1244.0,1671.8,1292.0 -2.529058370573999,0.7707004690158865,0.39269908169872414,486.5,487.9,708.6,1530.6,1129.3,910.0 -2.529088530109525,0.7707353098834766,0.5235987755982988,394.0,693.1,1071.7,2179.6,881.1,753.4 -2.528853949824131,0.7709839182206193,0.6544984694978736,359.1,1201.9,1142.9,2509.7,750.5,691.3 -2.528851910216341,0.7709785616647897,0.7853981633974483,363.3,1129.0,1128.6,2398.6,693.4,693.0 -2.5288527454175287,0.770991637082328,0.916297857297023,401.9,1142.8,1201.7,2466.6,691.6,750.5 -2.5288606885417653,0.7709697853229063,1.0471975511965976,486.1,1256.8,1383.9,1590.0,752.7,739.2 -2.528879480647474,0.7709393343625768,1.1780972450961724,646.5,1525.9,1744.9,1073.5,709.3,488.6 -2.5288655649914737,0.7709528398774621,1.3089969389957472,992.3,2161.5,2540.8,833.0,534.1,406.7 -2.528867672037911,0.7709527269291565,1.4398966328953218,1120.4,2545.8,2487.4,711.5,438.8,380.6 -2.5289281638369694,0.7709394555182132,1.5707963267948966,1099.0,2428.5,2428.6,663.1,393.3,393.2 -2.5289096529992188,0.7709388764914202,1.7016960206944713,1163.0,2487.5,2484.5,669.2,381.2,439.9 -2.528895296485891,0.7709339087206741,1.832595714594046,1337.7,1668.0,1290.0,740.6,405.8,533.7 -2.5289418699217077,0.7709639140590352,1.9634954084936205,1692.9,1128.1,909.5,741.2,488.0,709.1 -2.528952611245046,0.7709771002519552,2.0943951023931953,2464.9,879.4,752.3,485.8,695.3,1075.9 -2.5289393466698695,0.7709499927299515,2.2252947962927703,2466.2,750.1,691.5,401.6,1201.2,1142.3 -2.528943376577776,0.7709649001132328,2.356194490192345,2399.8,692.9,693.8,362.5,1128.5,1128.9 -2.528940973693554,0.7709880649670524,2.4870941840919194,2510.7,691.7,750.7,359.1,1143.3,1202.4 -2.528947271138448,0.7709726813396018,2.6179938779914944,1311.4,753.6,740.2,393.5,1257.1,1385.0 -2.5289357781727304,0.7709879920867686,2.748893571891069,910.6,738.9,487.2,487.8,1529.5,1749.6 -2.5289511126387003,0.7709756231334068,2.8797932657906435,739.5,533.2,406.1,716.6,2164.6,2544.9 -2.5289470854895146,0.7709786771705711,3.010692959690218,668.9,439.8,381.1,1163.6,2547.1,2488.5 -2.5289813271060906,0.8712638630828755,0.0,762.9,393.1,393.1,999.0,2428.6,2429.1 -2.528967366318295,0.8706744258273749,0.1308996938995747,816.3,381.0,440.2,1017.9,2489.4,2548.8 -2.5290046698474336,0.8706864711804512,0.2617993877991494,807.2,406.0,533.5,1128.4,1871.6,1491.6 -2.529042556775397,0.8707108190803319,0.39269908169872414,486.5,487.9,708.6,1388.7,1270.8,1051.3 -2.5290718008889566,0.8707445761736123,0.5235987755982988,394.0,693.0,1071.9,1980.1,996.5,869.0 -2.529099825994564,0.8707942875067811,0.6544984694978736,359.1,1098.7,1039.5,2510.3,854.1,795.1 -2.529105323973643,0.8708238176285872,0.7853981633974483,363.2,1029.0,1028.4,2399.4,793.4,793.0 -2.529104540846339,0.8708855658685737,0.916297857297023,402.0,1039.2,1098.1,2465.9,794.9,853.7 -2.52909774271614,0.8709121849508603,1.0471975511965976,485.8,1140.9,1268.4,1791.4,867.8,724.1 -2.529090742505056,0.8709226649253421,1.1780972450961724,645.9,1383.4,1602.5,1216.3,719.7,489.0 -2.529044262412173,0.870967068343772,1.3089969389957472,990.7,1959.8,2338.6,949.0,534.3,406.7 -2.5290096208383805,0.870987423105978,1.4398966328953218,1017.1,2546.5,2487.4,815.1,439.1,380.6 -2.5290317643736717,0.8709831517021185,1.5707963267948966,999.0,2428.7,2428.7,762.9,393.3,393.0 -2.5289773268589344,0.870981921482066,1.7016960206944713,1059.4,2487.0,2545.7,772.4,381.2,439.6 -2.528930754412837,0.8709682791140669,1.832595714594046,1221.8,1869.2,1490.3,855.9,405.6,533.3 -2.5289503325606946,0.8709821158024567,1.9634954084936205,1550.1,1270.0,1050.8,645.0,487.6,708.5 -2.5289409802471514,0.870974311615478,2.0943951023931953,2261.9,995.4,867.9,486.0,694.2,1074.2 -2.528914543056742,0.8709241539528878,2.2252947962927703,2466.2,853.8,794.9,401.5,1098.3,1039.1 -2.5289123820649184,0.8709149595263086,2.356194490192345,2399.6,793.1,793.4,362.4,1028.5,1029.2 -2.5289106532760637,0.8709147231756391,2.4870941840919194,2510.2,795.0,854.1,359.0,1039.6,1098.8 -2.5289228146285474,0.870878933765858,2.6179938779914944,1512.0,868.8,725.3,393.3,1141.3,1268.9 -2.5289239863844655,0.8708732139435125,2.748893571891069,1021.1,720.7,487.5,487.4,1387.0,1606.9 -2.5289506834943953,0.8708504147018659,2.8797932657906435,855.1,533.7,406.2,715.4,1963.1,2342.3 -2.5289612909357295,0.8708459902582317,3.010692959690218,772.4,439.9,381.0,1060.5,2547.0,2488.2 -2.4289476199999,0.17075563973970453,0.0,63.0,493.0,493.0,1699.2,2329.3,2328.8 -2.4289880199850327,0.17146005195513103,0.1308996938995747,91.5,484.6,543.8,1742.7,964.8,233.6 -2.4289421761022663,0.1714450538503527,0.2617993877991494,139.6,521.6,649.2,1937.3,474.9,95.3 -2.4288899749235924,0.17141129436790936,0.39269908169872414,223.8,629.6,850.3,2380.5,282.3,63.0 -2.42884676143984,0.17136558840841776,0.5235987755982988,393.3,892.2,1271.4,2724.8,187.5,59.8 -2.4288276126957267,0.1713257096356906,0.6544984694978736,462.5,1776.8,1764.1,2406.5,129.5,70.5 -2.428811761846981,0.1712621185641754,0.7853981633974483,463.2,1728.9,1728.3,2298.8,93.8,93.2 -2.4288134823384024,0.171418788593114,0.916297857297023,505.3,1763.5,1822.7,917.7,70.7,129.5 -2.4288358992050463,0.17115564420555596,1.0471975511965976,601.4,1949.5,2077.0,393.9,59.5,186.8 -2.428858607515287,0.17111643661006704,1.1780972450961724,756.1,2371.4,2590.1,224.3,63.4,282.4 -2.428859419426704,0.1711142605248841,1.3089969389957472,1190.2,2772.0,2644.0,139.9,95.6,474.9 -2.4288823096568968,0.17110159387913693,1.4398966328953218,1741.2,2442.2,2384.7,91.1,238.5,591.8 -2.428966165298406,0.17108116322125677,1.5707963267948966,1699.0,2328.6,2328.7,63.3,493.3,493.1 -2.4289704725396564,0.17107983081911393,1.7016960206944713,1783.4,1066.9,238.5,48.6,484.7,543.1 -2.428976929695947,0.17108009846542305,1.832595714594046,2030.8,474.8,95.6,47.1,521.3,648.9 -2.42904128017064,0.17112000100317748,1.9634954084936205,2541.9,282.4,63.3,63.7,629.4,850.3 -2.4290654490453214,0.17114633184786232,2.0943951023931953,2630.0,186.8,59.5,117.4,894.2,1274.4 -2.4290605780129515,0.17113449004822323,2.2252947962927703,2363.0,129.5,70.7,319.5,1784.7,1763.3 -2.4290681521044597,0.17116536117108194,2.356194490192345,2299.3,93.2,93.8,462.5,1728.3,1729.0 -2.4290648895415883,0.17120355872107607,2.4870941840919194,316.9,70.5,129.6,462.6,1764.0,1822.8 -2.4290662494508055,0.17120129503284098,2.6179938779914944,117.7,59.9,187.6,509.0,1950.3,2078.3 -2.4290490050601754,0.17122290372965954,2.748893571891069,62.7,62.7,282.8,628.9,2376.2,2596.7 -2.4290527753989384,0.17121960146503246,2.8797932657906435,46.6,95.0,474.8,915.3,2770.7,2643.1 -2.4290381330016033,0.17122674045262132,3.010692959690218,48.2,235.3,585.9,1781.9,2443.8,2384.7 -2.4290612788349666,0.2715039123522436,0.0,163.2,493.0,493.1,1598.9,2328.6,2328.6 -2.4290077961190466,0.2707308878249348,0.1308996938995747,195.0,484.5,543.8,1639.4,1433.3,617.4 -2.42903079307162,0.27073842590059427,0.2617993877991494,255.0,521.6,649.1,1822.1,674.3,294.5 -2.4290608068664663,0.270757807605259,0.39269908169872414,365.2,629.6,850.4,2238.5,423.3,204.0 -2.4290851981473622,0.27078638551254985,0.5235987755982988,509.6,892.3,1271.1,2724.8,302.9,175.2 -2.429110248993069,0.2708307753120609,0.6544984694978736,462.6,1742.7,1660.7,2406.5,232.8,173.8 -2.4291143894283,0.27085497996739094,0.7853981633974483,463.2,1629.0,1628.5,2298.8,193.5,193.0 -2.4291135556946792,0.27091165269608686,0.916297857297023,505.3,1660.1,1719.0,1304.6,173.9,232.7 -2.4291079089114485,0.2709336692274824,1.0471975511965976,601.4,1833.9,1961.4,592.9,174.7,301.9 -2.429103059606093,0.2709403430687525,1.1780972450961724,787.0,2230.4,2449.2,365.7,204.0,423.0 -2.429059355699251,0.2709818025374211,1.3089969389957472,1190.3,2771.9,2643.9,255.1,294.2,522.2 -2.4290279323137436,0.27100010469708513,1.4398966328953218,1637.7,2521.9,2384.5,194.2,542.4,484.1 -2.4290535255932526,0.27099489338020044,1.5707963267948966,1599.1,2328.8,2328.7,163.0,493.3,493.0 -2.4290023683150417,0.2709936218698221,1.7016960206944713,1680.3,1455.6,626.9,151.7,484.7,543.1 -2.4289587729642146,0.2709806922519038,1.832595714594046,1915.0,673.5,294.3,162.3,521.3,648.9 -2.4289808327063453,0.2709960296041136,1.9634954084936205,2400.5,423.2,204.0,204.9,629.2,850.2 -2.428973274417749,0.2709902273266782,2.0943951023931953,2630.0,301.9,174.6,316.4,894.1,1274.1 -2.428947957137648,0.27094223388067884,2.2252947962927703,2363.2,232.7,173.9,505.1,1741.9,1660.4 -2.4289462160079904,0.2709352777724361,2.356194490192345,2299.7,193.0,193.5,462.4,1628.6,1628.9 -2.428944215151223,0.27093718056384164,2.4870941840919194,616.8,173.7,232.8,462.4,1660.7,1719.8 -2.4289556617565626,0.2709031604303116,2.6179938779914944,316.4,175.2,302.8,508.9,1834.7,1962.2 -2.428955650849312,0.27089885959394366,2.748893571891069,203.8,203.8,423.7,628.8,2235.4,2455.9 -2.428981033857288,0.27087699615409355,2.8797932657906435,161.9,293.9,521.6,914.9,2770.8,2643.4 -2.428990248426792,0.27087307665055094,3.010692959690218,151.5,543.3,484.4,1681.7,2443.6,2384.8 -2.4290414149082027,0.3711716782092138,0.0,262.9,493.0,493.0,1498.8,2329.2,2329.1 -2.429012138734819,0.37117115419164026,0.1308996938995747,298.4,484.6,543.9,1536.0,1816.7,1000.9 -2.4289561109611184,0.37115482054576,0.2617993877991494,370.4,521.6,649.1,1706.6,873.2,493.6 -2.4289016155580043,0.3711215027111181,0.39269908169872414,506.7,629.4,818.9,2097.4,564.2,345.0 -2.4288579376656525,0.3710772398569788,0.5235987755982988,548.0,848.3,1271.2,2724.9,418.5,290.8 -2.428838607739902,0.3710390028874664,0.6544984694978736,462.5,1616.5,1557.4,2406.6,336.4,277.2 -2.4288225448757945,0.3709768459101359,0.7853981633974483,463.1,1529.1,1528.6,2298.8,293.5,293.0 -2.42882419377175,0.3709516555744732,0.916297857297023,505.3,1556.6,1615.4,1691.8,277.4,336.2 -2.4288407273601003,0.37090039158794985,1.0471975511965976,601.3,1718.4,1845.8,792.8,290.2,417.5 -2.4288734124713147,0.3708467587616413,1.1780972450961724,787.0,2089.2,2308.6,507.5,345.1,564.2 -2.4288770458936177,0.37084366133964064,1.3089969389957472,1190.1,2771.6,2643.6,370.8,493.5,629.6 -2.428863006911695,0.3708485924272724,1.4398966328953218,1534.3,2442.5,2384.6,297.8,542.4,483.9 -2.42914373735412,0.37078646256276016,1.5707963267948966,1499.0,2329.5,2328.7,263.0,493.3,493.0 -2.4290291299890296,0.3707827205567502,1.7016960206944713,1576.8,1845.6,1016.8,255.2,484.6,543.1 -2.42900537376073,0.370775579952517,1.832595714594046,1799.6,873.0,493.7,278.0,521.3,649.0 -2.429066056614159,0.37081496387002333,1.9634954084936205,2258.4,564.4,345.3,346.7,629.5,850.2 -2.4290926541402627,0.3708457014194484,2.0943951023931953,2629.5,417.5,290.3,516.0,894.1,1274.2 -2.4290902442577447,0.3708404360351836,2.2252947962927703,2363.5,336.3,277.5,620.3,1615.5,1556.8 -2.429098962496943,0.37087846728319507,2.356194490192345,2299.5,293.0,293.5,462.5,1528.8,1529.0 -2.429095450415531,0.3709235348484463,2.4870941840919194,1002.4,277.3,336.4,462.5,1557.1,1616.4 -2.4290953354206093,0.37092750547098885,2.6179938779914944,515.6,290.8,418.4,509.0,1719.4,1847.0 -2.4290756857683524,0.37095461985420175,2.748893571891069,345.2,345.2,565.2,628.7,2094.5,2314.3 -2.429076218632901,0.37095601364546527,2.8797932657906435,277.4,493.3,629.7,915.1,2771.2,2643.6 -2.429057645629426,0.37096696570430066,3.010692959690218,255.0,543.4,484.6,1578.1,2443.5,2385.0 -2.4290751878769545,0.47124009862912675,0.0,362.9,493.1,493.0,1399.1,2328.8,2329.1 -2.429011562281265,0.47065205072153593,0.1308996938995747,402.1,484.5,543.9,1432.2,2201.5,1385.6 -2.429041128923331,0.47066179756145776,0.2617993877991494,486.1,521.7,649.2,1591.1,1073.2,693.4 -2.4291187660184015,0.47071376629674044,0.39269908169872414,627.6,629.7,850.3,1955.8,705.7,486.4 -2.4291277911068674,0.4707258218176156,0.5235987755982988,509.4,892.2,1271.3,2724.6,534.1,406.4 -2.4287985663544758,0.47102600311000287,0.6544984694978736,462.6,1512.2,1453.5,2406.2,439.8,380.9 -2.428803513880607,0.4710804013840941,0.7853981633974483,463.2,1428.9,1428.3,2299.0,393.5,393.1 -2.4288065345653265,0.4710099189960779,0.916297857297023,505.6,1453.5,1512.4,2074.7,381.0,439.9 -2.428815844685281,0.47098377726744123,1.0471975511965976,601.7,1603.7,1731.0,991.3,406.0,533.4 -2.428837733778534,0.47094845691433496,1.1780972450961724,787.7,1949.4,2168.5,648.8,486.6,630.2 -2.4288280238810236,0.47095802705929657,1.3089969389957472,1191.6,2759.6,2643.3,486.2,649.7,522.1 -2.4288349784926235,0.47095528513586205,1.4398966328953218,1430.6,2442.3,2383.8,401.2,542.5,484.0 -2.428900545083456,0.4709407569522084,1.5707963267948966,1398.7,2329.1,2328.4,363.0,493.3,493.2 -2.428886817646915,0.47094021394281427,1.7016960206944713,1473.5,2230.9,1403.5,358.9,484.9,543.4 -2.4288767594743708,0.47093639998582226,1.832595714594046,1684.6,1071.2,692.4,393.8,521.6,649.4 -2.428966093167312,0.47099577775566437,1.9634954084936205,2118.2,705.1,486.1,488.7,629.8,851.1 -2.4289832929489,0.4710151583822899,2.0943951023931953,2628.7,533.0,405.7,601.4,895.2,1275.6 -2.4289560204886285,0.4709612821402982,2.2252947962927703,2362.3,439.7,381.0,505.0,1511.6,1453.2 -2.428971380341999,0.471027568804522,2.356194490192345,2299.0,392.9,393.6,462.5,1428.3,1429.1 -2.428970479555756,0.471019576396857,2.4870941840919194,1469.8,380.9,440.1,462.6,1454.0,1513.1 -2.4289769158294687,0.47100419783458713,2.6179938779914944,714.2,406.6,534.5,509.4,1604.1,1732.0 -2.428962252110502,0.4710236171777029,2.748893571891069,486.5,487.0,628.7,629.4,1953.5,2173.9 -2.428966984501005,0.47102123236474625,2.8797932657906435,392.9,648.9,521.7,916.2,2763.7,2642.0 -2.428952035444629,0.4710300942766972,3.010692959690218,358.6,543.3,484.7,1474.3,2443.1,2384.7 -2.428973521799986,0.5713059369030244,0.0,463.0,493.1,493.1,1298.7,2329.2,2329.3 -2.4289601108152317,0.5706741425252084,0.1308996938995747,505.6,484.6,543.9,1328.3,2385.6,1771.0 -2.428997386457567,0.5706861586159448,0.2617993877991494,601.6,521.7,649.1,1475.0,1273.1,849.4 -2.4290353311602515,0.5707105103447185,0.39269908169872414,627.8,629.6,850.2,1813.3,847.2,627.8 -2.429064638419041,0.5707442872919211,0.5235987755982988,509.6,892.0,1270.8,2577.3,649.9,522.1 -2.4290927535032187,0.57079405321019,0.6544984694978736,462.7,1409.1,1350.3,2406.7,543.6,484.4 -2.42909830169915,0.5708236356856404,0.7853981633974483,463.3,1329.0,1328.5,2298.6,493.6,493.0 -2.429097577327247,0.5708854720247847,0.916297857297023,505.4,1349.9,1408.3,2362.6,484.4,543.1 -2.429090808510509,0.5709121912334569,1.0471975511965976,601.3,1487.1,1614.6,1148.5,521.3,648.4 -2.429083792639349,0.5709227408594328,1.1780972450961724,786.9,1806.5,2026.0,790.8,627.2,674.0 -2.429037284667467,0.5709672249316908,1.3089969389957472,1190.0,2556.7,2644.5,602.0,650.1,522.4 -2.4290025940509197,0.5709876684903572,1.4398966328953218,1327.4,2442.4,2384.1,504.6,542.6,484.0 -2.4290246640938995,0.5709834036384474,1.5707963267948966,1298.9,2329.2,2328.3,463.0,493.4,493.1 -2.4289701574192484,0.570982169037993,1.7016960206944713,1369.5,2383.1,1797.2,462.1,484.8,543.2 -2.4289235171057437,0.570968529189029,1.832595714594046,1568.2,1271.8,892.5,509.1,521.4,648.9 -2.4289430526670173,0.570982311368263,1.9634954084936205,1974.9,846.5,627.3,629.9,629.3,850.2 -2.4289336932185766,0.5709744262786876,2.0943951023931953,2630.4,648.7,521.2,671.6,893.7,1273.8 -2.4289072561195675,0.5709242200623168,2.2252947962927703,2363.3,543.3,484.4,505.1,1408.6,1349.9 -2.4289051181143075,0.5709149829044842,2.356194490192345,2299.7,493.0,493.5,462.4,1328.6,1328.8 -2.4291805067821857,0.5709392464885776,2.4870941840919194,1863.3,484.3,543.3,462.4,1350.0,1408.8 -2.4291791883853273,0.5709448531884287,2.6179938779914944,915.3,521.9,649.3,508.7,1487.4,1614.9 -2.4291580873894465,0.5709739524358628,2.748893571891069,628.6,627.7,674.9,628.3,1810.2,2030.0 -2.4291563093260096,0.5709769811074097,2.8797932657906435,508.8,649.5,521.8,914.0,2558.6,2644.3 -2.429135331720357,0.5709889291368526,3.010692959690218,462.1,543.5,484.4,1371.5,2444.5,2385.6 -2.4291501459258873,0.6712600167916116,0.0,562.9,493.1,492.9,1198.9,2329.3,2328.9 -2.429042450226129,0.6706545302688529,0.1308996938995747,609.2,484.5,543.9,1225.0,2431.7,2153.5 -2.4290629285708434,0.6706614870287968,0.2617993877991494,717.2,521.6,649.1,1359.9,1471.9,1092.4 -2.429099359012064,0.6706851335897315,0.39269908169872414,630.7,629.6,850.4,1672.4,988.0,768.7 -2.429130678823108,0.6707214533093186,0.5235987755982988,509.4,892.3,1271.5,2379.6,765.3,637.8 -2.428796355544884,0.6710266547045487,0.6544984694978736,462.6,1305.5,1246.5,2406.1,646.9,587.9 -2.4287924575661144,0.6710125426843374,0.7853981633974483,463.2,1229.1,1228.6,2299.1,593.7,593.1 -2.4287937312363526,0.6710157674312611,0.916297857297023,505.6,1246.3,1305.3,2362.9,588.1,647.0 -2.4288046053984096,0.6709846089884453,1.0471975511965976,601.7,1372.2,1499.5,1390.7,637.1,764.5 -2.42882831475013,0.67094635452534,1.1780972450961724,787.8,1666.6,1886.2,931.9,768.9,657.3 -2.428820587432199,0.6709540586017315,1.3089969389957472,1191.7,2360.6,2643.2,717.3,649.7,522.2 -2.4288296440854173,0.6709501926988843,1.4398966328953218,1223.7,2442.3,2384.0,608.1,542.3,484.1 -2.428897342598569,0.6709351573374385,1.5707963267948966,1199.0,2329.1,2329.3,563.0,493.4,493.2 -2.428885595773818,0.6709346673463941,1.7016960206944713,1266.6,2448.4,2181.9,565.7,484.8,543.3 -2.428877292232571,0.6709313831204295,1.832595714594046,1453.3,1469.3,1090.7,625.1,521.7,649.3 -2.4289289739126847,0.6709643761588777,1.9634954084936205,1834.6,956.0,768.2,772.3,629.9,850.9 -2.428943573358429,0.6709814180812748,2.0943951023931953,2629.0,764.0,636.8,601.4,895.1,1276.2 -2.4289328268486505,0.670958660009088,2.2252947962927703,2362.6,646.5,588.0,505.1,1304.7,1246.3 -2.4289380713198585,0.670978126412435,2.356194490192345,2299.3,593.0,593.7,462.5,1228.4,1229.1 -2.4289356513090836,0.6710056841534211,2.4870941840919194,2239.8,588.1,647.2,462.7,1246.8,1306.1 -2.4289408500686256,0.6709942075571644,2.6179938779914944,1068.5,638.0,765.6,509.2,1372.7,1500.5 -2.428929183255063,0.6710088047769529,2.748893571891069,769.1,770.0,658.4,629.3,1670.8,1891.2 -2.428939894955828,0.6710008125877824,2.8797932657906435,624.0,648.9,521.7,916.4,2364.0,2642.6 -2.4289324968562447,0.6710056255311216,3.010692959690218,565.6,543.3,484.4,1267.3,2443.2,2384.7 -2.428963514938267,0.7712888469134989,0.0,663.0,493.1,493.2,1098.8,2329.0,2329.1 -2.4289522928731517,0.7706770778316008,0.1308996938995747,712.8,484.5,543.8,1121.5,2386.3,2445.0 -2.428989842481874,0.7706891626847154,0.2617993877991494,832.8,521.7,649.1,1244.0,1672.3,1292.2 -2.429027589411185,0.7707133550659861,0.39269908169872414,627.8,629.5,850.3,1530.2,1129.5,910.2 -2.4290566424060382,0.7707468079955511,0.5235987755982988,509.6,892.1,1270.9,2179.0,881.3,753.4 -2.4290846109617874,0.7706204039826252,0.6544984694978736,462.6,1202.3,1143.4,2406.3,750.6,691.3 -2.4288004147489093,0.7709732337750173,0.7853981633974483,463.2,1129.0,1128.5,2299.0,693.4,693.1 -2.4287917814763342,0.7711965452720684,0.916297857297023,505.5,1142.9,1201.7,2363.2,691.5,750.3 -2.4288446517018243,0.7710301387115153,1.0471975511965976,601.7,1256.7,1384.1,1589.7,752.6,880.0 -2.428885582820742,0.7709646130633165,1.1780972450961724,787.6,1525.5,1744.8,1073.6,850.8,630.2 -2.4288766681045253,0.7709736060952606,1.3089969389957472,1191.7,2161.1,2541.0,833.0,649.8,522.2 -2.428875221607239,0.7709755107935796,1.4398966328953218,1120.3,2442.1,2383.8,711.4,542.3,484.1 -2.4289286994271464,0.7709638881035759,1.5707963267948966,1099.2,2328.7,2328.7,663.0,493.3,493.2 -2.428902581645665,0.770963091210642,1.7016960206944713,1163.0,2383.9,2442.3,669.2,484.8,543.4 -2.428881128892242,0.7709560155620729,1.832595714594046,1337.8,1668.4,1289.8,740.5,521.6,649.3 -2.4289217097262537,0.7709822582061097,1.9634954084936205,1693.1,1128.3,909.3,785.7,629.9,851.0 -2.4289280205832378,0.7709906300939109,2.0943951023931953,2464.2,879.4,752.3,601.2,895.1,1275.6 -2.4289119571858215,0.770958220058791,2.2252947962927703,2362.6,750.0,691.6,505.0,1201.4,1142.6 -2.428914770629024,0.7709676568767871,2.356194490192345,2299.1,693.0,693.7,462.4,1128.4,1129.2 -2.4289126309636773,0.7709856114557787,2.4870941840919194,2407.0,691.6,750.8,462.7,1143.2,1202.4 -2.428920376083121,0.7709656920689392,2.6179938779914944,1311.7,753.5,881.5,509.2,1257.1,1384.9 -2.428913096293129,0.7709733205648175,2.748893571891069,879.4,848.5,628.5,629.2,1529.3,1749.5 -2.4289293691060743,0.7709602090253429,2.8797932657906435,739.6,648.9,521.7,916.1,2164.7,2544.5 -2.4289281860396383,0.7709618086008911,3.010692959690218,669.0,543.3,484.6,1163.8,2443.6,2384.8 -2.4289666834517116,0.87125072222463,0.0,762.9,493.1,493.2,999.1,2328.7,2329.0 -2.4289286409517636,0.8712494810805549,0.1308996938995747,816.6,484.6,544.1,1017.9,2386.3,2445.6 -2.428866215309367,0.8712306280741506,0.2617993877991494,914.1,521.8,649.5,1129.0,1869.2,1489.6 -2.428807110038511,0.8711936848931343,0.39269908169872414,627.2,630.0,850.8,1389.8,1269.6,1050.5 -2.4287605220637825,0.8711452393954191,0.5235987755982988,509.4,893.0,1140.8,1983.0,996.2,868.4 -2.4287394919539387,0.8711025348070638,0.6544984694978736,462.5,1098.3,1039.5,2406.0,853.9,794.9 -2.4287232406376065,0.8710362180547886,0.7853981633974483,463.3,1029.1,1028.6,2299.2,793.5,793.2 -2.4287254949457933,0.8710071546619715,0.916297857297023,505.5,1039.1,1098.2,2363.1,795.0,854.1 -2.4287434407191033,0.8709525932275017,1.0471975511965976,601.6,1141.0,1268.8,1789.3,868.1,893.0 -2.428778177623812,0.8708966149920121,1.1780972450961724,787.7,1384.2,1603.4,1215.4,850.9,630.2 -2.428783977472707,0.8708916668503892,1.3089969389957472,1147.4,1962.1,2341.1,948.6,649.6,522.2 -2.4288080927821527,0.8708798489209115,1.4398966328953218,1016.9,2442.4,2384.3,815.1,542.4,484.0 -2.4288913168167388,0.8708613309779256,1.5707963267948966,999.1,2328.9,2329.0,763.1,493.3,493.1 -2.428894015270207,0.8708614429243045,1.7016960206944713,1059.5,2383.4,2442.2,772.6,484.9,543.3 -2.428898466299941,0.8708622076690975,1.832595714594046,1221.9,1868.0,1488.8,856.5,521.6,649.3 -2.428960697995726,0.8709019977130987,1.9634954084936205,1551.0,1269.4,1050.4,882.8,629.8,851.0 -2.428983035368457,0.8709275573021402,2.0943951023931953,2264.7,995.0,867.7,601.4,895.1,1140.5 -2.428977114733905,0.8709141680021617,2.2252947962927703,2362.6,853.5,794.9,505.1,1097.7,1039.0 -2.428984446992583,0.8709432393389158,2.356194490192345,2300.0,793.0,793.7,462.6,1028.3,1029.1 -2.4289816244480833,0.8709798857147395,2.4870941840919194,2455.7,795.2,854.3,462.6,1039.6,1098.8 -2.4289843284321955,0.8709763808155826,2.6179938779914944,1510.9,869.1,891.1,509.2,1141.6,1269.3 -2.428968558436162,0.8709975485993784,2.748893571891069,1052.0,880.1,628.7,629.3,1387.8,1607.8 -2.4289740849880403,0.8709944547002613,2.8797932657906435,855.1,649.1,521.6,916.2,1964.7,2344.5 -2.4289609043217193,0.8710024515183408,3.010692959690218,772.5,543.3,484.6,1060.3,2443.1,2384.8 -2.328908432703637,0.17083548370433976,0.0,63.1,593.0,593.1,1698.6,2229.0,2228.6 -2.328938868317846,0.17147137779687727,0.1308996938995747,91.6,588.2,647.7,1742.8,1047.4,233.1 -2.328889013882835,0.17145498093782896,0.2617993877991494,139.7,637.3,765.1,1937.6,474.4,95.2 -2.3288352494294053,0.17141995702221058,0.39269908169872414,224.0,771.7,992.5,2381.4,282.1,63.0 -2.328791535660341,0.171373212690213,0.5235987755982988,393.7,1048.6,1472.3,2608.2,187.4,59.8 -2.3287721642694605,0.1713323275862344,0.6544984694978736,566.0,1822.8,1763.9,2302.9,129.4,70.5 -2.328756620353242,0.1712680351230107,0.7853981633974483,563.2,1728.9,1728.2,2198.9,93.7,93.3 -2.328758645622291,0.1712409033896416,0.916297857297023,609.0,1763.6,1822.8,831.0,70.7,129.6 -2.3287755403097004,0.1711879090303905,1.0471975511965976,717.0,1949.9,2077.0,393.4,59.5,186.9 -2.328808659846091,0.17113285681269952,1.1780972450961724,928.7,2372.1,2591.5,224.2,63.4,282.7 -2.3288126252901296,0.17112802923196346,1.3089969389957472,1390.9,2654.7,2527.6,139.8,95.8,475.4 -2.3288350274594336,0.1711155669570541,1.4398966328953218,1740.7,2338.7,2280.6,91.0,239.0,587.5 -2.328916958388566,0.171095846034925,1.5707963267948966,1698.6,2229.3,2228.5,63.3,593.3,593.3 -2.32891896175546,0.17109446020427188,1.7016960206944713,1783.9,979.3,237.9,48.6,588.3,646.7 -2.3289233189311185,0.1710937414768341,1.832595714594046,2031.5,474.3,95.5,47.1,637.2,764.9 -2.3289859175227736,0.17113236055025194,1.9634954084936205,2543.1,282.2,63.3,63.7,771.5,992.6 -2.3290088313299777,0.17115720263418743,2.0943951023931953,2513.6,186.7,59.5,117.5,1094.7,1475.5 -2.3290034345261725,0.17114353175299146,2.2252947962927703,2259.0,129.4,70.7,320.2,1821.9,1763.5 -2.329011004026087,0.17117265082293853,2.356194490192345,2199.4,93.2,93.9,562.5,1728.1,1728.9 -2.329008000591845,0.17120944865106225,2.4870941840919194,316.3,70.5,129.7,566.2,1764.3,1823.4 -2.3290101507298737,0.1712059276099327,2.6179938779914944,117.5,59.9,187.7,624.9,1950.9,2078.5 -2.328993571694969,0.17122672898689917,2.748893571891069,62.7,62.8,282.9,770.7,2377.6,2598.5 -2.328998298324213,0.171222817153297,2.8797932657906435,46.6,95.1,475.2,1115.7,2654.1,2526.5 -2.328984559789334,0.17122959325642229,3.010692959690218,48.3,235.7,588.0,1784.3,2339.9,2281.1 -2.3290086776708896,0.27150746144929894,0.0,163.2,593.0,593.1,1598.6,2229.0,2229.1 -2.3289841298691827,0.2707326860227828,0.1308996938995747,195.0,588.0,647.4,1639.2,1433.7,532.9 -2.3290127308625115,0.27074192847587875,0.2617993877991494,254.9,637.2,764.6,1822.0,674.3,294.5 -2.3288863708752907,0.2711245101468307,0.39269908169872414,365.4,771.5,961.3,2239.4,423.2,204.0 -2.328874007842523,0.2711121866594055,0.5235987755982988,592.6,1092.0,1471.5,2608.8,302.9,175.3 -2.3288723942515768,0.27110543337532933,0.6544984694978736,566.2,1719.6,1660.2,2302.7,232.9,173.9 -2.328864386195094,0.27107469567168163,0.7853981633974483,563.2,1628.6,1628.2,2198.9,193.6,193.1 -2.3288654883243427,0.2710788013821839,0.916297857297023,609.0,1660.1,1719.1,1303.5,174.0,232.9 -2.328874228426843,0.27105365057733377,1.0471975511965976,717.1,1834.3,1961.4,548.9,174.9,302.2 -2.328893512679919,0.2710215467635728,1.1780972450961724,928.5,2231.1,2450.2,365.7,204.3,423.5 -2.3288800356021775,0.27103404302547185,1.3089969389957472,1390.6,2655.0,2528.3,255.3,294.7,637.9 -2.3288826435095507,0.2710332352898388,1.4398966328953218,1637.5,2339.1,2280.6,194.4,628.2,587.4 -2.3289437422934043,0.2710191495092058,1.5707963267948966,1598.9,2229.2,2228.8,163.1,593.3,593.1 -2.3289259932210054,0.2710180440990606,1.7016960206944713,1680.5,1454.4,541.2,151.9,588.2,646.8 -2.328912451824187,0.27101297677842484,1.832595714594046,1915.5,629.6,294.4,162.5,637.0,764.9 -2.3289598758947783,0.2710430263131509,1.9634954084936205,2400.9,423.2,204.2,205.2,771.4,992.3 -2.328971382545041,0.27105646555375995,2.0943951023931953,2513.9,302.1,174.8,316.9,1094.4,1474.8 -2.328958559599478,0.2710299733427399,2.2252947962927703,2259.0,232.8,174.1,608.6,1718.9,1660.0 -2.3289627381071916,0.27104559779162196,2.356194490192345,2199.5,193.1,193.7,562.6,1628.1,1629.2 -2.3289602749811484,0.27106936498711165,2.4870941840919194,701.2,173.9,233.1,566.2,1660.7,1719.7 -2.3289660954355114,0.2710545317037494,2.6179938779914944,316.4,175.4,303.1,624.7,1835.1,1962.8 -2.3289559164845604,0.27106611928173097,2.748893571891069,203.9,204.0,424.2,770.4,2236.3,2456.1 -2.32896850968091,0.2710557491213348,2.8797932657906435,162.0,294.4,637.3,1115.2,2654.6,2527.1 -2.3289634087149547,0.27105882602079423,3.010692959690218,151.6,622.4,588.0,1681.5,2340.5,2280.8 -2.328997505638519,0.37134435406729316,0.0,263.0,593.1,593.1,1499.0,2228.6,2229.1 -2.3289564104732836,0.37134236728914827,0.1308996938995747,298.5,588.1,647.5,1535.9,1815.3,1000.2 -2.3288412825511897,0.3713031867678185,0.2617993877991494,370.6,637.4,739.4,1706.6,872.9,493.7 -2.328812424115268,0.37128486439806063,0.39269908169872414,507.0,771.3,992.4,2098.1,564.3,345.1 -2.328770879974983,0.37124155068638576,0.5235987755982988,625.0,1092.0,1471.2,2608.5,418.4,290.9 -2.328749275567418,0.37119752418621865,0.6544984694978736,566.1,1616.2,1557.4,2302.9,336.4,277.4 -2.32873198963915,0.3711271874573614,0.7853981633974483,563.1,1529.1,1528.6,2198.9,293.6,293.1 -2.328734240236133,0.37109353941827394,0.916297857297023,609.0,1556.7,1615.7,1690.4,277.6,336.4 -2.3287532377845173,0.3710345279733085,1.0471975511965976,716.8,1718.3,1846.4,792.6,290.4,417.7 -2.3287898860796834,0.37097453306165273,1.1780972450961724,928.5,2089.4,2309.5,507.4,345.5,564.7 -2.328798320244166,0.37096643081837266,1.3089969389957472,1390.3,2655.5,2527.6,370.9,494.1,637.9 -2.328825587618066,0.37095241527645406,1.4398966328953218,1534.1,2338.9,2280.4,297.9,645.9,587.5 -2.3289122527761394,0.37093242594676457,1.5707963267948966,1498.9,2228.5,2228.7,263.2,593.4,593.1 -2.3289183827394524,0.3709320888258185,1.7016960206944713,1576.8,1844.0,1016.2,255.4,588.2,646.8 -2.3288904894465468,0.3709198464150003,1.832595714594046,1800.1,872.7,493.7,278.2,637.0,764.8 -2.329131828595366,0.3710736939301573,1.9634954084936205,2259.2,564.2,345.3,346.9,771.4,992.4 -2.329075333958996,0.37101363644320773,2.0943951023931953,2514.5,417.6,290.4,516.7,1094.5,1474.6 -2.3290576856163083,0.3709777703300452,2.2252947962927703,2259.5,336.3,277.6,608.6,1615.4,1556.5 -2.329065701258896,0.3710098034153382,2.356194490192345,2199.6,293.0,293.7,562.6,1528.5,1528.7 -2.329062385583264,0.3710577645092099,2.4870941840919194,1086.6,277.5,336.6,566.2,1557.2,1616.5 -2.3290609297297054,0.37106677809350375,2.6179938779914944,515.5,291.0,418.8,624.9,1719.2,1847.1 -2.329037962244731,0.3710988186348314,2.748893571891069,345.3,345.4,565.5,739.4,2094.7,2315.0 -2.3290341659751657,0.37110378655856247,2.8797932657906435,277.5,494.0,637.3,1115.1,2654.2,2527.2 -2.3290106655451077,0.37111672083390235,3.010692959690218,255.1,646.9,588.1,1577.7,2340.2,2281.1 -2.329022457909036,0.47138535186802444,0.0,363.0,593.0,593.2,1399.1,2229.2,2228.8 -2.3289822198410794,0.47068410152060913,0.1308996938995747,402.1,588.3,647.4,1432.2,2202.6,1386.4 -2.329012891633137,0.4706940726590072,0.2617993877991494,486.0,637.3,764.6,1590.5,1073.4,693.5 -2.329048680085889,0.47071709730036804,0.39269908169872414,648.4,771.2,991.9,1955.8,705.9,486.5 -2.3290772220362705,0.4707501106785468,0.5235987755982988,747.1,1091.3,1470.2,2609.3,534.3,406.5 -2.3291049797164844,0.4707993628694871,0.6544984694978736,566.3,1512.7,1453.8,2303.0,439.9,380.9 -2.3291103648621805,0.470828543641999,0.7853981633974483,563.2,1429.2,1428.6,2198.6,393.6,393.0 -2.329109553302905,0.4708899950639407,0.916297857297023,609.0,1453.2,1512.0,2080.3,380.9,439.6 -2.329102790726397,0.4709163470219402,1.0471975511965976,716.8,1602.7,1730.1,992.4,405.7,532.9 -2.3290958811839135,0.4709265914629368,1.1780972450961724,928.2,1947.8,2166.7,649.2,486.1,705.1 -2.329018181114943,0.4710053590393568,1.3089969389957472,1389.2,2656.1,2528.6,486.4,692.5,637.9 -2.3290111477225657,0.47101087231474814,1.4398966328953218,1431.0,2339.3,2281.1,401.2,646.0,587.5 -2.329039584487576,0.47100514504392366,1.5707963267948966,1398.9,2228.9,2228.8,363.0,593.3,593.2 -2.3289838348153067,0.4710038599277573,1.7016960206944713,1473.5,2236.5,1407.0,358.6,588.1,646.5 -2.328933831272406,0.4709891743690582,1.832595714594046,1683.9,1072.0,692.9,393.4,636.9,764.5 -2.3289498930205204,0.47100081183851294,1.9634954084936205,2116.7,705.5,486.3,488.3,770.9,992.0 -2.3289377680074934,0.47099004919769727,2.0943951023931953,2514.6,533.0,405.7,715.4,1093.5,1473.5 -2.3289095208274926,0.47093655737707674,2.2252947962927703,2259.5,439.8,380.9,608.5,1512.3,1453.2 -2.328906521182293,0.4709238895918484,2.356194490192345,2199.7,392.9,393.5,562.5,1428.7,1429.0 -2.3289048715523313,0.47092032223332314,2.4870941840919194,1473.4,380.8,439.9,566.0,1453.7,1512.7 -2.3289178808934747,0.47088159115517225,2.6179938779914944,715.1,406.3,534.0,624.6,1603.6,1731.3 -2.3289205302088893,0.4708734203793814,2.748893571891069,486.6,486.6,706.4,770.2,1952.6,2172.7 -2.3289491164605867,0.47084878827007115,2.8797932657906435,393.0,692.7,637.3,1114.1,2655.5,2527.7 -2.3289618568483528,0.4708431727060114,3.010692959690218,358.5,646.9,588.1,1474.4,2340.2,2281.5 -2.3290171622747713,0.5711448984154932,0.0,462.9,593.0,593.2,1299.3,2229.1,2228.9 -2.3289908328633593,0.5711446121339645,0.1308996938995747,505.5,588.2,647.4,1328.8,2282.0,1770.1 -2.3289369409535343,0.5711290284325556,0.2617993877991494,601.4,637.1,764.4,1475.2,1272.7,892.8 -2.3288840610005908,0.5710967790177488,0.39269908169872414,769.0,771.0,991.4,1814.0,846.8,627.4 -2.328841535569511,0.5710537722770639,0.5235987755982988,625.0,1091.0,1470.2,2577.6,649.8,522.1 -2.328823018276405,0.5710169202552839,0.6544984694978736,566.0,1409.3,1350.4,2303.1,543.5,484.3 -2.3288073383774535,0.5709561494258568,0.7853981633974483,563.0,1329.0,1328.7,2198.7,493.5,492.9 -2.328809088498228,0.5709323410710492,0.916297857297023,608.7,1349.7,1408.5,2258.9,484.4,543.1 -2.32882540289814,0.5708823687774034,1.0471975511965976,716.8,1487.1,1614.8,1192.1,521.2,648.6 -2.328857565790654,0.5708297995141001,1.1780972450961724,928.0,1806.7,2025.7,790.9,627.3,772.3 -2.3288605066964285,0.5708275936902001,1.3089969389957472,1389.0,2557.1,2528.6,602.0,765.5,637.9 -2.3288815130104936,0.5708179828546533,1.4398966328953218,1327.4,2339.1,2281.1,504.8,646.0,587.6 -2.32896139888259,0.5708002794442861,1.5707963267948966,1298.9,2228.7,2228.8,463.0,593.4,593.1 -2.3289609254720935,0.5708006736431879,1.7016960206944713,1369.8,2280.0,1797.1,462.2,588.2,646.5 -2.3289622925250137,0.5708014150205525,1.832595714594046,1568.4,1271.7,892.5,509.1,636.9,764.5 -2.329021785046165,0.5708401420714668,1.9634954084936205,1974.8,815.6,627.5,630.1,771.0,992.0 -2.3290419461121874,0.5708639283989405,2.0943951023931953,2514.5,648.7,521.3,717.2,1093.3,1473.8 -2.329034218217277,0.5708486987311452,2.2252947962927703,2260.1,543.3,484.5,608.6,1408.4,1349.8 -2.329040418900861,0.5708755817192963,2.356194490192345,2199.7,493.0,493.6,562.5,1328.6,1328.9 -2.3290374481696294,0.5709097295306489,2.4870941840919194,1859.4,484.3,543.5,566.1,1350.3,1408.9 -2.3290403793139838,0.5709041177395096,2.6179938779914944,914.3,522.0,649.7,624.5,1487.9,1615.7 -2.329025914205374,0.5709233145188743,2.748893571891069,628.1,628.0,770.2,770.2,1810.9,2031.0 -2.3290328562936184,0.5709189336880451,2.8797932657906435,508.5,764.8,637.3,1114.3,2561.0,2527.3 -2.3290213967746904,0.5709262636896772,3.010692959690218,462.0,646.9,588.1,1370.8,2340.5,2281.4 -2.329047420644386,0.6712058190446129,0.0,562.9,593.0,593.0,1199.3,2228.9,2228.9 -2.328993010811503,0.6706531865051011,0.1308996938995747,609.3,588.2,647.4,1225.0,2417.5,2154.7 -2.3290244944789342,0.6706634997959946,0.2617993877991494,717.3,637.2,764.4,1359.8,1472.5,1092.7 -2.32906318502333,0.670688444653591,0.39269908169872414,768.9,771.0,991.7,1672.3,988.1,768.9 -2.3290944508645763,0.6707245050867063,0.5235987755982988,625.3,1091.4,1372.3,2378.6,765.4,637.7 -2.328785156932167,0.6710234799489279,0.6544984694978736,566.2,1305.4,1246.5,2302.3,647.0,587.9 -2.328781420327362,0.6710099510611769,0.7853981633974483,563.3,1229.0,1228.5,2199.0,593.4,593.1 -2.328782748710412,0.671012439234923,0.916297857297023,609.1,1246.0,1305.5,2305.0,588.1,647.0 -2.3287939813125806,0.6709802344754545,1.0471975511965976,717.3,1372.4,1499.9,1390.3,637.0,764.6 -2.32881834456386,0.6709410394381654,1.1780972450961724,928.9,1666.6,1885.8,931.9,769.1,816.2 -2.328811440436553,0.6709480284884874,1.3089969389957472,1385.1,2360.9,2527.2,717.4,849.2,637.7 -2.3288214144928627,0.6709436980850301,1.4398966328953218,1223.7,2338.9,2280.7,608.0,645.8,587.5 -2.328890056431805,0.6709284930882449,1.5707963267948966,1199.1,2228.9,2228.6,563.0,593.3,593.2 -2.3288791777326696,0.6709280572103153,1.7016960206944713,1266.7,2280.5,2181.4,565.8,588.3,646.8 -2.3288716435654058,0.6709250003014136,1.832595714594046,1453.3,1469.2,1090.5,625.0,637.2,765.0 -2.328923963047408,0.6709583953786225,1.9634954084936205,1834.6,987.1,768.3,772.5,771.8,992.8 -2.328939036304413,0.6709759461254887,2.0943951023931953,2513.7,763.8,636.7,857.8,1095.0,1371.3 -2.3289286130018807,0.6709537300067969,2.2252947962927703,2259.0,646.5,588.0,608.5,1304.5,1246.0 -2.3289340261514435,0.6709737637414952,2.356194490192345,2199.5,593.0,593.7,562.5,1228.4,1228.9 -2.32893161575488,0.6710018845498145,2.4870941840919194,2239.7,588.0,647.2,566.2,1246.8,1306.0 -2.328936713762481,0.670990906641846,2.6179938779914944,1112.3,637.9,765.7,624.9,1372.6,1500.7 -2.3289248133144183,0.6710059429539703,2.748893571891069,738.1,769.8,817.6,770.7,1670.9,1891.1 -2.3289352287669693,0.6709982869837361,2.8797932657906435,624.0,849.3,637.1,1116.0,2364.5,2527.0 -2.328927477060452,0.6710033307511105,3.010692959690218,565.5,646.8,588.0,1267.4,2339.7,2280.6 -2.3289580384578312,0.7712862041676227,0.0,663.0,593.1,593.3,1098.9,2228.7,2228.7 -2.328948220059391,0.7706747398213913,0.1308996938995747,712.8,588.1,647.4,1121.5,2282.0,2341.8 -2.328986315556567,0.7706869908621852,0.2617993877991494,832.7,637.1,764.5,1244.0,1672.4,1292.4 -2.3290243936114714,0.7707113808161332,0.39269908169872414,772.0,771.1,991.7,1530.4,1129.7,910.4 -2.3290536628421514,0.7707450479973859,0.5235987755982988,625.2,1091.1,1256.9,2178.9,881.3,753.3 -2.3290817813070706,0.7707946645994757,0.6544984694978736,566.2,1202.3,1143.2,2303.0,750.7,691.6 -2.3290873444320948,0.7708240671360913,0.7853981633974483,563.3,1129.1,1128.5,2198.9,693.5,692.8 -2.329086707539408,0.7708857744166893,0.916297857297023,609.0,1142.7,1201.2,2259.1,691.3,750.3 -2.329080046646892,0.7709124048300957,1.0471975511965976,716.9,1256.5,1383.7,1592.1,752.3,879.5 -2.3290731272709415,0.770922869897108,1.1780972450961724,928.0,1524.7,1743.0,1074.5,909.4,797.5 -2.329026725272675,0.7709673274084674,1.3089969389957472,1244.7,2158.5,2528.7,833.2,765.7,637.9 -2.328992128952843,0.7709877974413366,1.4398966328953218,1120.6,2339.2,2280.5,711.6,646.0,587.5 -2.329014267947041,0.7709835059855039,1.5707963267948966,1099.0,2228.6,2228.4,662.9,593.4,593.0 -2.328959824540419,0.7709822687842052,1.7016960206944713,1163.1,2279.8,2338.1,669.0,588.2,646.4 -2.3289132344215435,0.7709686648768379,1.832595714594046,1336.9,1670.7,1291.1,740.3,636.8,764.4 -2.32893283106964,0.7709824434073835,1.9634954084936205,1691.6,1098.1,910.0,913.1,770.8,991.8 -2.3289235497479948,0.7709745423703951,2.0943951023931953,2461.7,879.9,752.4,717.2,1093.2,1256.7 -2.3288971738056485,0.7709243686117817,2.2252947962927703,2259.5,750.4,691.4,608.6,1201.5,1142.6 -2.328895097656891,0.7709151777196817,2.356194490192345,2199.7,693.0,693.6,562.5,1128.5,1129.1 -2.3288935070308714,0.7709149374078061,2.4870941840919194,2302.9,691.4,750.4,566.1,1142.9,1202.2 -2.32890572531562,0.7708792228662988,2.6179938779914944,1313.2,753.3,880.8,624.6,1256.6,1384.4 -2.328907009391601,0.7708735603100949,2.748893571891069,911.1,910.5,798.9,770.0,1528.3,1748.2 -2.3289337127191225,0.7708508515511296,2.8797932657906435,739.8,764.9,637.4,1114.0,2161.7,2528.1 -2.3289442999955603,0.7708465013757293,3.010692959690218,669.0,647.0,588.1,1164.1,2340.3,2281.8 -2.329001544693374,0.8711586911475271,0.0,762.9,593.1,593.1,999.0,2228.8,2228.9 -2.3289701665988822,0.8711582689692694,0.1308996938995747,816.3,588.2,647.3,1018.0,2282.4,2387.2 -2.32891185878192,0.8711413313162435,0.2617993877991494,947.9,637.2,764.5,1128.3,1871.4,1491.7 -2.3288554162016863,0.8711068104328683,0.39269908169872414,769.0,771.0,991.7,1388.9,1270.5,1051.2 -2.328810260582672,0.8710608934310515,0.5235987755982988,625.0,1091.0,1141.6,1980.0,996.8,868.8 -2.3287901789885255,0.8710208736852287,0.6544984694978736,566.1,1098.9,1039.8,2303.1,854.0,795.0 -2.3287738328457928,0.8709568142429049,0.7853981633974483,563.1,1028.9,1028.3,2198.9,793.5,792.9 -2.3287758323022776,0.8709299829804675,0.916297857297023,585.9,1039.3,1097.9,2258.7,794.7,853.6 -2.3287931087611726,0.8708773648876353,1.0471975511965976,716.7,1140.8,1268.2,1792.2,867.7,995.1 -2.3288267368271827,0.8708226121217908,1.1780972450961724,927.7,1383.4,1602.5,1216.3,993.4,772.4 -2.3288314867577813,0.8708188672706874,1.3089969389957472,1129.1,1958.9,2338.0,949.0,765.7,637.9 -2.3288544736563694,0.8708083545269183,1.4398966328953218,1017.2,2339.7,2280.9,815.0,646.1,587.6 -2.328936352285723,0.870790195016957,1.5707963267948966,999.0,2229.0,2228.4,762.9,593.4,593.0 -2.3289377298471345,0.8707906554943492,1.7016960206944713,1059.6,2280.4,2406.9,772.7,588.1,646.4 -2.3289407255599293,0.8707919310686452,1.832595714594046,1221.6,1870.1,1490.6,855.8,636.9,764.5 -2.3290016073301096,0.8708314527732264,1.9634954084936205,1549.7,1270.1,1051.1,927.7,771.0,991.8 -2.3290228587273156,0.8708562206591561,2.0943951023931953,2261.4,995.5,867.9,717.3,1093.5,1141.2 -2.3290158552618156,0.8708421597783298,2.2252947962927703,2259.4,853.9,794.9,608.7,1098.3,1039.2 -2.3290224600544804,0.8708702761391618,2.356194490192345,2199.6,793.0,793.4,562.7,1028.6,1028.8 -2.3290196205882827,0.8709056067867369,2.4870941840919194,2302.7,794.9,854.0,566.2,1039.5,1098.5 -2.329022334904544,0.8709011226761243,2.6179938779914944,1512.6,868.7,996.3,624.5,1140.9,1268.8 -2.329007474315359,0.8709212672604842,2.748893571891069,1052.8,990.6,770.6,770.2,1386.7,1606.6 -2.3290137666217707,0.8709176519068738,2.8797932657906435,855.4,764.9,637.4,1114.2,1962.5,2341.9 -2.3290015337109686,0.8709255057669893,3.010692959690218,772.5,647.0,588.1,1060.5,2340.4,2281.3 -2.82907496401081,0.1708281859172951,0.0,63.0,93.1,93.1,1699.0,2729.0,2728.8 -2.8290903600703063,0.17141028533996594,0.1308996938995747,91.6,119.2,129.6,1742.7,963.7,233.3 -2.8289969945026643,0.17138065243769018,0.2617993877991494,116.7,59.3,186.9,1937.7,474.6,95.2 -2.828940551081692,0.17134433198369625,0.39269908169872414,62.7,63.0,283.8,2380.8,282.1,63.0 -2.8289032055822894,0.1713050787513648,0.5235987755982988,150.4,95.3,474.6,3186.6,187.4,59.8 -2.8288895993923564,0.17127593046792922,0.6544984694978736,48.3,234.7,1054.7,2820.4,129.5,70.5 -2.828876580492458,0.17122484944944305,0.7853981633974483,63.1,1728.7,1728.5,2698.8,93.7,93.3 -2.8288777634186726,0.1712105071122385,0.916297857297023,91.3,1763.7,1822.4,916.7,70.6,129.5 -2.8288907832942423,0.1711689231024558,1.0471975511965976,139.2,1949.7,2076.9,393.6,59.5,94.9 -2.828917694537876,0.17112308102330642,1.1780972450961724,222.7,2371.7,2591.2,224.2,63.3,110.3 -2.828914112020535,0.1711250512632423,1.3089969389957472,393.4,3233.8,3106.1,139.8,95.6,200.7 -2.828928181148598,0.1711170393606476,1.4398966328953218,837.2,2856.2,2798.2,91.0,128.5,70.1 -2.8290015230566308,0.17109924924436304,1.5707963267948966,1698.9,2729.3,2728.7,63.3,93.2,93.1 -2.828995513099733,0.1710977450086597,1.7016960206944713,1783.6,1065.4,238.0,48.6,122.5,129.3 -2.8289926512789214,0.17109522650695186,1.832595714594046,2031.3,474.4,95.5,47.1,58.9,186.6 -2.829049112480108,0.17113042519694077,1.9634954084936205,2542.8,282.3,63.3,63.7,62.5,283.6 -2.8290673194213665,0.17115076664317308,2.0943951023931953,3091.5,186.7,59.5,117.4,95.5,475.9 -2.8290586532850046,0.17113208221073717,2.2252947962927703,2776.6,129.4,70.7,90.9,235.6,1059.9 -2.82906445421117,0.17115583623186303,2.356194490192345,2699.6,93.2,93.8,62.4,1728.2,1728.8 -2.829061231059869,0.17118728146852047,2.4870941840919194,316.4,70.5,129.6,48.3,1764.4,1823.1 -2.8290643874282755,0.1711789646782924,2.6179938779914944,117.5,59.9,94.5,46.5,1950.5,2078.4 -2.8290500821412494,0.17119563370185364,2.748893571891069,62.7,62.7,110.3,63.2,2377.9,2597.2 -2.829057793794338,0.1711886367822706,2.8797932657906435,46.6,95.0,200.4,117.2,3232.1,3104.9 -2.8290475582998433,0.17119344444085582,3.010692959690218,48.2,129.2,70.4,318.6,2857.8,2798.9 -2.829033921785187,0.17119755031961414,0.0,63.3,93.0,93.0,1698.8,2728.9,2729.1 -2.8290590420956034,0.1711999304896643,0.1308996938995747,91.6,118.9,129.6,1742.5,964.1,233.6 -2.829021250983699,0.17118730783115232,0.2617993877991494,116.8,59.3,186.9,1937.9,474.8,95.3 -2.829007725446448,0.17117784917495538,0.39269908169872414,62.7,63.0,283.8,2380.4,282.2,63.1 -2.829001647909438,0.17117214068904985,0.5235987755982988,150.4,95.4,474.7,3186.3,187.5,59.9 -2.8290077587492317,0.17117977234694992,0.6544984694978736,48.4,234.9,1054.8,2820.4,129.5,70.5 -2.829003591431956,0.17116666228130795,0.7853981633974483,63.2,1728.7,1728.3,2699.0,93.8,93.3 -2.829003675662168,0.171188170895622,0.916297857297023,91.4,1763.5,1822.6,916.7,70.6,129.5 -2.8290069930468507,0.17117863156485624,1.0471975511965976,139.2,1950.0,2076.9,393.5,59.4,95.0 -2.8290174977342866,0.17115913977671138,1.1780972450961724,222.7,2371.8,2590.9,224.1,63.3,110.3 -2.8289932372914826,0.1711805886653055,1.3089969389957472,393.5,3233.5,3106.1,139.8,95.5,200.7 -2.8289840351847486,0.17118510652287533,1.4398966328953218,923.2,2856.0,2798.3,91.0,128.5,70.1 -2.8290332326075776,0.17117292004905793,1.5707963267948966,1698.8,2728.8,2728.4,63.2,93.3,93.1 -2.829004660143493,0.1711707369889517,1.7016960206944713,1784.0,1065.7,237.8,48.5,122.7,129.3 -2.828981749693134,0.17116221987386004,1.832595714594046,2030.9,474.4,95.4,47.0,58.8,186.5 -2.8290215160549685,0.17118701716841644,1.9634954084936205,2542.8,282.2,63.2,63.6,62.5,283.5 -2.8290273762559943,0.17119414884468642,2.0943951023931953,3091.1,186.6,59.4,117.4,95.5,475.9 -2.8290108732866557,0.17116086433369504,2.2252947962927703,2776.7,129.4,70.7,90.9,235.5,1059.5 -2.829013166304002,0.17116953166976723,2.356194490192345,2699.5,93.2,93.8,62.4,1727.9,1728.7 -2.82901046299703,0.17118658839603507,2.4870941840919194,316.4,70.4,129.6,48.3,1763.9,1823.1 -2.8290174762537315,0.17116564733816508,2.6179938779914944,117.5,59.9,94.5,46.5,1950.6,2078.2 -2.8290097262570755,0.1711718898432557,2.748893571891069,62.7,62.7,110.2,63.1,2377.4,2597.8 -2.829025709804532,0.1711571933403666,2.8797932657906435,46.6,95.0,200.4,117.2,3232.7,3104.9 -2.829024715612753,0.17131559054428447,3.010692959690218,48.2,129.2,70.4,318.5,2857.6,2798.3 -2.2288652505549025,0.37120229944974836,0.0,263.3,692.8,692.9,1498.7,2128.9,2129.0 -2.2289395011375808,0.3710190393035857,0.1308996938995747,298.7,691.6,751.0,1535.4,1817.6,1001.5 -2.2290911447210475,0.3710668840239706,0.2617993877991494,370.5,752.8,880.4,1706.5,873.6,494.0 -2.229014430176658,0.37101843493798214,0.39269908169872414,506.9,912.9,1133.8,2097.2,533.5,345.3 -2.2289972964372353,0.37100154575274225,0.5235987755982988,740.6,1290.8,1669.9,2493.3,418.6,291.0 -2.2290044598352106,0.3710115348740879,0.6544984694978736,669.7,1616.2,1557.1,2199.4,336.5,277.4 -2.229002020655298,0.37100608907369925,0.7853981633974483,663.3,1529.0,1528.3,2098.8,293.6,293.1 -2.2290021193899334,0.3710366960499798,0.916297857297023,712.5,1556.6,1615.6,1691.5,277.5,336.4 -2.229003294473264,0.3710359993177055,1.0471975511965976,832.5,1718.3,1845.7,792.9,290.3,417.7 -2.22900976732134,0.3710240737530872,1.1780972450961724,1069.5,2089.3,2308.1,476.4,345.4,564.4 -2.2289802646053354,0.371051611728032,1.3089969389957472,1589.0,2540.3,2413.0,370.9,493.7,753.4 -2.2289648832009785,0.371060651920746,1.4398966328953218,1534.0,2235.7,2177.4,297.8,749.3,690.9 -2.2290072861982813,0.3710508991848551,1.5707963267948966,1499.1,2129.0,2128.3,263.1,693.3,693.2 -2.2289720521896683,0.3710494132306956,1.7016960206944713,1576.8,1845.7,931.3,255.3,691.6,750.0 -2.2289428667405207,0.371040035742338,1.832595714594046,1799.3,872.9,493.7,278.1,752.5,880.2 -2.2289771801118596,0.37106221611538026,1.9634954084936205,2258.5,564.4,345.3,346.9,912.9,1133.9 -2.2289789025208973,0.3710654916946441,2.0943951023931953,2398.7,417.7,290.3,516.3,1293.4,1674.0 -2.2289596625753973,0.37102779884816917,2.2252947962927703,2155.7,336.3,277.5,712.0,1615.4,1556.9 -2.228960786624613,0.37103171379799194,2.356194490192345,2099.5,293.1,293.6,662.6,1528.4,1528.8 -2.228958547709415,0.3710441225370482,2.4870941840919194,1087.4,277.4,336.5,669.5,1557.0,1616.4 -2.2289671530645085,0.37101932348890876,2.6179938779914944,515.7,291.0,418.6,740.2,1719.3,1846.9 -2.2289621477780606,0.37102255702154063,2.748893571891069,345.4,345.3,565.3,911.7,2094.2,2314.5 -2.228981228323801,0.3710060548784764,2.8797932657906435,277.5,493.7,752.8,1314.4,2539.6,2412.2 -2.2289834674010853,0.3710052621661595,3.010692959690218,255.1,750.4,691.6,1577.9,2236.8,2177.6 -2.2290264633562265,0.4712975697531905,0.0,363.0,693.0,693.1,1399.2,2129.1,2128.9 -2.228991561946271,0.47129602487706945,0.1308996938995747,402.1,691.7,751.2,1432.2,2116.1,1385.2 -2.228931576236414,0.47127771480015257,0.2617993877991494,486.1,752.7,880.3,1591.4,1073.0,693.4 -2.228874332046531,0.4712418763373012,0.39269908169872414,648.5,913.0,1133.6,1955.7,705.7,486.3 -2.228828903960984,0.4711948604603562,0.5235987755982988,740.7,1290.6,1625.6,2493.5,534.1,406.5 -2.2288086340339364,0.47115388314808837,0.6544984694978736,669.6,1512.5,1453.7,2199.5,439.9,380.9 -2.228792303561469,0.471089141052621,0.7853981633974483,663.2,1428.9,1428.3,2098.6,393.7,393.1 -2.228794159628968,0.4710616148125164,0.916297857297023,712.4,1453.3,1511.7,2079.2,381.0,439.8 -2.228811270800912,0.4710082772114217,1.0471975511965976,832.3,1603.1,1730.2,992.5,405.9,533.2 -2.228877706583318,0.4709001634299739,1.1780972450961724,1069.4,1948.0,2167.4,649.4,486.5,705.6 -2.22885130222161,0.47092455737294925,1.3089969389957472,1588.7,2540.4,2412.9,486.5,693.1,829.1 -2.22886607269597,0.4709173448651345,1.4398966328953218,1431.0,2235.6,2177.4,401.3,875.3,690.9 -2.228949361495079,0.47089812338709147,1.5707963267948966,1398.8,2129.2,2128.7,363.2,693.2,693.0 -2.2289553501591666,0.4708979305885834,1.7016960206944713,1473.2,2149.4,1406.8,358.8,691.6,750.0 -2.2289637266546816,0.4708998780210314,1.832595714594046,1684.0,1072.3,649.4,393.8,752.6,880.0 -2.2290295807837657,0.47094177070643095,1.9634954084936205,2117.1,705.7,486.5,488.7,912.8,1133.9 -2.229054691203004,0.4709701108193223,2.0943951023931953,2398.9,533.3,405.8,715.9,1293.5,1603.0 -2.229050293271689,0.47096014827063426,2.2252947962927703,2155.9,439.9,381.1,711.9,1512.0,1453.2 -2.2290580621420912,0.47099270809240257,2.356194490192345,2099.8,393.1,393.6,662.5,1428.4,1428.9 -2.2290548602794322,0.47103241994763034,2.4870941840919194,1473.1,380.9,440.0,669.7,1453.4,1512.6 -2.2290561649698466,0.4710315988825202,2.6179938779914944,715.0,406.6,534.3,740.4,1603.5,1731.2 -2.2290656293697544,0.47101213051791,2.748893571891069,486.8,486.7,706.7,911.8,1952.7,2172.6 -2.229043775876333,0.4710336927219516,2.8797932657906435,393.1,693.1,829.6,1314.1,2539.6,2411.4 -2.2290217037951376,0.4710458744480246,3.010692959690218,358.6,838.5,691.5,1474.5,2236.6,2177.6 -2.2290449564412413,0.5713268564136571,0.0,463.0,693.0,693.1,1298.8,2128.3,2128.9 -2.2290223577673696,0.5707029742629304,0.1308996938995747,505.7,691.7,750.9,1328.6,2178.8,1770.5 -2.2290358539821526,0.5707076323065587,0.2617993877991494,601.6,752.9,880.3,1475.2,1272.8,893.1 -2.2290665705409767,0.5707274851201778,0.39269908169872414,790.0,912.8,1133.6,1813.6,847.1,627.8 -2.2290936549190614,0.5707589914229281,0.5235987755982988,740.8,1290.4,1488.2,2493.3,649.8,522.1 -2.2291209587891334,0.5708075419721841,0.6544984694978736,669.8,1409.1,1350.5,2199.0,543.5,484.4 -2.229126161999612,0.5708363349017536,0.7853981633974483,663.3,1329.0,1328.6,2098.9,493.5,492.8 -2.229125252206411,0.5708975009686248,0.916297857297023,712.3,1350.0,1408.7,2155.7,484.4,543.1 -2.2291184481303374,0.5709235927657583,1.0471975511965976,832.4,1487.5,1614.7,1192.5,521.2,648.4 -2.229111558461402,0.5709335923738519,1.1780972450961724,1069.0,1807.0,2026.0,790.8,627.1,846.4 -2.2290652936579853,0.5709775826765884,1.3089969389957472,1475.9,2540.9,2413.2,602.0,855.7,753.5 -2.229030963204677,0.5709976153521843,1.4398966328953218,1327.4,2235.7,2222.8,504.7,749.4,690.9 -2.2290534889647464,0.5709931467998226,1.5707963267948966,1299.1,2129.0,2128.7,462.9,693.3,693.1 -2.228999446771633,0.5709918562384899,1.7016960206944713,1369.8,2176.8,1797.1,462.1,691.7,749.9 -2.2289532443001696,0.5709782883076471,1.832595714594046,1568.2,1271.4,892.1,509.1,752.5,880.1 -2.2289731243944235,0.5709923237162804,1.9634954084936205,1975.0,846.5,627.4,629.7,912.7,1133.3 -2.228963963548622,0.5709847984279846,2.0943951023931953,2398.8,648.6,521.3,832.9,1293.0,1487.8 -2.2289375941531557,0.5709349485003479,2.2252947962927703,2155.8,543.3,484.5,712.1,1408.7,1349.8 -2.228935381643122,0.5709260502533466,2.356194490192345,2099.8,493.1,493.5,662.5,1328.4,1329.2 -2.2289335025355137,0.5709260559034728,2.4870941840919194,1859.3,484.3,543.4,669.5,1350.1,1409.5 -2.228945455200774,0.5708904237159427,2.6179938779914944,914.3,522.0,649.5,740.2,1488.1,1615.5 -2.2289463966594316,0.5708847741448078,2.748893571891069,628.1,627.9,847.9,911.5,1811.2,2030.8 -2.228972883706021,0.5708619667341166,2.8797932657906435,508.5,855.0,752.8,1313.6,2540.5,2412.1 -2.2289833238466077,0.5708574822702315,3.010692959690218,462.1,750.4,691.4,1371.0,2237.0,2178.0 -2.2290359183410104,0.6711571622898993,0.0,562.8,693.2,692.9,1199.2,2129.1,2128.7 -2.22900765857432,0.6711567633574889,0.1308996938995747,609.1,691.6,751.0,1225.1,2178.7,2154.3 -2.2289523500705966,0.6711407300572234,0.2617993877991494,717.1,752.7,880.1,1359.7,1472.2,1048.4 -2.2288983800912554,0.6711078148472263,0.39269908169872414,910.3,912.6,1133.3,1672.4,987.9,768.7 -2.22885504012945,0.6710639946676578,0.5235987755982988,740.8,1290.1,1372.7,2378.9,765.3,637.6 -2.2288359668678055,0.6710262480388081,0.6544984694978736,669.5,1305.8,1246.9,2199.9,646.9,587.9 -2.2288199800981237,0.6709645381680251,0.7853981633974483,663.2,1229.1,1228.6,2098.7,593.5,592.9 -2.22882165577033,0.6709398111851723,0.916297857297023,712.2,1246.0,1304.8,2297.0,587.8,646.7 -2.228838115831466,0.6708889785630026,1.0471975511965976,832.3,1372.0,1499.0,1392.0,636.8,764.0 -2.2288706173682966,0.6708356627237575,1.1780972450961724,1069.2,1665.6,1884.5,932.7,768.4,914.0 -2.2288740392020503,0.6708328633257374,1.3089969389957472,1360.2,2358.1,2413.0,717.8,881.1,753.4 -2.228895634651332,0.6708228323170404,1.4398966328953218,1223.9,2235.8,2177.1,608.0,749.5,690.9 -2.2289761722425143,0.6708049109328418,1.5707963267948966,1199.1,2128.8,2128.7,563.1,693.3,693.0 -2.228976331781202,0.6708052815622576,1.7016960206944713,1266.3,2177.1,2187.3,565.6,691.6,750.0 -2.2289782721800164,0.6708061748351362,1.832595714594046,1452.6,1470.9,1091.6,624.7,752.4,880.1 -2.229038234947592,0.6708452105010057,1.9634954084936205,1833.1,987.8,768.8,771.7,912.7,1133.5 -2.2290587189157645,0.6708694041923158,2.0943951023931953,2398.6,738.7,637.0,871.3,1293.2,1372.3 -2.2290511580607504,0.6708546193720923,2.2252947962927703,2156.0,646.8,588.1,712.1,1305.0,1246.4 -2.229057375697106,0.67088194501064,2.356194490192345,2099.5,593.0,593.4,662.4,1228.3,1228.9 -2.2290542903249175,0.6709164870637689,2.4870941840919194,2160.0,588.0,646.8,669.6,1246.7,1305.9 -2.229057017948513,0.6709111817493212,2.6179938779914944,1113.5,637.6,765.2,740.2,1372.5,1499.9 -2.2290422908373837,0.6709305925172753,2.748893571891069,769.6,769.3,911.8,911.7,1670.1,1889.7 -2.229048960731211,0.6709263295655605,2.8797932657906435,624.1,880.4,752.8,1313.8,2361.3,2411.9 -2.229037242504315,0.670933699653306,3.010692959690218,565.6,750.3,691.5,1267.5,2236.8,2177.9 -2.229063026142413,0.7712130774061705,0.0,662.9,693.0,693.1,1099.2,2129.2,2129.0 -2.2290034262971523,0.7706549105229306,0.1308996938995747,712.7,668.9,750.9,1121.2,2178.7,2238.1 -2.2290336656971763,0.770664851484828,0.2617993877991494,832.6,752.8,880.2,1244.0,1671.4,1291.9 -2.2290719408555204,0.7706895681322838,0.39269908169872414,910.0,913.0,1133.5,1530.2,1129.2,910.2 -2.229103053388162,0.7707255159758155,0.5235987755982988,740.7,1290.4,1257.1,2179.8,881.2,753.4 -2.2287881435196897,0.7710244043868737,0.6544984694978736,669.6,1201.8,1143.1,2199.2,750.4,691.6 -2.2287843169504526,0.7710105126008584,0.7853981633974483,663.4,1129.1,1128.4,2099.0,693.5,693.1 -2.2287856328661113,0.7710131486957126,0.916297857297023,712.6,1142.6,1202.0,2156.1,691.7,750.4 -2.2287967694347177,0.7709812269901211,1.0471975511965976,832.7,1256.7,1383.8,1589.8,752.7,879.9 -2.228820949634251,0.7709423017872292,1.1780972450961724,1070.1,1525.7,1744.7,1073.8,910.4,957.4 -2.2288138097579417,0.7709494985579406,1.3089969389957472,1243.7,2161.1,2412.0,832.9,1022.0,753.3 -2.2288235187394476,0.7709453026049617,1.4398966328953218,1120.2,2235.7,2176.8,711.5,749.3,691.0 -2.2288918873913364,0.7709301508830213,1.5707963267948966,1098.8,2128.7,2128.9,663.1,693.3,693.1 -2.228880755979194,0.7709297014763983,1.7016960206944713,1163.0,2176.9,2235.4,669.2,691.7,727.6 -2.228872997893331,0.7709265772346954,1.832595714594046,1337.7,1668.3,1289.5,740.6,752.8,880.7 -2.2289251311425406,0.770959855917607,1.9634954084936205,1692.8,1128.3,878.3,914.1,913.4,1134.5 -2.228940065500792,0.7709772597436957,2.0943951023931953,2398.1,879.4,752.2,832.4,1295.0,1255.9 -2.2289295492418204,0.7709548843165832,2.2252947962927703,2155.6,750.3,691.4,711.9,1201.1,1142.6 -2.228934915121353,0.7709747517116308,2.356194490192345,2099.7,692.9,693.8,662.5,1128.3,1129.2 -2.228932502592804,0.7710027094979848,2.4870941840919194,2199.9,691.6,750.7,669.8,1143.0,1202.4 -2.228937633136769,0.7709915865177741,2.6179938779914944,1311.1,753.7,881.3,740.6,1257.0,1384.8 -2.2289258006408947,0.7710064974381667,2.748893571891069,910.5,911.5,958.9,912.4,1529.2,1749.7 -2.2289363039739283,0.7709987456473191,2.8797932657906435,739.5,1021.0,752.7,1315.6,2164.9,2411.1 -2.228928655533019,0.7710037246163874,3.010692959690218,669.2,750.3,691.5,1163.6,2236.5,2177.4 -2.2289593483467294,0.871286697144432,0.0,762.8,693.0,693.1,999.0,2129.0,2128.9 -2.2289475877094667,0.8706726441546402,0.1308996938995747,816.1,691.6,750.9,1017.6,2179.2,2371.6 -2.2289855424594784,0.870684853318793,0.2617993877991494,948.1,752.7,880.1,1128.4,1872.1,1491.9 -2.2290237980275025,0.8707093533048293,0.39269908169872414,913.6,912.9,1133.5,1388.8,1270.8,1051.5 -2.2290532747082206,0.8707432396943937,0.5235987755982988,740.7,1290.5,1141.6,1980.0,996.8,869.0 -2.2290815482667123,0.8707931319389113,0.6544984694978736,669.8,1098.6,1039.6,2199.7,854.2,794.9 -2.2290871854169674,0.8708228293329126,0.7853981633974483,663.2,1029.1,1028.6,2098.8,793.5,793.1 -2.2290865497465226,0.8708848244039502,0.916297857297023,712.3,1038.9,1097.9,2155.7,795.0,853.7 -2.2290798205302296,0.8709117170234579,1.0471975511965976,832.3,1140.7,1267.9,1791.8,867.7,995.0 -2.229072774941402,0.8709223974228855,1.1780972450961724,1069.2,1383.5,1602.3,1216.2,1050.3,938.3 -2.229026211770658,0.8709670204544993,1.3089969389957472,1129.1,1959.2,2338.3,948.9,881.4,753.9 -2.228991430125047,0.8709876049038194,1.4398966328953218,1017.1,2235.9,2177.7,815.2,749.6,691.0 -2.2290133717941725,0.8709833627743919,1.5707963267948966,999.0,2128.7,2128.8,762.9,693.3,693.1 -2.228958742195605,0.8709821246518767,1.7016960206944713,1059.4,2176.4,2234.9,772.4,691.7,750.1 -2.228911983909102,0.8709684787536378,1.832595714594046,1221.6,1870.0,1490.7,855.9,752.4,879.9 -2.228931441086725,0.8709821709422965,1.9634954084936205,1550.1,1270.1,1051.0,1054.8,912.6,1133.5 -2.228922059178329,0.8709741559589423,2.0943951023931953,2261.4,995.4,867.9,832.7,1292.6,1141.0 -2.228895619485554,0.870923860644196,2.2252947962927703,2156.0,853.7,795.1,712.2,1098.1,1039.5 -2.228893518147588,0.8709145440618489,2.356194490192345,2099.5,793.0,793.4,662.5,1028.5,1029.1 -2.2288919410253043,0.8709141826355968,2.4870941840919194,2198.9,794.9,854.0,669.7,1039.5,1098.3 -2.228904196412231,0.870878367403233,2.6179938779914944,1512.6,868.8,996.4,740.1,1141.1,1268.7 -2.2289055451666955,0.8708726222003722,2.748893571891069,1052.6,1052.0,940.5,911.3,1386.7,1606.7 -2.22893232047561,0.8708498573178041,2.8797932657906435,855.4,880.4,752.9,1221.7,1962.4,2341.6 -2.228942985576865,0.8708454747077992,3.010692959690218,772.7,750.6,691.5,1060.7,2236.6,2178.1 -2.8290009978485706,0.17078341001690034,0.0,63.0,93.1,93.0,1699.1,2729.4,2729.2 -2.8290688755866595,0.17141838752339167,0.1308996938995747,91.6,119.2,129.6,1743.0,964.0,233.3 -2.8289853656292405,0.17139180327448056,0.2617993877991494,116.8,59.3,186.8,1937.7,474.6,95.2 -2.828930015869494,0.17135615083582945,0.39269908169872414,62.7,63.0,283.8,2381.0,282.1,63.0 -2.8288916701700515,0.17131578973576533,0.5235987755982988,150.3,95.3,474.6,3186.7,187.4,59.8 -2.8288770626204314,0.17128469086240283,0.6544984694978736,48.3,234.7,1054.7,2820.5,129.5,70.5 -2.828863530635592,0.17123131095767286,0.7853981633974483,63.1,1728.8,1728.1,2699.5,93.7,93.2 -2.828864819906947,0.1712147356729048,0.916297857297023,91.3,1763.5,1822.6,916.9,70.7,129.5 -2.8288784807382563,0.1711711394745472,1.0471975511965976,139.2,1949.5,2077.3,393.6,59.5,94.9 -2.8289064381479054,0.17112361716660263,1.1780972450961724,222.6,2372.0,2591.0,224.3,63.3,110.3 -2.8289041767379053,0.17112435751597177,1.3089969389957472,393.4,3233.9,3105.9,139.8,95.6,200.7 -2.828919726722349,0.17111557282378276,1.4398966328953218,837.2,2856.3,2797.8,91.0,128.5,70.1 -2.828994595380952,0.17109739658971423,1.5707963267948966,1698.9,2728.7,2728.5,63.3,93.2,93.0 -2.828990019669013,0.1710959121736395,1.7016960206944713,1783.7,1066.0,238.1,48.6,122.5,129.3 -2.828988434339802,0.17109377400817016,1.832595714594046,2030.5,474.6,95.5,47.1,58.9,186.6 -2.8290459754311836,0.17112960447388859,1.9634954084936205,2542.3,282.3,63.3,63.7,62.5,283.5 -2.8290650041175858,0.17115074940136155,2.0943951023931953,3091.9,186.7,59.5,117.4,95.5,475.9 -2.8290568644977565,0.17113299269815374,2.2252947962927703,2776.9,129.5,70.7,91.0,235.6,1059.7 -2.8290629187583827,0.17115771528916368,2.356194490192345,2699.2,93.2,93.8,62.4,1728.0,1728.8 -2.8290597058520577,0.17119008051047757,2.4870941840919194,316.5,70.5,129.6,48.4,1764.2,1823.1 -2.829062624759883,0.17118259624339793,2.6179938779914944,117.5,59.9,94.5,46.5,1950.3,2078.1 -2.8290479293386297,0.17119994485553547,2.748893571891069,62.7,62.7,110.3,63.2,2377.4,2598.3 -2.8290551037705733,0.17119345999098834,2.8797932657906435,46.6,95.0,200.4,117.2,3233.2,3104.9 -2.829044264504704,0.1711985912155456,3.010692959690218,48.2,129.2,70.4,318.6,2857.1,2798.5 -2.8290299869520665,0.1712028330918871,0.0,63.3,93.0,93.0,1698.5,2729.3,2728.8 -2.829054416305752,0.17120516147459353,0.1308996938995747,91.7,119.0,129.6,1742.8,964.3,233.7 -2.829016176456989,0.17119237708797064,0.2617993877991494,116.8,59.3,186.9,1937.6,474.8,95.4 -2.8290022549919978,0.1711826342951539,0.39269908169872414,62.7,63.0,283.8,2381.0,282.2,63.1 -2.8289958767681918,0.17117655764697104,0.5235987755982988,150.4,95.4,474.7,3187.0,187.5,59.9 -2.829001828376681,0.17118380232668096,0.6544984694978736,48.4,234.8,1054.9,2820.9,129.5,70.5 -2.8289975928904774,0.17117028825175362,0.7853981633974483,63.2,1728.8,1728.3,2698.7,93.8,93.3 -2.8289989215770195,0.17119618180220209,0.916297857297023,91.4,1763.7,1822.5,916.8,70.6,129.5 -2.8290032710305617,0.17118331535642906,1.0471975511965976,139.2,1949.4,2077.1,393.6,59.4,95.0 -2.8290142046153126,0.1711631619338141,1.1780972450961724,222.7,2371.9,2591.1,224.2,63.3,110.3 -2.828989879794052,0.17118468951281818,1.3089969389957472,393.5,3233.0,3106.4,139.8,95.5,200.8 -2.828980363007394,0.17118940042752184,1.4398966328953218,923.1,2856.1,2798.2,91.0,128.5,70.1 -2.829029139749703,0.17117728244979724,1.5707963267948966,1699.0,2728.7,2728.8,63.2,93.3,93.1 -2.8290001540498997,0.17117506485045308,1.7016960206944713,1783.5,1065.7,238.0,48.6,122.7,129.3 -2.8289768701573936,0.17116643330709014,1.832595714594046,2030.7,474.5,95.5,47.0,58.8,186.6 -2.829016339111686,0.1711910062606372,1.9634954084936205,2542.5,282.2,63.2,63.6,62.5,283.6 -2.8290220004188895,0.1711978540842105,2.0943951023931953,3091.7,186.7,59.5,117.4,95.5,475.9 -2.8290053760415566,0.17116429248347864,2.2252947962927703,2776.6,129.4,70.7,90.9,235.5,1059.2 -2.829007631121303,0.1711726830586433,2.356194490192345,2699.5,93.2,93.8,62.4,1728.2,1728.9 -2.829004977366465,0.17118947270570883,2.4870941840919194,316.5,70.4,129.6,48.3,1764.2,1823.1 -2.829012070176423,0.17116832043555386,2.6179938779914944,117.6,59.9,94.5,46.5,1951.0,2078.4 -2.8290044673944053,0.17117438080144765,2.748893571891069,62.7,62.7,110.3,63.1,2377.1,2597.8 -2.829020595688756,0.17115955830212126,2.8797932657906435,46.6,95.0,200.4,117.2,3232.8,3105.2 -2.829019760207617,0.17115937753956145,3.010692959690218,48.2,129.2,70.4,318.5,2857.9,2798.7 -2.12888344963668,0.37119166612315535,0.0,263.3,793.0,793.1,1498.7,2029.1,2029.0 -2.1289482023926203,0.3710218288227798,0.1308996938995747,298.6,795.2,854.4,1535.7,1817.6,1001.5 -2.1290976314433223,0.3710690004023467,0.2617993877991494,370.6,868.4,996.0,1706.6,873.6,450.0 -2.1290190725510256,0.371019396043343,0.39269908169872414,506.9,1054.6,1275.3,2097.2,564.5,345.2 -2.1290015926359978,0.37100214852004454,0.5235987755982988,791.3,1490.0,1719.1,2377.5,418.6,291.0 -2.129008754809066,0.37101216628033096,0.6544984694978736,773.2,1616.1,1557.1,2095.8,336.5,277.4 -2.1290063383417075,0.3710069020932145,0.7853981633974483,763.1,1528.9,1528.3,1999.0,293.7,293.1 -2.129006408617461,0.3710377243990395,0.916297857297023,816.1,1556.4,1614.9,1692.0,277.5,336.3 -2.1290074990345698,0.37103722776065906,1.0471975511965976,948.0,1718.3,1845.4,749.1,290.3,417.6 -2.129013845428346,0.3710254626011136,1.1780972450961724,1210.5,2089.0,2308.3,507.4,345.3,564.5 -2.1289841940633423,0.3710531123455809,1.3089969389957472,1706.9,2424.7,2297.3,370.9,493.7,843.7 -2.1289686548681575,0.371062217966287,1.4398966328953218,1534.1,2177.9,2073.4,297.8,852.7,794.4 -2.1290109019173524,0.37105248855344364,1.5707963267948966,1498.8,2029.1,2028.5,263.1,793.3,793.1 -2.128975526723274,0.3710509912068265,1.7016960206944713,1576.3,1846.0,1017.0,255.3,795.0,853.5 -2.128946217214458,0.3710415752562133,1.832595714594046,1799.7,872.9,493.8,278.0,868.2,995.8 -2.1289804250750985,0.37106369548581464,1.9634954084936205,2258.9,564.4,345.3,346.8,1054.7,1275.4 -2.1289820636520767,0.37106689659480585,2.0943951023931953,2283.2,417.6,290.3,516.3,1493.2,1718.7 -2.128962761513452,0.3710617485614631,2.2252947962927703,2052.5,336.3,277.5,815.7,1615.4,1556.8 -2.12896373272481,0.37103228414891176,2.356194490192345,1999.8,293.1,293.7,762.4,1528.5,1528.9 -2.1289615160965503,0.3710450798225866,2.4870941840919194,1087.4,277.4,336.5,773.2,1557.0,1616.1 -2.128970094396931,0.37102027505834667,2.6179938779914944,471.9,291.0,418.7,855.8,1719.2,1847.0 -2.1289651161078855,0.37102342638061514,2.748893571891069,345.4,345.4,565.3,1052.8,2094.3,2314.4 -2.1289842620592516,0.3710068352789888,2.8797932657906435,277.5,493.6,843.1,1513.7,2424.0,2296.3 -2.128986591957067,0.37100597500213994,3.010692959690218,255.1,854.0,795.0,1577.7,2133.0,2074.7 -2.1290297154640814,0.47129838114400746,0.0,363.0,793.1,793.1,1398.9,2029.1,2029.1 -2.1289948995958734,0.4712968309387804,0.1308996938995747,402.0,795.1,854.6,1432.2,2075.1,1385.0 -2.1289349814906893,0.47127854068335506,0.2617993877991494,486.0,868.3,996.0,1590.9,1072.9,693.2 -2.1288777860176165,0.4712427386864957,0.39269908169872414,648.6,1054.4,1275.2,1955.7,705.6,486.3 -2.1288323871148984,0.4711957695687188,0.5235987755982988,856.3,1489.8,1603.6,2378.0,534.2,406.4 -2.1288121265261,0.4711548419598486,0.6544984694978736,773.2,1512.9,1453.6,2096.1,440.0,381.0 -2.128795787448342,0.47109014659771953,0.7853981633974483,763.2,1429.0,1428.6,1998.8,393.7,393.1 -2.128797620960576,0.47106265786391943,0.916297857297023,815.8,1453.2,1511.9,1994.0,381.1,439.8 -2.1288147010661724,0.4710093456813349,1.0471975511965976,947.9,1603.0,1730.1,992.7,405.9,533.2 -2.1288482173786636,0.47095394327743234,1.1780972450961724,1210.3,1948.4,2166.8,649.5,486.4,705.6 -2.128852880456871,0.4709493149889441,1.3089969389957472,1591.0,2424.9,2297.2,486.6,693.2,869.0 -2.128875975764971,0.4709376907865861,1.4398966328953218,1430.8,2132.4,2074.0,401.3,931.4,794.4 -2.1289582934095432,0.470918698763084,1.5707963267948966,1399.1,2029.1,2028.7,363.1,793.2,793.0 -2.128960349746384,0.47091838138559505,1.7016960206944713,1473.3,2073.2,1406.8,358.8,795.1,853.5 -2.1289642752661186,0.4709189885809595,1.832595714594046,1684.0,1072.4,693.1,393.8,868.1,995.8 -2.1290261430394826,0.4709583969618423,1.9634954084936205,2116.7,705.6,486.4,488.7,1023.3,1275.2 -2.1290482301265867,0.470983513040232,2.0943951023931953,2283.5,533.4,405.9,716.0,1493.2,1602.9 -2.1290418905804667,0.47096995676370135,2.2252947962927703,2052.4,439.9,381.0,942.0,1511.6,1453.0 -2.12904877497673,0.47099879027951586,2.356194490192345,1999.4,393.1,393.7,762.4,1428.3,1429.0 -2.129045677232848,0.4710349401166938,2.4870941840919194,1473.1,380.9,439.9,773.0,1453.4,1512.8 -2.129047913329631,0.4710309820718066,2.6179938779914944,715.0,406.5,534.3,855.9,1603.6,1731.5 -2.1290321273274513,0.47105142704226277,2.748893571891069,486.8,486.7,706.8,1053.3,1952.8,2172.7 -2.1290375809160764,0.4710476612319945,2.8797932657906435,393.1,693.1,868.3,1513.8,2423.9,2296.5 -2.129024593107176,0.47105501209842093,3.010692959690218,358.6,923.7,795.0,1474.2,2133.3,2074.4 -2.1290491732341676,0.5713333824301616,0.0,463.0,793.0,793.0,1299.0,2029.3,2028.8 -2.1289983608085534,0.5706860708436248,0.1308996938995747,505.7,795.2,854.6,1328.7,2075.1,1770.4 -2.129026910085255,0.5706954130122075,0.2617993877991494,601.6,868.5,995.7,1475.1,1272.9,849.1 -2.1290620545466923,0.5707180841867823,0.39269908169872414,790.0,1054.4,1275.1,1813.7,847.0,627.6 -2.129090398815719,0.5705507147356075,0.5235987755982988,946.6,1489.6,1488.0,2378.1,649.7,522.1 -2.128786577117599,0.5710733923577911,0.6544984694978736,773.2,1408.9,1349.8,2095.6,543.4,484.4 -2.128778575978906,0.5710409734720834,0.7853981633974483,763.3,1328.9,1328.4,1998.8,493.5,493.2 -2.1287801225932714,0.5710367309083164,0.916297857297023,816.2,1349.7,1408.8,2052.7,484.5,543.5 -2.128792095999511,0.5710019641543842,1.0471975511965976,948.4,1487.8,1615.3,1190.9,521.5,649.0 -2.1288170912749793,0.5709616078665474,1.1780972450961724,1211.5,1808.1,2027.2,790.3,627.9,847.3 -2.1288107335309254,0.5709679457908903,1.3089969389957472,1474.9,2423.8,2296.3,576.4,893.0,985.6 -2.1287832159915183,0.5709793631337801,1.4398966328953218,1327.1,2131.5,2073.5,504.6,852.8,794.6 -2.129059453601581,0.5709184276560288,1.5707963267948966,1298.9,2028.5,2028.7,463.2,793.4,793.1 -2.1289306084852524,0.5709134965813971,1.7016960206944713,1370.0,2118.6,1793.0,462.4,795.2,853.7 -2.128896748240766,0.5709021716906737,1.832595714594046,1569.0,1270.5,891.5,509.4,868.5,996.4 -2.1289499744593883,0.5709359409337065,1.9634954084936205,1976.7,815.0,627.2,630.7,1055.2,1276.5 -2.1289715124858364,0.5709602684917368,2.0943951023931953,2282.4,648.4,521.3,916.6,1494.7,1487.1 -2.1289664797761594,0.5709480055941931,2.2252947962927703,2052.1,543.1,484.6,815.5,1408.1,1349.4 -2.1289745087105656,0.5709792274817367,2.356194490192345,1999.3,493.1,493.6,762.6,1328.3,1329.1 -2.1289717007476847,0.5710183053692892,2.4870941840919194,1854.4,484.4,543.8,773.4,1350.2,1409.6 -2.1289737921023413,0.5710170288753431,2.6179938779914944,913.4,522.4,650.1,856.2,1488.5,1616.2 -2.128956799340762,0.5710400707016956,2.748893571891069,627.8,628.5,848.6,1054.0,1812.3,2032.5 -2.1289607759380407,0.5710383008873436,2.8797932657906435,508.5,893.5,986.2,1515.1,2423.2,2295.6 -2.128945853609343,0.5710470476523077,3.010692959690218,462.1,853.6,795.0,1370.9,2133.0,2074.1 -2.128967804586722,0.6713233819831896,0.0,563.0,793.0,793.2,1198.9,2028.7,2029.2 -2.128956589254166,0.670679553166275,0.1308996938995747,609.1,795.3,854.7,1224.8,2075.0,2071.2 -2.1289937544051436,0.6706915174678492,0.2617993877991494,717.1,868.3,995.5,1359.4,1472.7,1092.9 -2.129070254969403,0.6707425174743884,0.39269908169872414,931.5,1054.5,1275.0,1672.1,988.3,769.0 -2.1290768262990523,0.670751654582594,0.5235987755982988,856.5,1489.3,1372.7,2377.9,765.5,637.7 -2.1291010260342573,0.6707940212865571,0.6544984694978736,773.3,1305.8,1246.7,2096.2,647.0,587.9 -2.129118396466384,0.6708785373345041,0.7853981633974483,763.4,1229.1,1228.4,1999.2,593.5,592.9 -2.1291188373812955,0.6709034516949919,0.916297857297023,815.9,1246.2,1304.9,2051.6,587.9,646.7 -2.1291139371786656,0.6709241808191224,1.0471975511965976,947.8,1371.8,1499.1,1392.3,636.8,763.9 -2.129105237553573,0.6709374742194156,1.1780972450961724,1210.1,1665.7,1884.3,932.8,768.2,987.2 -2.1290544995842526,0.6709859534379135,1.3089969389957472,1360.4,2357.6,2297.5,717.6,996.9,869.3 -2.129014207810924,0.6710094144364871,1.4398966328953218,1224.1,2132.6,2074.0,608.1,852.8,794.6 -2.1290301630721937,0.6710065490545556,1.5707963267948966,1199.2,2029.2,2028.7,563.0,793.4,793.0 -2.128969853163346,0.6710051190586868,1.7016960206944713,1266.4,2072.6,2102.1,565.6,795.0,853.5 -2.128918032486305,0.6709899118627318,1.832595714594046,1452.5,1471.1,1091.7,624.7,868.0,995.7 -2.128968108630095,0.6710252656724316,1.9634954084936205,1833.1,987.8,768.6,771.4,1054.2,1275.1 -2.1289589457365437,0.6710171182738167,2.0943951023931953,2283.9,764.3,636.8,948.3,1492.5,1372.3 -2.1289163477333095,0.6709364612698823,2.2252947962927703,2052.5,646.7,587.9,815.6,1305.0,1246.4 -2.1289229656867708,0.6709680179582083,2.356194490192345,1999.6,592.9,593.4,762.5,1228.7,1229.3 -2.1289228171159995,0.6709321701371613,2.4870941840919194,2095.8,587.8,646.9,773.1,1246.6,1305.6 -2.1289368897805425,0.6708903622866129,2.6179938779914944,1113.7,637.5,765.2,855.8,1372.5,1500.0 -2.128936644735365,0.6708870722283984,2.748893571891069,769.6,769.4,989.1,1052.9,1669.8,1889.6 -2.1289594447736673,0.6708679752919875,2.8797932657906435,624.1,996.1,868.5,1469.4,2361.6,2296.7 -2.1289648862192045,0.6708663480039472,3.010692959690218,565.5,853.9,795.0,1267.8,2133.1,2074.8 -2.1290109327271276,0.7711609017359975,0.0,662.9,793.0,793.1,1099.1,2028.8,2028.9 -2.128978063239118,0.771160435691892,0.1308996938995747,712.5,795.3,854.7,1121.7,2075.1,2134.4 -2.1289192618483233,0.7711433491443282,0.2617993877991494,832.3,868.2,995.6,1244.1,1671.6,1292.1 -2.128862645669282,0.7711087312714351,0.39269908169872414,1051.4,1054.2,1275.0,1530.8,1129.5,909.9 -2.12881742147913,0.7710627659331997,0.5235987755982988,856.5,1385.1,1257.2,2179.4,881.2,753.3 -2.1287972737660477,0.7710227028974252,0.6544984694978736,773.2,1202.5,1143.2,2096.2,750.6,691.3 -2.1287808912269797,0.7709586150473964,0.7853981633974483,763.1,1129.2,1128.5,1999.0,693.5,692.8 -2.128782840708439,0.7709317303232583,0.916297857297023,815.8,1142.5,1201.4,2052.2,691.5,750.2 -2.1288000836797427,0.770879046631314,1.0471975511965976,947.7,1256.1,1383.5,1592.1,752.3,879.4 -2.1288337095329264,0.770824246122527,1.1780972450961724,1210.4,1524.4,1743.6,1074.7,909.4,1055.7 -2.1288384664898556,0.7708204389249118,1.3089969389957472,1244.4,2158.6,2297.4,833.2,1047.2,869.1 -2.128861479117153,0.7708098528485032,1.4398966328953218,1120.7,2132.6,2074.2,711.6,852.9,794.5 -2.12894340622557,0.7707916810522151,1.5707963267948966,1099.0,2028.8,2028.8,663.0,793.4,792.9 -2.128944832922096,0.7707921378449727,1.7016960206944713,1162.9,2073.0,2131.2,669.0,795.1,853.4 -2.12894787947135,0.7707934065789932,1.832595714594046,1337.2,1670.7,1291.1,740.3,868.0,995.7 -2.1290087931523094,0.7708329685640001,1.9634954084936205,1691.7,1128.9,909.9,913.3,1054.4,1275.3 -2.1290300474861477,0.7708577998594397,2.0943951023931953,2283.5,879.9,752.3,1070.6,1383.9,1256.6 -2.12902303823522,0.7708437787028932,2.2252947962927703,2052.8,750.4,691.5,815.6,1201.7,1142.7 -2.129029615927241,0.7708719292914814,2.356194490192345,1999.4,693.0,693.4,762.5,1128.5,1128.9 -2.129026718062351,0.7709072937167747,2.4870941840919194,2141.2,691.5,750.4,773.2,1143.1,1202.2 -2.1290293935628446,0.7709028079847295,2.6179938779914944,1313.0,753.1,880.9,856.0,1256.7,1384.4 -2.129014468270149,0.7709229481342779,2.748893571891069,911.1,910.6,1053.4,1053.0,1528.6,1748.4 -2.1290207320972647,0.7709193064532005,2.8797932657906435,739.6,1047.5,868.5,1337.5,2161.8,2296.6 -2.129008481956006,0.770927130970571,3.010692959690218,669.1,854.0,795.1,1164.4,2132.9,2074.8 -2.129033486444695,0.8712059047136471,0.0,762.9,793.0,793.0,999.4,2029.0,2029.1 -2.1289802553778707,0.8706502706226962,0.1308996938995747,816.4,795.2,854.5,1017.7,2075.4,2134.3 -2.129012344056234,0.870660752461405,0.2617993877991494,948.2,868.3,995.7,1128.3,1871.7,1491.9 -2.1290514634361166,0.87068591917696,0.39269908169872414,1051.3,1054.3,1274.9,1388.6,1270.6,1051.5 -2.129083030614047,0.8707222295003245,0.5235987755982988,856.5,1269.1,1141.5,1980.4,996.8,869.1 -2.1287820190342455,0.8710228618350719,0.6544984694978736,773.2,1098.3,1039.5,2095.8,853.9,795.0 -2.128778485712769,0.8710102017811354,0.7853981633974483,763.4,1028.9,1028.5,1998.4,793.5,793.0 -2.1287798221457104,0.8710126258996884,0.916297857297023,816.0,1039.2,1098.3,2052.4,795.0,854.1 -2.1287911628622584,0.8709800870903892,1.0471975511965976,948.3,1141.1,1268.8,1789.5,868.4,995.5 -2.1288157511958836,0.8709405377446575,1.1780972450961724,1211.5,1384.5,1603.7,1215.1,1051.5,1098.7 -2.128809150525565,0.8709472476544595,1.3089969389957472,1128.2,1961.7,2296.3,948.5,996.5,868.8 -2.1288194722046474,0.8709427364256281,1.4398966328953218,1016.6,2131.4,2073.6,814.9,852.6,794.4 -2.1288884753697177,0.8709274466385712,1.5707963267948966,999.0,2028.7,2028.6,763.2,793.3,793.2 -2.1288779352084553,0.8709270200966768,1.7016960206944713,1059.3,2073.5,2131.8,772.8,795.3,853.6 -2.128870702013208,0.8709240537933627,1.832595714594046,1222.0,1867.5,1488.5,856.4,868.6,996.3 -2.1289232742628537,0.8709576013843447,1.9634954084936205,1551.1,1269.3,1019.3,1055.9,1055.4,1276.2 -2.1289385378119894,0.8709753454985671,2.0943951023931953,2264.7,995.0,867.7,947.9,1267.5,1140.7 -2.1289282371865133,0.8709533475581137,2.2252947962927703,2052.3,853.6,794.9,815.4,1097.7,1039.1 -2.1289337092582263,0.8709736083640738,2.356194490192345,1999.9,793.0,793.7,762.5,1028.2,1029.0 -2.1289312993026956,0.8710019463388177,2.4870941840919194,2095.7,795.1,854.3,773.4,1039.5,1098.7 -2.1289363435693116,0.8709911631148357,2.6179938779914944,1510.2,869.2,997.2,856.3,1141.4,1269.1 -2.1289243502943003,0.8710063608039689,2.748893571891069,1051.8,1053.1,1100.7,1053.8,1388.1,1608.3 -2.128934641629458,0.8709988265407951,2.8797932657906435,855.2,995.4,868.3,1221.1,1964.9,2295.9 -2.1289267492630963,0.8710039488635584,3.010692959690218,772.6,853.8,794.9,1060.2,2132.9,2073.9 -2.8289971166060472,0.17094092413849005,0.0,63.1,93.1,93.2,1698.8,2728.8,2728.9 -2.829015950061986,0.17143871198364136,0.1308996938995747,91.7,118.6,129.8,1743.1,961.5,232.7 -2.8289179140302605,0.171407338552509,0.2617993877991494,116.7,59.4,187.1,1938.3,473.9,95.1 -2.8288582696519002,0.17136857379941817,0.39269908169872414,62.7,63.1,284.2,2382.7,281.9,63.0 -2.8288190003754536,0.17132652654251013,0.5235987755982988,150.7,95.6,475.5,3185.5,187.3,59.8 -2.828804219244886,0.17129431649598503,0.6544984694978736,48.4,235.7,1057.9,2819.7,129.4,70.5 -2.8287912168589657,0.1712404687310478,0.7853981633974483,63.2,1728.8,1728.6,2698.3,93.7,93.3 -2.8287928871153567,0.17122349377722745,0.916297857297023,91.5,1763.8,1822.9,914.4,70.6,129.6 -2.8288069821674853,0.1711797072326613,1.0471975511965976,139.4,1950.5,2077.7,393.0,59.5,94.9 -2.8288354600116743,0.17113249109373596,1.1780972450961724,223.0,2373.4,2592.7,224.0,63.4,110.5 -2.828833422134309,0.17113338265318556,1.3089969389957472,394.2,3232.6,3105.2,139.6,95.8,200.7 -2.828849027573317,0.1711244412633086,1.4398966328953218,839.6,2855.7,2797.3,91.0,128.5,70.2 -2.8289239416081915,0.17110661001882632,1.5707963267948966,1698.8,2729.1,2728.5,63.2,93.2,93.2 -2.828919325728854,0.17110513828745777,1.7016960206944713,1784.3,1063.1,237.4,48.6,121.9,129.4 -2.8289178307835665,0.17110251615343275,1.832595714594046,2031.8,473.9,95.4,47.1,58.9,186.8 -2.8289754974713373,0.17113815901102303,1.9634954084936205,2544.6,282.1,63.3,63.8,62.7,283.9 -2.8290016401232276,0.17116380214889348,2.0943951023931953,3090.7,186.5,59.5,117.6,95.8,476.8 -2.828991443899233,0.171141063293907,2.2252947962927703,2776.7,129.3,70.8,91.0,236.6,1062.7 -2.828997838652869,0.17116485100495815,2.356194490192345,2700.2,93.2,93.9,62.5,1728.1,1728.6 -2.8289948759363215,0.1711980178830661,2.4870941840919194,315.6,70.4,129.7,48.4,1764.3,1823.7 -2.8289980312859546,0.17119158584675698,2.6179938779914944,117.4,59.9,94.6,46.6,1951.3,2079.0 -2.8289827200074957,0.1712102426220392,2.748893571891069,62.6,62.8,110.5,63.3,2378.7,2599.5 -2.8289892613258556,0.17120473143198933,2.8797932657906435,46.6,95.2,200.4,117.5,3231.2,3104.6 -2.82897747584533,0.17121052540625747,3.010692959690218,48.2,129.2,70.5,319.8,2857.3,2798.0 -2.828962329153319,0.1712150407843538,0.0,63.3,93.0,93.2,1698.6,2728.6,2729.0 -2.8289860021033446,0.1712172672250878,0.1308996938995747,91.7,118.4,129.8,1742.9,961.8,233.1 -2.8289467047264543,0.17120394911464887,0.2617993877991494,116.7,59.4,187.1,1938.5,474.2,95.2 -2.82893216787052,0.17119348917585886,0.39269908169872414,62.8,63.2,284.1,2381.8,282.0,63.0 -2.8289256703261745,0.17118669283184573,0.5235987755982988,150.8,95.7,475.5,3185.3,187.3,59.9 -2.8289315303992915,0.17119309984442888,0.6544984694978736,48.5,235.7,1057.6,2820.4,129.4,70.5 -2.8289277447888064,0.17117907649709085,0.7853981633974483,63.3,1729.0,1728.4,2698.7,93.7,93.3 -2.8289282157278297,0.17119969526219503,0.916297857297023,91.5,1763.9,1822.7,914.6,70.6,129.6 -2.8289320949459262,0.17118949483461754,1.0471975511965976,139.4,1950.6,2077.8,393.1,59.4,95.0 -2.8289433302482285,0.17116986168461956,1.1780972450961724,223.0,2373.0,2592.3,223.9,63.3,110.5 -2.828919596581403,0.1711911410575604,1.3089969389957472,394.1,3232.6,3105.0,139.6,95.7,200.8 -2.828910804182813,0.17119532158597295,1.4398966328953218,925.7,2855.7,2797.4,90.9,128.5,70.2 -2.8289604116697102,0.17118332139183812,1.5707963267948966,1699.0,2729.0,2729.0,63.2,93.3,93.2 -2.828932158082789,0.1711811180106224,1.7016960206944713,1784.2,1063.1,237.3,48.5,122.1,129.4 -2.8289096575237562,0.17117222168234814,1.832595714594046,2031.9,473.8,95.3,47.0,58.9,186.8 -2.8289498363663523,0.17119696146318208,1.9634954084936205,2543.7,281.9,63.2,63.7,62.7,284.0 -2.8289560938961307,0.17120423490408143,2.0943951023931953,3089.6,186.5,59.5,117.6,95.7,476.7 -2.8289402132090116,0.17117091146051577,2.2252947962927703,2777.2,129.3,70.7,90.9,236.4,1062.1 -2.8289431108099574,0.17117973654434904,2.356194490192345,2699.4,93.1,93.9,62.4,1728.1,1729.0 -2.8289407104531192,0.17119730294129654,2.4870941840919194,315.7,70.4,129.7,48.4,1764.3,1823.9 -2.828948150088802,0.17117679407030795,2.6179938779914944,117.4,59.9,94.5,46.6,1951.2,2079.2 -2.828940233708725,0.17118369365022823,2.748893571891069,62.6,62.8,110.4,63.3,2378.4,2599.0 -2.8289561210729364,0.1711694747558663,2.8797932657906435,46.6,95.2,200.4,117.5,3231.3,3104.5 -2.828954797465392,0.171169715482542,3.010692959690218,48.2,129.2,70.5,319.7,2856.6,2798.0 -2.028831420210248,0.3711948480394798,0.0,263.3,893.1,893.2,1498.7,1928.8,1928.9 -2.028931511302122,0.3710222339671527,0.1308996938995747,298.6,898.8,958.0,1535.8,1817.4,1001.7 -2.0290830364495696,0.37107001139775164,0.2617993877991494,370.5,983.9,1111.6,1706.6,873.7,493.9 -2.029008188433646,0.37102272018214943,0.39269908169872414,507.0,1196.3,1417.3,2097.2,564.6,345.3 -2.0289910094751957,0.37100575567356686,0.5235987755982988,791.6,1689.1,1719.1,2262.0,418.6,290.9 -2.028997835721388,0.37101507193689964,0.6544984694978736,876.8,1616.1,1557.0,1992.2,336.5,277.4 -2.028995207936557,0.37100871873875896,0.7853981633974483,863.2,1529.0,1528.7,1898.8,293.6,293.1 -2.028995355900232,0.37103840523134823,0.916297857297023,919.6,1556.7,1615.4,1692.2,277.6,336.3 -2.028996803979373,0.3710368704968121,1.0471975511965976,1063.5,1718.4,1845.6,792.9,290.4,417.7 -2.029003723868691,0.37102425529242833,1.1780972450961724,1351.6,2089.1,2308.1,507.6,345.3,564.5 -2.028974775664557,0.37105128433297785,1.3089969389957472,1706.8,2308.9,2181.2,345.4,493.7,872.9 -2.02896001194721,0.37105999613773544,1.4398966328953218,1534.2,2131.7,1970.5,297.8,933.8,897.9 -2.0290030526689655,0.37105009386683463,1.5707963267948966,1498.9,1928.9,1928.6,263.1,893.2,893.0 -2.028968415090029,0.37104861842670367,1.7016960206944713,1576.6,1845.8,1016.9,255.3,898.4,957.0 -2.0289397636142192,0.3710393868045403,1.832595714594046,1799.5,872.9,493.8,278.1,983.8,1111.4 -2.0289745284424665,0.37106182809260346,1.9634954084936205,2258.0,564.3,345.3,346.8,1165.1,1417.3 -2.0289765938957927,0.3710654411692975,2.0943951023931953,2167.8,417.6,290.3,516.3,1692.9,1718.5 -2.0289575830804933,0.37102812759731285,2.2252947962927703,1949.1,336.3,277.5,919.1,1615.2,1556.6 -2.0289588236140825,0.3710324426271372,2.356194490192345,1899.8,293.0,293.6,862.6,1528.4,1528.8 -2.028956591885004,0.3710452414997538,2.4870941840919194,1087.5,277.4,336.5,876.8,1557.4,1616.1 -2.0289651104321305,0.37102079170335944,2.6179938779914944,515.8,290.9,418.7,971.6,1718.8,1847.1 -2.0289599376019147,0.3710243194571743,2.748893571891069,345.4,345.4,565.3,1194.5,2094.2,2314.4 -2.028978796697817,0.37100803731002974,2.8797932657906435,277.5,493.6,873.5,1713.0,2308.3,2181.4 -2.028980781376404,0.371007384869096,3.010692959690218,255.1,934.5,898.6,1578.0,2029.6,1970.6 -2.0290234621340484,0.4712994486875486,0.0,363.0,893.1,893.0,1399.1,1928.8,1928.9 -2.0289883465346477,0.47129788719029553,0.1308996938995747,402.0,898.8,958.2,1432.0,1971.7,1385.4 -2.0289282029667826,0.4712795146737696,0.2617993877991494,486.1,983.9,1111.4,1591.0,1073.0,693.3 -2.0288708461715332,0.471243585200102,0.39269908169872414,648.6,1196.2,1417.1,1955.6,705.7,455.3 -2.028825346439945,0.4711964624288485,0.5235987755982988,971.8,1689.2,1603.5,2262.3,534.1,406.5 -2.0288050419592354,0.4711553745760906,0.6544984694978736,876.8,1513.1,1453.6,1992.4,439.9,380.9 -2.028788709816258,0.4710905270443535,0.7853981633974483,863.0,1428.8,1428.5,1898.7,393.6,393.1 -2.028790589160993,0.47106290865171707,0.916297857297023,919.3,1452.9,1512.0,1948.7,381.0,439.8 -2.028807741566971,0.4710094956836761,1.0471975511965976,1063.5,1603.0,1730.4,992.6,405.9,533.2 -2.028841343195471,0.47095402445643475,1.1780972450961724,1351.4,1948.2,2167.5,649.4,486.4,705.6 -2.028846091857019,0.4709493548286088,1.3089969389957472,1591.3,2309.3,2181.9,486.5,692.9,984.6 -2.0288692671667836,0.47093770916574385,1.4398966328953218,1430.9,2029.0,1969.9,401.3,956.4,897.7 -2.0289516572552957,0.470918710508077,1.5707963267948966,1399.1,1928.9,1928.7,363.2,893.2,893.3 -2.0289537776061963,0.4709183938211621,1.7016960206944713,1473.1,1969.7,1407.0,358.9,898.7,957.0 -2.0289577629259794,0.47091900552633104,1.832595714594046,1683.8,1072.1,649.2,393.7,983.9,1111.3 -2.0290196894378254,0.4709584245772702,1.9634954084936205,2116.9,674.6,486.4,488.6,1196.5,1417.2 -2.0290418345152945,0.4709835589647371,2.0943951023931953,2167.9,533.2,405.9,716.1,1692.7,1602.7 -2.0290355516005185,0.4709700303033244,2.2252947962927703,1949.2,439.8,381.1,1008.1,1511.9,1452.8 -2.029042487122041,0.4709989047687433,2.356194490192345,1900.1,393.0,393.6,862.6,1428.3,1429.0 -2.0290394283607562,0.47103510868169196,2.4870941840919194,1472.9,381.0,440.0,876.8,1453.4,1512.4 -2.0290416871327737,0.4710312122721618,2.6179938779914944,671.2,406.5,534.2,971.6,1603.2,1731.2 -2.029025901431526,0.47105172168628795,2.748893571891069,486.6,486.8,706.9,1194.6,1953.0,2172.8 -2.0290313349220352,0.4710480130306902,2.8797932657906435,393.1,693.2,983.9,1708.8,2308.6,2181.1 -2.0290183088912888,0.47105540617425845,3.010692959690218,358.6,957.5,898.6,1474.4,2029.5,1970.8 -2.0290428217221397,0.5713337204037923,0.0,463.0,893.0,893.3,1298.9,1929.0,1928.5 -2.028992941292135,0.5706832648731277,0.1308996938995747,505.7,898.9,958.1,1328.5,2033.3,1770.4 -2.029022013254923,0.5706927645509154,0.2617993877991494,601.6,983.9,1111.4,1475.1,1272.7,893.1 -2.0290575383162555,0.5707156589380211,0.39269908169872414,790.1,1196.1,1416.9,1814.1,847.0,627.6 -2.029086152890837,0.5707488046912053,0.5235987755982988,972.2,1615.8,1488.3,2262.7,649.9,522.2 -2.02911397333477,0.5707982929103042,0.6544984694978736,876.9,1409.1,1350.4,1992.6,543.4,484.4 -2.029119380876453,0.5708277611786954,0.7853981633974483,863.2,1328.9,1328.6,1898.6,493.5,493.1 -2.0291184982374606,0.5708894620115996,0.916297857297023,919.5,1349.7,1408.4,1993.8,484.4,543.2 -2.029111612064763,0.570916019384361,1.0471975511965976,1063.5,1487.5,1614.9,1192.1,521.2,648.4 -2.029104557997802,0.5709264409180428,1.1780972450961724,1351.5,1807.2,2026.0,790.9,627.3,846.2 -2.0290580448296645,0.5709707583413186,1.3089969389957472,1475.9,2309.5,2181.4,602.1,891.7,1027.9 -2.0290234046706574,0.5709910102401183,1.4398966328953218,1327.5,2028.6,1970.4,504.7,956.4,897.9 -2.0290455881126905,0.5709866998270574,1.5707963267948966,1299.0,1929.0,1929.0,462.9,893.4,893.1 -2.028991201651939,0.570985449216963,1.7016960206944713,1369.8,2064.8,1796.4,462.0,898.4,956.8 -2.028903026852372,0.5709558032068673,1.832595714594046,1568.3,1271.4,892.1,509.0,983.8,1111.3 -2.0291256496499295,0.5710988653391433,1.9634954084936205,1975.5,846.6,627.4,629.9,1196.2,1417.1 -2.029023349013333,0.5709913405477094,2.0943951023931953,2168.0,648.6,521.3,915.1,1614.9,1487.8 -2.0289818597415237,0.5709128053909946,2.2252947962927703,1949.5,543.2,484.4,919.1,1408.4,1349.9 -2.0289798120953937,0.5709041524280918,2.356194490192345,1899.7,492.9,493.5,862.4,1328.6,1329.0 -2.028977642141753,0.5709142427110288,2.4870941840919194,1859.0,484.3,543.3,876.7,1350.4,1409.2 -2.0289860770601114,0.5708904571210469,2.6179938779914944,914.3,522.1,649.6,971.4,1488.0,1615.7 -2.0289804071235844,0.5708955108580898,2.748893571891069,628.1,628.0,847.7,1194.5,1811.3,2031.4 -2.0289982855271953,0.5708808731532149,2.8797932657906435,508.6,892.3,1028.5,1568.3,2308.9,2181.4 -2.0289989693725676,0.5708816976668507,3.010692959690218,462.0,957.3,898.6,1371.0,2029.6,1970.8 -2.02903966134897,0.6711723479582785,0.0,562.9,893.1,893.1,1199.1,1928.8,1928.8 -2.029003020860567,0.6711717517527185,0.1308996938995747,609.0,898.8,958.1,1225.1,1971.5,2030.9 -2.028941453372027,0.67115384427112,0.2617993877991494,716.9,958.5,1111.3,1359.8,1471.8,1092.1 -2.0288827052592264,0.6711179617826515,0.39269908169872414,931.4,1196.1,1416.7,1672.1,988.0,768.7 -2.0288359167489154,0.6710704373052752,0.5235987755982988,1113.0,1500.1,1372.5,2262.3,765.4,637.6 -2.0288146747768727,0.6710286166360275,0.6544984694978736,876.6,1305.8,1246.8,1992.6,646.9,587.8 -2.028797757406844,0.6709627182597395,0.7853981633974483,863.1,1229.2,1228.4,1898.8,593.4,592.9 -2.0287995994450627,0.6709340369086123,0.916297857297023,919.5,1246.2,1304.9,1948.5,587.9,646.7 -2.0288171846477785,0.6708796895743747,1.0471975511965976,1063.2,1371.9,1499.2,1392.1,636.7,764.2 -2.0288515552485387,0.6708235296743899,1.1780972450961724,1351.4,1665.8,1884.8,932.4,768.4,987.5 -2.028831304632188,0.6708474027237088,1.3089969389957472,1360.2,2309.4,2181.8,717.7,1091.0,984.6 -2.0288782661063185,0.6708238673705573,1.4398966328953218,1224.0,2029.1,1970.5,608.2,956.3,897.9 -2.0289664864932053,0.6708042827653988,1.5707963267948966,1198.8,1928.8,1928.7,563.1,893.3,893.1 -2.028967812153859,0.6708047526774896,1.7016960206944713,1266.4,1969.5,2027.8,565.6,898.5,956.8 -2.02896889105335,0.6708054035723041,1.832595714594046,1452.8,1471.0,1091.7,624.8,983.6,1111.3 -2.0290275790714247,0.6708436653703389,1.9634954084936205,1833.4,987.9,768.6,771.7,1196.1,1417.0 -2.029046981859719,0.6708667174140257,2.0943951023931953,2168.0,764.3,636.9,1063.7,1499.4,1372.2 -2.0290387309945603,0.6708505826155629,2.2252947962927703,1949.3,646.9,587.9,919.2,1305.2,1246.5 -2.0290446650817033,0.6708764984041031,2.356194490192345,1899.1,593.0,593.5,862.6,1228.3,1229.1 -2.0290416665691393,0.6709097158318118,2.4870941840919194,1992.8,587.9,647.0,876.6,1246.8,1305.5 -2.02904481742882,0.670903253289227,2.6179938779914944,1113.4,637.5,765.2,971.4,1372.5,1500.1 -2.0290307300099077,0.6709217449673235,2.748893571891069,769.6,769.3,989.3,1194.7,1670.0,1889.9 -2.0290382038269668,0.6709168227268703,2.8797932657906435,624.2,1091.7,983.8,1452.6,2308.5,2180.9 -2.029027352392226,0.6709237994359667,3.010692959690218,565.5,957.2,898.7,1267.6,2029.9,1970.9 -2.0290541388330747,0.7712039349986668,0.0,662.9,893.1,893.1,1099.1,1929.0,1929.1 -2.028996656775831,0.7706480433128091,0.1308996938995747,712.8,898.7,958.2,1121.5,1971.9,2031.0 -2.0290281329288598,0.7706583700312815,0.2617993877991494,832.7,983.9,1111.3,1244.2,1671.8,1292.0 -2.029067303094543,0.7706836378738677,0.39269908169872414,1073.2,1196.1,1416.7,1530.2,1129.3,909.9 -2.0290990499062893,0.7707202437996712,0.5235987755982988,972.0,1384.5,1257.1,2179.7,881.0,753.4 -2.028785801677546,0.7710224024620531,0.6544984694978736,876.7,1202.0,1142.9,1991.9,750.4,691.5 -2.028782128592067,0.7710091488766468,0.7853981633974483,863.2,1128.8,1128.4,1898.6,693.6,693.2 -2.0287834488365806,0.7710118177157501,0.916297857297023,919.5,1142.8,1201.7,1948.8,691.7,750.5 -2.028794639238346,0.7709797481336029,1.0471975511965976,1063.8,1256.8,1384.1,1589.7,752.7,880.1 -2.028818938265578,0.7709406585942613,1.1780972450961724,1352.5,1525.7,1744.7,1073.7,910.3,1129.6 -2.0288119549114625,0.7709477236970546,1.3089969389957472,1243.9,2161.0,2180.6,833.0,1111.8,984.3 -2.028821840440103,0.7709434415751382,1.4398966328953218,1120.2,2028.5,1970.2,711.6,956.1,897.9 -2.028890390728553,0.7709282617509976,1.5707963267948966,1099.1,1928.7,1928.8,663.2,893.3,893.1 -2.028879425432829,0.7709278267156467,1.7016960206944713,1163.0,1970.0,2074.0,669.2,875.9,957.2 -2.028871813571739,0.7709247485268202,1.832595714594046,1337.6,1668.3,1289.7,740.6,984.3,1112.0 -2.028924066789086,0.7709581064250777,1.9634954084936205,1692.6,1128.3,878.3,914.1,1197.0,1418.1 -2.028939089300862,0.7709756090096855,2.0943951023931953,2167.3,879.4,726.9,1063.2,1383.4,1256.3 -2.0289286334061996,0.7709533366927084,2.2252947962927703,1948.8,750.3,691.7,919.0,1201.1,1142.4 -2.028934031165982,0.7709733112909134,2.356194490192345,1899.6,693.0,693.7,862.6,1128.4,1129.2 -2.028931620828703,0.7710013758689642,2.4870941840919194,2069.8,691.5,750.7,876.9,1143.4,1202.3 -2.0289367343606823,0.7709903474852564,2.6179938779914944,1311.4,753.6,881.6,971.9,1257.3,1385.2 -2.028924859173551,0.7710053432340935,2.748893571891069,910.5,911.4,1131.7,1195.4,1529.2,1749.5 -2.0289353085866337,0.7709976576170752,2.8797932657906435,739.5,1111.0,983.9,1336.4,2164.7,2180.2 -2.0289275944539633,0.7710026838341559,3.010692959690218,669.0,957.1,898.7,1163.7,2029.3,1970.6 -2.0289581996540242,0.8712855885475348,0.0,763.1,893.1,893.2,999.1,1929.1,1928.8 -2.0289146524958697,0.8712840157596655,0.1308996938995747,816.6,899.1,958.4,1017.8,1971.7,2031.4 -2.0288481631072215,0.8712637562925118,0.2617993877991494,948.7,984.3,1112.0,1129.0,1868.8,1489.6 -2.028786027855449,0.8712247235509074,0.39269908169872414,1191.7,1196.8,1414.8,1389.9,1269.6,1050.5 -2.028737325448919,0.8711737635594743,0.5235987755982988,971.7,1268.6,1141.0,1982.7,996.2,868.7 -2.028715017581527,0.8711283618074752,0.6544984694978736,876.7,1098.4,1039.4,1991.9,854.0,795.0 -2.028698283162429,0.8710593418395516,0.7853981633974483,863.2,1028.9,1028.5,1898.7,793.5,793.0 -2.028700712706549,0.8710277601457612,0.916297857297023,919.6,1039.2,1098.0,1948.9,795.1,854.0 -2.028719397787603,0.8709709775241055,1.0471975511965976,1064.0,1141.2,1268.6,1789.5,868.2,995.6 -2.0287553059867296,0.8709132024996731,1.1780972450961724,1352.3,1384.2,1603.6,1215.5,1051.4,1196.9 -2.028762525401654,0.8709068982215413,1.3089969389957472,1128.4,1961.9,2181.0,948.7,1247.9,984.5 -2.028788219125695,0.8708941477716861,1.4398966328953218,1016.9,2028.5,1970.4,815.0,956.2,897.9 -2.0288730951572944,0.8708751737836247,1.5707963267948966,998.8,1928.7,1928.5,763.1,893.5,893.2 -2.0288773642356954,0.8708752179036765,1.7016960206944713,1059.5,1969.8,2028.4,772.8,898.8,957.1 -2.0288832649297683,0.8708762457833628,1.832595714594046,1221.7,1867.7,1488.8,856.3,984.1,1111.8 -2.02894675972354,0.8709166451546966,1.9634954084936205,1551.0,1269.2,1050.4,1056.1,1197.0,1414.2 -2.0289700888901474,0.8709430610064086,2.0943951023931953,2167.1,995.1,867.7,1063.5,1267.6,1140.6 -2.0289648740226065,0.8709306572134141,2.2252947962927703,1948.6,853.7,795.0,919.1,1097.7,1039.0 -2.028972595011128,0.8709608104857898,2.356194490192345,1899.5,793.0,793.7,862.4,1028.1,1029.0 -2.0289698209123044,0.8709985510735738,2.4870941840919194,1992.6,795.2,854.3,876.9,1039.6,1098.7 -2.028972303463115,0.8709960211475858,2.6179938779914944,1510.4,869.3,997.0,971.8,1141.5,1269.2 -2.0289560309344865,0.871018014484104,2.748893571891069,1052.0,1053.1,1194.2,1195.4,1387.8,1608.2 -2.028960908613623,0.8710155061665892,2.8797932657906435,855.2,1249.0,983.7,1221.1,1965.0,2180.4 -2.028946982671858,0.8710238360044853,3.010692959690218,772.5,957.2,898.3,1060.4,2029.3,1970.2 -2.8290163667550017,0.17097030202400743,0.0,63.1,93.1,93.2,1699.1,2728.8,2729.3 -2.8290260089008012,0.17143811313699908,0.1308996938995747,91.7,118.6,129.8,1743.3,961.5,232.7 -2.8289250648912017,0.17140584296229733,0.2617993877991494,116.7,59.4,187.1,1938.4,474.0,95.1 -2.828864908535651,0.17136677711886783,0.39269908169872414,62.7,63.1,284.2,2382.4,281.9,62.9 -2.8288257306573557,0.1713248691517435,0.5235987755982988,150.7,95.6,475.5,3185.4,187.3,59.8 -2.828811106090062,0.17129301305685352,0.6544984694978736,48.4,235.6,1057.7,2819.6,129.4,70.5 -2.828798162208911,0.1712395884134701,0.7853981633974483,63.2,1728.6,1728.4,2699.3,93.7,93.3 -2.828799787150319,0.17122303147990636,0.916297857297023,91.5,1763.7,1822.8,914.5,70.6,129.6 -2.8288137373929936,0.17117961434911821,1.0471975511965976,139.4,1950.2,2078.0,393.0,59.5,94.9 -2.8288419944704652,0.17113268375281443,1.1780972450961724,223.0,2373.2,2592.8,224.0,63.4,110.5 -2.828839701534894,0.1711337837738809,1.3089969389957472,394.1,3233.3,3105.2,139.7,95.8,200.8 -2.8288550339178613,0.17112498055410574,1.4398966328953218,839.8,2855.7,2797.1,91.0,128.4,70.2 -2.828929670751998,0.17110719719353673,1.5707963267948966,1698.9,2728.3,2728.2,63.2,93.2,93.2 -2.828924800437884,0.1711057169952439,1.7016960206944713,1784.1,1063.2,237.4,48.6,121.9,129.4 -2.8289230747264553,0.17110304603324855,1.832595714594046,2031.6,473.8,95.4,47.1,58.9,186.8 -2.8289805435657347,0.17113858536583249,1.9634954084936205,2544.1,282.0,63.3,63.8,62.7,284.0 -2.828999575183565,0.17115957062104115,2.0943951023931953,3090.3,186.5,59.5,117.7,95.8,476.8 -2.8289917963797078,0.17114138303778859,2.2252947962927703,2776.5,129.4,70.8,90.9,236.5,1062.5 -2.828998306517694,0.1711658420094151,2.356194490192345,2699.5,93.2,93.9,62.5,1727.9,1729.0 -2.8289953371529273,0.1711983174813616,2.4870941840919194,315.6,70.4,129.7,48.4,1764.7,1823.8 -2.8289987638158,0.171190874858693,2.6179938779914944,117.4,59.9,94.6,46.6,1951.3,2079.4 -2.82898403068816,0.17120856421484132,2.748893571891069,62.6,62.8,110.4,63.3,2379.2,2599.5 -2.8289913408905325,0.17120230247400348,2.8797932657906435,46.6,95.2,200.4,117.5,3231.3,3104.1 -2.8289804418162148,0.1712076052705802,3.010692959690218,48.3,129.2,70.5,319.7,2857.2,2798.4 -2.8289662173290013,0.17121189850969065,0.0,63.3,93.0,93.2,1698.9,2728.4,2729.3 -2.82899086872821,0.17121416944002665,0.1308996938995747,91.7,118.4,129.8,1742.8,962.0,233.0 -2.828952290498529,0.17120108180410787,0.2617993877991494,116.7,59.4,187.1,1938.4,474.1,95.3 -2.8289383726337842,0.17119102908045614,0.39269908169872414,62.8,63.2,284.2,2382.3,282.0,63.0 -2.828932330479102,0.17118475748609518,0.5235987755982988,150.8,95.7,475.4,3185.3,187.3,59.9 -2.8289384730800196,0.17119174658937242,0.6544984694978736,48.5,235.7,1057.7,2820.1,129.5,70.5 -2.828934788874713,0.1711783121341155,0.7853981633974483,63.3,1728.6,1728.6,2698.6,93.7,93.3 -2.828935213038147,0.17119948236861515,0.916297857297023,91.5,1764.2,1822.9,914.7,70.6,129.6 -2.8289389154507636,0.1711897641205684,1.0471975511965976,139.4,1950.2,2077.8,393.0,59.4,95.0 -2.8289498753999682,0.17117050903432718,1.1780972450961724,223.0,2373.2,2592.4,224.0,63.3,110.5 -2.8289258163123274,0.1711920640346798,1.3089969389957472,394.1,3232.4,3104.4,139.7,95.7,200.8 -2.828916671062579,0.17119642416536807,1.4398966328953218,925.5,2855.7,2797.7,90.9,128.5,70.2 -2.8289659188415053,0.1711844913545646,1.5707963267948966,1698.5,2728.6,2728.4,63.2,93.3,93.2 -2.828937333829223,0.17118227594752433,1.7016960206944713,1783.9,1063.2,237.4,48.5,122.1,129.4 -2.828914535141755,0.1711733070690269,1.832595714594046,2031.5,473.8,95.3,47.0,58.9,186.8 -2.8289544607320276,0.1711979062490383,1.9634954084936205,2543.8,282.0,63.2,63.7,62.6,283.9 -2.828960522496012,0.17120499482612916,2.0943951023931953,3091.0,186.5,59.5,117.6,95.7,476.6 -2.8289444986193857,0.17117147038403613,2.2252947962927703,2776.7,129.4,70.7,90.9,236.4,1062.0 -2.8289473114655768,0.17118007736846286,2.356194490192345,2699.8,93.2,93.9,62.4,1728.1,1728.8 -2.8289448914917195,0.1711974191871719,2.4870941840919194,315.6,70.4,129.7,48.4,1764.1,1823.6 -2.828952357746622,0.1711767069943151,2.6179938779914944,117.4,59.9,94.5,46.6,1951.1,2079.0 -2.828944529099704,0.17118342342963389,2.748893571891069,62.6,62.8,110.4,63.3,2378.8,2598.6 -2.8289605336177495,0.17116906403483445,2.8797932657906435,46.6,95.1,200.4,117.5,3231.2,3104.4 -2.828959354937457,0.17116921025837373,3.010692959690218,48.2,129.1,70.5,319.6,2856.6,2798.0 -1.9288474950024368,0.3711891725999359,0.0,263.3,992.8,993.1,1498.8,1829.0,1829.3 -1.9289382427592532,0.37102466869589534,0.1308996938995747,298.6,1002.3,1061.8,1535.9,1817.6,1001.4 -1.9290883217282373,0.37107200937169416,0.2617993877991494,370.6,1099.7,1227.2,1706.3,873.7,493.9 -1.9290118473360922,0.3710236983564532,0.39269908169872414,506.9,1337.8,1558.6,2096.8,564.6,345.3 -1.9289943427649154,0.37100639403182867,0.5235987755982988,791.5,1872.2,1719.2,2146.6,418.6,290.9 -1.9290011513956689,0.3710157009128823,0.6544984694978736,980.2,1616.2,1557.1,1888.7,336.5,277.4 -1.9289985368356555,0.37100946950825375,0.7853981633974483,963.2,1529.1,1528.5,1798.6,293.7,293.1 -1.9289986629804856,0.3710393093276385,0.916297857297023,1022.9,1556.3,1615.5,1692.0,277.6,336.3 -1.9290000483681005,0.3710379188135249,1.0471975511965976,1178.9,1718.6,1845.6,792.8,290.3,417.7 -1.9290068751581608,0.371025419244265,1.1780972450961724,1492.9,2089.2,2308.2,507.5,345.3,564.4 -1.9289778179225772,0.3710525283141288,1.3089969389957472,1706.2,2193.5,2066.1,370.8,493.8,872.9 -1.9289629390012508,0.3710612862246232,1.4398966328953218,1534.0,1925.6,1867.2,297.8,1016.8,1001.4 -1.9290058664719134,0.37105139962469025,1.5707963267948966,1499.0,1829.2,1828.5,263.1,993.4,993.1 -1.9289711267843948,0.3710499149580937,1.7016960206944713,1576.7,1845.4,1017.0,255.3,1002.1,1060.5 -1.9289423858919983,0.37104065488310156,1.832595714594046,1799.6,872.9,493.7,278.0,1099.2,1227.1 -1.9289770747442794,0.3710630526106564,1.9634954084936205,2258.8,564.4,345.3,346.8,1337.9,1559.1 -1.9289790795869128,0.3710666122054689,2.0943951023931953,2052.1,417.6,290.2,516.3,1871.0,1718.4 -1.928960023381732,0.37102923866590576,2.2252947962927703,1845.2,336.4,277.5,1022.4,1615.6,1556.6 -1.9289612335802613,0.37103348842535877,2.356194490192345,1799.6,293.1,293.6,962.6,1528.4,1529.0 -1.9289589873375996,0.3710462198334179,2.4870941840919194,1087.3,277.4,336.5,980.1,1557.1,1616.4 -1.9289675072069017,0.37102170444007965,2.6179938779914944,515.9,291.0,418.6,1087.1,1718.9,1846.9 -1.9289623518198664,0.37102517128850354,2.748893571891069,345.3,345.4,565.4,1335.9,2094.1,2314.2 -1.9289812422366939,0.3710088378250733,2.8797932657906435,277.6,493.7,873.4,1798.9,2192.9,2065.4 -1.9289832695755476,0.3710081472373652,3.010692959690218,255.1,1009.1,1001.9,1578.0,1926.2,1867.0 -1.9290260131036558,0.4713002589119588,0.0,363.0,993.0,992.9,1399.1,1828.7,1828.8 -1.9289909381061556,0.4712986916428139,0.1308996938995747,402.1,1002.4,1061.7,1432.4,1868.5,1385.3 -1.928930827854254,0.47128032797423836,0.2617993877991494,486.0,1099.7,1227.0,1590.9,1072.9,693.1 -1.928873494419123,0.4712444170888703,0.39269908169872414,648.6,1338.0,1558.6,1955.6,674.6,486.3 -1.9288280070416903,0.47119731885774585,0.5235987755982988,990.5,1731.4,1603.5,2146.3,534.1,406.6 -1.928807703392442,0.4711562569296366,0.6544984694978736,980.2,1512.6,1453.7,1888.5,439.9,380.9 -1.928791361781122,0.4710914328103568,0.7853981633974483,963.2,1429.0,1428.5,1798.8,393.6,393.0 -1.928793223980008,0.4710638314260731,0.916297857297023,1022.9,1453.4,1512.1,1845.2,381.1,439.8 -1.9288103553682991,0.47101042731359977,1.0471975511965976,1179.0,1602.6,1730.1,992.4,405.9,533.2 -1.9288439362973484,0.4709549567470679,1.1780972450961724,1492.7,1947.9,2167.2,649.3,486.5,705.5 -1.9288486679095052,0.4709502814643154,1.3089969389957472,1591.0,2193.6,2066.0,486.6,693.1,1072.3 -1.9288718316553437,0.4709386268642668,1.4398966328953218,1430.8,1925.0,1867.1,401.3,1059.9,1001.1 -1.9289542158999722,0.47091961943128324,1.5707963267948966,1398.7,1829.1,1828.4,363.1,993.1,993.1 -1.928956334386292,0.4709192968667091,1.7016960206944713,1473.4,1866.2,1406.9,358.8,1002.0,1060.3 -1.928960319293902,0.47091990694632946,1.832595714594046,1684.0,1072.4,693.0,393.7,1099.5,1201.5 -1.929022244003265,0.47095932855769895,1.9634954084936205,2116.8,705.6,486.5,488.6,1338.0,1559.1 -1.9290443835177307,0.4709844678999797,2.0943951023931953,2052.2,533.2,406.0,716.1,1729.9,1602.8 -1.929038090438366,0.4709709439129497,2.2252947962927703,1845.5,439.9,381.0,1022.6,1511.8,1453.4 -1.9290450118433424,0.470999820026091,2.356194490192345,1799.4,393.1,393.7,962.6,1428.4,1429.0 -1.9290419370607192,0.471036020501888,2.4870941840919194,1472.9,380.9,440.0,980.2,1453.7,1512.8 -1.9290441807857812,0.4710321150084418,2.6179938779914944,715.1,406.6,534.3,1087.1,1603.8,1731.1 -1.929028384060411,0.47105261051532876,2.748893571891069,486.8,486.8,706.7,1336.1,1952.7,2172.7 -1.9290338124660278,0.4710488856192754,2.8797932657906435,393.1,693.0,1073.0,1683.6,2192.7,2066.0 -1.929020788039411,0.4710562632971518,3.010692959690218,358.6,1060.9,1002.0,1474.4,1926.1,1867.3 -1.9290453136954018,0.5713345873575557,0.0,463.0,993.0,993.0,1299.1,1829.0,1829.1 -1.9289944462784236,0.5706828993444193,0.1308996938995747,505.6,1002.3,1061.5,1328.5,1868.2,1770.1 -1.929023370850585,0.5706923562994626,0.2617993877991494,601.8,1099.6,1226.9,1475.5,1272.8,893.0 -1.929058900357656,0.5707152590939211,0.39269908169872414,790.0,1337.7,1558.5,1813.7,847.0,627.6 -1.9290875504076943,0.570748451356651,0.5235987755982988,1087.7,1615.8,1488.3,2146.8,649.9,522.1 -1.92911539371183,0.570798000738511,0.6544984694978736,980.2,1409.2,1350.1,1889.1,543.6,484.4 -1.9291208106129214,0.5708275376700211,0.7853981633974483,963.4,1329.1,1328.6,1798.7,493.6,493.0 -1.9291199164714798,0.5708892993698056,0.916297857297023,1023.1,1349.8,1408.4,1909.4,484.4,543.1 -1.9291130054598205,0.5709159083827513,1.0471975511965976,1178.9,1487.4,1614.6,1192.0,521.2,648.6 -1.9291059193418678,0.5709263740062518,1.1780972450961724,1492.9,1806.8,2026.3,759.6,627.3,846.4 -1.9290593674627476,0.5709707200802356,1.3089969389957472,1475.9,2193.7,2066.1,602.0,891.8,1100.4 -1.9288741491220458,0.5708306841245843,1.4398966328953218,1327.2,1925.2,1866.8,504.6,1059.6,1001.2 -1.9291212255704175,0.570776381369483,1.5707963267948966,1298.8,1829.1,1828.6,463.0,993.4,993.1 -1.9290003686873125,0.570772189281102,1.7016960206944713,1369.7,1866.2,1794.6,462.3,1002.1,1060.5 -1.9289804666961072,0.5707658066693915,1.832595714594046,1568.4,1270.9,891.8,509.3,1099.7,1227.2 -1.9290471268693412,0.5708086979139195,1.9634954084936205,1975.8,846.3,627.4,630.5,1338.4,1559.4 -1.9290788706300377,0.5708447908174121,2.0943951023931953,2051.8,648.6,521.3,916.1,1614.4,1487.1 -1.929080071520772,0.5708456230961769,2.2252947962927703,1845.4,543.2,484.5,1022.5,1408.3,1349.3 -1.9290905770707654,0.5708901713334498,2.356194490192345,1799.4,493.0,493.6,962.4,1328.2,1329.1 -1.929086938444303,0.5709416814278707,2.4870941840919194,1856.0,484.3,543.5,980.4,1350.0,1409.4 -1.9290853343323784,0.5709512725110086,2.6179938779914944,913.6,522.1,649.9,1087.5,1488.5,1616.0 -1.92906269604957,0.5709831692317822,2.748893571891069,627.8,628.3,848.4,1336.7,1812.1,2032.1 -1.9290595730693902,0.5709880444144797,2.8797932657906435,508.5,892.7,1099.4,1567.7,2192.0,2065.2 -1.9290368283828925,0.5710011859969961,3.010692959690218,461.9,1060.9,1002.2,1371.1,1925.9,1867.0 -1.9290493099632493,0.6712704421123754,0.0,562.8,993.2,993.0,1198.9,1828.8,1828.9 -1.9290007770352162,0.670653657138035,0.1308996938995747,609.2,1002.3,1061.7,1225.0,1868.5,1927.6 -1.9290331479132,0.6706642532643758,0.2617993877991494,717.2,1099.5,1227.1,1359.5,1472.1,1092.3 -1.9290719673217984,0.6706893174334256,0.39269908169872414,931.7,1337.8,1558.5,1672.3,988.2,768.7 -1.9291031771702989,0.6707253743605175,0.5235987755982988,1145.8,1499.8,1372.4,2146.4,765.3,637.8 -1.9287865172991245,0.6710232406106964,0.6544984694978736,980.4,1305.2,1246.2,1888.4,646.9,587.9 -1.9287825922287083,0.6710088832271579,0.7853981633974483,963.3,1228.8,1228.7,1798.7,593.6,593.1 -1.9287839210634423,0.6710113258845831,0.916297857297023,1023.2,1246.3,1305.5,1845.5,588.0,646.9 -1.928795095787063,0.6709793133566269,1.0471975511965976,1179.4,1372.5,1499.7,1390.3,637.1,764.6 -1.9288508305242111,0.6708896859866826,1.1780972450961724,1493.6,1666.9,1885.9,932.0,769.1,988.3 -1.9286619636189581,0.6710640258415397,1.3089969389957472,1359.7,2192.6,2065.4,717.3,1092.7,1228.9 -1.9287890391090328,0.6709979723129471,1.4398966328953218,1223.8,1925.1,1866.6,608.0,1059.5,1001.3 -1.9288888067691816,0.6709757819375279,1.5707963267948966,1198.9,1828.9,1828.7,563.0,993.3,993.2 -1.9288788231272882,0.6709754389850959,1.7016960206944713,1266.6,1866.5,1924.9,565.8,1002.1,1037.9 -1.9288631351665917,0.6709699372382827,1.832595714594046,1453.3,1468.9,1090.4,625.0,1099.9,1227.5 -1.928906061556715,0.6709974672373586,1.9634954084936205,1834.8,987.1,768.2,772.3,1338.6,1560.0 -1.9289135347310962,0.671006877698753,2.0943951023931953,2051.6,764.0,636.7,1116.3,1498.8,1371.6 -1.9288981520252908,0.6709753859081917,2.2252947962927703,1845.4,646.6,587.9,1022.3,1304.7,1245.9 -1.9289013259734946,0.6709857424113455,2.356194490192345,1799.7,593.1,593.6,962.5,1228.5,1229.0 -1.9288992446515372,0.6710046120197424,2.4870941840919194,1889.1,587.9,647.3,980.6,1246.6,1306.1 -1.9289068288674194,0.6709854987622963,2.6179938779914944,1112.2,637.9,765.8,1087.6,1372.7,1500.9 -1.9289271051318697,0.6709106657267245,2.748893571891069,769.0,770.0,990.3,1336.9,1671.1,1890.8 -1.9289110665924805,0.6709685359012487,2.8797932657906435,624.0,1093.1,1229.9,1452.1,2192.2,2064.7 -1.9289074414960847,0.6709713316070218,3.010692959690218,565.5,1060.6,1002.1,1267.3,1926.1,1866.8 -1.928947422529654,0.7712622233583966,0.0,663.0,993.1,993.1,1099.0,1828.9,1828.8 -1.928965726763184,0.7712666037882479,0.1308996938995747,712.9,1002.8,1062.2,1121.5,1868.3,1980.5 -1.9288691144117107,0.7712369205573084,0.2617993877991494,833.1,1100.2,1227.5,1244.5,1669.6,1290.6 -1.9288040696674074,0.771196007575615,0.39269908169872414,1073.9,1338.9,1556.0,1531.5,1128.5,909.4 -1.9287588486015024,0.7711487545344693,0.5235987755982988,1087.1,1384.2,1256.5,2145.6,880.7,753.1 -1.9287399898034525,0.7711097797420401,0.6544984694978736,980.2,1202.0,1142.9,1888.3,750.4,691.5 -1.9287250100449431,0.7710482724369769,0.7853981633974483,963.3,1129.1,1128.4,1798.8,693.6,693.2 -1.9287272093159926,0.7710240616789663,0.916297857297023,1000.5,1142.9,1201.6,1844.9,691.6,750.5 -1.928743867327705,0.7709739545947323,1.0471975511965976,1179.6,1256.8,1384.1,1589.9,752.7,880.1 -1.9287763386865386,0.7709216983545135,1.1780972450961724,1493.4,1525.5,1744.7,1073.6,910.1,1129.6 -1.928779217104092,0.7709194738229137,1.3089969389957472,1243.9,2161.2,2065.8,832.9,1227.6,1100.1 -1.9288000242275285,0.7709093395033246,1.4398966328953218,1120.2,1925.2,1866.5,711.4,1059.7,1001.2 -1.9288798339112652,0.7708915397492211,1.5707963267948966,1099.0,1828.4,1828.8,662.9,993.3,993.1 -1.9288793694651583,0.7708914355661962,1.7016960206944713,1163.1,1866.6,2010.7,669.3,1002.1,1060.8 -1.9288810681270525,0.7708911921867803,1.832595714594046,1337.9,1668.3,1289.7,740.8,1099.7,1227.5 -1.9289410647742535,0.7709294061929284,1.9634954084936205,1692.8,1128.5,909.3,914.1,1338.6,1555.0 -1.9289618063234715,0.7709530533457094,2.0943951023931953,2051.5,879.3,752.3,1178.8,1383.3,1256.2 -1.9289549534480313,0.7709375845192341,2.2252947962927703,1844.9,750.1,691.5,1022.5,1201.2,1142.3 -1.9289619426042237,0.7709645732965382,2.356194490192345,1799.5,693.0,693.7,962.7,1128.3,1128.9 -1.928959274182695,0.7709993010491234,2.4870941840919194,1889.1,691.5,750.9,980.7,1143.3,1202.2 -1.9289625670443926,0.7709941232690394,2.6179938779914944,1311.4,753.5,881.3,1087.4,1257.1,1385.0 -1.9289476601750033,0.771013932459371,2.748893571891069,910.5,911.4,1131.7,1336.6,1529.3,1749.9 -1.9289542699524942,0.7710098070785949,2.8797932657906435,739.6,1226.7,1099.4,1336.6,2164.3,2064.9 -1.928942278718008,0.7710171041971114,3.010692959690218,669.1,1060.5,1001.9,1163.6,1926.1,1867.4 -1.928967722357767,0.8712960999311303,0.0,762.9,993.1,993.3,998.8,1828.7,1829.2 -1.9289520588956017,0.8706707524515027,0.1308996938995747,816.4,1002.3,1061.6,1017.9,1868.2,1927.3 -1.9289893855718419,0.8706827751030988,0.2617993877991494,948.0,1099.4,1226.8,1128.4,1871.7,1491.8 -1.9290276930626264,0.8707073237609395,0.39269908169872414,1214.3,1337.3,1384.8,1388.5,1270.6,1051.7 -1.9290573528950405,0.8707414307686043,0.5235987755982988,1087.8,1269.2,1141.4,1979.8,996.9,869.0 -1.9290857594365654,0.8707916189141898,0.6544984694978736,980.5,1098.8,1039.8,1889.0,854.2,795.1 -1.929091454135818,0.8708216434073659,0.7853981633974483,963.2,1029.1,1028.4,1798.7,793.6,792.9 -1.9290907855377073,0.8708839420594006,0.916297857297023,1022.8,1039.2,1097.8,1845.2,794.9,853.7 -1.9290839537869018,0.8708328637745828,1.0471975511965976,1178.9,1140.7,1267.9,1791.9,867.7,994.8 -1.9290741540825962,0.8709287038641598,1.1780972450961724,1390.0,1383.3,1602.6,1216.4,1050.5,1269.6 -1.929030698255724,0.8709703619546603,1.3089969389957472,1129.1,1959.4,2065.9,948.9,1228.5,1100.7 -1.928996422368994,0.870990654333984,1.4398966328953218,1017.0,1925.6,1867.0,815.1,1059.9,1001.3 -1.9290178154120545,0.8709865448251708,1.5707963267948966,999.2,1829.1,1828.7,762.8,993.4,993.0 -1.9289623213751583,0.8709852845967281,1.7016960206944713,1059.6,1866.2,1924.7,772.5,1002.0,1060.2 -1.928914684601855,0.8709713744194787,1.832595714594046,1221.4,1869.8,1490.5,855.8,1099.2,1226.7 -1.9289333716712431,0.8709846017080076,1.9634954084936205,1549.6,1270.3,1051.0,1054.7,1337.5,1384.3 -1.9289234019272226,0.8709759890022264,2.0943951023931953,2052.8,995.2,868.2,1269.7,1268.5,1141.2 -1.9288965817678156,0.8709250162165716,2.2252947962927703,1845.6,853.7,794.9,1022.7,1098.0,1039.4 -1.9288942981199038,0.8709149932133353,2.356194490192345,1799.3,793.0,793.5,962.5,1028.6,1028.9 -1.9288927207913125,0.8709139559569739,2.4870941840919194,1888.8,794.9,854.1,980.2,1039.5,1098.5 -1.9289051441418736,0.8708775352900096,2.6179938779914944,1512.5,868.9,996.2,1087.1,1141.1,1268.9 -1.9289067828833377,0.870871288521097,2.748893571891069,1052.4,1052.1,1271.8,1335.6,1387.0,1606.9 -1.928933944807336,0.8708481457366812,2.8797932657906435,855.2,1227.2,1099.7,1222.0,1962.1,2065.6 -1.9289450478150314,0.8708435196347344,3.010692959690218,772.6,1061.0,1002.1,1060.7,1926.1,1867.2 -1.828932105110453,0.17075452796946067,0.0,63.0,1093.2,1092.9,1699.0,1729.0,1728.9 -1.8289809046952665,0.1714599419232976,0.1308996938995747,91.6,1106.0,1165.2,1742.9,1049.2,233.6 -1.8289367036910942,0.17144544420608532,0.2617993877991494,139.5,1215.1,1342.6,1937.3,431.0,95.3 -1.8288848326417004,0.17141187498061372,0.39269908169872414,223.8,1479.5,1700.2,2380.4,282.3,63.0 -1.8288416143561663,0.1713661303831433,0.5235987755982988,393.3,2087.5,1950.2,2031.3,187.5,59.8 -1.828822409238435,0.17132609883405014,0.6544984694978736,912.7,1823.1,1764.0,1785.4,129.5,70.4 -1.8288065497767767,0.1712623253760226,0.7853981633974483,1062.9,1728.8,1728.5,1698.7,93.8,93.3 -1.8288083015334395,0.17123568096447817,0.916297857297023,1126.4,1763.6,1822.1,917.7,70.7,129.5 -1.8288248314505635,0.1711830157733638,1.0471975511965976,1294.5,1949.3,2076.8,349.9,59.5,186.8 -1.828857486541565,0.1711279247400994,1.1780972450961724,1634.0,2371.2,2380.9,224.3,63.4,282.5 -1.8288611597958593,0.17112311355809462,1.3089969389957472,1937.4,2078.1,1950.4,139.9,95.6,474.8 -1.8288833687130017,0.17111082487054952,1.4398966328953218,1740.8,1822.2,1763.6,91.1,238.5,1067.2 -1.8289651121040411,0.17109090027994434,1.5707963267948966,1699.0,1728.9,1728.8,63.3,1093.1,1093.2 -1.8289669988715451,0.17108949295652742,1.7016960206944713,1783.3,1066.7,238.4,48.6,1105.6,1163.8 -1.8289711715316113,0.17108905097388294,1.832595714594046,2030.8,474.8,95.6,47.1,1215.1,1342.5 -1.8290335842947167,0.17112772559496348,1.9634954084936205,2371.6,282.4,63.3,63.7,1479.8,1700.9 -1.8290563170106964,0.17115249757924955,2.0943951023931953,1936.8,186.8,59.5,117.4,2092.1,1949.5 -1.8290505521751366,0.17113892231503325,2.2252947962927703,1741.8,129.5,70.7,319.6,1822.1,1763.4 -1.8290577447959906,0.171168012095549,2.356194490192345,1699.6,93.2,93.8,1062.5,1727.8,1728.6 -1.829054563948102,0.1712045288848183,2.4870941840919194,316.8,70.5,129.6,1084.0,1764.1,1823.0 -1.829056404393286,0.17120079200299165,2.6179938779914944,73.8,59.9,187.6,1202.9,1950.3,2078.0 -1.8290399314723835,0.17122119877676045,2.748893571891069,62.7,62.7,282.8,1477.5,2377.0,2376.2 -1.829044676851192,0.17121700900083137,2.8797932657906435,46.6,95.0,474.9,2030.2,2077.7,1949.8 -1.8290311119902094,0.17122358351041234,3.010692959690218,48.2,235.3,1058.5,1785.1,1822.5,1763.8 -1.8290555478264539,0.2715017229643919,0.0,163.2,1093.0,1093.2,1598.9,1728.9,1729.1 -1.8290036636264386,0.2707245840743282,0.1308996938995747,195.0,1106.1,1165.4,1639.1,1433.6,617.4 -1.8290277968644675,0.2707324797451811,0.2617993877991494,255.0,1215.1,1342.4,1822.0,674.1,294.5 -1.8290586369928605,0.27075237911698125,0.39269908169872414,365.2,1479.5,1699.9,2238.7,423.3,204.0 -1.829083614755039,0.27078157893814225,0.5235987755982988,592.0,1962.9,1835.0,2031.1,303.0,175.2 -1.829109048371038,0.27082664853375116,0.6544984694978736,1083.7,1719.8,1660.7,1785.4,232.9,173.8 -1.8291133658058423,0.2708515482756382,0.7853981633974483,1063.0,1629.0,1628.8,1698.7,193.5,193.0 -1.8291125384812212,0.27090888994259865,0.916297857297023,1126.2,1660.1,1719.3,1304.7,173.9,232.7 -1.8291067378696761,0.2709315143310247,1.0471975511965976,1294.5,1834.1,1961.2,593.0,174.7,302.0 -1.8291016011186219,0.27093868852387737,1.1780972450961724,1633.9,2230.4,2380.9,365.7,203.9,423.1 -1.8290575281011057,0.27098053436558356,1.3089969389957472,1822.5,2077.9,1950.2,255.2,294.1,673.2 -1.8290256780288108,0.27099910538084715,1.4398966328953218,1637.6,1822.0,1763.5,194.2,626.6,1104.8 -1.8290508149246654,0.27099401239825416,1.5707963267948966,1599.2,1728.7,1728.7,162.9,1093.4,1093.2 -1.8289992256456804,0.2709927420679026,1.7016960206944713,1680.4,1455.7,627.1,151.7,1105.5,1163.9 -1.8289552392053305,0.27097971681168276,1.832595714594046,1915.2,673.5,294.2,162.3,1215.0,1342.7 -1.828976974272781,0.270994854008449,1.9634954084936205,2372.2,423.1,204.0,204.9,1479.6,1700.7 -1.8289691823042784,0.27098878640306867,2.0943951023931953,1937.0,301.9,174.6,316.4,1961.8,1833.9 -1.8289437183102872,0.2709405093415247,2.2252947962927703,1742.3,232.7,173.9,705.2,1719.2,1660.4 -1.8289419216123004,0.27093326014260977,2.356194490192345,1699.7,193.0,193.5,1062.2,1628.4,1629.1 -1.8289399561807873,0.2709348815907979,2.4870941840919194,701.6,173.7,232.8,1083.8,1661.0,1719.9 -1.828951493471026,0.27090062916521696,2.6179938779914944,316.4,175.2,302.8,1202.5,1835.2,1962.5 -1.8289516368736924,0.2708961397576575,2.748893571891069,203.8,203.7,423.9,1477.1,2235.4,2376.6 -1.828977189837688,0.2708741506372059,2.8797932657906435,161.9,293.9,673.6,1914.9,2077.7,1949.8 -1.8289865861114798,0.2708701610830573,3.010692959690218,151.5,621.2,1105.5,1681.4,1822.7,1763.8 -1.829037951987057,0.37116890628295485,0.0,262.9,1093.0,1093.0,1498.7,1728.9,1728.9 -1.829008824451091,0.3711684059598117,0.1308996938995747,298.4,1105.7,1165.2,1535.8,1732.4,1001.1 -1.8289528997404418,0.3711521158647768,0.2617993877991494,370.3,1214.9,1342.2,1706.7,873.3,493.6 -1.8288984820880791,0.3711188525618263,0.39269908169872414,506.7,1479.4,1700.1,2097.4,533.2,345.0 -1.8288548586800066,0.37107464784242605,0.5235987755982988,790.9,1846.9,1719.4,2030.9,418.5,290.7 -1.8288355770157243,0.3710364771416288,0.6544984694978736,1210.0,1616.3,1557.3,1785.2,336.3,277.2 -1.8288195391153226,0.3709743827837779,0.7853981633974483,1063.1,1529.1,1528.1,1698.6,293.5,292.9 -1.8288212082305604,0.37094926314611687,0.916297857297023,1126.4,1557.0,1615.5,1691.8,277.4,336.2 -1.828837745879716,0.370898070920209,1.0471975511965976,1294.3,1718.3,1845.6,792.8,290.2,417.5 -1.8288704145037422,0.37084449677116593,1.1780972450961724,1633.5,2089.1,2308.2,507.5,345.1,564.1 -1.8288740220380144,0.3708414577735375,1.3089969389957472,1707.1,2077.9,1950.3,370.8,493.5,872.8 -1.8288958350340536,0.37083119719011504,1.4398966328953218,1534.5,1822.0,1763.7,297.8,1016.5,1104.8 -1.8289766315163063,0.3708132042299135,1.5707963267948966,1498.9,1728.9,1729.0,263.0,1093.2,1093.1 -1.8289770437973722,0.37081353628742475,1.7016960206944713,1576.6,1760.0,1017.0,255.2,1105.5,1163.9 -1.8289792423163298,0.3708143967764008,1.832595714594046,1799.8,873.0,449.7,278.0,1215.0,1342.7 -1.8290394278793989,0.3708535250601621,1.9634954084936205,2258.9,564.4,345.2,346.7,1479.9,1700.4 -1.8290600722610344,0.3708778903717269,2.0943951023931953,1936.9,417.6,290.2,516.1,1845.8,1718.8 -1.829052645855585,0.3708632578644082,2.2252947962927703,1741.7,336.2,277.4,1092.7,1615.5,1556.7 -1.8290589302862328,0.3708907622427011,2.356194490192345,1699.8,293.0,293.5,1062.5,1528.7,1529.0 -1.8290558046235224,0.3709255141390495,2.4870941840919194,1087.3,277.3,336.4,1083.8,1556.9,1616.3 -1.8290584864266588,0.37092035498841125,2.6179938779914944,515.6,290.8,418.5,1202.7,1719.3,1846.9 -1.8290435987896305,0.37093990332845506,2.748893571891069,345.2,345.2,565.1,1477.7,2094.4,2314.3 -1.8290501383982378,0.3709357024146831,2.8797932657906435,277.4,493.3,873.3,1799.5,2077.3,1950.0 -1.8290382769689673,0.3709430832134957,3.010692959690218,254.9,1008.0,1105.5,1578.4,1822.5,1763.5 -1.8290639248070648,0.47122234912949934,0.0,362.9,1093.1,1092.9,1399.2,1729.3,1728.8 -1.8290051643111216,0.4706506238814283,0.1308996938995747,402.1,1106.0,1165.4,1432.0,1764.6,1385.5 -1.8290360835402022,0.47066078685917034,0.2617993877991494,486.0,1214.9,1342.5,1590.6,1073.2,693.6 -1.829074897405295,0.47068585936072727,0.39269908169872414,648.3,1479.5,1700.2,1955.4,705.8,486.4 -1.829106405596748,0.4707222544981524,0.5235987755982988,990.5,1731.3,1603.7,2031.0,534.1,406.4 -1.8287876370199743,0.47102299673763004,0.6544984694978736,1083.8,1512.4,1453.7,1784.9,439.8,380.9 -1.8287838036690987,0.47100905351142597,0.7853981633974483,1063.2,1429.0,1428.3,1698.4,393.5,393.0 -1.828785121194513,0.4710117071556923,0.916297857297023,1103.8,1453.2,1512.4,1741.9,381.0,439.9 -1.8287962513839606,0.47097982349808776,1.0471975511965976,1295.0,1603.7,1730.8,991.3,405.9,533.4 -1.8288204173469482,0.4709409445900177,1.1780972450961724,1635.1,1949.1,2168.5,648.8,486.7,705.9 -1.8288132514585969,0.47094817798400435,1.3089969389957472,1590.6,2077.1,1949.4,486.2,693.8,1073.5 -1.8288229266390736,0.47094400499068834,1.4398966328953218,1430.7,1821.6,1763.2,401.1,1163.0,1104.8 -1.828891258021988,0.47092887696319075,1.5707963267948966,1398.8,1728.9,1728.7,363.0,1093.1,1093.2 -1.8288800874443745,0.4709284364069828,1.7016960206944713,1473.3,1763.2,1403.5,358.8,1105.6,1164.2 -1.8288722932218617,0.4709253027148228,1.832595714594046,1684.4,1070.8,692.4,393.7,1215.5,1343.2 -1.8289243933051023,0.4709585678865722,1.9634954084936205,2118.2,705.1,486.2,488.8,1480.7,1701.8 -1.8289393005331434,0.4709759532836255,2.0943951023931953,1935.9,533.0,405.7,716.8,1729.6,1602.6 -1.828928770758078,0.4709535484173095,2.2252947962927703,1741.6,439.6,381.0,1125.9,1511.6,1452.7 -1.8289341334679672,0.47097338519826004,2.356194490192345,1699.7,393.1,393.7,1062.6,1428.4,1429.2 -1.8289317232507254,0.47100131842492776,2.4870941840919194,1469.5,380.9,440.1,1084.1,1453.8,1512.9 -1.8289368700100326,0.4709901722607377,2.6179938779914944,714.2,406.6,534.5,1203.2,1604.2,1731.6 -1.8289250511560189,0.47100507085553023,2.748893571891069,486.5,487.1,707.4,1478.4,1953.7,2174.2 -1.8289355759893557,0.470997312008258,2.8797932657906435,392.9,693.8,1073.9,1683.1,2076.7,1949.2 -1.8289279470384867,0.47100229117230175,3.010692959690218,358.6,1164.3,1105.4,1474.0,1821.7,1763.1 -1.8289586565687552,0.5712852739668746,0.0,463.0,1092.9,1093.1,1299.2,1728.8,1728.7 -1.8289151818270188,0.5712837042941372,0.1308996938995747,505.8,1106.1,1165.5,1329.0,1764.8,1765.4 -1.8288487468970536,0.5712634630449076,0.2617993877991494,601.8,1215.5,1343.0,1475.8,1271.2,891.8 -1.8287866521789513,0.5712244582808907,0.39269908169872414,790.5,1480.6,1701.6,1815.0,846.2,627.2 -1.8287379785934472,0.5711735329162364,0.5235987755982988,1191.0,1615.0,1487.7,2030.2,649.5,522.0 -1.8287156856770617,0.5711281672436455,0.6544984694978736,1083.8,1409.1,1350.1,1784.9,543.4,484.4 -1.8286989571002303,0.5710591845633277,0.7853981633974483,1063.3,1328.9,1328.4,1698.8,493.5,493.1 -1.8287013814703463,0.5710276355010848,0.916297857297023,1126.7,1350.1,1408.8,1741.8,484.5,543.4 -1.8287200542412465,0.5709708805733762,1.0471975511965976,1294.9,1487.7,1614.9,1191.1,521.5,648.9 -1.8287559460883978,0.5709131290595821,1.1780972450961724,1634.6,1807.2,2027.0,790.4,627.9,847.2 -1.8287631456241626,0.5709068404904911,1.3089969389957472,1475.1,2077.0,1950.0,601.8,892.9,1215.4 -1.8287888181101029,0.5708940981210835,1.4398966328953218,1327.3,1821.7,1763.2,504.7,1289.5,1104.7 -1.8288736734406212,0.5708751302336108,1.5707963267948966,1298.8,1728.8,1728.4,463.0,1093.5,1093.1 -1.828877923049928,0.5708751748184462,1.7016960206944713,1370.2,1762.9,1792.8,462.3,1105.8,1164.3 -1.8288838065317214,0.5708761972149101,1.832595714594046,1568.9,1270.2,891.6,509.4,1215.3,1343.1 -1.8289472857247269,0.5709165898521578,1.9634954084936205,1976.6,846.0,627.4,630.7,1480.4,1701.9 -1.8289706013607432,0.5709429974479336,2.0943951023931953,1935.9,648.5,521.2,916.4,1614.4,1487.2 -1.8289653770977161,0.5709305816261101,2.2252947962927703,1741.5,543.2,484.6,1125.7,1408.4,1349.6 -1.8289730919227492,0.5709607215359571,2.356194490192345,1699.4,493.0,493.6,1062.6,1328.3,1329.0 -1.828970313877349,0.5709984493363787,2.4870941840919194,1770.1,484.4,543.7,1083.9,1350.3,1409.3 -1.8289727979278623,0.5709959058531286,2.6179938779914944,913.4,522.4,650.1,1203.2,1488.4,1616.4 -1.8289565280609017,0.5710178881027972,2.748893571891069,627.7,628.5,848.6,1478.1,1812.4,2032.7 -1.8289614130753042,0.5710153703214784,2.8797932657906435,508.5,893.3,1215.0,1567.6,2077.0,1949.1 -1.8289474961844048,0.5710236938883406,3.010692959690218,462.0,1290.5,1105.5,1370.8,1822.4,1763.3 -1.8289706119959468,0.6713009256672091,0.0,563.0,1093.3,1093.3,1199.1,1728.6,1729.1 -1.8289549586900387,0.6706714552004827,0.1308996938995747,609.1,1106.0,1165.3,1224.8,1764.3,1823.9 -1.8289921812310475,0.670683448939301,0.2617993877991494,717.0,1215.1,1342.4,1359.7,1472.5,1093.0 -1.829030394074417,0.6707079488538452,0.39269908169872414,931.5,1479.2,1698.7,1671.8,988.4,768.9 -1.8290599808136807,0.6707419941527,0.5235987755982988,1203.4,1500.4,1372.6,2031.3,765.6,637.8 -1.829088324596042,0.6707921056677641,0.6544984694978736,1084.1,1306.0,1246.8,1785.4,647.2,587.9 -1.8290939862633036,0.6708220522776498,0.7853981633974483,1063.3,1229.1,1228.5,1698.6,593.6,593.1 -1.8290932974686813,0.6708842642573738,0.916297857297023,1103.6,1246.2,1304.9,1741.3,587.9,646.6 -1.8290864688505504,0.6709113370973303,1.0471975511965976,1294.4,1371.8,1498.8,1392.3,636.8,763.8 -1.8290793023206997,0.6709221707007498,1.1780972450961724,1633.5,1665.5,1884.8,932.7,768.2,987.2 -1.829032596819106,0.6709668886205427,1.3089969389957472,1360.1,2078.1,1950.3,717.8,1090.8,1216.0 -1.8289976688099934,0.670987512487977,1.4398966328953218,1224.1,1821.6,1808.9,608.2,1163.6,1105.0 -1.8290194736857597,0.6709833081542722,1.5707963267948966,1199.2,1729.1,1728.7,563.0,1093.4,1092.9 -1.8289647167059235,0.6709820707113261,1.7016960206944713,1266.5,1762.7,1821.3,565.6,1105.6,1163.7 -1.8289178472149037,0.6709683845809724,1.832595714594046,1452.7,1471.2,1091.7,624.5,1214.7,1342.4 -1.8289372003643898,0.6709820378307112,1.9634954084936205,1832.9,987.9,768.7,771.4,1479.2,1697.6 -1.8289277226761556,0.6709739776676737,2.0943951023931953,1937.1,764.2,636.8,1114.3,1499.6,1372.2 -1.8289012136619582,0.6709236057305312,2.2252947962927703,1742.0,646.9,587.9,1126.4,1305.1,1246.2 -1.8288990608297218,0.6709142014362595,2.356194490192345,1699.6,593.0,593.5,1062.4,1228.6,1229.1 -1.8288974418473922,0.6709137551725572,2.4870941840919194,1785.0,587.8,646.9,1083.7,1246.7,1305.7 -1.8289096982822035,0.6708778418447405,2.6179938779914944,1113.8,637.5,765.2,1202.4,1372.4,1499.8 -1.8289110522061203,0.6708720147109619,2.748893571891069,738.5,769.2,989.0,1477.3,1669.7,1889.5 -1.8289378740995677,0.6708491752392518,2.8797932657906435,624.2,1091.6,1215.4,1452.6,2077.9,1950.3 -1.8289486012378404,0.6708447405516003,3.010692959690218,542.8,1164.5,1105.8,1267.8,1822.6,1764.0 -1.8290013892688546,0.7711445391898002,0.0,662.9,1093.1,1093.2,1099.0,1729.0,1728.4 -1.8289733265793575,0.7711442428810793,0.1308996938995747,712.5,1105.8,1165.0,1121.5,1764.4,1823.9 -1.8289181187221881,0.7711282683924277,0.2617993877991494,832.3,1214.9,1342.3,1244.1,1671.7,1292.0 -1.828864248261764,0.7710953762902895,0.39269908169872414,1072.8,1479.1,1526.4,1530.3,1129.4,910.1 -1.8288210126275148,0.7710515470702848,0.5235987755982988,1344.2,1384.8,1257.0,2030.9,881.0,753.3 -1.8288021303760014,0.7710138252000158,0.6544984694978736,1083.7,1202.7,1143.3,1785.3,750.6,691.4 -1.8287863169571423,0.7709521456328818,0.7853981633974483,1063.1,1129.3,1128.4,1698.5,693.5,692.9 -1.8287882173325503,0.7709275456799729,0.916297857297023,1126.2,1142.9,1201.3,1741.7,691.4,750.2 -1.8288048645170656,0.7708769121410992,1.0471975511965976,1294.3,1256.3,1383.6,1592.0,752.5,879.4 -1.8288374606660844,0.770823796138397,1.1780972450961724,1531.9,1524.3,1743.6,1074.6,909.3,1128.4 -1.8288409159815835,0.7708212502859506,1.3089969389957472,1244.6,2078.5,1950.2,833.4,1290.0,1216.1 -1.8288268654227702,0.7708265778563732,1.4398966328953218,1120.6,1822.3,1763.6,711.6,1163.3,1104.8 -1.8291075018004799,0.7707644688444752,1.5707963267948966,1098.9,1728.8,1728.7,663.0,1093.4,1093.1 -1.8289919513743975,0.7707608863383519,1.7016960206944713,1163.0,1762.6,1821.1,669.1,1105.5,1163.9 -1.8289676001454434,0.770753777821938,1.832595714594046,1336.8,1670.9,1291.3,740.3,1214.8,1342.4 -1.8290279170151025,0.7707929209066218,1.9634954084936205,1691.6,1129.2,909.9,913.3,1479.3,1525.2 -1.8290543565806718,0.7708232728035369,2.0943951023931953,1936.8,879.8,752.5,1295.0,1384.2,1256.8 -1.829051885964776,0.7708177080267078,2.2252947962927703,1742.1,750.6,691.4,1126.2,1201.7,1142.5 -1.829060704707963,0.7708554486384134,2.356194490192345,1699.6,693.1,693.5,1062.4,1128.6,1128.9 -1.8290575034391046,0.7709002329460506,2.4870941840919194,1784.8,691.4,750.4,1083.5,1143.0,1202.3 -1.8290576534851277,0.7709041204171281,2.6179938779914944,1313.2,753.0,880.8,1202.7,1256.7,1384.2 -1.8290384277027687,0.7709312091112241,2.748893571891069,911.3,910.5,1130.5,1477.6,1528.3,1748.5 -1.8290392179011494,0.7709327344609687,2.8797932657906435,739.7,1290.8,1215.4,1337.3,2077.5,1950.3 -1.8290208351735033,0.7709438799932218,3.010692959690218,669.1,1164.6,1105.6,1164.1,1822.6,1763.6 -1.8290383891296398,0.8712170138670732,0.0,763.0,1093.4,1093.2,999.3,1729.0,1729.2 -1.8289816152036378,0.8706454710863027,0.1308996938995747,816.4,1105.9,1165.1,1017.8,1764.6,1823.5 -1.829013454182148,0.8706558823975898,0.2617993877991494,948.2,1214.9,1342.3,1128.0,1871.4,1491.7 -1.829092415278528,0.8707085663847771,0.39269908169872414,1214.6,1479.4,1384.8,1388.7,1270.8,1051.5 -1.8291019574187355,0.8707210367342919,0.5235987755982988,1203.3,1269.1,1141.5,1980.0,996.9,869.0 -1.8287911253562648,0.8710243135784399,0.6544984694978736,1083.9,1098.5,1039.2,1784.5,854.0,795.1 -1.8287965511427215,0.871053622700869,0.7853981633974483,1063.3,1028.9,1028.7,1698.2,793.6,793.1 -1.8287988144888376,0.8710268407435406,0.916297857297023,1126.7,1039.4,1097.9,1741.6,795.1,854.0 -1.8288118457401585,0.870988744750177,1.0471975511965976,1294.9,1141.1,1268.6,1789.5,868.3,995.7 -1.828835623916197,0.8709504499478005,1.1780972450961724,1388.7,1384.2,1603.8,1215.4,1051.6,1270.8 -1.8288264176988978,0.8709595742842209,1.3089969389957472,1128.4,1961.5,1949.6,948.7,1343.0,1215.7 -1.8288331847275692,0.8709569497624707,1.4398966328953218,1016.8,1821.5,1763.2,814.8,1162.9,1104.7 -1.8288982815407537,0.8709425337613894,1.5707963267948966,999.0,1728.7,1728.7,763.1,1093.3,1093.3 -1.8288840285890458,0.8709419748518394,1.7016960206944713,1059.4,1763.0,1821.6,772.7,1083.1,1164.2 -1.8288734767798447,0.8709380110971232,1.832595714594046,1221.9,1867.5,1488.8,856.4,1215.6,1343.4 -1.828962352413771,0.870997086513384,1.9634954084936205,1550.9,1269.2,1050.3,1055.9,1480.6,1383.1 -1.8289792342294664,0.8710161053795911,2.0943951023931953,1935.8,994.9,867.6,1294.5,1267.9,1140.5 -1.8289518004284786,0.870961899956469,2.2252947962927703,1741.2,853.7,795.0,1125.9,1097.7,1038.9 -1.8289670805020846,0.8710277631192826,2.356194490192345,1699.4,793.0,793.7,1062.4,1028.5,1029.2 -1.8289662104016042,0.8710194410374319,2.4870941840919194,1785.4,795.2,854.5,1084.0,1039.5,1098.6 -1.8289727585284483,0.8710037548235157,2.6179938779914944,1510.8,869.2,997.1,1203.2,1141.5,1269.3 -1.8289582784240728,0.871022916797604,2.748893571891069,1051.9,1053.0,1273.2,1478.4,1387.9,1607.8 -1.828963231138217,0.8710203458896995,2.8797932657906435,855.0,1342.0,1214.7,1221.2,1965.1,1949.6 -1.828948522280459,0.8710290923736781,3.010692959690218,772.5,1164.4,1105.6,1060.2,1821.9,1763.5 -1.728893986344678,0.1708553704143041,0.0,63.2,1193.1,1193.2,1698.9,1628.9,1628.7 -1.728925502704109,0.1714758726371779,0.1308996938995747,91.6,1209.8,1269.4,1743.0,1046.9,233.0 -1.72887520984913,0.1714592979860705,0.2617993877991494,139.7,1330.9,1458.6,1938.2,474.3,95.2 -1.7288210061060134,0.1714239254021046,0.39269908169872414,224.0,1622.3,1843.3,2381.5,282.0,31.9 -1.7291375820324915,0.17095364092597576,0.5235987755982988,393.7,2077.1,1949.8,1914.6,187.3,59.7 -1.729238051283428,0.17114480118574682,0.6544984694978736,914.2,1822.7,1763.9,1681.4,129.3,70.3 -1.7292107000981032,0.17103403461659905,0.7853981633974483,1163.4,1729.1,1728.2,1599.1,93.6,93.2 -1.7292106560016245,0.1710495141072652,0.916297857297023,1230.1,1764.2,1822.9,914.8,70.5,129.4 -1.7292071116685677,0.17106187935627593,1.0471975511965976,1410.7,1950.2,2077.2,392.9,59.3,186.7 -1.729201622180928,0.1710683393226211,1.1780972450961724,1775.8,2372.9,2238.3,223.8,63.1,282.4 -1.7291551615462313,0.17111103643554548,1.3089969389957472,1937.6,1961.7,1834.3,139.5,95.3,475.0 -1.7291201430968697,0.1711298322200019,1.4398966328953218,1740.8,1718.0,1660.0,90.8,238.2,1068.9 -1.729142179006418,0.17112479173212125,1.5707963267948966,1698.9,1629.1,1628.7,63.0,1193.3,1193.0 -1.729087867599217,0.17112269145968972,1.7016960206944713,1783.9,1063.6,236.8,48.4,1208.8,1267.7 -1.7290417767924715,0.17110802075019116,1.832595714594046,2031.6,473.8,95.0,46.8,1305.4,1458.8 -1.7290618366088604,0.1711216717700934,1.9634954084936205,2230.0,281.8,63.0,63.4,1621.8,1843.2 -1.7290527061683514,0.1711142464118447,2.0943951023931953,1820.9,186.4,59.3,117.2,2076.2,1949.1 -1.7290264345167041,0.17106429613103002,2.2252947962927703,1638.5,129.2,70.5,319.5,1822.2,1763.8 -1.729024041612854,0.17105542032920606,2.356194490192345,1599.8,93.0,93.7,1162.4,1728.2,1729.2 -1.7290214250135547,0.1710556134254979,2.4870941840919194,230.8,70.3,129.5,1187.7,1764.6,1823.5 -1.7290328684431209,0.17101966394035317,2.6179938779914944,117.2,59.7,187.5,1318.8,1951.2,2078.7 -1.7290327673131234,0.17101363706324357,2.748893571891069,62.5,62.6,282.7,1619.6,2378.1,2233.8 -1.729058767030375,0.17098999997624142,2.8797932657906435,46.4,94.8,475.2,2029.6,1961.3,1833.8 -1.7290689442997758,0.1709845194766153,3.010692959690218,48.1,235.3,1059.8,1784.5,1718.9,1660.0 -1.729121923421948,0.2712844948735227,0.0,163.1,1192.9,1193.1,1599.1,1629.2,1629.1 -1.7290938221891525,0.27128310538173683,0.1308996938995747,195.1,1209.6,1269.2,1639.3,1429.9,615.7 -1.7290389962115598,0.27126647124997394,0.2617993877991494,255.0,1331.0,1458.5,1822.6,673.3,294.1 -1.728985559163594,0.2712333097320727,0.39269908169872414,365.5,1621.8,1842.7,2240.5,422.9,203.9 -1.7289428073935913,0.2711896776381222,0.5235987755982988,592.9,1961.7,1834.3,1914.8,302.8,175.2 -1.7289237181134975,0.2711521677547619,0.6544984694978736,1187.0,1719.4,1660.7,1681.5,232.8,173.8 -1.7289077332912095,0.27109102893686066,0.7853981633974483,1163.0,1629.1,1628.6,1598.9,193.5,193.1 -1.7289087646334123,0.27106650088522977,0.916297857297023,1229.8,1660.3,1719.5,1301.7,174.0,232.9 -1.7289244139403734,0.2710155812802604,1.0471975511965976,1410.5,1834.6,1962.1,592.5,174.9,302.2 -1.7289562468855657,0.2709622069683568,1.1780972450961724,1775.8,2231.7,2238.3,365.6,204.3,423.7 -1.7289589466778548,0.27095876349745995,1.3089969389957472,1821.4,1961.5,1834.4,255.2,294.9,674.5 -1.7289800648083757,0.2709475339691083,1.4398966328953218,1637.5,1718.2,1659.8,194.4,628.8,1207.9 -1.7290605885392387,0.27092901705824257,1.5707963267948966,1598.5,1629.1,1628.6,163.1,1193.1,1193.0 -1.7290609904498697,0.2709286837725524,1.7016960206944713,1680.2,1453.0,626.0,152.0,1208.9,1267.4 -1.7290634921279788,0.2709287229574504,1.832595714594046,1915.8,672.9,294.3,162.5,1330.8,1458.7 -1.729123998679326,0.2709676805613095,1.9634954084936205,2230.3,422.9,204.1,205.3,1622.2,1843.3 -1.7291447754572875,0.27099231117442546,2.0943951023931953,1820.7,302.0,149.4,317.1,1960.3,1833.3 -1.7291374544914702,0.2709778013433837,2.2252947962927703,1638.2,232.7,174.1,707.6,1718.5,1660.0 -1.7291435414303298,0.27100551622963853,2.356194490192345,1599.9,193.1,193.7,1162.5,1628.2,1629.1 -1.7291397056626017,0.27104057005273696,2.4870941840919194,700.3,173.9,233.1,1187.5,1661.0,1720.2 -1.7291418198331223,0.27103524814497204,2.6179938779914944,316.2,175.4,303.2,1318.7,1835.1,1963.2 -1.7291259243605293,0.27105451876622055,2.748893571891069,203.8,204.0,424.2,1619.6,2236.7,2233.4 -1.7291319175250481,0.27104961892671553,2.8797932657906435,161.9,294.5,674.6,1914.3,1961.2,1834.1 -1.7291197250814987,0.2710561252234349,3.010692959690218,151.6,623.0,1208.8,1681.1,1718.8,1660.4 -1.7291456491583581,0.3713355708543611,0.0,263.1,1192.7,1193.0,1499.2,1628.9,1629.0 -1.7290883610013608,0.37081644765409094,0.1308996938995747,298.6,1209.6,1269.2,1535.5,1661.3,999.4 -1.7291004459487718,0.37082062413465455,0.2617993877991494,370.7,1331.0,1458.5,1706.5,872.5,493.5 -1.7291199258460128,0.37083353758036597,0.39269908169872414,507.3,1622.2,1842.7,2098.4,564.1,345.1 -1.7291360882153173,0.37085357480803127,0.5235987755982988,792.2,1846.0,1718.9,1915.0,418.3,290.8 -1.7291553971893006,0.3708881932259873,0.6544984694978736,1215.1,1615.9,1556.6,1681.2,336.3,277.4 -1.7291568394438948,0.37090232503619647,0.7853981633974483,1162.8,1529.1,1528.4,1599.0,293.5,293.1 -1.7291556837544433,0.3709491075774134,0.916297857297023,1230.1,1556.8,1615.7,1602.8,277.5,336.4 -1.7291521229257558,0.37096204839601077,1.0471975511965976,1410.7,1719.2,1846.6,791.9,290.3,417.7 -1.7291514591048889,0.3709613217894847,1.1780972450961724,1776.3,2090.6,2238.2,507.0,345.3,564.7 -1.7291131475538835,0.37099695661167265,1.3089969389957472,1706.2,1961.7,1834.2,370.6,494.0,873.5 -1.7290880152760268,0.37101106682426654,1.4398966328953218,1534.3,1718.0,1659.8,297.6,1018.9,1334.3 -1.7291204184698616,0.3710041734909426,1.5707963267948966,1521.2,1629.0,1628.9,262.9,1193.2,1193.3 -1.7290756984223945,0.37100292890078235,1.7016960206944713,1577.1,1659.5,1014.5,255.2,1209.0,1267.4 -1.7290379490038248,0.3709913558008784,1.832595714594046,1800.3,871.8,493.1,278.0,1330.9,1458.6 -1.729064795707762,0.37100977902113597,1.9634954084936205,2230.0,563.9,345.0,346.9,1622.0,1843.3 -1.7290605754345132,0.3710081021656191,2.0943951023931953,1820.8,417.4,290.2,516.7,1845.0,1717.9 -1.729037337903279,0.3709643430798242,2.2252947962927703,1638.2,336.1,277.4,1095.1,1615.0,1556.6 -1.7290362907958863,0.3709617261246334,2.356194490192345,1599.9,292.9,293.6,1162.5,1528.2,1528.9 -1.7290335328712052,0.37096782144315954,2.4870941840919194,1084.8,277.4,336.6,1187.4,1557.5,1616.7 -1.7290435612419757,0.3709371244387871,2.6179938779914944,515.1,290.9,418.6,1318.5,1719.5,1847.6 -1.7290410700675916,0.37093554786896443,2.748893571891069,345.0,345.4,565.6,1619.5,2095.5,2234.0 -1.7290639343578118,0.3709154159307284,2.8797932657906435,277.4,494.0,874.1,1798.9,1961.2,1834.0 -1.7290704907086085,0.37091243491485293,3.010692959690218,232.3,1010.5,1335.3,1577.6,1719.0,1660.0 -1.729118801839425,0.47120892757483324,0.0,363.0,1192.8,1193.0,1398.9,1629.0,1629.0 -1.729087358165755,0.4712080743829019,0.1308996938995747,402.1,1209.8,1268.9,1432.3,1707.3,1382.0 -1.7290298607672436,0.4711911694866524,0.2617993877991494,486.1,1330.6,1458.3,1591.4,1071.7,692.6 -1.7289742176624392,0.471157151724205,0.39269908169872414,648.7,1622.0,1842.4,1957.0,705.1,486.1 -1.7289297320218353,0.47111217348722856,0.5235987755982988,991.2,1730.7,1603.3,1914.8,508.4,406.3 -1.7289095131185852,0.4710730160894381,0.6544984694978736,1187.1,1512.6,1453.5,1681.5,439.7,380.8 -1.7288929915837596,0.47101002769375633,0.7853981633974483,1163.0,1429.0,1428.7,1598.8,393.5,393.1 -1.7288941377010236,0.47098373751951916,0.916297857297023,1229.9,1453.5,1512.1,1638.7,380.9,439.8 -1.7289104533277857,0.47093129175406157,1.0471975511965976,1410.3,1603.3,1730.7,991.6,405.9,533.4 -1.7289433470585165,0.4708767607141069,1.1780972450961724,1775.6,1948.8,2168.6,648.7,486.7,705.8 -1.728947332039894,0.4708726753857664,1.3089969389957472,1590.9,1961.7,1834.4,486.2,693.5,1073.2 -1.728969776459703,0.4708613143996365,1.4398966328953218,1430.7,1763.3,1660.2,401.2,1266.2,1208.0 -1.7290514976200522,0.47084302950257473,1.5707963267948966,1399.0,1629.2,1628.9,363.0,1193.2,1193.1 -1.7290528408896102,0.47084324556453616,1.7016960206944713,1473.6,1704.9,1403.9,358.7,1208.8,1244.7 -1.7290559849487335,0.4708440259697979,1.832595714594046,1684.3,1071.2,692.4,393.7,1330.8,1458.7 -1.7291168714258247,0.4708837187389774,1.9634954084936205,2118.0,705.0,486.1,488.8,1622.4,1843.3 -1.729137826782433,0.4709089953352694,2.0943951023931953,1820.7,533.0,405.7,716.5,1729.6,1602.7 -1.7291305460223831,0.47089504618658684,2.2252947962927703,1638.2,439.8,381.0,1229.5,1511.8,1453.2 -1.729136642892342,0.4709232135122312,2.356194490192345,1599.7,393.1,393.7,1162.2,1428.5,1429.2 -1.7291328639331442,0.47095864038402246,2.4870941840919194,1470.0,380.8,440.1,1187.4,1453.8,1512.9 -1.729135039725627,0.47095371384222284,2.6179938779914944,714.2,406.5,534.4,1318.7,1604.2,1732.1 -1.7291192536145947,0.4709734188990411,2.748893571891069,486.5,486.9,707.1,1619.4,1954.0,2173.6 -1.7291252753666597,0.47096904331859824,2.8797932657906435,392.9,693.5,1073.8,1682.7,1961.5,1833.8 -1.7291130030379636,0.47097613311698683,3.010692959690218,358.5,1267.4,1209.0,1474.4,1718.9,1660.0 -1.7291385468072236,0.571255344343411,0.0,462.9,1192.8,1193.0,1299.2,1628.5,1629.0 -1.7290784065714884,0.5706574145332997,0.1308996938995747,505.9,1209.5,1269.2,1328.6,1661.2,1682.3 -1.7291081335149714,0.5706673313515114,0.2617993877991494,601.9,1331.2,1458.4,1475.7,1271.4,892.1 -1.7291458836939928,0.5706920341600874,0.39269908169872414,790.6,1621.8,1838.2,1814.7,846.3,627.2 -1.7291765779460713,0.5707280098466927,0.5235987755982988,1191.1,1615.2,1487.7,1914.7,649.5,522.0 -1.7288074712635764,0.5710254533997097,0.6544984694978736,1187.1,1408.7,1350.0,1681.2,543.4,484.5 -1.728802698032852,0.5710075358608497,0.7853981633974483,1163.1,1329.0,1328.4,1598.8,493.5,493.1 -1.728803945702997,0.5710110171883571,0.916297857297023,1230.3,1350.1,1408.8,1638.4,484.5,543.5 -1.7288143694603688,0.5709813002599802,1.0471975511965976,1410.4,1487.9,1615.4,1190.6,521.6,649.0 -1.728837132678723,0.5709446065473576,1.1780972450961724,1776.4,1808.0,2027.3,790.3,627.9,847.0 -1.72882810610071,0.5709535413553357,1.3089969389957472,1474.9,1961.3,1834.3,576.5,893.1,1272.8 -1.7288356617408385,0.5709504681017257,1.4398966328953218,1327.1,1717.8,1660.0,504.6,1323.9,1208.1 -1.7289017949862688,0.5709358441666299,1.5707963267948966,1298.8,1629.1,1628.8,463.0,1193.2,1193.1 -1.7288885689696456,0.5709353413815514,1.7016960206944713,1369.9,1659.2,1706.9,462.3,1209.1,1267.9 -1.72887894769404,0.5709316606022257,1.832595714594046,1568.9,1270.1,891.3,509.3,1331.1,1459.1 -1.7289295146559145,0.5709639984173827,1.9634954084936205,1976.4,846.1,627.1,630.6,1622.3,1836.7 -1.728943268327556,0.5709802079099378,2.0943951023931953,1820.3,648.3,521.3,916.6,1613.8,1487.0 -1.7289319897224897,0.5709564835686505,2.2252947962927703,1638.0,543.2,484.5,1313.0,1407.9,1349.7 -1.7289369890996114,0.5709749451454085,2.356194490192345,1599.3,492.9,493.6,1162.6,1328.5,1329.2 -1.7289345735509962,0.5710015574990566,2.4870941840919194,1681.8,484.5,543.7,1187.8,1350.4,1409.4 -1.7289400372901742,0.5709892287345266,2.6179938779914944,913.2,522.3,650.1,1319.1,1488.5,1616.4 -1.728928782175112,0.571003141004067,2.748893571891069,627.7,628.4,848.9,1620.1,1812.2,2032.7 -1.7289400564167448,0.5709946377388844,2.8797932657906435,508.4,893.8,1273.7,1567.5,1960.7,1833.2 -1.7289332812058489,0.5709991343320469,3.010692959690218,462.0,1313.5,1209.3,1370.6,1718.3,1660.0 -1.7289650482406236,0.6712829228469308,0.0,563.0,1193.0,1193.2,1199.2,1628.5,1628.8 -1.7289223006877257,0.6712813781818203,0.1308996938995747,609.4,1209.9,1269.2,1225.5,1660.9,1720.6 -1.7288564125819832,0.6712613179994067,0.2617993877991494,717.5,1331.1,1458.8,1360.2,1470.1,1091.1 -1.7287947234216166,0.6712225950862134,0.39269908169872414,932.3,1622.1,1666.4,1673.1,987.5,768.4 -1.7287463309114064,0.6711720176822005,0.5235987755982988,1318.6,1499.5,1372.3,1914.5,764.9,637.5 -1.7287241858744185,0.6711270191903513,0.6544984694978736,1187.4,1305.4,1246.5,1681.1,646.9,587.8 -1.728707501783655,0.6710584078897226,0.7853981633974483,1163.3,1229.1,1228.4,1598.9,593.5,593.0 -1.728709866765849,0.6710271872064844,0.916297857297023,1230.0,1246.4,1305.2,1638.2,588.1,646.9 -1.72872840746441,0.6709707081603795,1.0471975511965976,1410.9,1372.4,1499.6,1390.5,637.1,764.6 -1.7287641232956739,0.6709131776558717,1.1780972450961724,1672.1,1666.7,1886.1,931.8,769.0,988.4 -1.728771119304208,0.6709070367044148,1.3089969389957472,1359.5,1962.1,1834.1,717.4,1092.6,1331.3 -1.7287965799824332,0.670894374513431,1.4398966328953218,1223.6,1718.0,1794.8,608.1,1266.4,1208.2 -1.7288812300949823,0.6708754522109528,1.5707963267948966,1198.9,1628.7,1628.6,563.1,1193.3,1193.2 -1.7288852902297187,0.6708754950281652,1.7016960206944713,1266.6,1659.5,1717.8,565.8,1209.3,1267.4 -1.7288910045263564,0.670876471832881,1.832595714594046,1453.2,1469.4,1090.6,625.1,1331.2,1458.9 -1.7289543308988773,0.6709168001784485,1.9634954084936205,1834.8,987.3,768.2,772.4,1622.4,1664.9 -1.7289775139914374,0.6709431253174467,2.0943951023931953,1820.6,763.9,636.8,1116.5,1498.5,1371.5 -1.728972188461256,0.6709305989632388,2.2252947962927703,1638.2,646.6,588.1,1229.6,1304.7,1246.1 -1.7289798303876243,0.6709606122056546,2.356194490192345,1599.4,593.1,593.6,1162.5,1228.3,1229.0 -1.7289770063294725,0.6709982091366498,2.4870941840919194,1770.1,588.1,647.2,1187.7,1246.8,1306.0 -1.7289794898328579,0.6709955288223144,2.6179938779914944,1112.7,637.9,765.6,1318.9,1372.8,1500.6 -1.7289632449732748,0.6710173889125179,2.748893571891069,769.1,770.1,990.3,1620.0,1671.2,1891.1 -1.728968196617744,0.6710147668862778,2.8797932657906435,624.0,1093.1,1330.5,1452.3,1961.1,1833.5 -1.7289543696601464,0.6710230174398419,3.010692959690218,565.5,1268.0,1209.2,1267.4,1718.6,1660.1 -1.7289776182634766,0.7713003534326675,0.0,663.0,1193.2,1193.3,1099.1,1629.0,1629.2 -1.7289591675319727,0.7706889024082748,0.1308996938995747,712.8,1209.5,1268.8,1121.2,1660.9,1719.9 -1.728995570909438,0.7707006663917337,0.2617993877991494,832.8,1330.4,1457.8,1244.1,1672.4,1292.3 -1.7290320607341514,0.7707240661500763,0.39269908169872414,1073.1,1620.9,1526.4,1530.0,1129.7,910.4 -1.7290600838410541,0.7707564301608218,0.5235987755982988,1319.0,1384.9,1257.1,1915.5,881.1,753.5 -1.7290873700352127,0.770804583211093,0.6544984694978736,1187.4,1202.1,1143.0,1681.7,750.8,691.5 -1.7290925218908577,0.7708324583577486,0.7853981633974483,1163.1,1129.1,1128.4,1599.0,693.5,692.9 -1.729091859773518,0.7708926965886196,0.916297857297023,1230.2,1142.7,1201.6,1637.8,691.4,750.1 -1.7290855242778138,0.7709179855983688,1.0471975511965976,1409.9,1256.3,1383.6,1591.9,752.2,879.4 -1.7290792201706289,0.7709273233678124,1.1780972450961724,1531.8,1524.7,1743.5,1074.4,909.4,1128.4 -1.7290336282108438,0.770970914233793,1.3089969389957472,1244.8,1962.6,1835.1,833.3,1289.7,1426.1 -1.7289999767782667,0.770990792556584,1.4398966328953218,1120.5,1718.5,1660.0,711.6,1266.9,1208.4 -1.7290231271590406,0.7709862156319625,1.5707963267948966,1099.0,1628.6,1628.6,662.9,1193.4,1193.3 -1.7289696474019682,0.770984969853604,1.7016960206944713,1163.1,1659.1,1717.5,669.0,1209.0,1267.3 -1.7288825018633558,0.7709556883397615,1.832595714594046,1337.2,1670.7,1291.1,740.2,1330.3,1458.2 -1.7291054851620797,0.7710988416590323,1.9634954084936205,1691.4,1129.1,909.7,913.3,1621.2,1525.7 -1.7290038684017968,0.7709918415520871,2.0943951023931953,1821.5,879.8,752.5,1314.0,1384.2,1256.6 -1.7289627898160946,0.7709139142456587,2.2252947962927703,1638.3,750.3,691.4,1229.8,1202.0,1142.8 -1.7289609930191243,0.7709058904751365,2.356194490192345,1599.6,693.0,693.6,1162.8,1128.5,1128.8 -1.7289589731939632,0.7709165642551947,2.4870941840919194,1681.4,691.5,750.5,1187.2,1143.0,1202.2 -1.728967317570285,0.7708933854940059,2.6179938779914944,1313.1,753.3,880.7,1317.9,1256.7,1384.2 -1.7289615162666103,0.770898930725024,2.748893571891069,911.1,910.5,1130.4,1618.5,1528.3,1748.2 -1.7289790605678077,0.7708847117752489,2.8797932657906435,739.8,1290.7,1427.2,1337.1,1962.1,1834.6 -1.7289793405010416,0.7708858183693166,3.010692959690218,669.1,1268.2,1209.2,1164.3,1719.3,1660.3 -1.7290194739546598,0.8711760202530872,0.0,763.0,1193.0,1193.1,999.1,1629.3,1628.9 -1.7289824982510857,0.8711754012759041,0.1308996938995747,816.2,1209.6,1268.6,1017.9,1660.8,1720.2 -1.7289206637272176,0.8711573734874003,0.2617993877991494,948.3,1330.7,1457.9,1128.5,1827.5,1491.6 -1.7288617430124014,0.8711213068266983,0.39269908169872414,1214.5,1620.7,1385.1,1388.8,1270.7,1051.2 -1.7288148398089973,0.871073546364614,0.5235987755982988,1319.0,1269.2,1141.7,1915.7,996.7,868.9 -1.7287936429272461,0.8710315321081903,0.6544984694978736,1187.3,1098.8,1039.8,1682.0,854.1,794.8 -1.7287767654404835,0.8709654185025419,0.7853981633974483,1163.2,1029.2,1028.3,1599.1,793.6,792.9 -1.7287787585835723,0.8709366289955525,0.916297857297023,1229.9,1039.2,1098.0,1638.0,794.9,853.6 -1.7287964967083576,0.870882236007857,1.0471975511965976,1409.8,1140.8,1267.8,1791.8,867.6,994.9 -1.7288309663614156,0.8708260013398097,1.1780972450961724,1389.8,1383.2,1602.3,1216.2,1050.5,1269.4 -1.7288107035733042,0.8708500044821876,1.3089969389957472,1128.9,1959.4,1834.9,949.0,1459.3,1331.8 -1.7288578421515568,0.8708264960899297,1.4398966328953218,1017.2,1718.7,1659.9,815.2,1266.9,1208.4 -1.728946123162519,0.8708068421750532,1.5707963267948966,999.1,1629.0,1628.7,762.9,1193.3,1193.0 -1.7289474868039905,0.8708072784756486,1.7016960206944713,1059.4,1658.9,1717.5,772.6,1209.0,1267.3 -1.728948584945325,0.8708079608659307,1.832595714594046,1221.1,1825.9,1490.8,855.9,1330.6,1458.0 -1.7290073332297884,0.870846152837607,1.9634954084936205,1549.8,1270.3,1051.1,1054.9,1620.9,1384.1 -1.7290268533417323,0.8708691011465266,2.0943951023931953,1821.6,995.5,867.9,1410.6,1268.6,1141.0 -1.7290187005953113,0.8708529666319145,2.2252947962927703,1638.5,854.1,794.9,1229.8,1098.0,1039.2 -1.7290247504597986,0.8708789124103036,2.356194490192345,1599.4,793.0,793.5,1162.5,1028.4,1028.9 -1.7290219186902147,0.8709121532361779,2.4870941840919194,1681.4,795.0,854.0,1187.3,1039.4,1098.7 -1.7290251300501367,0.8709058038306292,2.6179938779914944,1512.6,868.8,996.4,1318.3,1141.2,1268.8 -1.729011159552268,0.870924382214399,2.748893571891069,1052.6,1051.9,1272.0,1547.7,1386.8,1606.9 -1.7290186208026626,0.8709195772434803,2.8797932657906435,855.4,1458.4,1330.8,1221.5,1961.9,1834.4 -1.729007724707663,0.8709266436214154,3.010692959690218,772.5,1268.2,1209.2,1060.5,1719.3,1660.6 -2.829060887576355,0.17089771314193714,0.0,63.0,93.1,93.0,1699.0,2728.3,2729.4 -2.829094953187069,0.1714189307417211,0.1308996938995747,91.6,119.2,129.6,1742.6,963.9,233.3 -2.829000520298327,0.1713889572651679,0.2617993877991494,116.7,59.3,186.8,1937.8,474.7,95.2 -2.82894302656649,0.1713519802785144,0.39269908169872414,62.7,63.0,283.8,2380.7,282.2,63.0 -2.828904841523059,0.17131184414393097,0.5235987755982988,150.3,95.3,474.6,3186.4,187.4,59.8 -2.8288906947963506,0.17128171195994368,0.6544984694978736,48.3,234.6,1054.8,2820.4,129.5,70.5 -2.828877401622831,0.1712295900157319,0.7853981633974483,63.1,1728.8,1728.3,2698.7,93.7,93.3 -2.8288785912487,0.1712142654532769,0.916297857297023,91.3,1763.5,1822.7,917.0,70.6,129.5 -2.828891850060046,0.17117179258471382,1.0471975511965976,139.2,1949.8,2077.4,393.6,59.5,94.9 -2.8289191802454354,0.17112518911950092,1.1780972450961724,222.6,2371.7,2591.1,224.2,63.3,110.3 -2.828916152615242,0.17112659161562815,1.3089969389957472,393.4,3233.6,3106.5,139.8,95.6,200.7 -2.8289308624096297,0.17111821661271853,1.4398966328953218,837.0,2856.0,2797.2,91.0,128.5,70.1 -2.829004877467542,0.17110022755006216,1.5707963267948966,1698.8,2729.2,2728.8,63.3,93.2,93.0 -2.828999509211308,0.17109871910472862,1.7016960206944713,1783.7,1065.7,238.0,48.6,122.5,129.3 -2.828997219021363,0.1710963765802871,1.832595714594046,2030.9,474.5,95.5,47.1,58.8,186.6 -2.8290541603384534,0.17113186713773,1.9634954084936205,2542.4,282.3,63.3,63.7,62.5,283.5 -2.8290727232612785,0.17115257973917153,2.0943951023931953,3091.3,186.7,59.5,117.4,95.5,475.9 -2.829064264850906,0.17113432727195366,2.2252947962927703,2776.8,129.5,70.7,91.0,235.6,1059.5 -2.8290701416286925,0.1711585222267169,2.356194490192345,2699.2,93.2,93.8,62.4,1728.0,1728.9 -2.829066886006946,0.1711903690412666,2.4870941840919194,316.5,70.5,129.6,48.3,1764.3,1823.4 -2.829069895542841,0.1711824048095747,2.6179938779914944,117.6,59.9,94.5,46.5,1950.8,2078.1 -2.8290553943491505,0.1711993421933211,2.748893571891069,62.7,62.7,110.3,63.2,2377.3,2598.0 -2.829062852698841,0.17139113423671248,2.8797932657906435,46.6,95.0,200.4,117.2,3233.1,3105.4 -2.8288970833671985,0.1709027149964526,3.010692959690218,48.1,129.3,70.4,318.0,2857.9,2799.1 -2.8289197330482785,0.17089931104718792,0.0,63.1,93.1,93.0,1699.1,2728.7,2728.8 -2.828984108458107,0.1709043995769275,0.1308996938995747,91.4,119.8,129.6,1742.5,965.6,233.6 -2.8289736204978886,0.17090110205968667,0.2617993877991494,117.1,59.4,186.8,1937.2,475.0,95.2 -2.8289841304067647,0.17090752580259405,0.39269908169872414,62.9,63.1,283.7,2379.9,282.2,62.9 -2.8289962097427663,0.17092201130274054,0.5235987755982988,149.9,95.4,474.3,3187.5,187.4,59.7 -2.829014170497188,0.17095195003219965,0.6544984694978736,48.4,234.7,1053.4,2820.5,129.4,70.3 -2.829015379647139,0.17096168618359964,0.7853981633974483,63.2,1728.9,1728.1,2698.6,93.6,93.1 -2.829015310211368,0.1710050006334578,0.916297857297023,91.4,1763.9,1822.4,917.9,70.5,129.2 -2.8290134454481866,0.17101520128119319,1.0471975511965976,139.2,1949.6,2076.6,393.7,59.2,95.3 -2.829014646203069,0.17101209235683124,1.1780972450961724,222.6,2370.9,2590.2,224.1,63.0,109.9 -2.8289784807902336,0.17104625565256315,1.3089969389957472,393.2,3234.7,3106.9,139.7,95.1,200.9 -2.8289555193189475,0.17105973170527977,1.4398966328953218,921.6,2909.0,2797.9,90.9,128.7,70.2 -2.828989941822207,0.17105196265142708,1.5707963267948966,1698.8,2729.1,2728.1,63.1,93.4,93.1 -2.828947195674598,0.17105039451065962,1.7016960206944713,1783.5,1066.6,237.6,48.4,123.9,129.3 -2.82891126589967,0.17103920359646674,1.832595714594046,2030.7,474.6,95.1,46.8,58.9,186.5 -2.828939964075067,0.17105792970924028,1.9634954084936205,2542.0,282.2,63.0,63.3,62.6,283.4 -2.8289375827937957,0.17105670994229483,2.0943951023931953,3092.2,186.6,59.2,116.9,95.5,475.6 -2.8289157495132984,0.17101411883349282,2.2252947962927703,2777.3,129.3,70.5,91.1,235.2,1057.9 -2.8289157968151972,0.1710129676936727,2.356194490192345,2699.5,93.1,93.6,62.5,1728.4,1729.1 -2.8289139471193914,0.17102052878699414,2.4870941840919194,316.5,70.3,129.3,48.4,1764.4,1823.2 -2.8289239905999137,0.17099160048843243,2.6179938779914944,117.3,59.7,94.7,46.5,1950.6,2077.9 -2.828921424693808,0.17099145803870353,2.748893571891069,62.5,62.5,109.9,63.2,2376.7,2596.6 -2.828943374291192,0.17097258649958524,2.8797932657906435,46.4,94.6,200.5,117.1,3233.1,3105.5 -2.828948743094004,0.17097038054447378,3.010692959690218,48.1,129.3,70.4,318.1,2857.7,2799.3 -2.8289506317077633,0.17097207377989831,0.0,63.1,93.1,93.0,1698.9,2728.8,2728.8 -2.828993119362331,0.17097627737335208,0.1308996938995747,91.4,119.9,129.6,1742.6,965.3,233.5 -2.828965807058611,0.1709678459751922,0.2617993877991494,117.1,59.4,186.8,1937.2,475.0,95.1 -2.8289617881303926,0.17096521223614625,0.39269908169872414,62.9,63.1,283.8,2379.9,282.2,62.9 -2.828962853194825,0.17096792537199845,0.5235987755982988,149.9,95.4,474.4,3187.0,187.4,59.7 -2.828973761320767,0.17098476812915164,0.6544984694978736,48.4,234.6,1053.3,2820.6,129.4,70.3 -2.828971775505182,0.17098090931459886,0.7853981633974483,63.2,1729.3,1728.5,2699.0,93.6,93.1 -2.828972077428113,0.17101135752601548,0.916297857297023,91.4,1763.3,1822.4,918.0,70.5,129.2 -2.828973679112102,0.17101004366230188,1.0471975511965976,139.2,1949.3,2076.5,393.6,59.2,95.3 -2.8289807631304713,0.1709974614394798,1.1780972450961724,222.6,2370.9,2590.3,224.1,63.0,109.9 -2.8289520218282287,0.17102461871418018,1.3089969389957472,393.2,3234.2,3106.6,139.7,95.1,200.9 -2.8289374215559357,0.17103358625265797,1.4398966328953218,921.7,2856.7,2797.8,90.9,128.6,70.2 -2.8289805225676234,0.17102380513751414,1.5707963267948966,1699.0,2728.7,2728.0,63.1,93.4,93.1 -2.828945885368924,0.1710224860389855,1.7016960206944713,1783.7,1066.9,237.7,48.4,123.8,129.3 -2.8289171588292605,0.17101345661210465,1.832595714594046,2030.7,474.5,95.2,46.8,58.9,186.5 -2.828951850717036,0.17103592951127933,1.9634954084936205,2542.1,282.2,63.0,63.3,62.6,283.4 -2.828953896069744,0.17103946488004484,2.0943951023931953,3091.9,186.6,59.2,116.9,95.5,475.6 -2.828934867769425,0.1710021223849323,2.2252947962927703,2776.6,129.3,70.5,91.0,235.3,1058.1 -2.8289361647177893,0.17100639034332366,2.356194490192345,2699.6,93.1,93.6,62.5,1728.8,1729.0 -2.8289341187014077,0.17101911701454697,2.4870941840919194,316.4,70.3,129.3,48.4,1764.4,1823.1 -2.828942773526978,0.17099471669929978,2.6179938779914944,117.3,59.7,94.7,46.5,1950.2,2078.5 -2.828937852075314,0.17099831464230153,2.748893571891069,62.5,62.5,109.9,63.2,2376.6,2596.4 -2.8289568358699673,0.17098220590581614,2.8797932657906435,46.4,94.6,200.5,117.1,3233.3,3105.3 -2.8289588925462823,0.17098176387546515,3.010692959690218,48.0,129.3,70.5,318.1,2858.0,2798.5 -2.8289573692541103,0.17098424397284528,0.0,63.1,93.0,93.0,1698.7,2729.2,2729.5 -2.8289961861802118,0.17098828787501064,0.1308996938995747,91.4,119.9,129.6,1742.5,965.1,233.5 -2.828966295179913,0.17097906883654934,0.2617993877991494,117.1,59.4,186.8,1937.2,474.8,95.1 -2.828959985851759,0.1709750099906031,0.39269908169872414,62.9,63.1,283.7,2379.6,282.2,62.8 -2.8289592984748753,0.17097585676456162,0.5235987755982988,149.8,95.4,474.3,3187.6,187.4,59.7 -2.828969073013759,0.1709906141031139,0.6544984694978736,48.4,234.6,1053.4,2821.1,129.4,70.3 -2.828966569759537,0.17098458909984338,0.7853981633974483,63.2,1728.7,1728.3,2698.8,93.6,93.0 -2.82896691807882,0.17101297990426834,0.916297857297023,91.4,1763.4,1822.2,917.8,70.5,129.2 -2.8289690617981487,0.17100981980504648,1.0471975511965976,139.2,1949.1,2076.8,393.6,59.2,95.2 -2.8289770790499538,0.17099571846928985,1.1780972450961724,222.6,2371.1,2590.1,224.1,63.0,109.9 -2.8289495189394147,0.17102174564612915,1.3089969389957472,393.1,3234.1,3106.6,139.6,95.1,200.9 -2.82893625385813,0.1710299781396558,1.4398966328953218,921.6,2856.7,2798.1,90.8,128.6,70.2 -2.828980746239442,0.17101987152823317,1.5707963267948966,1698.5,2728.4,2728.3,63.1,93.4,93.1 -2.828947410757264,0.17101858929973313,1.7016960206944713,1783.9,1066.8,237.7,48.4,123.8,129.2 -2.828919842542146,0.17100990165522467,1.832595714594046,2031.0,474.5,95.2,46.8,58.9,186.5 -2.828955496431114,0.17103297909341708,1.9634954084936205,2541.9,282.1,63.0,63.3,62.6,283.4 -2.828958247997061,0.1710372849453945,2.0943951023931953,3092.6,186.6,59.2,116.9,95.5,475.5 -2.8289396650521583,0.1710007873138959,2.2252947962927703,2776.6,129.3,70.5,91.0,235.3,1058.1 -2.8289411545252916,0.17100592615908194,2.356194490192345,2699.4,93.1,93.6,62.5,1728.6,1728.9 -2.8289390638623013,0.17101948269392886,2.4870941840919194,316.4,70.3,129.3,48.4,1764.3,1823.0 -2.828947487616044,0.17099580290012573,2.6179938779914944,117.3,59.7,94.7,46.5,1950.2,2078.0 -2.82894217618788,0.17098327019888537,2.748893571891069,62.5,62.5,109.9,63.2,2376.8,2596.7 -2.8289676265374575,0.17097781126064793,2.8797932657906435,46.4,94.6,200.5,117.1,3233.2,3105.9 -2.8289634257335416,0.1709806631347892,3.010692959690218,48.0,129.3,70.5,318.1,2857.5,2799.1 -1.6288829316445625,0.5710032919936556,0.0,463.1,1293.1,1293.0,1299.0,1528.9,1528.9 -1.6289546072910093,0.5715033308114488,0.1308996938995747,505.9,1313.1,1372.5,1328.3,1557.2,1616.7 -1.6289150507398713,0.5714901344350964,0.2617993877991494,601.9,1446.2,1573.8,1475.2,1272.6,892.9 -1.6288600595613663,0.5714544698551152,0.39269908169872414,790.5,1762.6,1807.6,1814.1,846.8,627.7 -1.6288127647188446,0.5714041675087735,0.5235987755982988,1190.3,1615.2,1487.7,1799.8,650.0,522.3 -1.628790615917717,0.5713583992156916,0.6544984694978736,1290.7,1409.0,1349.9,1578.2,543.7,484.6 -1.6287734290475246,0.5712884701732999,0.7853981633974483,1263.2,1328.6,1328.4,1498.9,493.8,493.3 -1.6287754342132,0.5712559501299876,0.916297857297023,1333.6,1349.4,1408.5,1535.0,484.7,543.6 -1.6287936024237475,0.5711980249607111,1.0471975511965976,1525.5,1487.1,1614.7,1192.4,521.7,649.0 -1.628828971098579,0.5711386117686867,1.1780972450961724,1814.2,1806.6,2025.5,791.0,627.9,847.0 -1.6288360306641436,0.5711305806352918,1.3089969389957472,1474.9,1846.5,1719.1,602.4,892.8,1272.0 -1.6288620410568624,0.5711161744222055,1.4398966328953218,1326.9,1614.9,1556.6,504.9,1370.3,1311.8 -1.6289477423237007,0.5710952541314682,1.5707963267948966,1298.7,1528.8,1528.6,463.3,1293.4,1293.2 -1.6289533545150288,0.5710938548419384,1.7016960206944713,1369.6,1556.2,1614.2,462.6,1312.4,1370.8 -1.6289608819187011,0.5710942798187422,1.832595714594046,1568.1,1271.9,892.6,509.5,1420.9,1574.0 -1.629026136940015,0.5711345739404652,1.9634954084936205,1975.3,846.9,627.8,630.7,1763.3,1806.6 -1.6290510215526603,0.5711614695222724,2.0943951023931953,1705.2,648.9,521.6,916.2,1614.1,1487.1 -1.6290466790989788,0.5711502849449002,2.2252947962927703,1534.9,543.5,484.8,1396.6,1408.0,1349.7 -1.6290545642651593,0.5711818960277615,2.356194490192345,1499.7,493.3,493.8,1262.5,1328.2,1328.6 -1.6290513664325763,0.5712208613550482,2.4870941840919194,1577.8,484.7,543.9,1291.0,1350.0,1409.1 -1.6290525980811499,0.5712192883606368,2.6179938779914944,914.4,522.4,650.1,1433.7,1487.7,1615.6 -1.629035006773035,0.571241490703327,2.748893571891069,628.5,628.5,848.5,1760.5,1811.3,2031.2 -1.6290383211088795,0.5712386070147393,2.8797932657906435,508.8,893.1,1272.7,1567.8,1846.3,1718.9 -1.6290231458155517,0.5712459775198817,3.010692959690218,462.4,1371.4,1312.6,1370.8,1615.3,1556.8 -1.629045647992211,0.6715226324087729,0.0,563.2,1293.1,1293.0,1198.8,1529.1,1528.8 -1.6289966736862105,0.6707296779120282,0.1308996938995747,609.3,1313.1,1372.7,1225.0,1557.6,1662.6 -1.6290208331803515,0.6707375586944444,0.2617993877991494,717.3,1446.2,1573.5,1359.6,1472.1,1092.4 -1.6290512336667167,0.6707571453878078,0.39269908169872414,931.5,1762.6,1667.0,1672.4,988.3,768.8 -1.6290757671633953,0.6707858167710947,0.5235987755982988,1388.8,1500.3,1372.4,1799.8,765.5,637.8 -1.6291009287156812,0.6708302753148019,0.6544984694978736,1290.9,1305.8,1246.7,1578.2,647.0,588.0 -1.629105129708409,0.6708545235986856,0.7853981633974483,1263.4,1229.1,1228.5,1498.9,593.5,593.0 -1.629104369499878,0.6709112738654688,0.916297857297023,1333.6,1246.1,1304.9,1534.4,587.9,646.7 -1.6290987688004204,0.6709333837608018,1.0471975511965976,1525.4,1372.0,1498.9,1391.9,636.9,763.8 -1.6290939193407663,0.6709401239108546,1.1780972450961724,1673.1,1665.8,1884.8,932.5,768.5,987.6 -1.6290502012633614,0.6709816664870365,1.3089969389957472,1360.2,1846.8,1719.2,717.7,1090.9,1447.3 -1.629018738543648,0.6710000635414275,1.4398966328953218,1224.0,1614.8,1556.5,608.1,1370.2,1311.7 -1.629044263714046,0.6709948609223686,1.5707963267948966,1199.0,1529.1,1528.8,563.0,1293.3,1293.2 -1.6289930408295286,0.6709935866784766,1.7016960206944713,1266.4,1555.7,1659.8,565.5,1312.4,1370.5 -1.6289493803776,0.670980660532094,1.832595714594046,1452.8,1470.9,1091.4,624.7,1445.9,1573.8 -1.628971402440093,0.6709959396787148,1.9634954084936205,1833.6,987.7,768.6,771.7,1762.7,1666.1 -1.628963845337945,0.6709900514559533,2.0943951023931953,1705.5,764.2,636.8,1115.0,1499.4,1372.0 -1.628938538269345,0.6709420079366692,2.2252947962927703,1534.9,646.7,587.9,1333.0,1305.1,1246.2 -1.6289368327060898,0.6709350104124794,2.356194490192345,1499.7,593.0,593.6,1262.2,1228.5,1229.0 -1.6289349060293672,0.6709368711760268,2.4870941840919194,1689.1,587.8,647.0,1290.7,1246.6,1305.9 -1.6289463958623471,0.6709028545963358,2.6179938779914944,1113.3,637.6,765.3,1434.0,1372.5,1500.2 -1.6289464628228079,0.6708985563536451,2.748893571891069,769.6,769.5,989.4,1760.1,1670.2,1889.7 -1.628971874355691,0.6708767205916824,2.8797932657906435,624.1,1092.0,1446.1,1452.6,1846.5,1718.9 -1.6289811053922443,0.6708728289549926,3.010692959690218,565.6,1371.2,1312.6,1267.7,1615.3,1556.6 -1.6290322564515978,0.7711714006662349,0.0,662.8,1293.0,1292.9,1099.2,1529.2,1528.9 -1.629002994698221,0.7711708818781118,0.1308996938995747,712.5,1312.9,1372.5,1121.5,1557.4,1616.8 -1.6289469689335814,0.7711545405337286,0.2617993877991494,832.6,1446.3,1573.8,1244.3,1671.5,1291.8 -1.6288924860790779,0.7711212054998497,0.39269908169872414,1073.1,1762.8,1526.2,1531.1,1129.3,909.7 -1.6288488213981038,0.7710769145899703,0.5235987755982988,1434.4,1384.8,1257.1,1799.9,880.9,753.4 -1.6288295474362846,0.7710386704808676,0.6544984694978736,1291.0,1202.1,1143.2,1578.0,750.6,691.6 -1.628813520447013,0.7709764993506698,0.7853981633974483,1263.0,1129.1,1128.5,1499.2,693.4,693.0 -1.6288152327165903,0.7709513341989236,0.916297857297023,1333.4,1142.7,1201.5,1534.4,691.6,750.2 -1.628831815510189,0.7709001152399151,1.0471975511965976,1525.1,1256.5,1383.7,1591.6,752.3,879.5 -1.6288645159852466,0.7708465082308202,1.1780972450961724,1531.4,1524.9,1743.8,1074.4,909.7,1128.6 -1.6288681585218532,0.7708434599355645,1.3089969389957472,1244.4,1847.1,1719.3,833.3,1290.4,1447.0 -1.6289038594734162,0.7708255244980158,1.4398966328953218,1120.4,1615.1,1556.7,711.6,1370.4,1311.7 -1.628974174441414,0.7708098913785051,1.5707963267948966,1098.9,1529.1,1528.7,663.1,1293.3,1293.0 -1.628972260789528,0.7708101163289991,1.7016960206944713,1162.9,1556.0,1614.3,669.1,1312.4,1370.6 -1.628974796551356,0.770811069331776,1.832595714594046,1337.2,1670.2,1290.8,740.5,1446.1,1573.8 -1.6290359800966825,0.770850778982999,1.9634954084936205,1691.7,1128.9,909.9,913.6,1762.9,1525.1 -1.6290575608703268,0.7708760729768673,2.0943951023931953,1705.9,879.6,727.0,1314.7,1383.9,1256.4 -1.6290507763905697,0.770862574935947,2.2252947962927703,1535.1,750.4,691.5,1333.0,1201.4,1142.7 -1.6290573759277558,0.7708912889981427,2.356194490192345,1499.3,693.0,693.5,1262.4,1128.4,1129.1 -1.6290542565368082,0.7709272033815093,2.4870941840919194,1578.1,691.5,750.6,1290.9,1143.0,1202.0 -1.6290566445646157,0.7709230926659645,2.6179938779914944,1312.5,753.1,880.8,1433.9,1256.7,1384.4 -1.6290412593330466,0.770943505268342,2.748893571891069,910.9,910.9,1130.9,1689.0,1528.4,1748.5 -1.6290471261620385,0.7709399558105154,2.8797932657906435,739.8,1291.0,1446.4,1336.9,1846.3,1719.0 -1.6290345050263484,0.770947753413251,3.010692959690218,669.0,1371.4,1312.8,1163.9,1615.8,1556.7 -1.6290592172288247,0.871226303847209,0.0,762.7,1292.8,1293.2,999.2,1529.0,1529.4 -1.6290000355985212,0.8706505755918905,0.1308996938995747,816.5,1312.9,1372.5,1017.8,1557.5,1616.7 -1.6290309019546885,0.8706607114907219,0.2617993877991494,948.4,1446.3,1573.6,1128.4,1718.6,1491.3 -1.6290697299833197,0.8706857698264603,0.39269908169872414,1214.8,1604.2,1384.8,1388.7,1270.5,1051.4 -1.6291012637086557,0.8707221579869142,0.5235987755982988,1543.9,1269.1,1141.2,1799.6,996.7,869.0 -1.6287886784488836,0.8710239388659309,0.6544984694978736,1290.9,1098.5,1039.4,1577.6,853.9,795.1 -1.6287850280457268,0.8710108362905999,0.7853981633974483,1263.2,1029.0,1028.4,1498.9,793.4,793.0 -1.6287863318159788,0.8710137076460611,0.916297857297023,1333.9,1039.2,1098.1,1534.8,795.2,854.0 -1.6287974484913246,0.8709818322279328,1.0471975511965976,1526.1,1141.1,1268.4,1706.4,868.3,995.7 -1.6288531346057304,0.8708922296935662,1.1780972450961724,1388.5,1384.3,1603.7,1215.3,1051.6,1270.8 -1.6286642604092993,0.8710665701979949,1.3089969389957472,1128.3,1846.1,1718.8,948.3,1491.3,1447.3 -1.628791306605866,0.8710005107755561,1.4398966328953218,1016.9,1614.6,1556.4,814.9,1370.1,1311.5 -1.6288910633232603,0.8709782872027885,1.5707963267948966,999.0,1528.7,1528.6,763.2,1293.1,1293.1 -1.6288810824483382,0.8709779250005543,1.7016960206944713,1059.7,1555.9,1614.3,772.7,1312.6,1371.0 -1.6288653988694373,0.8709724282957936,1.832595714594046,1221.7,1720.3,1488.5,856.4,1446.4,1574.2 -1.6289083340524526,0.870999954091574,1.9634954084936205,1551.0,1269.4,1050.4,1056.2,1602.0,1383.0 -1.6289158172309675,0.871009359393625,2.0943951023931953,1704.8,994.9,867.7,1516.1,1267.7,1140.7 -1.6289004287071023,0.8709778818557916,2.2252947962927703,1534.9,853.6,794.9,1333.0,1097.6,1039.0 -1.628903590262587,0.870988250535808,2.356194490192345,1499.1,792.9,793.6,1262.4,1028.3,1029.1 -1.6289015018624096,0.8710071180384478,2.4870941840919194,1578.5,795.3,854.4,1291.0,1039.6,1098.7 -1.628909060400687,0.8709880062012145,2.6179938779914944,1510.4,869.2,997.0,1434.5,1141.7,1269.1 -1.6289293352362968,0.8709519234924743,2.748893571891069,1051.9,1053.2,1273.3,1546.1,1387.5,1607.9 -1.6289186640378068,0.8709636503739786,2.8797932657906435,855.1,1492.4,1448.4,1221.0,1845.1,1718.4 -1.6289097793760907,0.8709692224854109,3.010692959690218,772.5,1371.2,1312.7,1060.2,1615.4,1556.6 diff --git a/tools/localisation_machine_learning/data/sector4.csv b/tools/localisation_machine_learning/data/sector4.csv deleted file mode 100644 index 06be3000..00000000 --- a/tools/localisation_machine_learning/data/sector4.csv +++ /dev/null @@ -1,2496 +0,0 @@ -2.828952192164696,1.8289997058496303,0.0,1721.1,93.1,93.2,40.9,2729.1,2729.0 -2.829015094059926,1.8294389817312315,0.1308996938995747,698.7,70.3,129.8,25.4,2800.7,2860.6 -2.8289192700815335,1.8294082950824215,0.2617993877991494,116.7,59.4,50.9,21.2,3107.6,3234.9 -2.828859993699072,1.8293697736577774,0.39269908169872414,62.7,63.1,31.6,31.9,2620.6,2401.5 -2.828820621621919,1.8293276339744853,0.5235987755982988,46.9,95.6,33.4,72.2,2077.4,1975.9 -2.8288056827914927,1.8292951628703578,0.6544984694978736,48.4,106.3,47.4,232.0,1845.8,1787.0 -2.828792588675131,1.829240985909381,0.7853981633974483,63.2,70.7,70.3,2699.0,1751.9,1751.7 -2.8287942515514723,1.8292236735681497,0.916297857297023,91.5,47.2,106.3,2776.9,1055.9,235.6 -2.828808424034774,1.8291795731956533,1.0471975511965976,114.0,33.7,161.3,3093.9,717.5,94.9 -2.8288370510726875,1.829132095278746,1.1780972450961724,31.4,31.3,250.8,2571.0,284.1,63.6 -2.8288352082357617,1.829132787038054,1.3089969389957472,20.9,50.7,430.8,2055.5,187.2,59.8 -2.8288510395251256,1.8291237112507983,1.4398966328953218,25.6,152.2,983.6,1806.0,128.4,70.2 -2.8289261934162053,1.8291058232327666,1.5707963267948966,40.8,2728.6,2728.9,1721.5,93.2,93.2 -2.8289670279632237,1.8291036781863728,1.7016960206944713,68.1,2798.0,2856.6,921.3,70.8,129.4 -2.8289364315400825,1.8290921763199808,1.832595714594046,114.0,3108.4,3237.0,391.0,58.9,50.4 -2.828988971680752,1.8291245728169572,1.9634954084936205,192.5,2619.9,2401.3,221.3,62.7,31.3 -2.8290091005937783,1.8291467100577197,2.0943951023931953,350.2,2101.3,1973.7,139.3,95.8,33.8 -2.829003083334592,1.8291317662658721,2.2252947962927703,833.7,1845.2,1786.7,91.0,105.9,47.3 -2.8290105593613437,1.8291603071070228,2.356194490192345,2699.8,1750.7,1751.8,62.5,70.1,70.8 -2.8290074505179486,1.8291969249828044,2.4870941840919194,2821.6,1050.0,233.9,48.4,47.3,106.6 -2.829009766831573,1.829193188750614,2.6179938779914944,3189.3,715.7,94.6,46.6,33.3,161.2 -2.828993102378388,1.8292139735026314,2.748893571891069,2405.0,282.8,63.2,63.3,32.1,252.4 -2.828997973206131,1.8292100065832695,2.8797932657906435,1936.0,186.7,59.5,117.5,51.6,432.1 -2.8289843366190586,1.8292167788106193,3.010692959690218,1764.3,129.2,70.6,68.4,151.9,977.8 -2.8289204393595107,1.7289132325379315,0.0,1621.0,93.0,93.2,140.6,2728.8,2729.1 -2.8289408915567456,1.7293328430035246,0.1308996938995747,595.1,70.3,129.7,129.0,2800.3,2860.7 -2.8289033697155617,1.7293205096068853,0.2617993877991494,116.8,59.4,187.0,136.8,3106.9,3199.8 -2.8288652113396098,1.7292955710522266,0.39269908169872414,62.8,63.1,172.8,173.6,2480.8,2230.5 -2.828834498297621,1.7292630917662273,0.5235987755982988,47.0,95.5,149.0,271.6,1988.3,1860.6 -2.8288236404596527,1.7292384347376486,0.6544984694978736,48.4,232.7,150.9,617.9,1742.3,1683.3 -2.8288119780756187,1.7291910917503204,0.7853981633974483,63.2,170.8,170.3,2699.0,1651.7,1651.2 -2.828813509357292,1.7291800022581931,0.916297857297023,91.4,150.8,209.7,2776.9,1057.5,632.7 -2.8288261366276513,1.7291413902631863,1.0471975511965976,139.3,149.3,276.8,3214.0,621.0,95.0 -2.8288520459030573,1.7290982645093549,1.1780972450961724,191.8,172.6,391.9,2430.7,284.3,63.6 -2.828846877856957,1.7291023555523175,1.3089969389957472,136.5,250.2,629.7,1940.3,187.3,59.8 -2.8288589341231436,1.7290957572369692,1.4398966328953218,129.1,542.5,1372.7,1703.1,128.5,70.2 -2.8289300419626984,1.7290788863452267,1.5707963267948966,140.8,2728.8,2728.6,1621.6,93.3,93.1 -2.8289218191111636,1.729077515180447,1.7016960206944713,171.6,2797.8,2855.8,922.8,70.8,129.4 -2.828916982218583,1.7290743379526503,1.832595714594046,229.5,3108.3,3197.6,609.1,58.9,186.7 -2.8289718191935815,1.7291084407910997,1.9634954084936205,334.3,2479.3,2260.6,221.4,62.7,172.4 -2.8289889101548944,1.7291273918804058,2.0943951023931953,549.8,1985.8,1858.8,139.3,95.7,149.3 -2.828979785176669,1.7291070664769759,2.2252947962927703,1220.1,1742.0,1683.0,91.0,232.3,150.9 -2.8289856737379067,1.7291292330581791,2.356194490192345,2699.0,1651.3,1651.7,62.5,170.2,170.8 -2.8289829114032448,1.7291593864257055,2.4870941840919194,2821.4,1051.8,632.9,48.4,150.9,210.1 -2.828986947539617,1.7291500430671773,2.6179938779914944,3174.9,622.0,94.6,46.6,149.0,276.8 -2.8289735231913054,1.7291661199015314,2.748893571891069,2265.2,283.0,63.2,63.3,173.6,393.8 -2.8289822273589103,1.7291588228601147,2.8797932657906435,1846.4,186.8,59.5,117.4,251.3,631.5 -2.8289728636695965,1.7291635903791207,3.010692959690218,1660.7,129.2,70.5,172.0,539.6,1363.9 -2.8289137496476044,1.62886388474961,0.0,1521.5,93.0,93.1,240.6,2729.1,2728.7 -2.8289498062922864,1.6293255261276305,0.1308996938995747,491.4,70.3,129.7,232.6,2800.2,2859.9 -2.8289162358366378,1.6293144694388453,0.2617993877991494,116.8,59.4,187.0,252.4,3106.4,3001.3 -2.8288794250758245,1.6292904620766626,0.39269908169872414,62.8,63.1,283.9,315.3,2340.0,2121.0 -2.828849160856535,1.629258608629623,0.5235987755982988,46.9,95.5,264.6,470.8,1873.0,1745.1 -2.828838490572868,1.6292344556804297,0.6544984694978736,48.4,235.0,254.5,1003.7,1638.6,1579.8 -2.8288267840078607,1.6291874773637638,0.7853981633974483,63.2,270.8,270.3,2698.7,1551.6,1551.3 -2.8288282378341516,1.6291767249289844,0.916297857297023,91.4,254.4,313.3,2777.2,1360.0,529.1 -2.828840716767151,1.6291383820331198,1.0471975511965976,139.3,264.9,392.4,3093.1,474.9,95.0 -2.828866409705926,1.6290953805288506,1.1780972450961724,222.8,313.7,533.0,2289.6,284.3,63.6 -2.828861057265401,1.6290995863975883,1.3089969389957472,252.2,449.6,829.1,1825.0,187.3,59.8 -2.828872942560013,1.6290931244193372,1.4398966328953218,232.5,932.4,1761.9,1599.6,128.5,70.2 -2.8289438695984064,1.6290762278558308,1.5707963267948966,240.8,2728.6,2728.8,1521.3,93.3,93.1 -2.8289354921916647,1.629074856948092,1.7016960206944713,275.0,2797.6,2856.4,923.4,70.8,129.3 -2.8289304877663253,1.6290717478815921,1.832595714594046,345.2,3107.7,2998.9,493.3,58.9,186.6 -2.8289851742678285,1.6291058162595826,1.9634954084936205,475.9,2339.7,2120.2,221.4,62.6,283.8 -2.829002142091084,1.629124672016772,2.0943951023931953,749.6,1870.5,1743.6,139.3,95.7,264.9 -2.8289928592718767,1.6291042984302986,2.2252947962927703,1607.4,1638.6,1579.5,91.0,236.0,254.3 -2.8289986142616037,1.6291263739826998,2.356194490192345,2700.2,1551.1,1552.0,62.5,270.2,270.9 -2.8289958095562935,1.6291563595925376,2.4870941840919194,2820.8,1360.3,529.4,48.4,254.4,313.7 -2.828999776588738,1.6291468851385917,2.6179938779914944,3020.2,473.4,94.6,46.6,264.6,392.4 -2.828986434162281,1.6291627875432724,2.748893571891069,2123.8,283.0,63.2,63.3,315.1,535.3 -2.8289951945564393,1.629155372791712,2.8797932657906435,1731.2,186.8,59.5,117.3,450.9,831.1 -2.8289859376691466,1.6291600631350396,3.010692959690218,1557.3,129.2,70.5,298.3,927.1,1750.9 -2.8289268943205395,1.5288605035076095,0.0,1421.5,93.0,93.1,340.6,2729.1,2729.1 -2.8289621962444595,1.5293248289429244,0.1308996938995747,314.3,70.3,129.6,336.1,2800.4,2860.5 -2.8289285045883195,1.5293137607192484,0.2617993877991494,116.8,59.3,186.9,368.0,3106.5,2802.2 -2.828891695095093,1.529289808179112,0.39269908169872414,62.7,63.1,283.9,457.0,2198.7,1980.0 -2.828861413751039,1.5292580377856428,0.5235987755982988,46.9,95.4,380.3,670.2,1757.2,1629.6 -2.8288507380584558,1.5292339983193404,0.6544984694978736,48.4,234.9,358.0,1389.3,1535.7,1476.3 -2.8288389467470036,1.5291870854269658,0.7853981633974483,63.2,370.8,370.3,2699.2,1451.8,1451.1 -2.8288403355051592,1.5291764011884421,0.916297857297023,91.3,357.8,416.7,2776.7,1256.2,425.6 -2.828852737121434,1.5291380960645307,1.0471975511965976,139.2,380.5,507.8,3060.4,474.9,95.0 -2.8288783381549503,1.5290950558199237,1.1780972450961724,222.7,454.9,674.1,2148.1,457.2,63.6 -2.8288729375070214,1.529099239705825,1.3089969389957472,393.3,648.7,1028.3,1709.6,187.3,59.8 -2.8288848017649344,1.5290927960876088,1.4398966328953218,336.0,1322.1,2151.5,1496.2,128.5,70.2 -2.828955713056238,1.5290758438615657,1.5707963267948966,340.8,2729.3,2729.1,1421.4,93.3,93.1 -2.828947335709628,1.5290744655507877,1.7016960206944713,378.5,2797.8,2856.3,1233.8,70.8,129.3 -2.8289423145865613,1.529071422493316,1.832595714594046,460.8,3107.5,2800.4,391.5,58.9,186.6 -2.828996979497023,1.5291055165080876,1.9634954084936205,617.6,2198.2,1979.4,221.5,62.6,283.6 -2.8290139195534345,1.5291243753917274,2.0943951023931953,949.1,1755.6,1628.2,139.4,95.6,380.3 -2.8290045602767253,1.5291040425921723,2.2252947962927703,1994.6,1535.0,1476.7,91.0,235.8,357.8 -2.82901022916488,1.529126130800816,2.356194490192345,2699.8,1450.7,1451.8,62.5,370.2,370.8 -2.829007375454266,1.5291560705749294,2.4870941840919194,2821.0,1256.8,425.7,48.4,358.1,417.2 -2.829011261045814,1.529146558822195,2.6179938779914944,2821.6,473.6,94.6,46.6,380.3,508.0 -2.828997926366784,1.529162379222034,2.748893571891069,1982.5,455.5,63.2,63.2,456.5,676.6 -2.8290066769948075,1.529154902671746,2.8797932657906435,1615.6,186.8,59.5,117.3,650.5,1030.6 -2.8289974470206842,1.529159544367005,3.010692959690218,1453.6,129.2,70.5,318.8,1314.4,2137.9 -2.8289384133718616,1.428860053033536,0.0,1321.1,93.0,93.0,440.6,2729.0,2729.0 -2.8289720746639406,1.429324821300059,0.1308996938995747,314.4,70.2,129.6,439.8,2800.4,2859.7 -2.828938018345829,1.429313658813514,0.2617993877991494,354.6,59.3,186.9,483.6,2982.2,2603.4 -2.8289011110160702,1.4292896848689824,0.39269908169872414,62.7,63.1,283.8,598.6,2057.9,1838.9 -2.8288707756483276,1.4292579327519055,0.5235987755982988,46.9,95.4,474.7,869.2,1641.8,1514.0 -2.8288600765306278,1.4292339435349386,0.6544984694978736,48.4,234.8,461.6,1775.0,1432.0,1372.9 -2.8288482131355526,1.4291870483918014,0.7853981633974483,63.1,470.8,470.3,2698.6,1351.7,1351.3 -2.8288495524680695,1.4291763870015697,0.916297857297023,91.3,461.4,520.3,2776.2,1130.0,322.0 -2.828861901910093,1.4291380847932311,1.0471975511965976,139.2,496.0,623.4,2904.2,475.0,95.0 -2.82888744503841,1.4290949938262467,1.1780972450961724,222.6,596.1,815.1,2006.6,284.4,63.6 -2.828882023077893,1.4290991444664551,1.3089969389957472,393.5,848.1,1227.6,1593.9,187.3,59.8 -2.8288938891207582,1.4290927031117198,1.4398966328953218,439.4,1711.8,2541.1,1392.5,128.5,70.2 -2.8289648075788247,1.4290757028889973,1.5707963267948966,440.8,2728.9,2728.7,1321.3,93.3,93.1 -2.828956448638681,1.4290743182170673,1.7016960206944713,482.0,2797.5,2856.1,1130.3,70.8,129.3 -2.8289514316753452,1.429071328861383,1.832595714594046,576.3,2980.7,2601.4,391.5,58.9,186.6 -2.829006094427289,1.4292295923084062,1.9634954084936205,759.2,2057.3,1838.2,221.5,62.6,283.6 -2.8290286352385414,1.4291281344270153,2.0943951023931953,1148.7,1639.9,1512.7,139.4,95.6,476.0 -2.8290171236133417,1.4291039568311832,2.2252947962927703,2381.8,1431.6,1373.0,91.0,235.7,461.4 -2.8290225677677845,1.42912535649626,2.356194490192345,2699.7,1351.2,1351.7,62.5,470.2,470.8 -2.829019663993696,1.4291556739191906,2.4870941840919194,2821.3,1130.0,322.2,48.4,461.6,520.7 -2.8290232779228437,1.429146821426245,2.6179938779914944,2622.9,473.5,94.6,46.5,495.8,623.6 -2.829009533219573,1.4291632433469474,2.748893571891069,1841.7,283.1,63.2,63.2,597.8,818.1 -2.829017724904979,1.4291562353549137,2.8797932657906435,1500.1,186.8,59.5,117.2,849.9,1229.8 -2.8290078887637584,1.429161175209594,3.010692959690218,1350.4,129.2,70.5,318.6,1701.1,2524.6 -2.8289481020881686,1.3288611634266516,0.0,1221.4,93.0,93.0,540.6,2728.3,2729.3 -2.8289799174988564,1.3293242608616986,0.1308996938995747,314.4,70.2,129.6,543.3,2800.4,2859.8 -2.828945513248929,1.3293130058653477,0.2617993877991494,239.0,59.3,186.9,599.2,2783.6,2404.3 -2.8289085698099683,1.3292890412496483,0.39269908169872414,62.7,63.0,283.8,740.3,1916.6,1698.1 -2.8288782464225015,1.3292573621161043,0.5235987755982988,46.9,95.4,474.6,1068.5,1526.4,1398.5 -2.8288675681481603,1.3292334861142188,0.6544984694978736,48.3,234.7,565.1,2160.5,1328.5,1269.4 -2.8288556676404277,1.329186685355151,0.7853981633974483,63.1,570.8,570.3,2698.9,1251.7,1251.1 -2.828856966185149,1.3291761185754498,0.916297857297023,91.3,564.9,623.7,2777.1,1058.9,236.3 -2.8288692545153906,1.3291378877949338,1.0471975511965976,139.2,611.5,738.9,2705.0,475.1,286.1 -2.8288947180454396,1.3290948153197908,1.1780972450961724,222.6,737.1,956.3,1864.9,284.4,63.6 -2.828889235326101,1.3290989831277653,1.3089969389957472,393.3,1047.6,1426.5,1478.5,187.3,59.7 -2.828901052645857,1.3290925712635602,1.4398966328953218,542.9,2101.2,2798.3,1289.1,128.5,70.2 -2.8289719244300904,1.329075547760013,1.5707963267948966,540.8,2728.6,2728.5,1221.3,93.3,93.1 -2.8289635304107765,1.3290741581039185,1.7016960206944713,585.4,2797.3,2855.9,1004.0,70.8,129.3 -2.828958472493986,1.3290711979123861,1.832595714594046,691.9,2781.3,2402.4,391.6,58.9,186.6 -2.829013096259006,1.3291053189015236,1.9634954084936205,900.9,1916.4,1697.4,221.5,62.6,283.6 -2.8290299894102433,1.329124173329657,2.0943951023931953,1348.1,1524.4,1397.3,280.3,95.5,475.9 -2.8290205211192805,1.329103884874868,2.2252947962927703,2768.8,1327.9,1269.2,91.0,235.5,564.8 -2.829026070603792,1.3291259791946426,2.356194490192345,2699.4,1251.2,1251.7,62.5,570.3,570.8 -2.829023149211964,1.3291558470938705,2.4870941840919194,2820.7,1143.2,234.4,48.4,565.1,624.2 -2.8290269268015873,1.3291462749665666,2.6179938779914944,2423.9,473.6,287.0,46.5,611.5,739.1 -2.8290136050325794,1.3291619764292784,2.748893571891069,1700.0,283.1,63.2,63.2,739.3,959.3 -2.829022347789432,1.3291544092664744,2.8797932657906435,1384.9,186.8,59.4,117.2,1049.4,1429.5 -2.829013160542431,1.329158979971655,3.010692959690218,1246.9,129.2,70.5,318.5,2088.4,2799.0 -2.8289541503846087,1.2288595873785404,0.0,1121.4,93.0,93.0,640.7,2728.9,2729.0 -2.8289854831013477,1.2293248618877017,0.1308996938995747,314.5,70.2,129.6,646.9,2800.3,2860.0 -2.828950905407344,1.2293135632324383,0.2617993877991494,116.8,59.3,186.8,714.7,2584.5,2205.0 -2.828913855507463,1.2292895538511068,0.39269908169872414,204.0,63.0,283.8,881.8,1776.0,1556.5 -2.8288834428142655,1.2292578218114143,0.5235987755982988,46.9,95.3,474.5,1267.6,1410.5,1282.8 -2.8288727099945774,1.229233896808486,0.6544984694978736,48.3,234.6,668.6,2545.8,1224.9,1165.7 -2.8288607483126924,1.2291870223496766,0.7853981633974483,63.1,670.8,670.4,2698.8,1151.8,1150.9 -2.828862020793181,1.2291763888357792,0.916297857297023,91.3,668.4,727.2,2777.3,1058.9,236.3 -2.8288743003500625,1.2291380878749967,1.0471975511965976,139.2,727.1,854.3,2505.5,475.0,95.0 -2.828899766409303,1.229094926095641,1.1780972450961724,222.6,878.4,1097.4,1723.1,284.4,236.4 -2.82889431722277,1.2290990300394662,1.3089969389957472,393.3,1246.4,1626.2,1362.8,187.3,59.7 -2.82890618753682,1.2290925905024417,1.4398966328953218,646.3,2491.2,2797.8,1185.4,128.5,70.1 -2.8289771176910072,1.2290755247765865,1.5707963267948966,640.7,2729.0,2728.9,1121.1,93.3,93.1 -2.8289687855756642,1.229074131426211,1.7016960206944713,688.9,2797.3,2856.0,1017.0,70.8,129.3 -2.8289637760209447,1.2290712150577796,1.832595714594046,807.6,2582.3,2203.4,391.6,58.9,186.6 -2.8290184373574823,1.2291053745997012,1.9634954084936205,1042.6,1775.4,1556.5,221.5,62.6,283.5 -2.8290353535821504,1.2291242660771315,2.0943951023931953,1548.0,1408.7,1281.7,139.4,95.5,475.9 -2.829025874069988,1.229104036034023,2.2252947962927703,2776.6,1224.4,1165.7,91.0,235.5,668.4 -2.8290313955594875,1.2291261781524736,2.356194490192345,2699.7,1151.3,1151.8,62.5,670.2,670.8 -2.8290284508259864,1.2291560660743652,2.4870941840919194,2820.6,1053.3,234.5,48.4,668.7,727.8 -2.829032180701847,1.2291465126712762,2.6179938779914944,2225.2,473.6,94.6,46.5,727.1,854.9 -2.829018842971533,1.229162206315571,2.748893571891069,1558.7,283.2,235.7,63.2,880.8,1100.8 -2.829027557099396,1.2291546320503857,2.8797932657906435,1269.2,186.8,59.4,117.2,1248.7,1628.9 -2.8290183551512804,1.2291591930658496,3.010692959690218,1143.1,129.3,70.5,318.5,2474.9,2799.2 -2.828959318329021,1.1288598073222493,0.0,1021.3,93.0,93.0,740.7,2729.0,2728.7 -2.8289898971670473,1.1293249340882547,0.1308996938995747,314.5,70.2,129.6,750.6,2800.5,2859.7 -2.8289551428622137,1.1293135889558088,0.2617993877991494,116.9,59.3,186.8,830.3,2385.1,2005.6 -2.8289180396781846,1.1292895638091152,0.39269908169872414,62.7,63.0,283.7,1023.5,1635.0,1415.6 -2.828887596231405,1.1292578325680833,0.5235987755982988,46.9,95.3,474.4,1467.0,1295.1,1167.1 -2.8288768488479215,1.1292339220937753,0.6544984694978736,48.3,234.6,772.3,2820.7,1121.3,1062.4 -2.828864853218942,1.129187047537433,0.7853981633974483,63.1,770.8,770.3,2698.3,1051.6,1051.1 -2.828866103882427,1.1291764166626153,0.916297857297023,91.3,772.0,830.8,2776.8,1059.1,236.3 -2.828878362156172,1.129138110246044,1.0471975511965976,139.2,842.6,969.8,2306.3,475.1,95.0 -2.8289038057643063,1.1290949202781193,1.1780972450961724,222.6,1019.4,1238.5,1581.6,284.4,63.5 -2.8288983513265,1.1290990051928502,1.3089969389957472,393.3,1445.7,1825.0,1247.2,187.3,59.7 -2.828910227259813,1.129092563839837,1.4398966328953218,749.8,2856.7,2798.0,1082.1,128.5,70.1 -2.8289811656793686,1.129075475356148,1.5707963267948966,740.8,2728.6,2728.8,1021.3,93.3,93.1 -2.8289728465797697,1.129074079118554,1.7016960206944713,792.4,2797.5,2856.4,924.3,70.8,129.3 -2.8289678432359393,1.129071187767524,1.832595714594046,923.2,2383.0,2004.3,391.6,58.9,186.5 -2.8290225072974167,1.1291053616640436,1.9634954084936205,1184.2,1603.2,1415.1,221.5,62.5,283.5 -2.829039421565072,1.1291242618806245,2.0943951023931953,1747.7,1293.5,1165.9,139.4,95.5,475.9 -2.8290299209329497,1.1291040541979949,2.2252947962927703,2777.2,1121.0,1062.1,91.0,235.5,771.9 -2.8290354152573842,1.129126209566075,2.356194490192345,2699.7,1051.3,1051.8,62.5,770.2,770.8 -2.829032453174156,1.1291560905858846,2.4870941840919194,2820.4,1053.5,234.5,48.4,772.0,831.3 -2.8290361527321988,1.129146531844026,2.6179938779914944,2025.9,473.7,94.6,46.5,842.8,970.4 -2.8290228130174007,1.1291622035521218,2.748893571891069,1417.1,283.1,63.2,63.2,1022.2,1242.3 -2.829031518477022,1.1291546122502187,2.8797932657906435,1153.8,186.8,59.4,117.2,1448.3,1828.4 -2.829022319909326,1.1291591588440926,3.010692959690218,1039.8,129.3,70.4,318.4,2857.8,2799.1 -2.729015886142992,1.8292519979902422,0.0,1721.2,193.0,193.0,40.8,2629.4,2629.1 -2.729002613517055,1.828947465734458,0.1308996938995747,698.7,173.8,233.1,25.5,2696.9,2756.0 -2.729002643913587,1.8289474928336698,0.2617993877991494,316.3,174.9,51.2,21.3,2990.2,3117.5 -2.7289528937447063,1.8289217280251089,0.39269908169872414,203.9,204.6,31.8,32.0,2623.6,2403.8 -2.728987829724162,1.8289612736291865,0.5235987755982988,162.6,161.2,33.5,72.2,2104.2,1976.5 -2.7290038002907364,1.8289883748344746,0.6544984694978736,151.9,106.6,47.5,231.4,1846.4,1787.1 -2.7290013597560647,1.8289839380673505,0.7853981633974483,163.2,70.9,70.4,2598.6,1751.5,1750.8 -2.7290014249473193,1.8290100717379556,0.916297857297023,194.8,47.5,106.3,2673.7,1566.7,735.8 -2.7290042226985274,1.8290036404273147,1.0471975511965976,73.3,34.0,161.3,2977.2,675.0,294.7 -2.7290138840605564,1.8289865063881987,1.1780972450961724,31.8,31.6,250.7,2574.1,426.3,205.3 -2.7289885997015175,1.8290100993169502,1.3089969389957472,21.2,51.0,430.2,2056.7,303.0,175.4 -2.7289780442854794,1.8290166388525018,1.4398966328953218,25.8,152.3,980.9,1806.2,232.0,173.6 -2.729025459407898,1.8290058655461958,1.5707963267948966,40.9,2629.1,2628.6,1721.0,193.3,193.0 -2.7289948676017968,1.829004706776638,1.7016960206944713,68.3,2694.0,2752.5,1544.0,174.3,232.7 -2.7289697326330806,1.8289967751627063,1.832595714594046,114.0,2991.4,3119.3,724.3,174.5,51.0 -2.729007326353805,1.8290212815303073,1.9634954084936205,192.5,2622.2,2402.6,362.6,204.2,31.6 -2.729011374857718,1.8290273975153002,2.0943951023931953,349.8,2102.3,1974.7,254.9,161.3,34.0 -2.728993508858559,1.828992747780927,2.2252947962927703,831.2,1845.4,1786.3,194.5,106.3,47.5 -2.7289951392379406,1.8289997128156545,2.356194490192345,2599.4,1751.1,1751.9,162.4,70.4,71.0 -2.7289926463375163,1.829014955035798,2.4870941840919194,2716.8,1566.9,736.3,151.9,47.5,106.6 -2.7290004000585775,1.828992599616121,2.6179938779914944,3133.8,737.2,293.8,162.1,33.5,161.2 -2.728994089995956,1.8289978393079334,2.748893571891069,2407.0,424.6,204.5,204.5,32.3,252.3 -2.7290115848544416,1.8289828459301865,2.8797932657906435,1962.6,302.4,175.0,114.3,51.8,431.6 -2.729012077063184,1.8289830771070255,3.010692959690218,1764.5,232.7,173.9,68.8,151.9,974.7 -2.728964265101849,1.7286923117731048,0.0,1621.3,193.1,193.0,140.8,2629.3,2629.2 -2.728999739886674,1.72929333674033,0.1308996938995747,698.7,173.8,233.1,129.1,2696.5,2756.2 -2.728969554014504,1.7292835088000906,0.2617993877991494,316.3,174.9,294.4,136.8,2990.3,3117.6 -2.7289361049463126,1.729261905182195,0.39269908169872414,203.9,204.6,172.9,173.5,2481.9,2262.8 -2.7289082981180495,1.729233185541247,0.5235987755982988,162.5,294.5,149.0,271.3,1989.0,1860.9 -2.7288992139411112,1.7292125802648814,0.6544984694978736,151.8,210.0,151.0,616.4,1742.6,1683.4 -2.7288878742054035,1.7291690435963463,0.7853981633974483,163.1,170.8,170.3,2598.9,1652.1,1651.4 -2.7288889684576287,1.7291615675003196,0.916297857297023,194.8,150.9,209.7,2673.3,1463.3,623.7 -2.7289171459732784,1.729071475042868,1.0471975511965976,254.7,149.4,276.7,2976.8,674.9,294.7 -2.7289204508482587,1.729063646815025,1.1780972450961724,173.3,172.5,391.5,2432.0,426.2,205.3 -2.7289067828264923,1.729075406635375,1.3089969389957472,136.6,250.0,629.1,1941.0,303.0,175.3 -2.728917344355859,1.7290697468737748,1.4398966328953218,129.1,541.4,1369.7,1703.0,232.0,173.6 -2.7289897512733345,1.7290523310374253,1.5707963267948966,140.8,2628.4,2628.3,1621.3,193.3,193.0 -2.7289836941736105,1.7290510784521074,1.7016960206944713,171.5,2693.3,2752.3,1440.7,174.3,232.7 -2.728980937014095,1.7290490249272343,1.832595714594046,229.4,2991.9,3119.6,591.0,174.4,293.8 -2.7290375203702255,1.7290845197232803,1.9634954084936205,333.9,2480.6,2262.3,362.7,204.3,172.5 -2.7290558446155093,1.7291050411656448,2.0943951023931953,549.2,1986.9,1859.6,254.9,295.1,149.3 -2.7290471678922494,1.7290866478586493,2.2252947962927703,1217.9,1742.1,1683.5,194.5,209.7,150.8 -2.729052973846691,1.7291106281419792,2.356194490192345,2599.6,1651.3,1652.1,162.5,170.2,170.8 -2.7290499069703817,1.7291421786278431,2.4870941840919194,2716.9,1463.5,620.0,151.9,150.9,210.0 -2.7290691754186254,1.7290823496672023,2.6179938779914944,3072.3,673.0,293.9,162.2,149.0,276.6 -2.729035458134129,1.7291307473781252,2.748893571891069,2235.1,424.5,204.6,204.6,173.5,393.5 -2.7290680028987797,1.7291023462178159,2.8797932657906435,1821.8,302.5,175.0,229.7,251.0,630.9 -2.7290333129477884,1.7291204617430853,3.010692959690218,1660.7,232.7,173.9,172.1,538.5,1361.4 -2.72897169799283,1.6288324651430404,0.0,1521.4,193.0,193.0,240.7,2629.4,2629.3 -2.7290027427146053,1.6293258074093486,0.1308996938995747,698.7,173.8,233.1,232.6,2697.1,2756.5 -2.7289678160927395,1.6293144368359425,0.2617993877991494,316.3,174.9,302.3,252.4,3095.4,3002.9 -2.7289305460865556,1.6292903611787395,0.39269908169872414,203.9,204.6,314.1,315.2,2341.1,2121.7 -2.7288999254685975,1.629258543302738,0.5235987755982988,162.5,294.4,264.6,470.4,1873.3,1745.5 -2.7288890647028534,1.6292345475665961,0.6544984694978736,151.9,313.6,254.5,1002.2,1639.2,1580.3 -2.728876929802629,1.6291875251179049,0.7853981633974483,163.1,270.8,270.2,2599.2,1551.6,1551.3 -2.728878118397943,1.6291767603141267,0.916297857297023,194.8,254.4,313.2,2673.5,1446.9,623.7 -2.7288903502632382,1.629138309056125,1.0471975511965976,254.7,264.8,392.3,3061.7,674.9,294.7 -2.728915789803313,1.6290949248301454,1.1780972450961724,332.6,313.6,532.7,2290.1,599.1,205.2 -2.728910402315693,1.6290988721982198,1.3089969389957472,252.2,449.2,828.4,1825.2,303.0,175.3 -2.7289223893694374,1.6290923755718336,1.4398966328953218,232.5,931.1,1759.2,1599.4,232.0,173.6 -2.7289934503037423,1.6291501392461898,1.5707963267948966,240.7,2628.7,2628.7,1521.1,193.3,193.0 -2.728983735387362,1.6290730026480555,1.7016960206944713,275.0,2693.4,2752.6,1337.3,174.3,232.7 -2.7289798643547094,1.629070563281545,1.832595714594046,345.0,3092.8,3000.6,591.0,174.5,302.1 -2.7290349207705726,1.629105024361953,1.9634954084936205,475.7,2339.7,2120.6,362.6,204.2,313.7 -2.7290519419218455,1.629124070997908,2.0943951023931953,748.8,1870.9,1743.7,254.9,295.1,264.8 -2.729042409020431,1.6291039950011035,2.2252947962927703,1605.0,1638.8,1579.8,194.5,313.2,254.3 -2.7290478285415065,1.6291262305275753,2.356194490192345,2599.5,1551.0,1551.8,162.5,270.2,270.8 -2.729044813215352,1.629156118457358,2.4870941840919194,2717.2,1439.3,620.1,151.9,254.5,313.6 -2.729048412025337,1.629146566684864,2.6179938779914944,3022.1,673.0,293.8,162.1,264.6,392.2 -2.7290350566527652,1.6291621886052663,2.748893571891069,2124.6,597.2,204.6,204.6,314.9,534.9 -2.729043721272228,1.6291545585584952,2.8797932657906435,1731.5,302.4,175.0,316.6,450.6,830.3 -2.729034517556432,1.6291590696611982,3.010692959690218,1557.5,232.8,174.0,275.6,925.6,1748.7 -2.7289754481501785,1.5288597447231218,0.0,1421.0,193.0,193.0,340.7,2629.3,2629.0 -2.72900372164695,1.5293250128836267,0.1308996938995747,698.6,173.8,233.1,336.2,2696.7,2755.9 -2.7289684418333606,1.5293135312902384,0.2617993877991494,470.0,174.9,302.4,367.9,2990.8,2803.2 -2.728931189448076,1.5292894683760967,0.39269908169872414,203.9,204.6,425.3,456.8,2200.1,1980.6 -2.72890066139493,1.5292577528048945,0.5235987755982988,162.5,294.5,380.2,669.6,1757.6,1629.9 -2.7288898755417224,1.529233901753412,0.6544984694978736,151.9,417.1,358.0,1387.7,1535.8,1476.6 -2.728877776558651,1.5291870408860635,0.7853981633974483,163.1,370.8,370.2,2599.2,1451.6,1451.3 -2.7288789584029467,1.5291764314294358,0.916297857297023,194.8,357.9,416.8,2696.1,1446.9,623.7 -2.728891146473581,1.529138119667738,1.0471975511965976,254.7,380.4,507.7,2976.8,675.0,517.2 -2.728916513794892,1.5290948509834288,1.1780972450961724,363.7,454.8,673.8,2148.7,426.1,205.3 -2.728911035525274,1.5290988835250823,1.3089969389957472,367.8,648.6,1027.7,1709.8,303.0,175.3 -2.7289229207289245,1.529092441420001,1.4398966328953218,336.0,1320.6,2149.1,1496.2,232.0,173.6 -2.7289938762374173,1.529075283934595,1.5707963267948966,340.7,2629.4,2629.1,1421.3,193.3,193.0 -2.7289855896297346,1.5290738787657745,1.7016960206944713,378.5,2694.4,2752.5,1314.3,174.3,232.7 -2.7289805982147293,1.5290710640835596,1.832595714594046,460.6,2991.3,2801.5,590.9,174.5,302.2 -2.7290352643827065,1.5291052793831483,1.9634954084936205,617.3,2198.8,1979.7,362.6,204.2,425.1 -2.72905216768147,1.5291242021874165,2.0943951023931953,948.5,1755.8,1628.6,254.9,295.1,380.5 -2.729042597658673,1.5291040592606677,2.2252947962927703,1992.4,1535.2,1476.4,194.5,416.6,357.8 -2.7290480053223125,1.5291262504959657,2.356194490192345,2599.4,1451.2,1451.7,162.5,370.2,370.7 -2.7290449890416038,1.5291561043434947,2.4870941840919194,2716.9,1439.5,620.0,151.9,358.0,417.1 -2.7290485950306507,1.5291465240893918,2.6179938779914944,2822.6,672.9,518.2,162.1,380.2,507.8 -2.729035251806209,1.5291621230808523,2.748893571891069,1983.1,424.5,204.6,204.6,456.4,676.4 -2.729043933388497,1.5291544756160038,2.8797932657906435,1616.0,302.4,175.0,316.7,650.0,1029.8 -2.7290347490784446,1.5293216906936287,3.010692959690218,1453.9,232.8,173.9,379.2,1312.6,2136.0 -2.72896730540172,1.4288485890810771,0.0,1321.4,193.0,193.0,440.6,2628.9,2629.2 -2.7290009515095512,1.4293169213470462,0.1308996938995747,698.8,173.8,233.2,439.8,2697.0,2755.9 -2.7289679221906367,1.429306151503189,0.2617993877991494,316.4,174.9,302.4,483.5,2984.1,2604.2 -2.728931857348604,1.4292828506644142,0.39269908169872414,203.9,204.6,425.4,598.5,2058.4,1838.9 -2.7289020390587964,1.4292519138620268,0.5235987755982988,162.5,294.5,495.8,868.9,1642.0,1514.4 -2.7288916679375763,1.429228848529429,0.6544984694978736,151.8,535.1,461.6,1773.2,1432.3,1372.9 -2.728879748378931,1.4291827690146648,0.7853981633974483,163.1,470.9,470.2,2598.7,1351.8,1351.3 -2.728880912792532,1.4291728911847783,0.916297857297023,194.8,461.4,520.3,2673.4,1361.7,623.7 -2.728892912898644,1.4291352337072225,1.0471975511965976,254.6,495.9,623.1,2905.6,674.9,401.5 -2.7289179572219933,1.4290925046842924,1.1780972450961724,363.6,595.8,814.9,2007.0,426.1,205.3 -2.728912070282255,1.429096945438134,1.3089969389957472,483.4,847.7,1226.9,1594.6,422.3,175.3 -2.7289234905564794,1.4290907784734292,1.4398966328953218,439.5,1710.4,2538.8,1392.7,232.0,173.6 -2.728993955999287,1.4290737523913697,1.5707963267948966,440.7,2629.0,2628.3,1321.3,193.3,193.1 -2.728985205014892,1.429072352205117,1.7016960206944713,481.9,2694.1,2753.0,1314.4,174.3,232.7 -2.728979793349491,1.4290694337776957,1.832595714594046,576.3,2981.6,2602.3,591.1,174.4,302.1 -2.729034104558886,1.429103445066948,1.9634954084936205,759.2,2058.1,1838.9,362.7,204.2,425.2 -2.7290507427910806,1.429122097333348,2.0943951023931953,1148.3,1640.2,1513.1,254.9,295.1,495.9 -2.729041001585625,1.4291016522734425,2.2252947962927703,2380.1,1431.5,1372.9,194.5,537.5,461.3 -2.72904633312298,1.4291235267912192,2.356194490192345,2599.6,1351.2,1351.7,162.5,470.3,470.8 -2.729043333142111,1.4291530756398014,2.4870941840919194,2717.4,1373.0,620.1,151.9,461.6,520.6 -2.729047027150802,1.4291432321545168,2.6179938779914944,2624.0,672.9,402.5,162.1,495.8,623.5 -2.729033835609913,1.429158617060505,2.748893571891069,1841.8,424.5,204.6,204.6,597.7,817.7 -2.729042701190449,1.4291508201072853,2.8797932657906435,1500.3,302.4,175.0,316.7,849.4,1229.3 -2.7290337180925945,1.4291552341513563,3.010692959690218,1350.5,232.8,173.9,482.6,1700.3,2522.6 -2.7289749011003566,1.328856104018465,0.0,1221.3,193.0,193.0,540.7,2628.6,2629.0 -2.7290035674645443,1.3293243333715727,0.1308996938995747,1070.8,173.8,233.2,543.3,2696.7,2756.5 -2.728968441616675,1.3293129011751437,0.2617993877991494,316.3,174.9,302.3,599.1,2784.1,2405.1 -2.728931278263984,1.3292888958337485,0.39269908169872414,345.5,204.6,425.3,740.0,1917.6,1698.1 -2.7289008064335656,1.3292572424134912,0.5235987755982988,162.5,294.5,629.7,1068.2,1526.3,1398.6 -2.728890054175938,1.3292334556026297,0.6544984694978736,151.9,620.0,565.1,2159.2,1328.6,1269.6 -2.7288779697212497,1.3291866591448211,0.7853981633974483,163.1,570.8,570.3,2598.9,1251.7,1251.3 -2.7288791499213136,1.3291761101310007,0.916297857297023,194.8,564.9,623.6,2673.4,1269.3,623.7 -2.7288913223019975,1.329137852425171,1.0471975511965976,254.6,611.5,738.9,2706.1,674.8,294.7 -2.7289166628382193,1.3290946283030132,1.1780972450961724,363.7,737.0,956.1,1865.2,426.2,378.2 -2.728911150780273,1.3290986945725025,1.3089969389957472,592.4,1047.0,1426.3,1478.6,303.0,175.3 -2.7289229975856313,1.3290922752576237,1.4398966328953218,543.0,2100.0,2694.5,1289.1,232.0,173.6 -2.7290220364620845,1.3290649524950555,1.5707963267948966,540.7,2628.8,2628.4,1221.1,193.3,193.0 -2.7289939762471898,1.3290628751506652,1.7016960206944713,585.4,2693.9,2752.5,1246.7,174.3,232.7 -2.7289853318306676,1.3290589384147011,1.832595714594046,691.8,2782.4,2403.2,591.0,174.4,302.1 -2.729041020759808,1.32909378578889,1.9634954084936205,900.7,1916.4,1697.3,362.6,204.3,425.0 -2.7290596974123575,1.3291146071730626,2.0943951023931953,1347.8,1524.4,1397.2,255.0,295.1,631.5 -2.7290514774808186,1.3290969868815736,2.2252947962927703,2673.8,1328.0,1269.3,194.5,622.7,565.0 -2.7290575255607554,1.3291219379258403,2.356194490192345,2600.0,1251.0,1252.0,162.5,570.1,570.8 -2.729054415732369,1.3291544728015605,2.4870941840919194,2717.5,1269.2,620.1,151.9,565.1,624.2 -2.729057301547529,1.3291472630949568,2.6179938779914944,2424.6,672.9,293.9,162.1,611.5,739.1 -2.729042733839357,1.329164826003198,2.748893571891069,1700.4,424.6,377.0,204.6,739.2,959.2 -2.7290498641934633,1.3291586352019567,2.8797932657906435,1384.5,302.4,175.0,316.6,1049.1,1428.8 -2.729038944107494,1.329164068876068,3.010692959690218,1246.8,232.8,173.9,586.3,2087.2,2695.4 -2.7289778009216623,1.2288631902369789,0.0,1121.2,193.0,193.0,640.7,2629.3,2628.8 -2.72900452234543,1.22932336266737,0.1308996938995747,967.4,173.8,233.1,646.9,2696.5,2756.0 -2.7289690781422693,1.2293118331903754,0.2617993877991494,316.3,174.9,302.4,714.7,2585.1,2205.5 -2.7289319472379736,1.2292878508332907,0.39269908169872414,203.9,204.6,425.3,881.7,1776.3,1556.7 -2.728901575163076,1.2292563082365429,0.5235987755982988,162.5,294.5,673.6,1267.3,1410.6,1283.0 -2.7288909015231315,1.2292326739637809,0.6544984694978736,151.9,620.0,668.6,2544.5,1225.0,1165.9 -2.7288788542959868,1.2291860463117257,0.7853981633974483,163.1,670.8,670.3,2599.0,1151.7,1151.1 -2.728880027494269,1.2291756593068528,0.916297857297023,194.8,668.4,727.2,2673.4,1165.7,1004.5 -2.7288921544339706,1.229137547018396,1.0471975511965976,254.6,727.2,854.3,2506.4,674.8,294.7 -2.728917419956732,1.2290944432564093,1.1780972450961724,363.6,878.2,1097.2,1723.6,426.2,205.3 -2.728911813686264,1.2290985985811829,1.3089969389957472,592.5,1246.4,1625.5,1363.1,302.9,175.3 -2.728923554689044,1.2290922367676254,1.4398966328953218,646.4,2489.6,2694.8,1185.8,232.0,173.6 -2.728994359951089,1.2290751179835444,1.5707963267948966,640.8,2628.9,2628.6,1121.2,171.3,193.0 -2.7289859317073986,1.2290737126730251,1.7016960206944713,688.9,2693.7,2752.5,1143.1,174.3,232.7 -2.728980812980323,1.2290708641205508,1.832595714594046,807.5,2582.7,2203.8,590.9,174.5,302.1 -2.729035371383744,1.2291050174870295,1.9634954084936205,1042.6,1775.6,1556.4,362.6,204.2,425.2 -2.7290521932528606,1.2291238595163563,2.0943951023931953,1547.6,1409.2,1281.7,254.9,295.1,675.3 -2.7290425702414516,1.229103625124636,2.2252947962927703,2673.3,1224.6,1165.9,194.5,622.6,668.5 -2.7290479528280596,1.2291257203173123,2.356194490192345,2599.5,1151.2,1152.0,162.5,670.3,670.9 -2.7290449379304995,1.2291554817280665,2.4870941840919194,2717.7,1165.9,1004.9,151.9,668.7,727.7 -2.729048568256097,1.2291458197596716,2.6179938779914944,2225.3,673.0,293.8,162.1,727.0,854.7 -2.729035267487035,1.2291613516939153,2.748893571891069,1558.8,424.6,204.6,204.6,880.7,1100.8 -2.7290440036338586,1.2291536555086322,2.8797932657906435,1269.2,302.4,175.0,316.6,1248.5,1628.4 -2.7288843670151386,1.2288833027906945,3.010692959690218,1143.3,232.8,173.9,704.6,2472.1,2695.8 -2.7288714575521067,1.128653609379723,0.0,1021.2,193.1,193.0,740.8,2628.9,2629.2 -2.728954109666052,1.1292944385338692,0.1308996938995747,863.9,173.8,233.2,750.6,2697.3,2755.9 -2.7289341652609918,1.1292877324209876,0.2617993877991494,316.3,174.9,302.5,830.4,2384.8,2005.6 -2.7289026081813916,1.1292672044668672,0.39269908169872414,203.9,204.7,425.5,1023.6,1634.9,1415.2 -2.728874607382843,1.1292380564217184,0.5235987755982988,162.5,294.6,673.9,1467.2,1295.1,1167.4 -2.7288650581190805,1.1292162728092072,0.6544984694978736,151.9,620.5,772.0,2717.6,1121.3,1062.4 -2.7288536197234765,1.129171364964995,0.7853981633974483,163.1,770.9,770.3,2598.7,1051.7,1051.1 -2.7288549210906945,1.1291625253878728,0.916297857297023,194.9,771.9,830.9,2673.3,1062.5,901.0 -2.7288668190712477,1.1291258370264359,1.0471975511965976,254.7,842.7,970.0,2305.9,674.8,294.7 -2.7288915712242865,1.1290840424750077,1.1780972450961724,363.8,1019.6,1238.5,1581.5,426.1,205.3 -2.7288851713421725,1.1290892019827914,1.3089969389957472,592.7,1446.2,1825.1,1247.4,302.9,175.3 -2.7288959233659975,1.1290834874418816,1.4398966328953218,749.8,2752.9,2694.7,1082.1,232.0,173.6 -2.7289656485396527,1.1290668065892222,1.5707963267948966,740.8,2629.4,2628.6,1021.3,193.3,193.1 -2.728956154618927,1.129065459195667,1.7016960206944713,792.4,2694.5,2752.6,1039.9,174.3,232.7 -2.7289500895757532,1.1290622808434143,1.832595714594046,923.2,2382.8,2003.9,590.8,174.5,302.3 -2.729003862521717,1.129095919198216,1.9634954084936205,1184.4,1634.3,1415.1,362.6,204.3,425.3 -2.729020129677825,1.129114115855577,2.0943951023931953,1747.4,1293.4,1166.2,255.0,295.2,675.4 -2.7290102665077014,1.1290930988166008,2.2252947962927703,2673.2,1120.9,1062.3,194.5,623.0,772.0 -2.729015662504275,1.1291144315390234,2.356194490192345,2599.9,1051.2,1051.7,162.5,770.3,771.0 -2.729012825921259,1.1291435707087016,2.4870941840919194,2717.5,1062.3,901.5,129.2,772.2,831.4 -2.729016853372083,1.1291333918836375,2.6179938779914944,2025.6,672.8,293.8,162.2,842.7,970.5 -2.7290039400158137,1.1291486147126313,2.748893571891069,1417.2,424.5,204.6,204.6,1022.3,1242.1 -2.729013145018306,1.1291407390782604,2.8797932657906435,1153.5,302.4,175.0,316.7,1448.4,1828.5 -2.729004443949584,1.1291451573072462,3.010692959690218,1039.9,232.8,174.0,706.0,2754.1,2695.4 -2.6289985224190713,1.82923911742401,0.0,1721.0,293.1,293.0,40.8,2529.0,2529.2 -2.6289832887850992,1.8285359621470738,0.1308996938995747,1083.0,277.4,149.2,25.6,2592.9,2652.0 -2.629034933996544,1.8285527233514651,0.2617993877991494,515.9,290.5,51.4,21.4,2875.1,3114.4 -2.629088720300264,1.8285873985750671,0.39269908169872414,345.3,251.3,31.9,32.1,2623.2,2404.1 -2.629130825493993,1.8286353704430132,0.5235987755982988,278.3,161.3,33.6,72.4,2103.7,1976.9 -2.6287790498649626,1.828991312264698,0.6544984694978736,255.5,106.5,47.6,232.4,1845.3,1786.9 -2.6287769649779076,1.8289847458138253,0.7853981633974483,263.3,70.9,70.5,2498.7,1751.8,1751.2 -2.6287780245658126,1.8290361130450035,0.916297857297023,298.5,47.5,106.5,2570.0,1786.8,1008.7 -2.6287981890431324,1.8289749074468578,1.0471975511965976,73.2,34.0,161.5,2862.5,873.6,494.0 -2.6288259563586007,1.8289306291604643,1.1780972450961724,31.8,31.6,251.1,2571.9,567.5,346.9 -2.628818126446064,1.8289386697235788,1.3089969389957472,21.2,51.1,430.9,2055.7,418.4,291.0 -2.6288249741960206,1.8289361070054884,1.4398966328953218,25.8,152.9,983.8,1806.1,335.5,277.2 -2.6288896092819853,1.82892202702881,1.5707963267948966,41.0,2528.5,2528.8,1721.0,293.3,293.2 -2.6288746955089684,1.8289216089313696,1.7016960206944713,68.3,2590.4,2649.4,1699.7,277.8,151.8 -2.6288634763595775,1.8289174955730834,1.832595714594046,114.2,2876.9,3108.4,789.4,290.3,50.9 -2.628912661024554,1.8289490510907607,1.9634954084936205,192.7,2619.9,2401.5,503.5,250.4,31.6 -2.6289253722411647,1.8289642285680028,2.0943951023931953,350.5,2100.9,1974.2,370.3,161.2,34.1 -2.628913481583206,1.8289392738870005,2.2252947962927703,833.8,1845.0,1786.4,298.0,106.2,47.6 -2.628918262254424,1.828956465950168,2.356194490192345,2499.3,1750.9,1751.5,262.5,70.3,71.0 -2.628915768293526,1.8290275559303069,2.4870941840919194,2614.0,1787.3,1003.6,255.5,47.5,106.8 -2.6289307756892364,1.828984587482638,2.6179938779914944,2957.8,871.2,492.8,278.0,33.5,161.4 -2.6289236552863375,1.828992220293119,2.748893571891069,2405.7,565.5,345.9,192.1,32.4,252.6 -2.6289349848053454,1.8289838960042413,2.8797932657906435,1961.5,417.9,290.6,114.2,52.0,432.4 -2.6289261709165936,1.8289896589347243,3.010692959690218,1764.1,336.3,277.6,68.7,152.6,977.5 -2.628828643952814,1.7286795699974216,0.0,1621.2,293.0,293.2,140.8,2528.6,2528.7 -2.628894678003749,1.7292679127385013,0.1308996938995747,1080.4,277.4,337.0,129.0,2593.4,2652.6 -2.6288753804009493,1.7292613378871278,0.2617993877991494,701.5,290.6,250.2,136.8,2875.7,3003.7 -2.628846622206186,1.7292423571087039,0.39269908169872414,345.0,346.7,172.8,173.7,2480.3,2261.3 -2.6288215131793784,1.7292158623152059,0.5235987755982988,278.1,276.5,149.0,271.7,1988.4,1860.1 -2.6288139130253603,1.7291971636041794,0.6544984694978736,255.5,209.9,151.0,618.3,1741.9,1683.4 -2.6288038051713802,1.7291558159640044,0.7853981633974483,263.3,170.8,170.3,2499.0,1651.4,1651.2 -2.6288053240172613,1.7291503281054412,0.916297857297023,298.5,150.9,209.8,2570.5,1683.4,1008.8 -2.6288166301936733,1.7291167700620038,1.0471975511965976,272.4,149.4,276.9,2862.3,873.6,723.0 -2.6288401872131537,1.7290779394244729,1.1780972450961724,173.2,172.6,392.0,2430.8,740.4,346.8 -2.628831918536794,1.729085275316866,1.3089969389957472,136.6,250.3,630.1,1940.3,418.5,291.0 -2.628840380935387,1.7290808157480013,1.4398966328953218,129.1,542.9,1373.6,1702.7,335.4,277.1 -2.628907681231318,1.7290650844371227,1.5707963267948966,140.8,2528.6,2528.8,1621.1,293.4,293.2 -2.628895819003971,1.7290637771794208,1.7016960206944713,171.6,2590.9,2649.2,1660.7,277.8,336.4 -2.628887713488704,1.7290596810171834,1.832595714594046,229.6,2876.7,3005.0,789.5,290.3,249.7 -2.6289398020141967,1.7290921409090187,1.9634954084936205,334.3,2479.6,2260.6,503.5,346.3,172.4 -2.6289548637857005,1.7291089607746555,2.0943951023931953,550.1,1986.1,1858.8,370.3,276.5,149.4 -2.628944534958856,1.729086190393342,2.2252947962927703,1221.1,1741.7,1682.9,298.0,209.6,150.9 -2.628949988186857,1.729105847253362,2.356194490192345,2499.8,1651.3,1651.7,262.5,170.2,170.9 -2.628947457129837,1.7291336879148596,2.4870941840919194,2614.1,1683.9,1003.5,255.5,150.9,210.1 -2.6289523436863904,1.7291223526575656,2.6179938779914944,2956.8,871.2,724.3,277.9,149.0,276.8 -2.628940114403865,1.729136907145717,2.748893571891069,2264.2,738.1,345.8,346.4,173.7,394.0 -2.628950290327192,1.729128565807677,2.8797932657906435,1846.6,417.9,290.5,229.5,251.4,631.9 -2.628942461984002,1.7291327686709665,3.010692959690218,1660.5,336.3,277.5,172.0,539.9,1364.9 -2.628885099699252,1.6288343232934306,0.0,1521.3,293.1,293.2,240.6,2528.6,2528.7 -2.6289256121593603,1.6293194681270546,0.1308996938995747,1381.8,277.4,336.9,232.6,2593.8,2652.4 -2.628893662370786,1.6293088850526576,0.2617993877991494,515.4,290.6,418.2,252.4,2875.5,3000.7 -2.628857765700772,1.6292853704472883,0.39269908169872414,345.0,346.5,314.0,315.3,2339.3,2120.5 -2.628828150533558,1.6292540465503962,0.5235987755982988,278.1,392.1,264.6,470.9,1872.9,1744.9 -2.6288178704859333,1.6292304096577208,0.6544984694978736,255.5,313.4,254.5,1004.3,1639.0,1579.7 -2.6288064856358067,1.6291840447813366,0.7853981633974483,263.2,270.8,270.3,2498.8,1551.6,1551.4 -2.62880804110101,1.6291738588757998,0.916297857297023,298.5,254.3,313.3,2570.3,1579.9,1009.0 -2.62882048267958,1.6291360663884291,1.0471975511965976,370.4,264.9,392.5,3015.0,873.7,633.1 -2.6288460368475017,1.6290936463592625,1.1780972450961724,314.8,313.8,533.1,2289.2,567.6,346.9 -2.6288403851222144,1.6290982789924113,1.3089969389957472,252.1,449.7,829.4,1824.9,418.5,290.9 -2.628851868324925,1.629092044578295,1.4398966328953218,232.5,933.0,1763.5,1599.3,335.4,277.1 -2.628922359595734,1.6290753738633168,1.5707963267948966,240.8,2528.9,2528.8,1521.4,293.3,293.2 -2.628913542085867,1.6290740213766794,1.7016960206944713,275.1,2590.9,2649.9,1557.2,277.8,336.3 -2.6289081697548036,1.6290706942445767,1.832595714594046,345.2,2876.8,2998.6,789.5,290.2,418.0 -2.62896255902279,1.6291045226077094,1.9634954084936205,476.0,2339.1,2119.6,503.7,346.2,313.4 -2.628979326150975,1.6291231161303925,2.0943951023931953,749.7,1870.7,1743.6,370.4,391.9,264.9 -2.6289700202522854,1.6291023820377133,2.2252947962927703,1608.4,1638.3,1579.4,298.0,313.1,254.3 -2.6289758599747666,1.6291241343175658,2.356194490192345,2499.5,1551.1,1552.0,262.5,270.2,270.8 -2.628973160400453,1.6291539141148432,2.4870941840919194,2614.2,1580.4,1003.7,255.6,254.4,313.7 -2.6289773594332986,1.6291442582594542,2.6179938779914944,2957.2,871.5,633.9,277.9,264.6,392.5 -2.628964147402442,1.6291601072553354,2.748893571891069,2123.3,565.7,345.9,346.3,315.1,535.4 -2.6289731003464203,1.629152663873677,2.8797932657906435,1730.8,417.8,290.6,345.0,451.0,831.2 -2.6289639854681193,1.6291573622255622,3.010692959690218,1557.4,336.3,277.5,275.6,927.6,1751.9 -2.6289051399260033,1.5288578478445778,0.0,1421.3,293.0,293.2,340.6,2528.2,2529.2 -2.6289428286428045,1.5293241496579426,0.1308996938995747,1278.2,277.4,336.9,336.2,2593.5,2652.5 -2.628909733712004,1.5293132314033906,0.2617993877991494,515.4,290.5,418.1,368.0,2926.4,2801.7 -2.6288731491839816,1.5292893424581195,0.39269908169872414,345.0,346.5,455.1,457.0,2198.9,1979.8 -2.6288430326372705,1.5292575994017437,0.5235987755982988,278.1,494.3,380.2,670.1,1757.1,1629.3 -2.6288324475515514,1.529233544259259,0.6544984694978736,255.4,417.1,358.1,1390.3,1535.2,1476.4 -2.628820820352326,1.5291866879429343,0.7853981633974483,263.1,370.7,370.4,2498.9,1451.8,1451.0 -2.628822304723399,1.5291760466664215,0.916297857297023,298.4,357.9,416.8,2569.8,1476.4,1315.4 -2.628834786501528,1.5291378154649988,1.0471975511965976,370.4,380.5,508.0,2861.9,873.9,494.0 -2.6288604626394383,1.529094942050338,1.1780972450961724,474.2,455.0,674.3,2147.8,567.6,346.9 -2.6288550539021824,1.5290992415764755,1.3089969389957472,367.8,648.9,1028.5,1709.6,418.4,290.9 -2.628866857379958,1.5290928263805725,1.4398966328953218,336.0,1323.1,2152.8,1495.8,335.4,277.1 -2.628937694306765,1.5290759853179328,1.5707963267948966,340.8,2529.2,2529.1,1421.0,293.3,293.2 -2.628929223704364,1.5290746199236969,1.7016960206944713,378.6,2590.8,2649.4,1453.8,277.8,336.3 -2.6289241432513824,1.5290714569579413,1.832595714594046,460.8,2928.4,2799.7,789.8,290.2,418.0 -2.628978769244249,1.529105471278197,1.9634954084936205,617.8,2198.0,1978.6,503.6,346.2,454.6 -2.6289956980122007,1.5291242708018005,2.0943951023931953,949.1,1755.0,1628.3,370.3,495.3,380.3 -2.6289864200846442,1.529103815546112,2.2252947962927703,1995.5,1535.1,1475.9,298.0,416.6,357.9 -2.628992204353717,1.529125820793276,2.356194490192345,2499.6,1451.2,1451.6,262.5,370.2,370.9 -2.6289894289839246,1.5291557684021122,2.4870941840919194,2614.1,1476.5,1315.7,255.5,358.1,417.2 -2.6289934561946464,1.529146260543521,2.6179938779914944,2821.1,871.5,492.8,277.9,380.2,508.1 -2.628980141440449,1.5291621625047367,2.748893571891069,1982.2,565.8,345.9,346.2,456.6,676.8 -2.6289889443887158,1.529154750392169,2.8797932657906435,1615.7,417.9,290.6,472.8,650.6,1030.6 -2.6289797144343092,1.5291594496105692,3.010692959690218,1453.5,336.2,277.5,379.1,1315.0,2139.1 -2.62892071147941,1.4288598924157232,0.0,1321.2,293.0,293.1,440.7,2528.9,2528.8 -2.628957023827625,1.4293246359180152,0.1308996938995747,1174.5,277.4,336.9,439.7,2593.5,2652.5 -2.6289235526854697,1.4293136271789428,0.2617993877991494,515.4,290.5,418.2,483.6,2875.4,2602.6 -2.6288868096831406,1.4292896965230986,0.39269908169872414,487.5,346.5,567.2,598.6,2057.7,1838.6 -2.628856565334385,1.4292579271683998,0.5235987755982988,278.1,494.1,495.8,869.4,1641.6,1513.9 -2.6288459068049317,1.4292338719016233,0.6544984694978736,255.5,520.5,461.5,1775.3,1432.0,1373.0 -2.628834154978685,1.4291869597948197,0.7853981633974483,263.2,470.7,470.4,2499.1,1351.9,1351.5 -2.628835569095868,1.4291762728973474,0.916297857297023,298.4,461.4,520.4,2569.6,1373.1,1211.8 -2.6288479954760158,1.4291379745068347,1.0471975511965976,370.4,496.1,623.3,2860.2,873.9,494.2 -2.6288736226979212,1.429094967493619,1.1780972450961724,505.1,596.0,815.3,2006.1,567.6,519.8 -2.6288682282906235,1.4290991739651422,1.3089969389957472,483.3,848.4,1227.8,1593.7,418.5,291.0 -2.628880086005235,1.4290927329613683,1.4398966328953218,439.4,1712.7,2542.1,1392.6,335.4,277.1 -2.628950987426594,1.4290758077734012,1.5707963267948966,440.8,2529.0,2528.4,1321.2,293.3,293.1 -2.628942594674248,1.4290744333798306,1.7016960206944713,482.1,2590.7,2649.2,1350.3,277.7,336.3 -2.6289375659380347,1.4290713616087949,1.832595714594046,576.4,2876.5,2600.8,789.8,290.2,418.0 -2.6289922271040482,1.4291054390243594,1.9634954084936205,759.4,2056.8,1838.2,503.6,346.2,567.2 -2.6290091689060895,1.4291242876919545,2.0943951023931953,1148.9,1639.9,1512.6,370.4,495.1,496.0 -2.6289998338408,1.42910392872921,2.2252947962927703,2382.9,1431.5,1372.9,298.0,520.1,461.4 -2.62900553419984,1.4291260011524365,2.356194490192345,2499.7,1351.5,1351.7,262.4,470.1,470.8 -2.6290027007999592,1.429155948538247,2.4870941840919194,2614.2,1373.1,1212.3,255.5,461.6,520.7 -2.6290066219510053,1.4291464427618479,2.6179938779914944,2622.7,871.8,492.9,277.9,495.9,623.7 -2.628993290112833,1.4291622886148443,2.748893571891069,1841.2,565.8,518.5,346.1,598.0,818.2 -2.629002051312138,1.4291548320904295,2.8797932657906435,1500.0,417.9,290.6,516.6,850.0,1230.2 -2.6289928178523745,1.4291594910014505,3.010692959690218,1350.6,336.3,277.5,482.5,1701.8,2525.8 -2.628933788203352,1.3288599808743142,0.0,1221.3,293.0,293.1,540.6,2528.9,2529.3 -2.6289681534080143,1.3293247417849772,0.1308996938995747,1081.6,277.4,336.8,543.3,2593.1,2652.5 -2.6289342392235433,1.3293136164688983,0.2617993877991494,515.6,290.5,418.1,599.2,2783.5,2404.1 -2.6288973697737155,1.3292896510667853,0.39269908169872414,345.1,346.4,567.2,740.4,1916.9,1697.5 -2.6288670553355145,1.3292578918023041,0.5235987755982988,278.2,494.0,611.4,1068.8,1526.3,1398.5 -2.6288563651008716,1.3292338826575756,0.6544984694978736,255.4,624.1,565.0,2160.9,1328.5,1269.4 -2.6288445300729455,1.3291869803761824,0.7853981633974483,263.2,570.6,570.4,2498.9,1251.7,1251.0 -2.6288458889275206,1.32917630968374,0.916297857297023,298.4,564.9,623.8,2570.2,1269.3,1085.3 -2.6288582591512473,1.3291380061264744,1.0471975511965976,370.4,611.6,738.9,2704.5,874.2,494.2 -2.62888382553305,1.3290949352440395,1.1780972450961724,505.0,737.2,956.3,1865.0,567.7,347.0 -2.6288784124427527,1.3290990991212794,1.3089969389957472,599.0,1047.5,1426.9,1478.7,418.5,291.0 -2.628890278126814,1.3290926570521915,1.4398966328953218,542.8,2102.1,2590.7,1289.1,335.5,277.1 -2.6289611939051,1.3290756762857865,1.5707963267948966,540.8,2528.9,2528.8,1221.2,293.3,293.1 -2.628952827801893,1.3290742946514218,1.7016960206944713,585.4,2590.6,2649.0,1246.7,277.8,336.2 -2.6289478091779803,1.329071284424321,1.832595714594046,692.0,2780.7,2401.8,790.2,290.2,417.8 -2.6290024725294012,1.3291053953099605,1.9634954084936205,901.2,1916.0,1696.9,503.6,346.1,567.1 -2.6290194058782705,1.329124262467392,2.0943951023931953,1348.7,1498.9,1397.3,370.3,495.1,611.4 -2.6290100153549854,1.3291039558063296,2.2252947962927703,2570.0,1327.9,1269.2,298.0,623.6,564.7 -2.6290156462628866,1.3291260574022359,2.356194490192345,2499.7,1251.1,1252.1,262.5,570.3,570.8 -2.6290127692898166,1.3291559833987079,2.4870941840919194,2613.5,1269.4,1085.7,255.5,565.1,624.3 -2.629016615223287,1.329146460645478,2.6179938779914944,2423.7,871.9,492.9,277.8,611.5,739.1 -2.6290032802764234,1.329162248400693,2.748893571891069,1699.7,565.8,346.0,346.1,739.4,959.5 -2.6290120220518776,1.3291547469210314,2.8797932657906435,1384.6,417.8,290.6,516.4,1049.5,1429.3 -2.6290027997462295,1.3291593683016436,3.010692959690218,1246.9,336.2,277.5,586.1,2089.1,2591.7 -2.6289437660460555,1.2288599065463979,0.0,1121.4,293.0,293.0,640.6,2529.0,2529.4 -2.6289766557684966,1.2293248041372968,0.1308996938995747,1082.2,277.4,336.8,647.0,2593.6,2652.5 -2.6289424074534105,1.2293135912460413,0.2617993877991494,515.6,290.5,418.1,714.7,2584.7,2204.6 -2.6289054437319463,1.229289600851255,0.39269908169872414,345.1,346.4,567.2,882.0,1775.7,1556.5 -2.628875077140696,1.2292578508804675,0.5235987755982988,278.2,493.9,727.2,1267.8,1410.5,1282.8 -2.6288643635027404,1.2294206259218305,0.6544984694978736,255.4,727.7,668.6,2546.2,1224.9,1165.8 -2.628845609119256,1.2291648371094768,0.7853981633974483,263.1,670.9,670.3,2499.2,1151.8,1151.3 -2.628846348723017,1.2291696008574682,0.916297857297023,298.3,668.4,727.3,2570.0,1165.7,1098.3 -2.6288577670383164,1.229134209899714,1.0471975511965976,370.2,727.2,854.4,2505.2,1036.4,494.2 -2.6288836905258,1.2290904320911635,1.1780972450961724,505.0,878.4,1097.6,1723.5,567.8,346.9 -2.62887960527173,1.2290932999878454,1.3089969389957472,714.6,1246.6,1626.0,1362.9,418.5,432.0 -2.628893319359017,1.2290858701781708,1.4398966328953218,646.4,2491.4,2591.0,1185.6,335.4,277.0 -2.6289662756421626,1.22906837915856,1.5707963267948966,640.8,2528.7,2528.7,1121.1,293.2,293.0 -2.6289598631201883,1.2290670546584197,1.7016960206944713,688.8,2590.4,2649.6,1143.3,277.7,336.2 -2.628956579957889,1.2290646147948192,1.832595714594046,807.7,2582.3,2203.1,790.1,290.1,417.8 -2.6290126858536897,1.229099653661407,1.9634954084936205,1042.7,1775.3,1525.3,503.7,346.1,567.1 -2.6290306785037636,1.2291196786930945,2.0943951023931953,1548.0,1408.8,1281.8,370.4,495.0,727.0 -2.629021920839612,1.2291006762545473,2.2252947962927703,2570.3,1224.5,1165.8,298.0,727.0,668.4 -2.6290278005645336,1.229124105172589,2.356194490192345,2499.6,1151.1,1151.8,262.4,670.2,670.8 -2.6290248463695587,1.2291552580552003,2.4870941840919194,2614.2,1165.9,1005.0,255.5,668.6,727.7 -2.6290283022273635,1.2291468144159161,2.6179938779914944,2224.6,871.8,493.0,277.8,727.1,854.7 -2.6290144018784876,1.2291634600380839,2.748893571891069,1558.8,566.0,345.9,346.1,880.9,1101.1 -2.6290224160025892,1.229156592838501,2.8797932657906435,1269.2,417.9,431.5,516.4,1249.0,1628.9 -2.629012405140795,1.229161613935815,3.010692959690218,1143.3,336.3,277.5,689.6,2475.9,2591.3 -2.628952404732023,1.1288614672435937,0.0,1021.2,293.0,293.1,740.7,2529.0,2528.7 -2.628983503317603,1.1293240909290974,0.1308996938995747,1082.3,277.3,336.8,750.5,2593.3,2652.9 -2.628948935616925,1.1293127926488864,0.2617993877991494,515.7,290.5,418.0,830.4,2385.1,2005.5 -2.6289119585786542,1.1292888219976258,0.39269908169872414,345.1,346.4,567.2,1023.5,1634.8,1415.4 -2.628881624272767,1.129257159130692,0.5235987755982988,278.1,493.9,868.3,1467.2,1294.7,1167.2 -2.6288709442771157,1.1292333145066868,0.6544984694978736,255.4,831.3,772.3,2613.0,1121.2,1062.4 -2.628859021349583,1.1291865350511014,0.7853981633974483,263.1,770.8,770.2,2498.5,1051.7,1051.2 -2.6288603016611196,1.1291759906328755,0.916297857297023,298.2,772.0,830.9,2570.0,1062.4,1010.5 -2.6288725675090228,1.1291377737136823,1.0471975511965976,370.3,842.6,969.9,2306.2,920.9,494.3 -2.6288980040868606,1.1290946940322049,1.1780972450961724,505.0,1019.4,1238.8,1581.6,567.7,346.9 -2.6288925057801937,1.129098858078089,1.3089969389957472,791.9,1445.9,1825.2,1247.2,418.5,290.9 -2.6289043145932505,1.1290924523059545,1.4398966328953218,749.8,2649.4,2591.0,1082.1,335.4,277.1 -2.6289751792509115,1.129075414700878,1.5707963267948966,740.8,2528.7,2529.0,1021.3,293.2,293.0 -2.628966782653836,1.129074023222712,1.7016960206944713,792.5,2590.6,2648.8,1039.8,277.7,336.2 -2.628961717945234,1.129071080156212,1.832595714594046,923.4,2383.0,2004.1,909.0,290.1,417.9 -2.629016333709944,1.1291052071088212,1.9634954084936205,1184.4,1634.2,1414.8,503.7,346.0,566.9 -2.629033217508708,1.1292284540096882,2.0943951023931953,1747.6,1293.6,1166.2,370.4,495.1,867.9 -2.6290191556364846,1.1290952748598198,2.2252947962927703,2570.0,1120.9,1062.3,298.1,830.5,771.9 -2.6290260937164818,1.129123664991252,2.356194490192345,2500.0,1051.4,1051.8,262.5,770.2,770.9 -2.629023108143288,1.129154911892377,2.4870941840919194,2614.2,1062.5,1005.4,255.4,772.2,831.4 -2.629026915602259,1.1291451477252763,2.6179938779914944,2025.4,896.4,493.0,277.8,842.7,970.5 -2.629013942754622,1.1291602715357199,2.748893571891069,1417.1,565.9,345.9,346.0,1022.2,1242.3 -2.6290232328443603,1.1291521733618524,2.8797932657906435,1153.4,418.0,290.5,516.3,1448.4,1828.6 -2.6290147113578732,1.1291563793735024,3.010692959690218,1039.8,336.3,277.5,793.1,2650.3,2592.0 -2.529009139132053,1.82925119915318,0.0,1721.3,393.1,393.0,40.8,2428.6,2429.1 -2.528990670480472,1.8285393705058797,0.1308996938995747,1588.5,380.9,149.2,25.6,2489.6,2548.9 -2.5290413016203743,1.8285558241421607,0.2617993877991494,816.6,406.1,51.4,21.4,2759.3,2886.5 -2.529094566275873,1.8285901923852281,0.39269908169872414,486.4,251.2,31.9,32.1,2623.1,2404.0 -2.529136363094642,1.828637867323513,0.5235987755982988,393.9,161.3,33.6,72.4,2104.7,1976.5 -2.528715567104176,1.829026552394663,0.6544984694978736,359.1,106.5,47.6,232.5,1845.7,1786.7 -2.5287114178286094,1.8290102235311116,0.7853981633974483,363.3,70.9,70.5,2398.7,1751.7,1750.9 -2.528713151676047,1.8290051799938536,0.916297857297023,231.8,47.5,106.4,2466.7,1786.6,1625.9 -2.5287271006731165,1.8289647347883469,1.0471975511965976,73.2,34.0,161.5,2746.7,1072.8,864.1 -2.5287561988056084,1.8289184887875678,1.1780972450961724,31.8,31.6,251.0,2571.8,881.8,488.6 -2.5287552115980185,1.8289201885847277,1.3089969389957472,21.2,51.1,431.0,2055.3,534.0,406.6 -2.5287717840662824,1.8289124212893166,1.4398966328953218,25.8,152.9,983.8,1805.7,438.9,380.6 -2.5288472320335136,1.8288958496277112,1.5707963267948966,41.0,2428.5,2428.8,1721.3,393.4,393.2 -2.528842656489133,1.828895701263885,1.7016960206944713,68.3,2487.3,2545.8,1764.2,381.4,151.7 -2.528840730093661,1.828894255440287,1.832595714594046,114.2,2761.0,2888.7,988.3,406.0,50.9 -2.5288977229123653,1.8289305290327535,1.9634954084936205,192.8,2620.5,2401.4,644.6,250.4,31.6 -2.5289162804326564,1.8289517529816854,2.0943951023931953,350.5,2101.0,1974.1,485.8,161.1,34.0 -2.5289081993243294,1.828933511834709,2.2252947962927703,833.8,1845.3,1786.5,401.5,106.2,47.5 -2.5289147975455184,1.8289577076554484,2.356194490192345,2399.4,1751.1,1751.7,362.6,70.3,71.0 -2.5289124085413617,1.8289899219678438,2.4870941840919194,2510.8,1787.3,1626.4,359.1,47.5,106.7 -2.5289166693709957,1.8289825622481426,2.6179938779914944,2842.2,1070.2,865.4,391.1,33.5,161.4 -2.528903010482642,1.829000722254591,2.748893571891069,2405.3,879.4,487.3,192.1,32.4,252.6 -2.5289111958237895,1.828995421661647,2.8797932657906435,1961.6,533.4,406.2,114.2,52.0,432.3 -2.5289008391209773,1.8290020315812896,3.010692959690218,1764.2,439.7,381.1,68.7,152.6,977.6 -2.5288398986181826,1.7287009286169543,0.0,1621.1,393.1,393.2,140.8,2428.8,2428.7 -2.528885820294992,1.7292784002421127,0.1308996938995747,1485.5,381.1,440.6,129.1,2490.2,2549.2 -2.5288594956505666,1.729269584218567,0.2617993877991494,714.2,406.4,250.2,136.9,2760.0,2938.8 -2.5288285026325417,1.7294709266118766,0.39269908169872414,486.1,391.7,172.8,173.7,2479.6,2261.1 -2.5291130635632513,1.7289115344377233,0.5235987755982988,393.6,276.7,149.1,271.5,1988.4,1860.6 -2.5291547885056054,1.7289907307085848,0.6544984694978736,359.0,210.1,151.1,617.8,1742.5,1683.3 -2.5291485729064163,1.728970229374697,0.7853981633974483,363.2,170.9,170.4,2398.9,1651.5,1650.7 -2.52914789129081,1.7290076175635156,0.916297857297023,401.9,151.0,209.8,2466.0,1683.3,1522.0 -2.529144737890204,1.7290194276586355,1.0471975511965976,272.8,149.6,276.9,2746.5,1073.6,693.7 -2.5291432899404396,1.7290196831188571,1.1780972450961724,173.5,172.8,392.0,2430.9,749.2,488.6 -2.5291034623708764,1.7290565369975095,1.3089969389957472,136.8,250.5,629.8,1940.5,533.9,406.4 -2.5290764302350075,1.729071512060696,1.4398966328953218,129.3,542.8,1372.4,1702.7,438.8,380.5 -2.5291068207463185,1.729064681479946,1.5707963267948966,141.0,2429.0,2429.0,1621.0,393.2,393.1 -2.5290603174688044,1.729063024068573,1.7016960206944713,171.8,2487.4,2545.3,1660.4,381.2,439.7 -2.5290210741682517,1.7290507512765574,1.832595714594046,229.7,2761.0,2954.8,988.8,405.6,250.2 -2.5290468256068097,1.7290680735826325,1.9634954084936205,334.4,2480.1,2261.2,644.6,391.7,172.7 -2.5290419473325945,1.7290651345683423,2.0943951023931953,549.9,1986.2,1859.1,485.8,276.8,149.6 -2.5290400079518554,1.72906251550014,2.2252947962927703,1220.6,1741.6,1683.3,401.3,209.8,151.0 -2.5290316394578234,1.7290270252282336,2.356194490192345,2399.2,1651.1,1651.6,362.3,170.4,171.0 -2.5290293846472442,1.7290247953057125,2.4870941840919194,2510.2,1683.4,1522.8,358.9,151.0,210.3 -2.5290394705884904,1.7289938150818114,2.6179938779914944,2933.0,1070.6,691.9,393.4,149.1,276.9 -2.5290358894277,1.728993934853233,2.748893571891069,2265.3,707.1,487.1,333.6,173.8,393.8 -2.5290566601712894,1.7289755201897807,2.8797932657906435,1846.5,533.4,405.9,229.7,251.5,631.5 -2.5290607075344496,1.7289736139271126,3.010692959690218,1660.8,439.6,380.9,172.2,539.6,1363.6 -2.529017472137234,1.6286861207951124,0.0,1521.3,392.9,393.0,240.7,2429.7,2429.4 -2.529062202892697,1.6292776822139885,0.1308996938995747,1467.4,380.9,440.2,232.6,2489.7,2549.3 -2.5290127295778757,1.6292619693663637,0.2617993877991494,715.2,405.9,450.1,252.4,2759.1,2886.9 -2.528977060569943,1.629239103282495,0.39269908169872414,486.3,487.9,314.1,315.1,2341.0,2121.6 -2.5289510584306303,1.6292125525236916,0.5235987755982988,393.8,392.3,264.6,470.4,1873.2,1745.8 -2.528943832017556,1.6291957771716599,0.6544984694978736,359.0,313.5,254.5,1001.9,1638.9,1580.1 -2.5289333115342507,1.6291566567718365,0.7853981633974483,363.0,270.8,270.3,2399.3,1551.8,1551.4 -2.5289340947208765,1.6291534801020573,0.916297857297023,401.8,254.4,313.2,2466.2,1579.9,1418.5 -2.528944129026231,1.629121810594202,1.0471975511965976,485.6,264.9,392.2,2745.8,1074.5,693.9 -2.5289659849128303,1.6290839527910481,1.1780972450961724,315.0,313.6,532.7,2290.8,709.6,488.6 -2.528956180870674,1.6290920026394513,1.3089969389957472,252.3,449.2,828.4,1825.5,534.2,406.5 -2.5289632474373755,1.629088203104343,1.4398966328953218,232.5,931.0,1759.1,1599.7,438.9,380.5 -2.529029206905272,1.6290722457209226,1.5707963267948966,240.8,2429.1,2428.8,1521.0,393.3,393.0 -2.5290602824482455,1.6290700719759035,1.7016960206944713,275.0,2487.3,2545.5,1557.2,381.2,439.6 -2.52902253614946,1.6290575122045512,1.832595714594046,345.0,2760.3,2888.0,989.6,405.7,449.3 -2.529068462784067,1.6290864509948038,1.9634954084936205,475.8,2339.7,2121.0,644.8,487.6,313.6 -2.5290834441697676,1.6291035760858168,2.0943951023931953,748.8,1871.4,1743.8,486.0,392.2,264.9 -2.5290735616504936,1.6290833366956752,2.2252947962927703,1605.0,1638.8,1579.7,401.5,313.2,254.4 -2.5290788687791954,1.6291060457114794,2.356194490192345,2399.7,1550.9,1552.0,362.4,270.3,270.8 -2.52907566988513,1.6291365252983478,2.4870941840919194,2510.4,1580.1,1419.2,359.0,254.5,313.5 -2.5290789367968123,1.6291275304359505,2.6179938779914944,2840.6,1071.6,692.3,393.4,264.6,392.3 -2.5290652260228166,1.6291435805850905,2.748893571891069,2124.2,707.3,487.4,487.3,314.9,535.0 -2.5290734759069795,1.6291362832023046,2.8797932657906435,1731.5,533.6,406.2,345.3,450.5,830.3 -2.5290638597474464,1.6291410384429452,3.010692959690218,1557.2,439.7,380.9,275.6,925.6,1748.0 -2.5290042785063735,1.5288414096748544,0.0,1421.4,392.9,393.0,340.7,2429.1,2429.1 -2.529024238474316,1.5293195186654018,0.1308996938995747,1467.3,381.0,440.2,336.2,2489.8,2549.3 -2.528987812621659,1.5293077309560084,0.2617993877991494,715.4,406.1,533.5,368.0,2925.4,2804.2 -2.528950780888429,1.529283894673576,0.39269908169872414,628.8,487.8,455.3,456.8,2199.5,1980.2 -2.52892065410768,1.529252767460624,0.5235987755982988,393.8,508.0,380.3,669.5,1758.0,1630.0 -2.5289101832778234,1.5292297002500994,0.6544984694978736,358.9,417.2,358.1,1387.0,1535.8,1476.7 -2.528898117691376,1.529183615297222,0.7853981633974483,363.1,370.8,370.2,2399.0,1451.7,1451.1 -2.5288991818772075,1.5291737562323013,0.916297857297023,401.8,357.9,416.7,2465.9,1476.0,1398.6 -2.5289110803541623,1.529136085300501,1.0471975511965976,485.6,380.4,507.7,2818.3,1074.4,694.0 -2.5289360183220952,1.529093249888868,1.1780972450961724,456.8,454.7,673.9,2149.3,709.6,661.5 -2.528930094001029,1.529097613489575,1.3089969389957472,367.9,648.4,1027.4,1710.0,665.2,406.6 -2.528941523523543,1.5290914320452602,1.4398966328953218,336.0,1320.3,2148.2,1496.2,438.9,380.5 -2.529012013556047,1.5290743115222605,1.5707963267948966,340.7,2429.2,2429.2,1421.0,393.3,393.0 -2.529003309121938,1.5290728954565045,1.7016960206944713,378.4,2487.6,2544.8,1453.3,381.2,439.6 -2.5289979192193965,1.5290700716927215,1.832595714594046,460.5,2926.8,2802.6,989.6,405.7,533.2 -2.5290522372563102,1.5291041404954022,1.9634954084936205,617.4,2198.9,1979.9,645.0,487.7,454.8 -2.5290688608421497,1.5291228306664006,2.0943951023931953,948.3,1756.1,1628.7,486.0,507.8,380.4 -2.5290590275284335,1.5291024749062634,2.2252947962927703,1991.5,1535.2,1476.5,401.5,416.7,357.9 -2.5290642403567305,1.529124400473162,2.356194490192345,2399.6,1451.0,1451.6,362.5,370.3,370.8 -2.529061157892535,1.529153918112728,2.4870941840919194,2510.3,1476.5,1391.9,359.0,358.0,417.1 -2.5290647213977673,1.5291440439716175,2.6179938779914944,2823.5,1071.6,692.4,393.3,380.2,507.9 -2.5290515121731887,1.5291593302544844,2.748893571891069,1983.3,707.4,660.1,487.4,456.3,676.2 -2.529060340685593,1.5291514516243303,2.8797932657906435,1616.1,533.6,406.2,460.8,649.9,1029.5 -2.5290513733152595,1.5291557952707195,3.010692959690218,1453.9,439.8,381.0,379.2,1312.3,2134.6 -2.528992559706395,1.4288567483755865,0.0,1321.3,393.0,392.9,440.6,2429.1,2429.2 -2.529018158985521,1.4293246383097444,0.1308996938995747,1382.9,380.9,440.2,439.7,2489.4,2548.7 -2.5289823180394486,1.4293130119039676,0.2617993877991494,715.4,406.0,533.4,483.5,2758.7,2604.7 -2.5289449427910746,1.4292889312807553,0.39269908169872414,486.4,487.8,596.5,598.5,2058.7,1839.2 -2.5289143622618147,1.4292572712999632,0.5235987755982988,393.8,649.0,495.9,868.7,1642.0,1514.4 -2.5289035610391717,1.429233529543623,0.6544984694978736,358.9,520.7,461.5,1773.0,1432.2,1372.9 -2.528891366306883,1.4291867337469597,0.7853981633974483,363.1,470.9,470.2,2399.1,1351.8,1351.0 -2.528892475049307,1.4291761947580888,0.916297857297023,401.8,461.4,520.2,2466.1,1372.6,1398.6 -2.528904577313988,1.4291379207697164,1.0471975511965976,485.7,495.9,623.2,2745.6,1074.3,694.1 -2.5289298438540038,1.429094606583754,1.1780972450961724,629.6,595.9,815.0,2007.1,709.7,488.6 -2.528924313435389,1.42909861178812,1.3089969389957472,483.4,847.7,1226.7,1594.3,534.3,406.6 -2.5289361771411474,1.4290921865971966,1.4398966328953218,439.4,1709.4,2487.7,1392.7,439.0,380.5 -2.529007117774905,1.42907496658342,1.5707963267948966,440.7,2428.9,2428.1,1321.2,393.3,393.0 -2.52899883402859,1.429073552618899,1.7016960206944713,481.9,2487.4,2545.8,1350.1,381.2,439.6 -2.528993827196986,1.42907081023946,1.832595714594046,576.2,2760.5,2602.4,989.8,405.6,533.2 -2.52904847186473,1.4291050551448605,1.9634954084936205,759.1,2058.2,1838.9,644.9,487.6,596.0 -2.529065345828038,1.4291239839124006,2.0943951023931953,1148.1,1639.9,1512.8,486.0,623.4,496.1 -2.529055692327103,1.429103888116189,2.2252947962927703,2378.9,1431.7,1372.9,401.6,520.1,461.4 -2.5290610048502224,1.4291260954613743,2.356194490192345,2400.0,1351.4,1351.8,362.4,470.3,470.7 -2.529057932892381,1.4291559009867048,2.4870941840919194,2510.1,1372.7,1391.6,358.9,461.5,520.6 -2.52906144761166,1.4291462806901745,2.6179938779914944,2624.3,1071.4,692.4,393.3,495.8,623.5 -2.529048110305988,1.4291617900088893,2.748893571891069,1842.2,707.5,487.4,487.3,597.7,817.7 -2.529056779361226,1.4291540741556923,2.8797932657906435,1500.2,533.5,406.1,576.5,849.5,1229.1 -2.529047623263442,1.4291585195844532,3.010692959690218,1350.7,439.8,380.9,482.7,1699.4,2488.5 -2.5289885903755294,1.328859289648587,0.0,1221.4,393.0,393.0,540.6,2429.4,2429.5 -2.529014862371841,1.3293250241762333,0.1308996938995747,1290.9,380.9,440.2,543.2,2489.6,2549.1 -2.5289791204341645,1.3293134211625581,0.2617993877991494,715.4,406.0,533.5,599.0,2741.1,2404.9 -2.5289417386794146,1.3292893223587445,0.39269908169872414,486.4,487.9,708.5,740.0,1917.9,1698.3 -2.5289111416945156,1.3292576186144904,0.5235987755982988,534.7,692.8,611.5,1068.0,1526.6,1398.7 -2.5289003253849667,1.329233816651584,0.6544984694978736,359.0,624.3,565.1,2158.3,1328.5,1269.6 -2.528888144007152,1.3291869691971334,0.7853981633974483,363.1,570.9,570.3,2398.8,1251.7,1251.1 -2.5288892704345654,1.3291763792561198,0.916297857297023,401.7,564.9,623.7,2466.0,1269.3,1328.0 -2.528901401487609,1.3291380653697664,1.0471975511965976,485.6,611.4,738.7,2706.3,1126.2,694.1 -2.528926706662161,1.3290947356274125,1.1780972450961724,645.8,737.1,956.0,1865.7,709.7,488.7 -2.528921207992331,1.3290987276349817,1.3089969389957472,599.1,1046.8,1426.1,1478.6,534.2,406.5 -2.5289330990936647,1.3290922857687018,1.4398966328953218,542.8,2099.5,2487.6,1289.0,438.9,380.5 -2.5290040666500753,1.3290750737982164,1.5707963267948966,540.8,2429.2,2428.5,1221.0,393.2,393.1 -2.5289958045268417,1.32907366179708,1.7016960206944713,585.4,2487.2,2546.0,1246.4,381.2,439.5 -2.5289908212595593,1.3290709082398617,1.832595714594046,691.9,2738.8,2403.6,1139.9,405.7,533.3 -2.5290454877399036,1.3291051561938083,1.9634954084936205,900.8,1916.7,1697.5,644.9,487.6,708.5 -2.5290623810820634,1.3291240964333746,2.0943951023931953,1347.7,1524.7,1397.3,486.0,694.4,611.5 -2.529052754771458,1.3291040043917963,2.2252947962927703,2466.1,1327.9,1269.3,401.6,623.6,564.9 -2.529058092693902,1.3291262232034173,2.356194490192345,2399.5,1251.1,1251.7,362.4,570.3,570.8 -2.529055032936273,1.3291560542353236,2.4870941840919194,2509.9,1269.6,1328.4,359.0,565.1,624.1 -2.5290585643907533,1.3291464557799726,2.6179938779914944,2424.6,1153.0,692.3,393.3,611.5,739.0 -2.5290452188821657,1.3291619958864542,2.748893571891069,1700.1,707.5,487.4,487.3,739.3,959.1 -2.5290538821374158,1.3291543030538784,2.8797932657906435,1384.8,533.6,406.1,715.5,1049.0,1428.5 -2.5290447100751794,1.3291587653134762,3.010692959690218,1246.9,439.8,381.0,586.2,2086.7,2488.7 -2.5289856635226333,1.2288595100689315,0.0,1121.3,393.0,392.9,640.8,2428.9,2429.0 -2.529012365414244,1.2293250403252367,0.1308996938995747,1187.4,380.9,440.2,646.9,2489.6,2548.7 -2.5289767151167637,1.2293134608682457,0.2617993877991494,715.2,406.0,533.4,714.7,2585.2,2205.0 -2.5289393562082205,1.229289366283675,0.39269908169872414,486.4,487.9,708.7,881.6,1776.2,1556.9 -2.528908771078394,1.2292576560145425,0.5235987755982988,393.8,692.8,727.1,1267.4,1410.7,1283.0 -2.5288979594586274,1.229233839098812,0.6544984694978736,359.0,727.7,668.6,2510.1,1225.0,1166.0 -2.5288857957041087,1.2291869847452377,0.7853981633974483,363.1,670.8,670.3,2398.9,1151.8,1151.0 -2.528886934672996,1.2291763867313685,0.916297857297023,401.7,668.4,727.3,2466.1,1165.9,1224.8 -2.528899079515727,1.2291380700388217,1.0471975511965976,485.7,727.0,854.3,2506.7,1140.9,694.1 -2.5289244003645943,1.2290947513884622,1.1780972450961724,645.7,878.3,1097.1,1723.4,709.6,488.7 -2.528918908414241,1.2290987505236637,1.3089969389957472,714.7,1246.1,1625.2,1363.1,534.2,406.5 -2.528930800569491,1.2290923072732922,1.4398966328953218,646.4,2489.7,2487.2,1185.6,438.9,380.5 -2.5290017678780603,1.229075107045119,1.5707963267948966,640.7,2429.3,2428.7,1121.1,393.3,393.0 -2.5289935025704766,1.2290736966920326,1.7016960206944713,688.8,2487.6,2545.6,1143.2,381.2,439.5 -2.5289885195494834,1.2290709299674991,1.832595714594046,807.5,2583.3,2203.9,1024.5,405.7,533.3 -2.5290431876557133,1.229105171643711,1.9634954084936205,1042.3,1775.7,1525.4,645.0,487.7,708.6 -2.529060084474053,1.2291241093577412,2.0943951023931953,1547.4,1409.1,1281.5,486.0,694.2,727.0 -2.529050471646269,1.229104007370765,2.2252947962927703,2466.2,1224.6,1166.0,401.5,727.3,668.3 -2.5290558256466475,1.2291262215120384,2.356194490192345,2399.7,1151.3,1151.9,362.4,670.2,670.8 -2.5290527756175334,1.2291560591703954,2.4870941840919194,2510.0,1166.0,1225.0,359.0,668.6,727.6 -2.5290563234869947,1.229146466114584,2.6179938779914944,2225.5,1141.8,692.2,393.4,727.1,854.8 -2.529042977818389,1.2291620205902332,2.748893571891069,1558.8,707.5,487.4,487.4,880.8,1100.6 -2.5290516443709326,1.2291543388039665,2.8797932657906435,1269.1,533.5,406.1,715.6,1248.3,1628.4 -2.5290424686142035,1.2291588100755497,3.010692959690218,1143.5,439.7,380.9,689.7,2473.6,2488.3 -2.528983421608618,1.1288595430580548,0.0,1021.4,393.0,393.0,740.5,2429.3,2429.1 -2.529010455200048,1.1293250279421043,0.1308996938995747,1083.7,381.0,440.4,750.6,2489.5,2548.4 -2.5289748781092234,1.1293134675392174,0.2617993877991494,715.2,406.1,533.5,830.3,2386.0,2006.1 -2.5289375393746423,1.1292893779452187,0.39269908169872414,486.3,488.0,708.5,1023.5,1634.8,1415.7 -2.528906965344996,1.1292576649430046,0.5235987755982988,393.8,692.9,842.8,1466.7,1295.3,1167.4 -2.528896158603756,1.1292338390795018,0.6544984694978736,359.0,831.2,772.3,2510.0,1121.5,1062.3 -2.52888400889939,1.1291869820086884,0.7853981633974483,363.1,770.8,770.3,2399.1,1051.9,1051.2 -2.5288851573826157,1.1291763802353585,0.916297857297023,401.8,771.9,830.6,2466.4,1062.3,1121.0 -2.5288973121312903,1.1291380635582264,1.0471975511965976,485.6,842.7,969.8,2306.7,1074.5,694.1 -2.528922643887043,1.1290947551768766,1.1780972450961724,645.9,1019.3,1238.3,1582.1,709.7,488.7 -2.528917155714006,1.1290987611075005,1.3089969389957472,830.2,1445.4,1824.5,1247.4,534.1,406.7 -2.528929047131697,1.1290923176968404,1.4398966328953218,749.8,2545.7,2487.8,1082.3,439.0,380.4 -2.529000012629276,1.1290751268859092,1.5707963267948966,740.6,2428.9,2428.6,1021.3,393.3,393.1 -2.5289917433512605,1.1290737178134287,1.7016960206944713,792.2,2487.0,2545.4,1039.8,381.2,439.6 -2.528986759129889,1.1290709406758945,1.832595714594046,922.9,2383.4,2004.8,989.6,405.6,533.4 -2.5290414273010566,1.1291051768855054,1.9634954084936205,1184.1,1634.3,1415.3,644.9,487.6,708.5 -2.5290583258894594,1.129124111786743,2.0943951023931953,1746.9,1293.5,1166.1,485.9,694.5,842.6 -2.5290487227946454,1.1291040011994886,2.2252947962927703,2466.9,1121.1,1062.3,401.5,830.8,771.9 -2.5290540888247843,1.1291262107215094,2.356194490192345,2399.6,1051.2,1051.9,362.5,770.2,770.9 -2.529051046270792,1.129156052436987,2.4870941840919194,2510.0,1062.4,1121.5,359.0,772.1,831.2 -2.529054606974887,1.1291464626294143,2.6179938779914944,2026.2,1071.3,692.3,393.3,842.7,970.2 -2.5290412616736058,1.1291620273764285,2.748893571891069,1417.7,707.4,487.4,487.4,1022.1,1241.9 -2.5290499313561505,1.1291543535314643,2.8797932657906435,1153.7,533.6,406.1,715.5,1448.0,1827.8 -2.529040753444053,1.1291588314029224,3.010692959690218,1039.8,439.8,381.0,793.1,2547.5,2488.5 -2.4290344015891185,1.829251930837567,0.0,1721.1,493.0,493.0,40.8,2328.8,2329.1 -2.4290025429483184,1.8285393205632368,0.1308996938995747,1808.6,484.6,149.2,25.6,2385.9,2445.6 -2.429050488556268,1.828554958681855,0.2617993877991494,914.6,431.1,51.4,21.4,2643.6,2771.2 -2.4291032306235305,1.828589029516488,0.39269908169872414,627.6,251.2,31.9,32.1,2622.8,2404.1 -2.429145068605725,1.82863679864897,0.5235987755982988,509.5,161.3,33.6,72.4,2104.2,1976.5 -2.4287729536707863,1.8289908578488285,0.6544984694978736,462.6,106.5,47.6,232.6,1846.0,1786.5 -2.4287702448401913,1.828981408102837,0.7853981633974483,463.3,70.9,70.5,2298.4,1751.6,1751.0 -2.4287715619661756,1.828985426123352,0.916297857297023,231.8,47.5,106.4,2362.9,1786.6,1780.8 -2.4287826941419968,1.8289538780810117,1.0471975511965976,73.2,34.0,161.5,2631.1,1272.1,892.8 -2.4288070139713662,1.82891516931479,1.1780972450961724,31.8,31.6,251.0,2571.6,890.6,630.2 -2.428799999452422,1.828922489757238,1.3089969389957472,21.2,51.1,431.0,2055.0,649.6,522.1 -2.4288098015640838,1.8289183586594413,1.4398966328953218,25.8,153.0,984.0,1805.6,542.3,484.1 -2.4288782319102733,1.8289034725924889,1.5707963267948966,41.0,2328.5,2329.1,1721.3,493.3,493.3 -2.428864496563236,1.828903770616244,1.7016960206944713,68.3,2384.4,2442.3,1764.2,484.9,151.8 -2.428858360177753,1.8289011964814976,1.832595714594046,114.2,2645.9,2773.8,1187.4,429.6,50.9 -2.4289106797923092,1.8289347301501722,1.9634954084936205,192.8,2620.5,2401.1,785.5,250.4,31.6 -2.4289253889119307,1.8289520769588743,2.0943951023931953,350.6,2101.1,1974.2,601.4,161.1,34.1 -2.428914722411904,1.8289293473958166,2.2252947962927703,833.8,1845.4,1786.7,505.0,106.2,47.6 -2.42892006358484,1.8289487965828068,2.356194490192345,2299.7,1751.1,1751.5,462.5,70.3,71.0 -2.4289176998046127,1.828976418998602,2.4870941840919194,2407.0,1787.1,1772.3,462.7,47.5,106.8 -2.4289230996067066,1.8289649753205295,2.6179938779914944,2725.6,1269.1,890.6,347.4,33.5,161.4 -2.4289114801726925,1.8289797412300326,2.748893571891069,2405.9,848.3,628.5,192.1,32.4,252.7 -2.428922316670689,1.8289719260224597,2.8797932657906435,1961.8,648.9,521.7,114.2,52.0,432.4 -2.428914955829236,1.8289769523589514,3.010692959690218,1764.0,543.3,484.6,68.7,152.7,977.7 -2.4288576578200596,1.728678609504473,0.0,1621.2,493.1,493.3,140.8,2329.0,2328.7 -2.428900687875397,1.7292769267789914,0.1308996938995747,1705.9,484.7,544.1,129.1,2386.1,2445.9 -2.428873960777025,1.729268018322141,0.2617993877991494,913.7,521.9,250.2,136.8,2644.9,2938.4 -2.42884296865141,1.7292475870491215,0.39269908169872414,627.2,391.8,172.8,173.7,2479.9,2261.0 -2.428817227838916,1.7292203451166193,0.5235987755982988,509.3,276.4,149.0,271.7,1987.9,1860.6 -2.428809431212064,1.7292012257798537,0.6544984694978736,462.5,209.9,151.0,618.3,1742.4,1683.5 -2.4287993183409564,1.729159636914405,0.7853981633974483,463.3,170.8,170.3,2298.8,1651.7,1651.2 -2.4288008561842203,1.7291539534783655,0.916297857297023,505.5,150.9,209.8,2363.3,1683.3,1742.4 -2.4288122188939996,1.7291202403983963,1.0471975511965976,272.3,149.4,276.9,2631.3,1272.1,892.9 -2.428835872209102,1.7290813297381418,1.1780972450961724,173.2,172.6,392.0,2430.5,850.8,630.0 -2.4288276880595583,1.7290885842558557,1.3089969389957472,136.6,250.3,630.1,1940.1,649.5,522.0 -2.428836236456286,1.7290840282524624,1.4398966328953218,129.1,543.1,1374.0,1702.6,542.2,484.0 -2.428903637550905,1.7290682938863084,1.5707963267948966,140.8,2328.4,2328.4,1621.2,493.3,493.2 -2.428891867709931,1.7290669752375407,1.7016960206944713,171.7,2384.3,2442.8,1660.9,484.7,543.4 -2.428883864109643,1.7290628378852775,1.832595714594046,229.6,2645.5,2909.5,1187.4,521.6,249.6 -2.4289360423147324,1.7290953227984767,1.9634954084936205,334.4,2479.3,2260.7,785.6,391.2,172.4 -2.4289511715950036,1.7291122074669545,2.0943951023931953,550.1,1986.0,1858.8,601.2,276.5,149.4 -2.428940921259485,1.7290894764244156,2.2252947962927703,1221.4,1741.7,1683.2,504.9,209.5,150.9 -2.428946431248845,1.7291091931422626,2.356194490192345,2299.5,1651.1,1651.7,462.5,170.2,170.9 -2.428943900427333,1.7291371293971358,2.4870941840919194,2406.8,1684.0,1743.0,462.6,150.9,210.1 -2.4289488016093705,1.7291258599686998,2.6179938779914944,2725.7,1269.3,890.5,509.3,149.0,276.9 -2.428936506189275,1.7291404961240926,2.748893571891069,2264.0,848.2,628.6,333.2,173.7,393.9 -2.42894663831513,1.729132199246525,2.8797932657906435,1846.7,649.0,521.6,229.5,251.4,631.8 -2.4289387474521207,1.729136422974426,3.010692959690218,1660.9,543.1,484.5,172.0,540.2,1365.2 -2.428881359872837,1.6288379098770849,0.0,1521.6,493.0,493.2,240.6,2328.9,2328.9 -2.4289203147015668,1.629320347391701,0.1308996938995747,1601.9,484.6,544.1,232.6,2386.9,2445.6 -2.4288879531378527,1.6293096230969997,0.2617993877991494,913.7,521.8,449.6,252.5,2644.7,2772.0 -2.4288113526398614,1.6292643322107203,0.39269908169872414,627.1,533.0,313.9,315.4,2339.5,2120.8 -2.4288026956429376,1.629255533723234,0.5235987755982988,509.3,392.1,264.6,471.0,1872.5,1744.5 -2.4287953328268164,1.629237402713588,0.6544984694978736,462.5,313.4,254.5,1004.5,1639.0,1579.9 -2.4287836508876213,1.6291896090108333,0.7853981633974483,463.3,270.8,270.3,2298.7,1551.6,1551.2 -2.428785345618408,1.6291757708852996,0.916297857297023,505.5,254.3,313.3,2363.0,1580.0,1638.9 -2.4287990250324345,1.6291340005298922,1.0471975511965976,471.7,264.9,392.4,2631.1,1272.6,892.9 -2.4288267817991787,1.6290881385364744,1.1780972450961724,314.9,313.8,533.2,2288.3,850.9,802.9 -2.4288239291775646,1.629090173592033,1.3089969389957472,252.1,449.7,829.3,1824.9,649.5,522.1 -2.4288385673983997,1.6290822441338317,1.4398966328953218,232.5,933.2,1763.7,1599.3,542.3,484.1 -2.428912334953423,1.6290648468991278,1.5707963267948966,240.8,2328.4,2328.7,1521.3,493.3,493.3 -2.4289065728669437,1.6290635956643515,1.7016960206944713,275.1,2383.6,2442.6,1556.9,484.8,543.3 -2.4289039222133733,1.6290610553390916,1.832595714594046,345.2,2645.8,2773.4,1187.7,521.5,448.8 -2.428960580031192,1.6290962839632885,1.9634954084936205,476.0,2338.2,2119.6,785.7,532.3,313.5 -2.428979029451424,1.6291166668129444,2.0943951023931953,749.6,1870.6,1743.5,601.3,391.9,264.9 -2.4289708182886973,1.6290978913533465,2.2252947962927703,1608.8,1638.3,1579.6,504.9,313.0,254.3 -2.4289771722311198,1.6291216800742057,2.356194490192345,2299.2,1551.2,1551.8,462.5,270.1,270.9 -2.4289744257529433,1.6291534286720646,2.4870941840919194,2407.0,1580.3,1639.8,462.7,254.4,313.7 -2.4289781422418555,1.6291454994824992,2.6179938779914944,2725.8,1269.5,891.0,509.2,264.6,392.5 -2.42896404171405,1.629162799479045,2.748893571891069,2123.5,848.3,801.1,474.6,315.1,535.3 -2.428971881616554,1.6291564299104035,2.8797932657906435,1730.6,649.1,521.6,345.1,451.0,831.4 -2.4289615045965873,1.6291618186733021,3.010692959690218,1557.0,543.2,484.5,275.5,927.7,1752.3 -2.4289011493527815,1.5288611418780704,0.0,1421.5,493.0,493.1,340.6,2329.0,2329.0 -2.428937626023434,1.5293231029268006,0.1308996938995747,1498.2,484.6,544.0,336.2,2386.5,2446.1 -2.4289043754012325,1.5293121267229732,0.2617993877991494,913.9,521.8,649.4,368.0,2644.6,2757.6 -2.4288678711914224,1.5292882661475211,0.39269908169872414,627.3,630.0,455.1,457.1,2199.0,1979.5 -2.4288378886109614,1.529256623269834,0.5235987755982988,509.3,507.7,380.2,670.3,1757.0,1629.5 -2.42882739964395,1.5292326944868524,0.6544984694978736,462.5,417.0,358.0,1390.3,1535.0,1476.4 -2.42881585633447,1.5291860026281692,0.7853981633974483,463.2,370.8,370.3,2298.9,1451.7,1451.4 -2.4288173647873017,1.5291755161770761,0.916297857297023,505.5,357.9,416.9,2363.1,1476.8,1535.6 -2.4288467212368707,1.5290826969916123,1.0471975511965976,601.7,380.6,507.9,2630.7,1383.1,893.2 -2.428851583091741,1.5290731774779664,1.1780972450961724,456.5,454.8,674.1,2147.7,850.9,686.4 -2.4288396469726945,1.529083573757958,1.3089969389957472,367.8,649.1,1028.6,1709.2,649.6,522.1 -2.428852029838467,1.529133565291589,1.4398966328953218,336.0,1322.9,2153.2,1495.6,542.4,484.0 -2.4289561494750473,1.5290486387798123,1.5707963267948966,340.8,2329.1,2328.6,1421.3,493.2,493.2 -2.428930950267805,1.5290466841008672,1.7016960206944713,378.6,2384.3,2442.7,1453.6,484.7,543.3 -2.428925982459274,1.5290435008895698,1.832595714594046,460.9,2645.3,2755.1,1187.7,521.5,649.2 -2.428985069660666,1.5290802833925285,1.9634954084936205,617.7,2198.0,1978.9,785.6,629.7,454.6 -2.429006392769775,1.5291037835357453,2.0943951023931953,949.3,1755.4,1628.0,601.4,507.5,380.3 -2.4290001685932046,1.5290889596491657,2.2252947962927703,1996.2,1535.1,1476.5,505.0,416.5,357.9 -2.429007379907559,1.5291169580551665,2.356194490192345,2299.4,1451.1,1451.7,462.5,370.2,370.8 -2.429004420509602,1.5291526975564402,2.4870941840919194,2406.9,1476.7,1535.8,462.6,358.1,417.2 -2.429022871790778,1.5290971431254983,2.6179938779914944,2725.6,1384.8,890.9,509.3,380.3,508.1 -2.428987458903476,1.5291484536258162,2.748893571891069,1982.1,848.5,628.6,629.3,456.5,676.7 -2.4290173073374675,1.5291228989732588,2.8797932657906435,1615.5,648.9,521.7,460.6,650.5,1030.8 -2.4289803110250836,1.529142328581819,3.010692959690218,1454.0,543.2,484.6,379.0,1314.8,2139.2 -2.4289156200508937,1.4288514772694525,0.0,1321.4,493.0,493.0,440.7,2329.0,2328.8 -2.428952857258837,1.4293264109323505,0.1308996938995747,1394.7,484.6,544.1,439.8,2386.1,2445.6 -2.4289192115272398,1.4293153380995007,0.2617993877991494,914.0,521.8,649.3,483.6,2738.2,2602.5 -2.428882275901847,1.4292912651270955,0.39269908169872414,627.3,629.7,596.3,598.7,2058.1,1838.4 -2.428851890866288,1.429259306545958,0.5235987755982988,509.4,623.4,495.8,869.4,1641.7,1514.1 -2.4288411404244137,1.4292350341807893,0.6544984694978736,462.5,520.6,461.6,1775.9,1431.9,1372.8 -2.42882937556777,1.4291879154622769,0.7853981633974483,463.2,470.8,470.3,2298.7,1351.9,1351.2 -2.4288308171556814,1.4291770310691196,0.916297857297023,505.5,461.5,520.3,2362.8,1372.6,1431.9 -2.4288433161447043,1.429138563761092,1.0471975511965976,601.5,496.0,623.5,2631.1,1372.2,893.2 -2.4288690531071135,1.429095441124924,1.1780972450961724,598.2,596.1,815.3,2006.2,851.1,630.2 -2.428863774172629,1.4290995584856816,1.3089969389957472,483.3,848.3,1228.0,1593.8,649.6,522.1 -2.428875751112939,1.4290930472512993,1.4398966328953218,439.5,1712.7,2384.0,1392.7,542.3,484.0 -2.428946775162985,1.4290761106065808,1.5707963267948966,440.8,2328.7,2328.7,1321.1,493.3,493.1 -2.4289384932108598,1.429074738722751,1.7016960206944713,481.9,2383.9,2442.5,1350.4,484.7,543.2 -2.4289335699545367,1.4290716705938482,1.832595714594046,576.5,2696.2,2600.8,1230.6,521.4,649.3 -2.4289883225819757,1.4291057881624645,1.9634954084936205,759.4,2056.8,1838.0,785.9,629.7,595.8 -2.4290053368402624,1.4291246998575597,2.0943951023931953,1149.0,1639.5,1487.1,601.4,623.0,495.8 -2.428996068514329,1.4291043989435603,2.2252947962927703,2362.8,1431.6,1372.6,505.0,520.0,461.4 -2.429001816751219,1.429126542261161,2.356194490192345,2299.5,1351.2,1351.7,462.5,470.2,470.8 -2.4289989974051545,1.429156577507184,2.4870941840919194,2406.7,1372.9,1432.2,462.6,461.5,520.7 -2.4290029262523176,1.4291471475674298,2.6179938779914944,2622.3,1373.3,891.0,509.2,495.9,623.7 -2.4289895573384945,1.429163072946011,2.748893571891069,1841.1,848.5,628.6,629.1,598.0,818.1 -2.428998278860167,1.4293169644778811,2.8797932657906435,1500.2,649.0,521.6,576.1,850.0,1230.2 -2.4288672687123354,1.4288882889059398,3.010692959690218,1350.3,543.5,484.5,482.8,1698.1,2385.1 -2.4288597526596654,1.3286572825456398,0.0,1221.3,493.1,493.0,540.9,2329.5,2329.5 -2.4289483279057307,1.3292958491599172,0.1308996938995747,1290.8,484.5,543.8,543.3,2386.1,2446.0 -2.4289295125655097,1.329289483733101,0.2617993877991494,914.5,521.7,649.2,599.1,2643.6,2404.2 -2.4288980401209472,1.3292689921187908,0.39269908169872414,627.4,629.7,737.6,740.3,1917.2,1697.6 -2.428869895624748,1.3292396588397983,0.5235987755982988,509.3,739.1,611.4,1068.6,1526.3,1398.6 -2.4288602110319752,1.3292175802114883,0.6544984694978736,462.5,624.1,565.1,2160.3,1328.6,1269.4 -2.4288487261363576,1.329172348132405,0.7853981633974483,463.1,570.9,570.3,2298.6,1251.9,1251.0 -2.428850058175683,1.3291631934076735,0.916297857297023,505.5,564.9,623.8,2362.9,1269.3,1328.1 -2.4288620610853,1.3291262275569928,1.0471975511965976,601.3,611.5,738.9,2630.3,1273.5,893.5 -2.4288869760863943,1.329084220106584,1.1780972450961724,771.3,737.2,956.2,1864.7,851.2,630.4 -2.428880764081137,1.3290892216809649,1.3089969389957472,599.0,1047.6,1426.8,1478.5,649.8,646.3 -2.428891718124644,1.3290833988924042,1.4398966328953218,542.9,2101.0,2384.1,1289.1,542.3,483.9 -2.4289616501930005,1.3290666813713197,1.5707963267948966,540.7,2329.0,2328.5,1221.1,493.4,493.0 -2.4289523469515792,1.3290653384353284,1.7016960206944713,585.4,2383.7,2441.7,1246.8,484.8,543.1 -2.428946456218876,1.3290621927818478,1.832595714594046,692.0,2645.5,2402.1,1244.7,521.4,649.0 -2.429000378423001,1.3290959083401381,1.9634954084936205,901.0,1915.8,1697.5,785.9,629.5,736.9 -2.429016761987701,1.329114211314458,2.0943951023931953,1348.4,1524.6,1397.2,601.6,738.8,611.5 -2.429006988980613,1.329093306954537,2.2252947962927703,2362.8,1327.8,1269.2,504.9,623.7,564.9 -2.4290124412630907,1.3291147651142678,2.356194490192345,2299.7,1251.0,1251.7,462.5,570.3,570.8 -2.4290096185473296,1.3291440388054032,2.4870941840919194,2407.2,1269.4,1328.9,462.5,565.1,624.2 -2.429013635754324,1.3291339803705857,2.6179938779914944,2423.9,1270.3,891.5,509.1,611.5,739.3 -2.429000668025479,1.3291493151485252,2.748893571891069,1700.2,848.7,628.8,629.0,739.4,959.3 -2.4290098040630155,1.3291415236932593,2.8797932657906435,1384.3,649.1,521.7,691.9,1049.4,1429.3 -2.4290010155922945,1.3291459975915783,3.010692959690218,1246.8,543.2,484.5,586.1,2088.4,2384.6 -2.4289424048858175,1.2288469174864638,0.0,1121.0,493.0,493.1,640.6,2328.9,2328.8 -2.4289781963076456,1.2293218176523506,0.1308996938995747,1187.6,484.6,543.9,647.1,2386.2,2445.1 -2.4289448293040787,1.2293108904583745,0.2617993877991494,914.5,521.6,649.3,714.8,2584.5,2204.8 -2.4289082852655786,1.229287182579847,0.39269908169872414,627.5,629.7,850.4,881.9,1775.6,1556.8 -2.428878140892491,1.2292557008906888,0.5235987755982988,509.3,880.1,727.0,1267.7,1410.5,1282.8 -2.428867551908834,1.2292319934885234,0.6544984694978736,462.5,727.7,668.6,2406.3,1225.1,1166.0 -2.428855687455409,1.2291853472691092,0.7853981633974483,463.2,670.9,670.3,2298.8,1151.8,1151.1 -2.428856984864906,1.2291749219953965,0.916297857297023,505.4,668.5,727.4,2362.5,1165.6,1224.7 -2.4288692399529443,1.229136817467177,1.0471975511965976,601.4,727.0,854.3,2505.3,1273.6,893.5 -2.428894644227068,1.2290938491077286,1.1780972450961724,787.3,878.4,1097.5,1723.3,851.2,630.4 -2.4288890861015586,1.2290980975731294,1.3089969389957472,714.7,1246.7,1626.1,1362.6,649.7,522.1 -2.4289101363962926,1.2290855894422688,1.4398966328953218,646.3,2443.2,2384.5,1185.5,542.3,483.9 -2.4289737755520497,1.2290702497876969,1.5707963267948966,640.8,2328.7,2328.9,1121.3,493.3,493.1 -2.428963785897816,1.2290688115698365,1.7016960206944713,688.9,2384.1,2442.1,1143.2,484.7,543.2 -2.4289589771482847,1.2290659333185507,1.832595714594046,807.5,2582.1,2203.1,1188.2,521.4,649.1 -2.4290142941853192,1.2291004931243625,1.9634954084936205,1042.7,1775.2,1556.0,785.9,629.3,850.5 -2.429031821386841,1.2291200308137342,2.0943951023931953,1547.5,1408.8,1281.8,601.5,879.8,727.0 -2.4290227812483787,1.2291005479784056,2.2252947962927703,2363.0,1224.4,1165.9,505.0,727.3,668.4 -2.4290285275502366,1.2291234909493953,2.356194490192345,2299.1,1151.3,1151.8,462.4,670.4,670.8 -2.4290255811630694,1.229154172537154,2.4870941840919194,2406.6,1165.9,1224.9,462.5,668.6,727.8 -2.429029144061567,1.2291453195593438,2.6179938779914944,2224.6,1270.4,891.4,509.1,727.3,854.9 -2.4290154586976715,1.2291616173062518,2.748893571891069,1558.5,848.7,628.8,629.0,880.8,1100.7 -2.4290237367827734,1.2291544960682412,2.8797932657906435,1269.2,649.1,521.6,807.5,1249.1,1628.5 -2.4290140277217946,1.2291593565139824,3.010692959690218,1143.1,543.2,484.5,689.7,2444.0,2384.5 -2.4289543805987464,1.128859492655279,0.0,1021.3,493.0,493.0,740.6,2328.9,2329.1 -2.428984849929241,1.1293250355725242,0.1308996938995747,1083.8,484.7,543.8,750.5,2386.2,2445.8 -2.428950024790566,1.1293136584899388,0.2617993877991494,1001.3,521.6,649.0,830.3,2384.8,2005.5 -2.4289128985026083,1.1292895972911408,0.39269908169872414,627.4,629.8,850.5,1023.6,1634.6,1415.4 -2.42888246544502,1.1292578357236347,0.5235987755982988,509.3,892.4,842.6,1467.1,1294.9,1167.4 -2.4288717262944086,1.1292338902512702,0.6544984694978736,462.6,831.1,772.2,2406.1,1121.3,1062.2 -2.4288597698359107,1.1291870042879237,0.7853981633974483,463.0,770.8,770.3,2299.3,1051.7,1051.3 -2.4288610471947765,1.1291763604497234,0.916297857297023,505.3,771.9,830.8,2362.6,1062.3,1121.0 -2.4288733337301838,1.1291380525501675,1.0471975511965976,601.4,842.6,970.0,2306.1,1166.3,1048.1 -2.4288988091190493,1.1290948913620902,1.1780972450961724,787.1,1019.4,1238.5,1582.0,851.3,630.3 -2.428893366159081,1.1290989948449335,1.3089969389957472,830.1,1445.8,1825.1,1247.5,649.8,522.2 -2.428905240723495,1.1290925518944017,1.4398966328953218,749.7,2442.6,2384.3,1082.3,542.3,484.0 -2.4289761748002907,1.1290754906564824,1.5707963267948966,740.7,2329.3,2328.6,1021.2,493.3,493.1 -2.428967845288225,1.1290740983969156,1.7016960206944713,792.3,2383.5,2441.6,1039.7,484.7,543.1 -2.428962839499745,1.129071177121558,1.832595714594046,923.2,2383.4,2003.9,1154.8,521.4,649.2 -2.4290175042042526,1.1291053359706813,1.9634954084936205,1184.5,1634.1,1384.0,785.9,629.5,850.5 -2.4290344235884516,1.129124229230262,2.0943951023931953,1747.3,1293.5,1166.1,601.5,894.3,842.4 -2.4290249510565056,1.129103997574153,2.2252947962927703,2363.2,1120.9,1062.2,505.1,830.6,771.8 -2.4290304798575524,1.1291261402043116,2.356194490192345,2299.4,1051.2,1051.7,462.5,770.3,770.8 -2.4290275386748204,1.1291560335322186,2.4870941840919194,2406.5,1062.3,1121.5,462.6,772.3,831.2 -2.4290312749006997,1.129146484402681,2.6179938779914944,2025.8,1167.5,1049.7,509.1,842.9,970.5 -2.4290179355437482,1.1291621860485022,2.748893571891069,1417.4,848.7,628.8,628.8,1021.9,1242.4 -2.4290266497317003,1.1291546177714624,2.8797932657906435,1153.7,649.1,521.6,915.5,1448.9,1828.8 -2.429017444729854,1.1291591835519768,3.010692959690218,1039.8,543.3,484.5,793.1,2443.7,2384.5 -2.3290109878312886,1.8292519492977033,0.0,1721.4,593.0,593.0,40.8,2229.3,2228.8 -2.328991428626562,1.8285391668701747,0.1308996938995747,1808.4,588.1,149.2,25.6,2282.5,2364.4 -2.3290418366793606,1.8285555524607437,0.2617993877991494,1114.1,431.0,51.4,21.4,2528.4,2655.1 -2.329095075342149,1.8285899061202404,0.39269908169872414,768.8,251.2,31.9,32.1,2622.6,2403.7 -2.3291368930392076,1.8286376062624632,0.5235987755982988,625.1,161.3,33.6,72.4,2104.2,1976.5 -2.329173000161072,1.8287030414725758,0.6544984694978736,566.2,106.7,47.6,231.9,1846.2,1786.9 -2.3291821304901554,1.8287489721816765,0.7853981633974483,563.1,71.1,70.5,2198.4,1751.6,1750.9 -2.329180701701657,1.8288261397816212,0.916297857297023,233.2,47.7,106.5,2258.9,1786.4,1845.3 -2.3291696541332496,1.8288665226604681,1.0471975511965976,73.7,34.2,161.5,2514.2,1473.7,1093.5 -2.3291556479014317,1.8288884279609041,1.1780972450961724,32.1,31.9,250.9,2573.6,993.2,772.2 -2.3291003353296054,1.8289413062658804,1.3089969389957472,21.4,51.4,430.5,2056.0,765.5,638.0 -2.3290557422801,1.8289671579272178,1.4398966328953218,26.0,153.1,981.7,1783.3,646.0,587.5 -2.3290675304237833,1.8289656341448384,1.5707963267948966,41.1,2228.8,2228.5,1720.8,593.4,593.1 -2.3290033116309643,1.828964436381773,1.7016960206944713,68.5,2280.0,2338.8,1763.9,588.2,153.2 -2.3289479502854062,1.8289484273881005,1.832595714594046,114.3,2528.9,2657.1,1388.0,430.6,51.4 -2.328960064120864,1.8289580221146127,1.9634954084936205,192.8,2621.9,2402.8,927.2,251.1,31.9 -2.32894504060221,1.8289446941105418,2.0943951023931953,350.3,2102.0,1974.9,716.9,161.5,34.2 -2.328914934354487,1.828888198413029,2.2252947962927703,831.7,1845.5,1786.4,608.6,106.5,47.7 -2.3289110359224363,1.8288723460386676,2.356194490192345,2199.2,1750.6,1751.4,562.5,70.6,71.1 -2.3289093624934574,1.8288657354191769,2.4870941840919194,2303.1,1786.8,1846.0,565.9,47.7,106.8 -2.328923238846445,1.8288242721696857,2.6179938779914944,2609.4,1469.9,1090.7,348.2,33.7,161.3 -2.3289273067391507,1.8288139355966604,2.748893571891069,2407.0,990.3,770.2,192.5,32.5,252.5 -2.3289578042716874,1.8287877723763595,2.8797932657906435,1962.6,764.7,637.2,114.4,52.1,431.9 -2.3289726344525272,1.8287813255624847,3.010692959690218,1764.2,646.8,588.0,68.9,152.4,975.1 -2.3289416157872576,1.7285032732774697,0.0,1620.9,592.9,592.9,141.0,2229.0,2229.1 -2.3289909063455605,1.7292627637662865,0.1308996938995747,1705.1,588.1,532.8,129.1,2282.7,2341.8 -2.328967053684881,1.729254968447735,0.2617993877991494,1114.1,637.2,250.6,136.8,2528.2,2655.2 -2.3289375209342214,1.7292358843685516,0.39269908169872414,768.7,392.2,172.9,173.6,2482.3,2262.5 -2.328912292183033,1.7292099865453645,0.5235987755982988,625.1,276.7,149.0,271.2,1988.8,1861.1 -2.3289047710709823,1.7291923384968833,0.6544984694978736,566.1,210.1,151.0,616.7,1742.8,1683.4 -2.3288941341276974,1.7291518003382644,0.7853981633974483,563.2,170.8,170.3,2198.6,1651.9,1651.3 -2.3288951658636434,1.7291471407904715,0.916297857297023,608.8,150.9,209.7,2258.7,1683.5,1742.0 -2.328905815549181,1.7291141624334927,1.0471975511965976,272.7,149.4,276.7,2514.7,1614.0,1093.3 -2.3289285533833284,1.7290753209188565,1.1780972450961724,173.3,172.5,391.5,2432.1,993.1,945.0 -2.3289197327932576,1.7290826904415946,1.3089969389957472,136.7,250.0,629.2,1940.8,765.5,637.8 -2.3289278132928977,1.7290784759494966,1.4398966328953218,129.1,541.5,1370.0,1702.9,645.8,587.4 -2.3289947649967826,1.7290624157065109,1.5707963267948966,140.8,2229.0,2228.6,1621.1,593.4,593.1 -2.3289826797202036,1.7290610585273853,1.7016960206944713,171.6,2280.2,2339.1,1660.2,588.2,623.8 -2.328974255997666,1.729057374038701,1.832595714594046,229.5,2529.8,2657.1,1388.0,636.9,250.0 -2.329026017360026,1.729089926825632,1.9634954084936205,334.1,2481.0,2261.9,927.2,391.5,172.5 -2.32904074266,1.729106654793258,2.0943951023931953,549.2,1986.9,1859.1,717.0,276.7,149.4 -2.3290297775592665,1.7290840323458,2.2252947962927703,1218.1,1742.1,1683.5,608.6,209.6,150.9 -2.329034566638837,1.7291036271469364,2.356194490192345,2199.4,1651.2,1651.7,562.5,170.3,170.8 -2.3290316693427693,1.7291309964326609,2.4870941840919194,2302.8,1683.9,1742.6,566.1,151.0,210.1 -2.3290360059691086,1.7291192563622508,2.6179938779914944,2609.6,1615.6,1090.7,546.8,149.0,276.6 -2.3290238816986744,1.7291331130178635,2.748893571891069,2266.1,990.0,942.9,333.6,173.6,393.5 -2.329034071689668,1.729124241112154,2.8797932657906435,1846.9,764.6,637.3,229.7,251.1,630.9 -2.32902653220461,1.7291280385580376,3.010692959690218,1661.0,646.8,588.0,172.1,538.5,1361.3 -2.3289693767434847,1.6288301733371227,0.0,1521.6,593.0,593.0,240.7,2229.3,2229.1 -2.3290004305209715,1.6293192858378858,0.1308996938995747,1601.8,588.0,647.4,232.7,2282.8,2341.9 -2.3289663342427747,1.629308181013141,0.2617993877991494,1114.0,637.2,450.0,252.3,2528.2,2716.1 -2.328929812171129,1.6292845815361139,0.39269908169872414,768.6,533.4,314.1,315.2,2340.9,2121.5 -2.3288997701705796,1.6292533851348112,0.5235987755982988,625.0,392.4,264.6,470.5,1873.4,1745.8 -2.328889278818772,1.6292300757253244,0.6544984694978736,566.1,313.6,254.5,1002.3,1639.1,1580.0 -2.3288773233422275,1.6291837711271364,0.7853981633974483,563.2,270.8,270.3,2199.0,1551.7,1551.2 -2.3288782397583896,1.6292200575827245,0.916297857297023,608.8,254.4,313.1,2259.7,1579.9,1638.6 -2.328899515271314,1.6291521429176503,1.0471975511965976,472.3,264.9,392.2,2514.6,1498.5,1093.2 -2.328928283903736,1.629103563217753,1.1780972450961724,315.0,313.6,532.7,2290.4,993.0,827.2 -2.3289218246297154,1.6291085669616465,1.3089969389957472,252.2,449.2,828.5,1825.6,864.6,637.8 -2.3289305132379967,1.6291038622232596,1.4398966328953218,232.5,930.9,1759.6,1599.5,645.7,587.3 -2.328997396283434,1.6290876724868397,1.5707963267948966,240.8,2228.1,2228.7,1521.1,593.1,593.1 -2.3289850595485015,1.6290861573937756,1.7016960206944713,275.0,2280.1,2338.7,1557.1,588.2,646.5 -2.3289763933115246,1.6290822404743501,1.832595714594046,345.0,2529.5,2714.0,1487.0,637.0,449.2 -2.3290279755523087,1.6291145372707474,1.9634954084936205,475.7,2339.7,2121.0,927.1,532.7,313.6 -2.329042592286922,1.6291310179945149,2.0943951023931953,748.8,1845.5,1744.1,858.1,392.2,264.9 -2.3290315786591567,1.6291081635291067,2.2252947962927703,1605.4,1638.7,1579.7,608.5,313.1,254.4 -2.3290363482575964,1.6291275546840764,2.356194490192345,2199.4,1551.4,1551.5,562.3,270.2,270.8 -2.3290331693897537,1.6292015136377902,2.4870941840919194,2303.4,1580.1,1639.1,566.1,254.5,313.6 -2.3290468305997067,1.6291592323001691,2.6179938779914944,2735.5,1499.8,1090.8,624.7,264.5,392.3 -2.3290383416749756,1.6291672143204408,2.748893571891069,2124.6,990.1,770.3,475.0,315.0,534.9 -2.329047851066823,1.6291588385998885,2.8797932657906435,1731.4,764.6,637.3,345.3,450.6,830.4 -2.329037498829904,1.629163992387825,3.010692959690218,1557.3,646.9,588.0,275.6,925.7,1748.7 -2.3289387992869344,1.528853246891066,0.0,1421.3,592.9,593.1,340.6,2229.1,2229.3 -2.3289880725979564,1.5292114917531139,0.1308996938995747,1497.9,588.0,647.5,336.2,2282.2,2341.8 -2.328971866545565,1.529206101205431,0.2617993877991494,1114.0,637.3,649.6,367.9,2527.9,2655.1 -2.3289489532685796,1.529191266289375,0.39269908169872414,768.8,674.6,455.4,456.8,2199.6,1980.3 -2.328928723636464,1.5291708454332502,0.5235987755982988,625.0,508.0,380.3,669.7,1757.6,1629.7 -2.328924390055948,1.529159251245649,0.6544984694978736,566.0,417.2,358.1,1387.6,1535.5,1476.6 -2.328915180090305,1.5291249628135586,0.7853981633974483,563.2,370.8,370.3,2198.7,1451.8,1451.2 -2.328916034498995,1.5291262077888246,0.916297857297023,608.8,357.9,416.7,2259.1,1476.3,1535.0 -2.3289251161914124,1.5290985170381888,1.0471975511965976,716.0,380.5,507.8,2514.5,1473.5,1093.6 -2.328945196790847,1.5290640419231676,1.1780972450961724,456.8,454.8,673.9,2148.4,993.0,772.2 -2.3289330208702412,1.5290746810062508,1.3089969389957472,367.9,648.6,1027.8,1709.6,765.6,637.9 -2.3289373041243113,1.529072626488181,1.4398966328953218,336.0,1320.9,2149.7,1496.0,645.9,587.6 -2.3290002818017204,1.5290575928738908,1.5707963267948966,340.8,2229.1,2228.9,1421.4,593.3,593.1 -2.328984446759287,1.5290562320992391,1.7016960206944713,378.5,2280.2,2338.6,1453.4,588.3,646.5 -2.3289726499753227,1.529051656135518,1.832595714594046,460.7,2529.3,2656.6,1476.0,636.9,648.7 -2.3290215675578123,1.5290825487515889,1.9634954084936205,617.4,2198.6,1979.6,927.2,673.9,454.8 -2.3290341639185543,1.5290971073406445,2.0943951023931953,948.6,1755.8,1628.2,717.0,507.7,380.5 -2.329021826581933,1.5290720525967674,2.2252947962927703,1992.4,1535.4,1476.1,608.6,416.7,357.9 -2.329025991797348,1.5290891040489671,2.356194490192345,2199.9,1450.9,1451.8,562.4,370.3,370.8 -2.3290231841260685,1.5291140313203098,2.4870941840919194,2303.0,1476.6,1535.4,566.0,358.1,417.1 -2.3290281972054783,1.5291001579918215,2.6179938779914944,2609.5,1469.7,1090.7,624.7,380.3,508.0 -2.329017234609354,1.529112270942615,2.748893571891069,1983.2,990.5,770.1,616.5,456.4,676.5 -2.329028874912586,1.5291021499537318,2.8797932657906435,1615.8,764.7,637.2,460.8,650.2,1030.0 -2.329022937503641,1.5291052008865953,3.010692959690218,1453.6,646.8,587.9,379.3,1313.0,2135.4 -2.3289676524647205,1.4288087615252025,0.0,1321.3,593.0,593.0,440.8,2228.9,2228.8 -2.329000267568222,1.4293157903762264,0.1308996938995747,1394.4,588.0,647.4,439.8,2282.4,2341.8 -2.3289668902743115,1.4293049181740576,0.2617993877991494,1114.3,637.2,764.6,483.4,2527.5,2604.0 -2.328930813368732,1.4292816087289986,0.39269908169872414,768.7,771.2,596.5,598.4,2058.4,1839.4 -2.328901061569112,1.4292507369168477,0.5235987755982988,763.8,623.5,495.8,868.8,1641.9,1514.5 -2.3288907461777697,1.4292277688056434,0.6544984694978736,566.0,520.7,461.6,1773.4,1432.3,1373.1 -2.328878864054428,1.4291818065444386,0.7853981633974483,563.1,470.9,470.3,2198.8,1351.9,1351.1 -2.328880031115122,1.4291720405978745,0.916297857297023,608.8,461.5,520.2,2259.4,1372.6,1431.5 -2.328892007659667,1.4291344868661064,1.0471975511965976,716.8,495.9,623.3,2617.9,1473.3,1093.3 -2.3289170091154245,1.4290918537213915,1.1780972450961724,598.6,595.9,814.9,2007.4,992.9,772.2 -2.3289110595225937,1.4290963653974567,1.3089969389957472,483.5,847.9,1226.9,1594.4,765.4,637.8 -2.328922404550253,1.4290902411943929,1.4398966328953218,439.5,1710.5,2280.9,1392.7,645.8,587.4 -2.328992790202647,1.4290732464577633,1.5707963267948966,440.7,2229.4,2228.8,1321.0,593.3,593.1 -2.3289839613324137,1.4290718501438713,1.7016960206944713,481.9,2280.0,2338.5,1350.1,588.2,646.6 -2.3289784809686647,1.4290689067294522,1.832595714594046,576.3,2554.8,2602.7,1387.9,636.9,764.6 -2.3290327337033148,1.4291028826797612,1.9634954084936205,759.1,2057.7,1838.4,927.1,771.2,595.9 -2.329049328161863,1.4291214915714474,2.0943951023931953,1148.5,1640.2,1512.9,717.0,623.3,496.0 -2.329039565653681,1.4291009908794565,2.2252947962927703,2259.1,1431.5,1372.7,608.6,520.2,461.4 -2.3290448931382426,1.4291228098937894,2.356194490192345,2199.5,1351.3,1351.8,562.5,470.3,470.7 -2.3290418994763935,1.4291523126511718,2.4870941840919194,2303.0,1373.0,1432.1,565.9,461.6,520.7 -2.329045618185086,1.4291424277324383,2.6179938779914944,2579.8,1469.7,1090.6,624.7,495.9,623.5 -2.329032450100305,1.4291577860130755,2.748893571891069,1841.7,990.3,770.1,770.2,597.8,817.7 -2.3290413489480617,1.4291499707335258,2.8797932657906435,1500.4,764.8,637.3,576.4,849.5,1229.6 -2.3290323976846437,1.4291543764635652,3.010692959690218,1350.4,646.9,588.0,482.7,1700.1,2281.6 -2.328973622032314,1.3288552730606478,0.0,1221.4,592.9,593.0,540.7,2229.2,2228.9 -2.3290023509296485,1.3293267108328446,0.1308996938995747,1290.8,588.1,647.5,543.4,2282.4,2342.1 -2.3289669325139024,1.3293151814940138,0.2617993877991494,1232.3,637.2,764.6,599.0,2527.7,2404.7 -2.328929479333972,1.3292909846000784,0.39269908169872414,768.7,771.2,737.7,740.2,1917.0,1697.9 -2.3288987841269226,1.3292590764500054,0.5235987755982988,625.0,739.2,611.5,1068.0,1526.3,1398.6 -2.328887887516378,1.329235003147987,0.6544984694978736,566.0,624.2,565.2,2158.8,1328.7,1269.5 -2.328875746500554,1.3291879151774686,0.7853981633974483,563.1,570.9,570.2,2198.6,1251.8,1251.1 -2.3288769413267705,1.3291770896808437,0.916297857297023,608.8,564.9,623.8,2259.1,1269.3,1328.0 -2.3288891930572064,1.3291385866505276,1.0471975511965976,716.8,611.4,739.0,2514.6,1397.4,1093.4 -2.3289146642556386,1.3290951669586122,1.1780972450961724,740.0,736.9,956.1,1865.0,993.0,772.1 -2.3289093105065923,1.3290990859585297,1.3089969389957472,599.0,1046.9,1426.3,1478.7,765.4,637.7 -2.328921333017201,1.32909256596372,1.4398966328953218,542.9,2100.5,2281.1,1289.3,645.9,587.5 -2.3289924311815295,1.3290753780332043,1.5707963267948966,540.7,2229.1,2228.7,1221.3,593.3,593.0 -2.3289842777581486,1.3290739743562963,1.7016960206944713,585.4,2280.0,2338.5,1246.7,588.1,646.6 -2.3289794076374495,1.3290711853661357,1.832595714594046,691.8,2529.6,2403.0,1385.7,636.9,764.6 -2.3290341765918225,1.3291054571200616,1.9634954084936205,900.9,1916.4,1697.5,927.3,771.2,737.1 -2.329051158042382,1.3291244565333455,2.0943951023931953,1347.7,1524.4,1397.5,717.0,738.9,611.5 -2.3290416442823516,1.3291043959769568,2.2252947962927703,2259.0,1328.0,1269.4,608.7,623.8,564.9 -2.329047082885779,1.3291266760978333,2.356194490192345,2199.8,1251.0,1251.7,562.4,570.3,570.8 -2.3290440689067156,1.3291566209879502,2.4870941840919194,2303.0,1269.5,1328.5,566.0,565.1,624.2 -2.3290476594665765,1.3291471204240097,2.6179938779914944,2424.4,1398.9,1090.6,624.7,611.4,739.1 -2.3290342751300654,1.3291627898760416,2.748893571891069,1700.2,990.3,770.2,770.1,739.2,959.2 -2.3290429066492813,1.3291551936989747,2.8797932657906435,1384.6,764.7,637.2,691.9,1049.0,1429.0 -2.329033663072493,1.3291597258395527,3.010692959690218,1246.8,646.8,588.1,586.2,2087.2,2281.3 -2.32897455186059,1.2288603660972959,0.0,1121.4,593.1,593.0,640.7,2228.7,2229.1 -2.32900279730015,1.2293283942862414,0.1308996938995747,1187.5,588.1,647.3,647.0,2282.3,2342.0 -2.32896708732346,1.2293167713351982,0.2617993877991494,1116.6,637.2,764.8,714.7,2528.4,2205.6 -2.3289294238394826,1.229292439650511,0.39269908169872414,768.6,771.3,878.9,881.7,1776.0,1557.1 -2.3288985794787496,1.2292603692581425,0.5235987755982988,625.1,854.8,727.0,1267.2,1410.7,1283.0 -2.3288875899960004,1.2292361211940273,0.6544984694978736,566.1,727.7,668.6,2303.1,1225.1,1165.9 -2.328875406210486,1.2291888536066904,0.7853981633974483,563.1,670.9,670.2,2199.4,1151.8,1151.1 -2.3288766046651768,1.229177858945937,0.916297857297023,608.7,668.4,727.3,2259.4,1165.6,1224.6 -2.3288888996461443,1.2291392039846176,1.0471975511965976,716.7,727.0,854.4,2506.1,1281.7,1138.1 -2.328914445138388,1.2290956573685645,1.1780972450961724,913.1,878.1,1097.0,1723.8,992.9,772.2 -2.3289091866101863,1.229099480971954,1.3089969389957472,714.7,1246.4,1625.8,1362.6,765.5,637.8 -2.328921317802893,1.2290928979381461,1.4398966328953218,646.4,2338.5,2281.5,1185.7,646.1,587.4 -2.3289925302437857,1.2290756783308032,1.5707963267948966,640.8,2229.2,2228.9,1121.3,593.3,593.1 -2.328984485302118,1.2290742735760318,1.7016960206944713,688.8,2280.0,2338.4,1143.1,588.2,646.6 -2.328979712852878,1.2290715106026118,1.832595714594046,807.7,2529.5,2203.5,1270.2,636.9,764.4 -2.3290345642832406,1.2291058303196274,1.9634954084936205,1042.5,1775.6,1556.3,927.1,771.2,878.2 -2.3290516073984753,1.2291248924602516,2.0943951023931953,1547.2,1409.1,1281.6,717.2,854.3,727.1 -2.3290421323936443,1.2291049031671353,2.2252947962927703,2259.2,1224.7,1165.8,608.6,727.0,668.3 -2.32904758759185,1.2291272574638237,2.356194490192345,2199.6,1151.2,1151.7,562.5,670.2,670.8 -2.329044569783136,1.2291572725909221,2.4870941840919194,2303.1,1165.8,1224.9,566.0,668.7,727.7 -2.3290481387047515,1.2291478332217898,2.6179938779914944,2225.6,1283.0,1165.2,624.6,727.1,854.6 -2.3290347200162906,1.2291635514971373,2.748893571891069,1558.8,990.4,770.3,770.2,880.7,1100.6 -2.329043308622522,1.2291559897723863,2.8797932657906435,1269.4,764.7,637.3,807.4,1248.7,1628.7 -2.3290340186089726,1.2291605417365106,3.010692959690218,1143.6,646.7,587.9,689.6,2340.2,2280.8 -2.3289748535556862,1.1288611419390184,0.0,1021.2,593.1,592.9,740.6,2229.1,2229.0 -2.329003018313051,1.1293290453745501,0.1308996938995747,1083.7,588.0,647.5,750.6,2282.3,2341.8 -2.328967215817883,1.1293173927746176,0.2617993877991494,1114.1,637.2,764.7,830.1,2385.5,2005.8 -2.328929473260939,1.1292930108326995,0.39269908169872414,768.8,771.3,991.9,1023.3,1634.6,1415.6 -2.3288985688228965,1.12926087591708,0.5235987755982988,624.9,970.4,842.8,1466.6,1295.0,1167.3 -2.328887541139997,1.1292365568695897,0.6544984694978736,566.1,831.3,772.3,2302.7,1121.5,1062.2 -2.328875339010926,1.1291892152752803,0.7853981633974483,563.1,770.8,770.2,2199.0,1051.8,1050.9 -2.3288765385973424,1.129178150807733,0.916297857297023,608.8,771.9,830.9,2259.4,1062.2,1121.0 -2.328888851133716,1.1291394329585698,1.0471975511965976,716.7,842.6,969.8,2306.5,1166.5,1152.8 -2.328914426982264,1.1290958332825036,1.1780972450961724,928.2,1019.2,1238.2,1581.9,993.0,772.1 -2.328909207849138,1.129099617156972,1.3089969389957472,830.2,1445.7,1825.1,1247.2,765.4,637.9 -2.3289213841929652,1.1290930082410933,1.4398966328953218,750.0,2339.3,2280.8,1082.3,645.9,587.4 -2.328992644069699,1.1290757751772875,1.5707963267948966,740.7,2229.1,2229.0,1021.3,593.3,593.0 -2.3289846442187354,1.1290743700671086,1.7016960206944713,792.3,2280.0,2338.5,1039.7,588.2,646.5 -2.3289799121807326,1.129071618559396,1.832595714594046,922.9,2383.9,2004.2,1154.5,636.9,764.7 -2.3290347976581107,1.129105958447735,1.9634954084936205,1184.3,1634.3,1415.2,927.2,771.2,992.0 -2.3290518661531983,1.129125046648793,2.0943951023931953,1747.0,1293.7,1166.4,717.1,969.8,842.4 -2.3290424066573987,1.12910508725415,2.2252947962927703,2259.7,1121.3,1062.4,608.6,830.7,772.0 -2.3290478681446882,1.1291274724281517,2.356194490192345,2199.8,1051.3,1051.8,562.5,770.4,770.7 -2.3290448485063258,1.1291575163478893,2.4870941840919194,2303.0,1062.3,1121.6,566.1,772.1,831.2 -2.32904840794442,1.129148102158953,2.6179938779914944,2025.7,1167.5,1154.2,624.8,842.6,970.4 -2.3290349752272963,1.1291638401734623,2.748893571891069,1417.4,990.1,770.3,770.3,1022.1,1242.2 -2.3290435460408903,1.1291562924464102,2.8797932657906435,1153.9,764.6,637.3,923.1,1448.3,1827.6 -2.329034236999501,1.1291608524670576,3.010692959690218,1040.0,646.9,588.0,793.2,2340.1,2281.0 -2.2290277031889936,1.8292535108097572,0.0,1721.6,693.0,693.0,40.8,2129.4,2129.2 -2.2289993337209304,1.82853960978697,0.1308996938995747,1808.6,691.8,149.1,25.6,2178.9,2238.4 -2.2290479434519286,1.8285554484353215,0.2617993877991494,1313.8,431.1,51.4,21.4,2412.5,2539.8 -2.2291007872497075,1.8285895739490532,0.39269908169872414,1053.7,251.2,31.9,32.1,2622.8,2403.5 -2.2291425876720727,1.8286372881496822,0.5235987755982988,740.7,161.3,33.6,72.4,2104.4,1976.6 -2.2291787203852014,1.8287028425710443,0.6544984694978736,669.8,106.7,47.6,231.9,1845.8,1786.8 -2.229187859977129,1.828748938612085,0.7853981633974483,663.1,71.1,70.5,2099.2,1751.7,1750.9 -2.2291863870597095,1.8288262557529997,0.916297857297023,233.2,47.7,106.5,2155.5,1786.7,1845.2 -2.2291752626605574,1.828866762848072,1.0471975511965976,73.7,34.2,161.5,2398.5,1703.5,1293.4 -2.2291611653599075,1.8288887723115885,1.1780972450961724,32.1,31.9,250.9,2573.4,1134.9,1086.9 -2.2291057482270893,1.828941711833091,1.3089969389957472,21.4,51.4,430.6,2056.0,881.0,753.5 -2.229061050302705,1.828967584662345,1.4398966328953218,26.0,153.1,981.6,1806.1,749.3,691.0 -2.229072743025373,1.8289660825888134,1.5707963267948966,41.2,2129.1,2128.6,1720.7,693.4,693.1 -2.229008437052491,1.828964881814243,1.7016960206944713,68.5,2177.0,2235.3,1763.7,691.7,153.2 -2.2289530007213534,1.828948842880839,1.832595714594046,114.3,2413.3,2541.5,1717.5,430.7,51.4 -2.2289650439260527,1.8289584117043844,1.9634954084936205,192.8,2622.0,2402.5,1068.3,251.0,31.9 -2.228949953682525,1.8289450553382278,2.0943951023931953,350.2,2101.9,1974.6,832.6,161.5,34.2 -2.2289197973242483,1.8288885091711258,2.2252947962927703,832.0,1845.1,1786.7,711.9,106.5,47.7 -2.2289158589351366,1.8288725980435485,2.356194490192345,2099.3,1750.5,1751.4,662.5,70.6,71.1 -2.2289141502420615,1.8286887216297711,2.4870941840919194,2199.8,1787.0,1846.0,669.6,47.7,106.8 -2.228932577742946,1.828804621690298,2.6179938779914944,2494.1,1705.6,1290.1,348.2,33.7,161.4 -2.228929344370627,1.8288059553135239,2.748893571891069,2407.2,1131.5,1084.3,192.5,32.5,252.5 -2.2289578195634423,1.8287816211501786,2.8797932657906435,1962.4,880.1,752.8,114.4,52.1,431.9 -2.2289732471088013,1.8287748250672031,3.010692959690218,1764.1,750.3,691.4,68.9,152.4,975.2 -2.2289442787515323,1.7284988390574403,0.0,1621.1,693.0,693.0,140.9,2128.8,2129.1 -2.2289929362307843,1.729264751695407,0.1308996938995747,1705.1,691.6,532.8,129.1,2179.1,2238.5 -2.228968749529302,1.7292568534669397,0.2617993877991494,1313.5,630.3,250.6,136.8,2412.4,2539.9 -2.228938959730801,1.7292376115438544,0.39269908169872414,909.9,392.2,172.9,173.5,2482.1,2263.0 -2.2289135384004837,1.7292115170853999,0.5235987755982988,740.7,276.7,149.0,271.3,1988.9,1861.3 -2.228905896194581,1.7291936568218491,0.6544984694978736,669.7,210.1,151.0,616.6,1742.8,1683.6 -2.228895192942221,1.7291528927588256,0.7853981633974483,663.0,170.9,170.3,2098.9,1651.9,1651.3 -2.2288962214570742,1.7291480208732628,0.916297857297023,704.7,150.9,209.7,2155.8,1683.1,1742.1 -2.228906918258272,1.7291148488250823,1.0471975511965976,272.7,149.4,276.7,2398.9,1718.5,1293.0 -2.228929742018773,1.7290758368045163,1.1780972450961724,173.3,172.5,391.6,2432.3,1134.6,968.0 -2.2289210401835176,1.7290830792776826,1.3089969389957472,136.6,250.0,629.3,1941.2,1022.1,753.3 -2.2289292603062942,1.7290787852134881,1.4398966328953218,129.1,541.4,1370.1,1703.2,749.2,691.0 -2.2289963594021,1.729062677162615,1.5707963267948966,140.8,2129.1,2128.6,1621.4,693.3,693.1 -2.2289844157666185,1.7290613182198007,1.7016960206944713,171.5,2176.8,2235.3,1660.5,691.7,541.4 -2.2289761172900233,1.7290576764561645,1.832595714594046,229.4,2414.0,2541.2,1602.2,629.3,250.0 -2.229027983309012,1.7290902953602623,1.9634954084936205,334.0,2481.0,2262.0,1068.1,391.7,172.5 -2.2290427853002184,1.7291071057273288,2.0943951023931953,549.1,1987.0,1859.3,832.7,276.6,149.4 -2.2290318609538478,1.7290845814057922,2.2252947962927703,1217.9,1742.4,1683.4,712.1,209.7,150.9 -2.2290366608125,1.7291042744699405,2.356194490192345,2099.4,1651.5,1651.7,662.6,170.3,170.8 -2.229033752475293,1.7291317295123336,2.4870941840919194,2199.2,1683.7,1742.7,669.6,150.9,210.0 -2.2290380508755216,1.7291200645686882,2.6179938779914944,2493.6,1720.1,1290.0,546.9,149.0,276.7 -2.229025883105277,1.7291339747384793,2.748893571891069,2265.8,1131.5,911.7,333.6,173.6,393.5 -2.22903601619468,1.7291251403081178,2.8797932657906435,1847.0,1021.3,752.8,229.7,251.1,630.9 -2.2290284197319363,1.7291289579471782,3.010692959690218,1660.9,750.4,691.5,172.2,538.6,1361.4 -2.2289711954443545,1.6288310497971812,0.0,1521.1,693.0,692.9,240.7,2129.0,2128.9 -2.2290019051960996,1.6293228340074948,0.1308996938995747,1601.6,691.6,750.9,232.6,2178.6,2238.5 -2.2289673196553275,1.6293115732200905,0.2617993877991494,1313.7,752.7,450.0,252.4,2412.4,2539.9 -2.2289303650887087,1.6292877003564241,0.39269908169872414,909.8,533.4,314.1,315.1,2341.1,2121.8 -2.22889998975871,1.6292561486286956,0.5235987755982988,740.6,392.3,264.6,470.5,1873.2,1745.4 -2.2288892857436324,1.6292324471306066,0.6544984694978736,669.6,313.6,254.5,1002.2,1639.0,1579.9 -2.228877225988575,1.629361656202915,0.7853981633974483,663.0,270.8,270.3,2099.0,1551.7,1551.1 -2.228878701522014,1.6291653643647377,0.916297857297023,712.4,254.4,313.2,2155.4,1579.6,1638.5 -2.228888895539024,1.6291335095472679,1.0471975511965976,472.3,264.9,392.1,2399.2,1673.2,1293.0 -2.2289134531587913,1.6290915600546492,1.1780972450961724,315.0,313.6,532.6,2290.5,1134.9,913.7 -2.2289080126021066,1.6290955677001595,1.3089969389957472,252.2,449.2,828.6,1825.2,881.1,753.5 -2.2289203653935425,1.629088883349123,1.4398966328953218,232.5,931.1,1759.5,1599.3,749.3,691.0 -2.228991956908195,1.629071590020005,1.5707963267948966,240.7,2128.9,2128.8,1521.3,693.2,693.0 -2.2289843099217577,1.6290702136170534,1.7016960206944713,275.0,2176.3,2235.4,1557.0,691.7,750.0 -2.228979899862741,1.629067578811929,1.832595714594046,345.0,2413.4,2541.2,1587.4,752.6,449.3 -2.2290350525352154,1.629102102920767,1.9634954084936205,475.6,2340.0,2120.9,1068.6,532.8,313.7 -2.229052316244227,1.629121415717525,2.0943951023931953,748.7,1870.9,1743.7,832.6,392.2,264.9 -2.2290429776657916,1.6291017004729313,2.2252947962927703,1605.0,1638.3,1580.0,712.1,313.2,254.4 -2.229048492651412,1.629124333320752,2.356194490192345,2099.7,1551.1,1551.8,662.4,270.2,270.8 -2.2290454670613467,1.6291546106893358,2.4870941840919194,2199.5,1580.2,1639.0,669.6,254.5,313.6 -2.2290489687562167,1.6291454041359472,2.6179938779914944,2493.5,1669.2,1289.9,740.3,264.6,392.3 -2.22903543993292,1.6291613168314534,2.748893571891069,2124.4,1131.7,911.7,474.9,315.0,535.0 -2.229043884757994,1.6291539055357704,2.8797932657906435,1731.6,880.2,752.8,345.2,450.5,830.3 -2.2290344313464074,1.629158561318319,3.010692959690218,1557.8,750.4,691.4,275.6,925.5,1748.4 -2.2289750581743872,1.528859010773415,0.0,1421.5,693.1,693.0,340.6,2129.0,2129.1 -2.229003198534312,1.5293296699437824,0.1308996938995747,1497.7,691.7,750.9,336.2,2179.0,2238.4 -2.228967307940483,1.5293179892313093,0.2617993877991494,1463.4,752.7,649.5,368.0,2412.2,2540.3 -2.2289294858034228,1.529293556831863,0.39269908169872414,909.9,674.6,455.3,456.9,2200.0,1980.2 -2.228898519887811,1.5292613559240114,0.5235987755982988,740.7,508.0,380.2,669.7,1757.6,1629.7 -2.228909741348812,1.529281584094345,0.6544984694978736,669.6,417.0,358.0,1387.6,1535.7,1476.4 -2.2288899290889157,1.5292006839441024,0.7853981633974483,663.1,370.8,370.2,2099.1,1451.6,1450.9 -2.2288914055860394,1.5291817155009808,0.916297857297023,712.4,357.9,416.7,2155.4,1476.5,1535.0 -2.228903613061861,1.5291433888396262,1.0471975511965976,672.0,380.4,507.7,2399.3,1628.2,1292.9 -2.2289276733179704,1.5291022284334734,1.1780972450961724,456.7,454.7,673.8,2148.5,1134.6,913.8 -2.2289199632455645,1.5291083550523932,1.3089969389957472,367.7,648.5,1027.6,1709.8,880.9,753.3 -2.2289291062547543,1.529103372771825,1.4398966328953218,336.0,1320.8,2149.4,1496.1,749.3,690.9 -2.2289971379187037,1.5290868840254384,1.5707963267948966,340.7,2128.9,2128.6,1421.3,693.4,693.0 -2.228986096847451,1.5290853817866015,1.7016960206944713,378.4,2176.6,2235.0,1453.9,691.6,750.0 -2.228978656465325,1.5290818131633754,1.832595714594046,460.7,2413.9,2541.0,1587.3,752.6,648.5 -2.229031285700871,1.5291147423647575,1.9634954084936205,617.3,2198.9,1979.6,1068.3,673.9,454.6 -2.229046685533962,1.529132041978008,2.0943951023931953,948.5,1755.6,1628.1,832.5,507.8,380.4 -2.2290591933023043,1.5291554029962224,2.2252947962927703,1992.5,1535.3,1476.3,712.0,416.6,357.9 -2.2290563963002272,1.5291417319088787,2.356194490192345,2099.4,1451.4,1451.7,662.5,370.3,370.8 -2.2290537801148975,1.5291619533089433,2.4870941840919194,2199.5,1476.3,1535.4,669.7,358.0,417.0 -2.229057717797609,1.5291513392105334,2.6179938779914944,2579.8,1630.3,1290.3,740.2,380.2,507.8 -2.229043547407203,1.5291682651046525,2.748893571891069,1983.1,1131.7,911.6,616.5,456.4,676.4 -2.229050588216731,1.5291621506822715,2.8797932657906435,1615.9,880.4,752.8,460.7,650.1,1030.0 -2.229039334370532,1.529167752002119,3.010692959690218,1453.9,750.2,691.5,379.2,1313.2,2135.9 -2.2289776926498237,1.4288664546283598,0.0,1321.3,692.9,692.9,440.6,2128.7,2128.9 -2.2290542165870777,1.428864017389774,0.1308996938995747,1394.7,691.5,751.0,439.7,2179.0,2238.4 -2.2290657449097306,1.428866524001867,0.2617993877991494,1347.9,752.8,880.3,483.4,2412.7,2539.8 -2.2291103628354807,1.4288934638426007,0.39269908169872414,909.8,815.5,596.4,598.3,2058.8,1839.0 -2.2291521161794097,1.4289390849546442,0.5235987755982988,740.6,623.5,495.7,868.8,1642.4,1514.3 -2.2291897540725336,1.4290053732525112,0.6544984694978736,669.7,520.6,461.5,1773.0,1431.9,1373.1 -2.2291999000746787,1.4290535928716666,0.7853981633974483,663.2,470.8,470.3,2098.8,1351.8,1351.3 -2.229198340788151,1.4291333913624875,0.916297857297023,712.6,461.4,520.2,2155.8,1372.6,1431.5 -2.229186005714393,1.4291760956018207,1.0471975511965976,832.5,495.9,623.3,2398.9,1512.9,1394.5 -2.229169855408798,1.4291995216239115,1.1780972450961724,598.5,595.9,815.0,2007.1,1134.8,914.1 -2.229112012809423,1.429252835952681,1.3089969389957472,483.5,847.8,1227.3,1594.4,881.2,845.2 -2.2290649634981543,1.4292780470512878,1.4398966328953218,439.5,1710.7,2177.2,1392.4,749.4,691.0 -2.2290747917048246,1.429275041886088,1.5707963267948966,440.9,2128.7,2128.5,1321.2,693.3,693.1 -2.229009400503051,1.4292718642462816,1.7016960206944713,482.0,2176.6,2235.1,1349.9,691.6,750.1 -2.228953695835085,1.4292537903916573,1.832595714594046,576.3,2413.9,2541.4,1501.2,752.4,880.2 -2.2289661457550096,1.429261649588415,1.9634954084936205,759.1,2057.2,1838.5,1068.5,815.1,596.0 -2.2289518327296673,1.4292471456698606,2.0943951023931953,1148.5,1640.0,1512.9,832.6,623.3,495.9 -2.228922465171538,1.4291900550202532,2.2252947962927703,2155.9,1431.8,1372.5,711.9,520.3,461.4 -2.228919007576879,1.429174084608999,2.356194490192345,2099.8,1351.1,1351.9,662.4,470.2,470.9 -2.2289172727650084,1.4291675610823567,2.4870941840919194,2199.5,1373.3,1432.2,669.6,461.6,520.7 -2.2289306047784936,1.4291260382490445,2.6179938779914944,2493.5,1514.2,1396.4,740.1,495.8,623.4 -2.2289337684737287,1.4291152457164633,2.748893571891069,1841.5,1131.7,911.6,757.9,597.7,818.0 -2.2289633250690146,1.4290880666727719,2.8797932657906435,1500.5,880.0,752.8,576.4,849.6,1229.3 -2.228977479767549,1.4290800803062171,3.010692959690218,1350.5,750.3,691.4,482.7,1699.5,2177.8 -2.2289466140148555,1.3288019008289087,0.0,1221.6,692.9,693.0,540.6,2128.7,2129.0 -2.2289949046068425,1.3293444224699242,0.1308996938995747,1290.6,691.7,750.8,543.3,2179.0,2238.1 -2.2289618595902967,1.3293336039998422,0.2617993877991494,1313.5,752.8,880.2,599.1,2497.1,2404.8 -2.2289231902152125,1.3293086091912518,0.39269908169872414,910.0,912.7,737.7,740.1,1917.5,1698.1 -2.228890770001104,1.329274810125949,0.5235987755982988,740.7,739.0,611.5,1068.1,1526.5,1398.7 -2.2288706341721802,1.3292341439950026,0.6544984694978736,669.6,624.1,565.1,2158.3,1328.4,1269.5 -2.228860385019584,1.3291950516774964,0.7853981633974483,663.1,570.8,570.2,2098.8,1251.8,1251.2 -2.2288615744761864,1.3291840838228133,0.916297857297023,712.3,564.9,623.6,2155.7,1269.3,1328.0 -2.22887459736364,1.3291430063732292,1.0471975511965976,832.4,611.5,738.9,2449.8,1397.2,1383.4 -2.228901796837724,1.3290967580354567,1.1780972450961724,740.1,737.1,956.0,1865.3,1134.6,913.8 -2.228898819705384,1.3290984051470414,1.3089969389957472,599.1,1047.1,1426.1,1478.4,881.0,753.3 -2.2289135988693127,1.3290903797840898,1.4398966328953218,542.9,2099.6,2177.4,1289.2,749.3,690.9 -2.2289875900990404,1.3290724691362579,1.5707963267948966,540.8,2129.0,2128.7,1221.5,693.3,693.1 -2.228982164210699,1.3290711048264239,1.7016960206944713,585.3,2176.5,2235.0,1246.9,691.6,750.1 -2.228979731133581,1.3290690188968886,1.832595714594046,691.8,2495.6,2403.0,1385.6,752.6,880.1 -2.2290365471335316,1.3291045196973257,1.9634954084936205,900.9,1916.4,1697.7,1068.4,912.8,737.1 -2.2290550594114182,1.32912509468788,2.0943951023931953,1347.8,1524.7,1397.2,832.6,738.7,611.4 -2.2290465190019675,1.3291068080702373,2.2252947962927703,2156.0,1328.1,1269.3,712.2,623.6,564.9 -2.2290523985626,1.3291309310262238,2.356194490192345,2099.9,1251.4,1251.7,662.4,570.2,570.8 -2.2290493356747394,1.329162629872834,2.4870941840919194,2199.5,1269.5,1328.3,669.6,565.0,624.1 -2.229052443988021,1.3291546778309595,2.6179938779914944,2425.2,1398.7,1385.6,740.3,611.5,739.2 -2.2290382591647937,1.329171611789571,2.748893571891069,1700.4,1131.9,911.6,911.7,739.3,959.3 -2.2290458616700186,1.3291649433979456,2.8797932657906435,1384.8,880.3,752.7,692.1,1049.0,1428.9 -2.229035476041353,1.3291700507588327,3.010692959690218,1247.3,750.4,691.6,586.2,2087.1,2177.9 -2.228974986365113,1.2288696669068035,0.0,1121.3,693.0,693.0,640.6,2128.9,2129.1 -2.2290033026660345,1.2293324432572739,0.1308996938995747,1187.2,691.7,750.9,646.9,2179.2,2238.4 -2.228967115048724,1.2293206640665701,0.2617993877991494,1313.8,752.7,880.2,714.6,2412.3,2205.2 -2.228928983006191,1.2292960312891863,0.39269908169872414,909.9,912.8,878.9,881.9,1776.1,1556.9 -2.228897769956328,1.2292635591635326,0.5235987755982988,740.7,854.8,727.0,1267.4,1410.9,1283.0 -2.2288865431212708,1.2292388625762176,0.6544984694978736,669.6,727.7,668.6,2199.3,1225.0,1165.8 -2.2288742494483205,1.2291911281842651,0.7853981633974483,663.1,670.8,670.3,2099.2,1151.8,1151.2 -2.22887545901809,1.2291796924574383,0.916297857297023,712.4,668.4,727.2,2155.5,1165.7,1224.6 -2.228887868700067,1.2291406413965942,1.0471975511965976,832.2,727.0,854.0,2399.2,1282.1,1292.9 -2.228913609797325,1.2290967643645585,1.1780972450961724,881.7,878.1,1097.5,1723.5,1134.8,913.9 -2.2289086011121237,1.2291003403992748,1.3089969389957472,714.8,1246.2,1625.6,1363.0,880.9,753.4 -2.228921016608398,1.229093594541307,1.4398966328953218,646.4,2236.3,2177.6,1185.7,749.3,690.9 -2.2289925272199373,1.2290762936667048,1.5707963267948966,640.8,2128.6,2129.1,1121.3,693.3,693.2 -2.228984764841926,1.2290748871385535,1.7016960206944713,688.8,2176.9,2235.1,1143.4,691.6,750.1 -2.2289802465000523,1.2290721925316168,1.832595714594046,807.4,2413.8,2203.5,1270.2,752.5,880.2 -2.2290353125395566,1.2291066370822228,1.9634954084936205,1042.6,1775.5,1556.4,1068.3,912.8,878.2 -2.229052516444292,1.2291258620734107,2.0943951023931953,1547.3,1408.9,1281.9,832.6,854.2,727.0 -2.229043143042364,1.2291060578281199,2.2252947962927703,2156.0,1224.6,1166.0,712.1,727.2,668.5 -2.2290486427112244,1.2291286049159051,2.356194490192345,2099.5,1151.0,1151.7,662.5,670.3,670.8 -2.2290456166372423,1.2291588029927163,2.4870941840919194,2199.2,1166.1,1225.0,669.6,668.7,727.7 -2.229049130880507,1.2291495237273389,2.6179938779914944,2225.1,1283.2,1290.1,740.2,727.1,854.6 -2.2290356242877514,1.2291653704681398,2.748893571891069,1558.8,1131.6,911.6,911.7,880.4,1100.6 -2.2290441020215,1.2291579002424187,2.8797932657906435,1269.4,880.2,752.8,807.4,1248.6,1628.3 -2.2290346912563774,1.2291625057295081,3.010692959690218,1143.3,750.4,691.6,689.7,2236.5,2177.9 -2.228975384957117,1.128863001517404,0.0,1021.4,692.9,693.0,740.5,2128.8,2129.2 -2.229003446687025,1.129331775953782,0.1308996938995747,1083.6,691.7,751.1,750.6,2179.2,2238.2 -2.2289673000269032,1.1293200118729743,0.2617993877991494,1246.7,752.8,880.2,830.2,2385.9,2005.9 -2.2289292338625817,1.129295422507754,0.39269908169872414,910.0,912.9,1020.0,1023.5,1634.9,1415.6 -2.2288980776257494,1.1292630138512583,0.5235987755982988,740.6,970.4,842.7,1466.6,1295.2,1167.5 -2.228886888334323,1.1292383902917575,0.6544984694978736,669.6,831.5,772.2,2199.9,1121.4,1062.3 -2.2288746111632536,1.12919073195992,0.7853981633974483,663.0,770.8,770.3,2099.1,1051.8,1051.2 -2.2288758179304975,1.129179368271854,0.916297857297023,712.3,771.9,830.8,2155.3,1062.3,1121.3 -2.228888207977035,1.1291403816229193,1.0471975511965976,832.3,842.5,969.8,2306.5,1166.2,1293.0 -2.228913916299647,1.1290965575426974,1.1780972450961724,1054.7,1019.1,1238.3,1581.6,1243.1,913.8 -2.228908866626378,1.1291001732978956,1.3089969389957472,830.2,1445.4,1825.1,1247.6,881.1,753.4 -2.228921235924753,1.1290934539115067,1.4398966328953218,749.7,2235.6,2177.2,1082.2,749.3,691.0 -2.228992698195578,1.1290761656482045,1.5707963267948966,740.6,2129.1,2128.9,1021.3,693.2,693.0 -2.228984890152916,1.1290747594805164,1.7016960206944713,792.3,2177.1,2234.8,1039.8,691.6,750.0 -2.2289803305084313,1.1290720547115942,1.832595714594046,923.1,2383.8,2004.8,1154.5,752.6,880.2 -2.229035361477554,1.1291064795718495,1.9634954084936205,1184.3,1634.1,1415.4,1089.1,913.0,1019.2 -2.2290525388406404,1.1291256784667096,2.0943951023931953,1747.3,1293.5,1166.2,832.6,970.0,842.5 -2.229043147892357,1.1291058448371216,2.2252947962927703,2155.8,1121.1,1062.3,712.0,830.9,771.9 -2.229048639141751,1.129128360868589,2.356194490192345,2099.4,1051.2,1051.6,662.4,770.2,770.9 -2.2290456136030334,1.1291585287558368,2.4870941840919194,2199.3,1062.6,1121.4,669.7,772.2,831.3 -2.2290491356452313,1.1291492230017748,2.6179938779914944,2026.2,1167.6,1289.9,740.2,842.7,970.4 -2.2290356432871636,1.1291650478832331,2.748893571891069,1417.5,1245.1,911.6,911.7,1022.2,1242.1 -2.229044138910914,1.1291575620247836,2.8797932657906435,1153.6,880.3,752.8,923.0,1448.1,1827.8 -2.229034748110017,1.1291621582586933,3.010692959690218,1039.9,750.4,691.5,793.2,2236.6,2177.8 -2.1290281150717925,1.8292545925963617,0.0,1721.2,793.1,793.0,40.8,2029.0,2029.0 -2.128999510331458,1.828539841434495,0.1308996938995747,1808.6,795.3,149.2,25.6,2075.6,2135.0 -2.1290480510302037,1.8285556583822336,0.2617993877991494,1513.0,431.0,51.4,21.4,2296.9,2424.9 -2.129100858723943,1.8285897611112065,0.39269908169872414,1051.4,251.2,31.9,32.1,2622.5,2403.4 -2.1291426376151996,1.8286374522756057,0.5235987755982988,856.3,161.3,33.6,72.4,2104.1,1976.6 -2.129178757406958,1.8287029834300743,0.6544984694978736,773.3,106.7,47.6,231.9,1846.2,1786.9 -2.129187891155943,1.828749056309132,0.7853981633974483,763.3,71.1,70.5,1998.9,1751.5,1751.0 -2.1291864181324454,1.8288263514965186,0.916297857297023,233.2,47.7,106.5,2052.0,1786.6,1845.7 -2.1291752988080166,1.8288668387482945,1.0471975511965976,73.7,34.2,161.5,2283.1,1873.1,1493.0 -2.1291612108833955,1.8288888318161813,1.1780972450961724,32.1,31.9,250.9,2573.2,1276.4,1108.9 -2.1291058058331296,1.8289417587524701,1.3089969389957472,21.4,51.4,430.6,2056.3,996.6,869.0 -2.1290611218339204,1.8289676228969802,1.4398966328953218,26.0,153.2,981.8,1806.1,852.8,794.5 -2.1290728294090626,1.8289661168559155,1.5707963267948966,41.1,2029.0,2028.6,1720.8,793.2,793.2 -2.1290085375285352,1.8289649160541606,1.7016960206944713,68.4,2073.5,2132.0,1763.7,795.0,153.2 -2.1289531139255913,1.8289488803441352,1.832595714594046,114.2,2298.1,2426.1,1786.4,430.6,51.4 -2.128965167705946,1.8289584556521779,1.9634954084936205,192.8,2622.0,2402.3,1209.5,251.0,31.9 -2.1289500850674736,1.8289451078795211,2.0943951023931953,350.2,2101.8,1974.7,948.1,161.5,34.2 -2.1289199333909696,1.8288885710182554,2.2252947962927703,831.8,1845.1,1786.8,815.4,106.5,47.7 -2.1289159967442712,1.8288726694418955,2.356194490192345,1999.7,1750.8,1751.2,762.4,70.6,71.1 -2.128914286916005,1.8288660098274714,2.4870941840919194,2096.0,1786.8,1845.7,773.1,47.7,106.8 -2.1289281551403962,1.8288244840497137,2.6179938779914944,2377.9,1868.3,1489.2,348.2,33.7,161.4 -2.1289322158313984,1.828814092876532,2.748893571891069,2406.7,1273.1,1053.1,192.5,32.5,252.5 -2.128962736949951,1.828787876397414,2.8797932657906435,1962.2,995.9,868.4,114.4,52.1,431.9 -2.128977603423634,1.8287813898257044,3.010692959690218,1764.2,853.9,795.0,68.9,152.4,975.2 -2.1289466619841577,1.7285033874234284,0.0,1621.3,792.9,793.1,140.9,2029.3,2029.2 -2.128993689603528,1.7292629724686863,0.1308996938995747,1705.4,795.2,532.8,129.1,2075.5,2134.5 -2.128969334989121,1.7292550252843482,0.2617993877991494,1513.2,630.3,250.6,136.8,2297.4,2424.6 -2.1289396783158234,1.7292358712044984,0.39269908169872414,1051.0,392.2,172.9,173.6,2482.5,2262.8 -2.128914425645908,1.7292099630508582,0.5235987755982988,856.2,276.7,149.0,271.3,1989.1,1861.1 -2.128906904417486,1.7291923356159835,0.6544984694978736,773.1,210.1,151.0,616.6,1742.5,1684.1 -2.1288962575251986,1.7291518222563118,0.7853981633974483,763.2,170.9,170.3,1998.7,1651.8,1651.2 -2.128897277203922,1.7291471893955912,0.916297857297023,619.5,150.9,209.7,2052.2,1683.3,1742.2 -2.128907908745267,1.729114231827193,1.0471975511965976,272.8,149.4,276.6,2283.5,1859.4,1492.5 -2.128930623594047,1.7290753976452526,1.1780972450961724,173.4,172.5,391.6,2432.0,1276.5,1055.7 -2.128921784325451,1.7290827724678974,1.3089969389957472,136.7,250.0,629.2,1941.1,1064.0,869.1 -2.128929849363236,1.729078564688665,1.4398966328953218,129.1,541.4,1369.8,1703.2,852.8,794.4 -2.1289967868374067,1.729062498694702,1.5707963267948966,140.8,2029.0,2028.8,1621.1,793.4,793.0 -2.1289846907413765,1.7290611396662685,1.7016960206944713,171.5,2072.9,2131.3,1660.6,795.0,541.5 -2.1289762553543574,1.7290574609454654,1.832595714594046,229.5,2297.7,2426.0,1786.6,629.2,249.9 -2.1290280055540465,1.7290900129709408,1.9634954084936205,333.9,2481.3,2262.3,1209.5,391.6,172.6 -2.1290427201078734,1.7291067363689534,2.0943951023931953,549.3,1986.6,1859.4,1087.5,276.7,149.4 -2.1290317392964684,1.7290841133006336,2.2252947962927703,1217.9,1742.1,1683.1,815.6,209.7,150.9 -2.129036512833217,1.7291037028918397,2.356194490192345,1999.4,1651.4,1651.8,762.5,170.3,170.8 -2.1290336063857827,1.729131058781227,2.4870941840919194,2096.0,1683.4,1742.6,773.2,150.9,210.0 -2.129037931601572,1.7291193061744117,2.6179938779914944,2377.8,1861.4,1489.5,546.9,149.0,276.7 -2.129025809513801,1.72913314480512,2.748893571891069,2266.3,1273.2,1053.0,333.6,173.6,393.6 -2.129036001422354,1.7291242584274915,2.8797932657906435,1847.2,995.8,868.4,229.7,251.1,630.8 -2.129028470265976,1.7291280447243278,3.010692959690218,1660.9,853.7,795.0,172.2,538.5,1361.3 -2.12897132436723,1.628830196336692,0.0,1521.4,792.9,793.0,240.7,2029.3,2029.3 -2.1290019998363103,1.6293251083525537,0.1308996938995747,1601.5,795.3,854.5,232.6,2075.6,2134.6 -2.128967137714643,1.6293137576279668,0.2617993877991494,1553.8,868.2,450.0,252.3,2296.9,2424.5 -2.1289299139368683,1.62928971128427,0.39269908169872414,1051.2,533.3,314.0,315.1,2340.7,2121.5 -2.12889932789908,1.6292579286323932,0.5235987755982988,856.2,392.3,264.6,470.4,1873.4,1745.4 -2.1288884882065604,1.6292339691793793,0.6544984694978736,773.3,313.6,254.4,1002.1,1639.4,1580.0 -2.1288763670164648,1.6291869862332107,0.7853981633974483,763.0,270.8,270.3,1998.6,1551.9,1551.1 -2.1288775577717045,1.6291762578638527,0.916297857297023,816.0,254.4,313.1,2052.0,1579.6,1638.5 -2.128889783563081,1.629137840556856,1.0471975511965976,472.3,264.9,392.2,2284.0,1744.0,1625.7 -2.12891521103419,1.6290944887061687,1.1780972450961724,315.0,313.7,532.7,2290.3,1276.6,1055.7 -2.128909804606333,1.6290984605114442,1.3089969389957472,252.3,449.1,828.6,1825.7,996.5,869.0 -2.128921767869015,1.629091979022659,1.4398966328953218,232.5,931.0,1759.7,1599.6,852.8,794.6 -2.128992802823343,1.6290748074830392,1.5707963267948966,240.8,2029.0,2028.6,1521.4,793.2,792.9 -2.1289845894415387,1.629073406279878,1.7016960206944713,275.0,2073.6,2131.7,1557.4,795.0,853.5 -2.128979663504826,1.6290706089097098,1.832595714594046,345.0,2298.0,2425.8,1732.6,868.0,449.2 -2.129034384556333,1.6291048562853878,1.9634954084936205,475.7,2339.7,2120.6,1209.4,532.6,313.6 -2.129056850197154,1.6291277192441544,2.0943951023931953,748.9,1871.1,1743.7,948.1,392.2,264.9 -2.1290451941714856,1.6291036987024536,2.2252947962927703,1605.2,1638.5,1579.7,815.6,313.1,254.4 -2.129050452275123,1.629125201859386,2.356194490192345,1999.7,1551.3,1551.8,762.5,270.3,270.8 -2.1290474291890056,1.6291554853297594,2.4870941840919194,2095.8,1580.2,1639.3,773.2,254.5,313.5 -2.129050828733831,1.6291466109023185,2.6179938779914944,2378.0,1745.7,1627.6,746.0,264.6,392.2 -2.1290370657230033,1.6291628932006257,2.748893571891069,2124.6,1273.1,1053.1,474.9,314.9,534.9 -2.1290451885966397,1.6291557780528008,2.8797932657906435,1731.2,995.8,868.3,345.2,450.6,830.5 -2.1290353659273253,1.6291606262887302,3.010692959690218,1557.4,853.8,795.0,275.7,925.6,1748.7 -2.128975545248375,1.5288607385206643,0.0,1421.5,792.9,793.1,340.7,2029.2,2029.4 -2.128992902379039,1.5288593103309012,0.1308996938995747,1498.2,795.1,854.6,336.0,2075.8,2135.0 -2.129044402348417,1.5288741093946603,0.2617993877991494,1568.2,868.3,649.1,367.7,2297.0,2516.7 -2.1290969377801443,1.5289060547156406,0.39269908169872414,1051.2,674.5,455.1,456.6,2200.0,1980.8 -2.1291381220561054,1.5289511049192472,0.5235987755982988,963.1,507.8,380.2,669.3,1758.0,1630.0 -2.1291739741550284,1.5290140896718376,0.6544984694978736,773.3,417.1,357.9,1387.5,1535.7,1476.7 -2.1291830858187772,1.5290579044063042,0.7853981633974483,763.2,370.8,370.2,1999.0,1451.8,1451.2 -2.129181664502894,1.529133224337855,0.916297857297023,815.9,357.9,416.7,2052.0,1476.2,1535.2 -2.129170577655871,1.529171825991519,1.0471975511965976,672.1,380.5,507.8,2283.4,1628.3,1510.1 -2.1291565541667006,1.5291918516339176,1.1780972450961724,456.8,454.8,673.9,2149.0,1276.8,1055.6 -2.1291013992053887,1.5292426531354975,1.3089969389957472,367.9,648.5,1027.7,1709.7,996.8,1010.2 -2.12905737390275,1.5292662568699569,1.4398966328953218,336.1,1321.1,2073.9,1496.1,853.0,794.4 -2.129070334572623,1.5292625406761067,1.5707963267948966,340.8,2029.1,2029.0,1421.2,793.2,792.9 -2.1290078649281274,1.5292594682194354,1.7016960206944713,378.5,2072.9,2131.8,1453.4,795.0,853.5 -2.1289547495101506,1.529242188761944,1.832595714594046,460.7,2297.6,2514.8,1616.7,868.1,648.5 -2.128969350782699,1.5292514045793493,1.9634954084936205,617.4,2199.0,1979.7,1209.3,673.8,454.7 -2.1289566259143777,1.5292386132265927,2.0943951023931953,948.6,1755.3,1628.2,948.2,507.8,380.5 -2.128928263674392,1.5291834115365694,2.2252947962927703,1992.5,1534.9,1476.1,815.6,416.7,357.9 -2.128925256344004,1.5291693887558029,2.356194490192345,1999.6,1451.1,1451.7,762.4,370.3,370.8 -2.128923458714782,1.5291647202426744,2.4870941840919194,2095.7,1476.7,1535.4,773.1,358.0,417.1 -2.128936299573087,1.5291248284203274,2.6179938779914944,2536.6,1629.9,1511.8,855.8,380.2,508.0 -2.1289386296642805,1.5291153865197606,2.748893571891069,1983.2,1273.1,1053.0,616.4,456.3,676.5 -2.128967128554784,1.5290892128156481,2.8797932657906435,1615.6,995.9,1009.3,460.7,650.1,1029.8 -2.12898009744073,1.5290818760825888,3.010692959690218,1454.0,854.1,795.0,379.1,1312.7,2074.2 -2.128947790899579,1.4288026199292698,0.0,1321.3,793.0,793.0,440.6,2029.2,2028.9 -2.128995211304516,1.4293428313661454,0.1308996938995747,1394.2,795.2,854.5,439.7,2075.4,2134.9 -2.128962135334173,1.4293320061013683,0.2617993877991494,1512.9,868.3,848.9,483.5,2296.8,2424.4 -2.1288824410365828,1.4292850562657393,0.39269908169872414,1050.9,815.7,596.5,598.4,2058.4,1839.1 -2.128871540610162,1.4292743716634875,0.5235987755982988,856.2,623.5,495.8,868.8,1641.9,1514.1 -2.1288624800907,1.4292537764966884,0.6544984694978736,773.2,520.6,461.5,1772.9,1432.1,1372.8 -2.1288494521505275,1.429202907552595,0.7853981633974483,763.2,470.8,470.3,1999.1,1351.9,1351.3 -2.128850831677281,1.4291861501384129,0.916297857297023,815.7,461.3,520.2,2052.1,1372.6,1431.3 -2.128864911488754,1.4291415962574603,1.0471975511965976,871.6,496.0,623.2,2283.6,1512.9,1492.9 -2.128893595933968,1.4290929682767042,1.1780972450961724,598.5,595.9,815.0,2007.1,1276.4,1055.8 -2.1288923602109744,1.4290929802106669,1.3089969389957472,483.4,847.7,1227.0,1594.1,996.7,868.9 -2.1289090463009828,1.4290839334539813,1.4398966328953218,439.4,1710.1,2073.9,1392.8,852.6,794.4 -2.1289849956521505,1.429065573299171,1.5707963267948966,440.7,2029.2,2029.1,1321.2,793.3,793.0 -2.1289813919540577,1.429064269022652,1.7016960206944713,481.8,2073.3,2131.4,1350.1,795.0,853.3 -2.1289840367638666,1.4290626583934496,1.832595714594046,576.2,2298.2,2425.6,1501.3,868.2,847.7 -2.1290403582015642,1.4290978577599738,1.9634954084936205,759.1,2057.8,1838.9,1209.3,814.9,595.9 -2.129059631318579,1.4291192461620157,2.0943951023931953,1148.2,1640.2,1512.8,948.2,623.3,495.9 -2.129051823730435,1.4291023308014905,2.2252947962927703,2052.7,1431.6,1373.0,815.7,520.1,461.4 -2.129058072946233,1.4291280479434316,2.356194490192345,1999.5,1351.3,1351.8,762.5,470.2,470.8 -2.1290549545464605,1.4291613249700839,2.4870941840919194,2095.9,1373.1,1431.9,773.2,461.6,520.6 -2.1290576372658223,1.4291547765731893,2.6179938779914944,2378.0,1514.5,1489.4,855.7,495.7,623.4 -2.1290427258987297,1.4291728768695942,2.748893571891069,1842.1,1273.2,1053.3,757.7,597.7,817.7 -2.129049408204359,1.4291670746351475,2.8797932657906435,1500.4,995.7,868.5,576.4,849.6,1229.3 -2.1290379920914275,1.4291727384321669,3.010692959690218,1350.2,853.9,795.0,482.7,1700.0,2074.0 -2.1289762565215216,1.3288714213841704,0.0,1221.3,792.9,793.0,540.6,2028.7,2029.1 -2.128992277369138,1.3288699027659985,0.1308996938995747,1291.2,795.3,854.4,543.1,2074.9,2134.3 -2.1290427941477303,1.3288843524959604,0.2617993877991494,1477.7,868.3,995.9,599.0,2296.8,2405.5 -2.1290945961002805,1.3289157880734543,0.39269908169872414,1051.3,956.9,737.4,739.8,1917.5,1698.1 -2.1291352584870893,1.3289602257458193,0.5235987755982988,856.4,739.1,611.5,1067.8,1526.5,1398.5 -2.129170800532347,1.3290225632658919,0.6544984694978736,773.2,624.1,565.0,2095.9,1328.5,1269.5 -2.129179774521237,1.32906571746441,0.7853981633974483,763.2,570.9,570.2,1998.7,1251.7,1251.2 -2.1291783841470027,1.3291404280877712,0.916297857297023,816.0,564.9,623.7,2052.3,1269.4,1328.4 -2.129181446482392,1.3291330742841359,1.0471975511965976,947.9,611.5,738.7,2449.7,1397.2,1492.8 -2.129150458092142,1.3291801788172186,1.1780972450961724,740.4,737.0,956.2,1865.4,1276.9,1055.8 -2.1290903004414474,1.3292355938063576,1.3089969389957472,599.1,1047.0,1426.2,1478.5,996.9,869.1 -2.1290472350924063,1.3292586379831317,1.4398966328953218,542.9,2100.1,2074.0,1289.1,853.0,794.4 -2.129063571245624,1.3292540884814712,1.5707963267948966,540.9,2028.9,2028.8,1221.2,793.2,793.0 -2.1290050199103714,1.3292510933683532,1.7016960206944713,585.3,2073.2,2131.6,1246.6,795.1,853.6 -2.1289556345610725,1.329234902691648,1.832595714594046,692.0,2297.8,2403.2,1385.9,868.2,995.9 -2.128973426903549,1.3292460632394536,1.9634954084936205,900.8,1916.2,1697.3,1209.4,956.3,737.2 -2.1289630947336695,1.3292357748087746,2.0943951023931953,1347.7,1524.5,1397.3,948.2,738.9,611.5 -2.128936258507796,1.3291833743649635,2.2252947962927703,2052.4,1328.2,1269.1,815.5,623.7,565.0 -2.1289339410491346,1.3291722588555004,2.356194490192345,1999.7,1251.3,1251.9,762.5,570.4,570.9 -2.1289320571546653,1.3291703627953058,2.4870941840919194,2096.2,1269.4,1328.7,773.1,565.1,624.2 -2.1289613613974825,1.329077508196851,2.6179938779914944,2378.4,1398.5,1489.0,855.9,611.3,739.2 -2.128941411925753,1.329103846245457,2.748893571891069,1700.2,1273.0,1053.1,899.2,739.2,959.2 -2.128994997196923,1.329055744485514,2.8797932657906435,1384.9,995.7,868.4,692.0,1049.0,1428.8 -2.1289798804357947,1.3290632908010642,3.010692959690218,1246.8,853.8,795.0,586.1,2086.3,2074.5 -2.128944056922855,1.2287956228125736,0.0,1121.3,793.0,792.9,640.6,2029.3,2029.2 -2.1289944386970663,1.2293488238663186,0.1308996938995747,1187.4,795.2,854.6,646.9,2075.5,2134.7 -2.128961154352996,1.2293379242590248,0.2617993877991494,1362.2,868.3,995.8,714.8,2296.7,2205.6 -2.1289220305971295,1.2293126347091854,0.39269908169872414,1051.1,1054.5,879.0,881.8,1776.1,1556.8 -2.1288892067419747,1.2292783914558938,0.5235987755982988,856.0,854.9,727.1,1267.2,1410.7,1283.0 -2.1288767821645553,1.2292513979732824,0.6544984694978736,773.1,727.9,668.7,2095.8,1225.0,1165.9 -2.1288639175663593,1.2292011564858938,0.7853981633974483,763.0,670.8,670.1,1998.8,1151.8,1151.2 -2.1288652140638034,1.2291873241571267,0.916297857297023,815.9,668.4,727.2,2052.1,1165.9,1224.6 -2.1288782780166304,1.2291461193706499,1.0471975511965976,947.9,726.9,854.4,2283.9,1281.6,1409.0 -2.1289051112990616,1.2291004500909257,1.1780972450961724,882.0,878.0,1097.2,1723.0,1384.2,1055.5 -2.1289014859584117,1.229102695810032,1.3089969389957472,714.7,1246.3,1625.5,1337.7,996.6,868.9 -2.1289154632015355,1.2290950889604844,1.4398966328953218,646.4,2132.6,2073.8,1185.7,852.9,794.5 -2.1289885994599427,1.2290773631026526,1.5707963267948966,640.8,2028.9,2028.8,1121.2,793.2,792.9 -2.1289823707341826,1.2290759606464796,1.7016960206944713,688.8,2096.1,2131.7,1143.1,795.1,853.6 -2.128979226687308,1.22907364756117,1.832595714594046,807.5,2298.1,2203.9,1270.3,868.2,995.8 -2.1290354546033607,1.2291087673089338,1.9634954084936205,1042.6,1775.6,1556.4,1230.5,1054.5,878.1 -2.129053535406113,1.2291288657333022,2.0943951023931953,1547.4,1409.2,1281.9,948.2,854.2,727.0 -2.1290447235429077,1.229110057623529,2.2252947962927703,2052.7,1224.6,1166.0,815.6,727.0,668.4 -2.1290504829090877,1.2291336455258286,2.356194490192345,1999.7,1151.1,1151.8,762.4,670.3,670.8 -2.129047438758084,1.2291648358050313,2.4870941840919194,2095.6,1165.8,1224.9,773.2,668.7,727.8 -2.129050680221751,1.2291564368512935,2.6179938779914944,2226.0,1282.9,1411.0,855.9,727.0,854.7 -2.129036721220817,1.2291729989509437,2.748893571891069,1558.9,1386.3,1053.0,1053.0,880.7,1100.6 -2.12904460969318,1.2291660511398357,2.8797932657906435,1269.2,996.0,868.4,807.5,1248.5,1628.2 -2.129034546013083,1.2291709740356067,3.010692959690218,1143.4,853.7,795.1,689.9,2133.3,2074.5 -2.128974450877364,1.1288708853856493,0.0,1021.4,793.2,793.0,740.7,2029.0,2028.6 -2.1289916346857183,1.128869379114221,0.1308996938995747,1084.1,795.2,854.6,750.4,2075.5,2134.7 -2.12904302491387,1.1288840773356266,0.2617993877991494,1246.9,868.3,995.8,830.1,2296.6,2006.4 -2.1290954998098863,1.1289159151859884,0.39269908169872414,1051.3,1054.5,1020.0,1023.1,1635.0,1415.8 -2.12913665475033,1.1289608619628817,0.5235987755982988,856.4,970.3,842.5,1466.6,1295.2,1167.5 -2.1291725106701795,1.1290237638447165,0.6544984694978736,773.2,831.3,772.1,2096.2,1121.7,1062.6 -2.129181626989009,1.1290675048004595,0.7853981633974483,763.2,770.9,770.3,1998.6,1051.9,1051.1 -2.1291802210488,1.1291427719605116,0.916297857297023,815.9,772.0,830.8,2052.1,1062.3,1121.0 -2.1291691446184045,1.1291813278264593,1.0471975511965976,948.1,842.5,970.0,2262.6,1166.0,1293.1 -2.1291551229441907,1.1292012963399802,1.1780972450961724,1023.7,1019.3,1238.4,1582.0,1276.6,1055.7 -2.12909997632103,1.1292520429865338,1.3089969389957472,830.2,1445.6,1824.9,1247.3,996.8,869.1 -2.1290559688632036,1.1292755951760285,1.4398966328953218,749.9,2132.3,2074.0,1082.1,852.9,794.5 -2.129068959965135,1.1292718068871919,1.5707963267948966,740.8,2029.1,2028.6,1021.3,793.6,793.0 -2.129006539487468,1.1292686753486756,1.7016960206944713,792.6,2073.0,2132.0,1039.6,795.2,853.5 -2.1289534865771436,1.1292513642877517,1.832595714594046,923.0,2297.8,2004.7,1154.4,868.0,995.7 -2.128968162605071,1.1292605609926998,1.9634954084936205,1184.2,1634.3,1415.3,1248.5,1054.6,1019.4 -2.1289555134964417,1.129247772226484,2.0943951023931953,1747.4,1293.6,1166.1,948.0,970.0,842.6 -2.1289272066040117,1.1291926083629447,2.2252947962927703,2052.4,1121.1,1062.2,815.4,830.6,772.0 -2.128924231346986,1.1291786406223148,2.356194490192345,1999.5,1051.3,1051.8,762.4,770.3,770.9 -2.1289224437902603,1.1291740263651606,2.4870941840919194,2095.8,1062.5,1121.2,773.1,772.1,831.1 -2.1289352552312786,1.1291341877357974,2.6179938779914944,2026.0,1167.3,1295.1,855.8,842.6,970.4 -2.128937546693065,1.1291247736136503,2.748893571891069,1417.6,1273.1,1053.0,1052.9,1022.2,1242.2 -2.1289659851915883,1.1290986053165122,2.8797932657906435,1153.7,995.9,868.4,923.1,1447.8,1827.4 -2.128978897112761,1.1290912459731752,3.010692959690218,1039.9,853.7,795.0,793.2,2133.3,2074.6 -2.0289724819203254,1.8292506991727047,0.0,1721.3,893.0,893.0,40.8,1929.0,1928.8 -2.0289781400175513,1.8285540980958699,0.1308996938995747,1808.5,898.9,149.1,25.6,1971.9,2031.2 -2.0290347162508473,1.8285723694640241,0.2617993877991494,1810.1,431.1,51.4,21.4,2181.3,2309.0 -2.029087699794803,1.8286065393529654,0.39269908169872414,1192.3,251.3,31.9,32.1,2623.2,2403.7 -2.0291279668289137,1.8286525377527938,0.5235987755982988,972.0,161.3,33.6,72.4,2104.3,1976.4 -2.0291627719492427,1.828715521912306,0.6544984694978736,876.8,106.7,47.6,231.9,1846.1,1787.0 -2.029171290173463,1.8287587329634423,0.7853981633974483,863.3,71.1,70.5,1898.9,1751.4,1750.9 -2.0291699366401117,1.8288332508062373,0.916297857297023,233.1,47.7,106.5,1948.6,1786.4,1845.4 -2.0291596002641996,1.82887124013211,1.0471975511965976,73.7,34.2,161.5,2167.5,1974.7,1856.4 -2.0291468144259373,1.8288911888729662,1.1780972450961724,32.1,31.8,250.9,2573.3,1418.5,1197.2 -2.029093027801754,1.8289425944711182,1.3089969389957472,21.4,51.4,430.6,2056.3,1253.5,984.7 -2.029050156122245,1.8289674584249893,1.4398966328953218,26.0,153.1,981.8,1806.2,956.3,897.6 -2.0290637474486166,1.8289655012790362,1.5707963267948966,41.1,1928.8,1928.6,1720.8,893.2,893.0 -2.029001221541983,1.8289643206919657,1.7016960206944713,68.4,1969.9,2028.1,1763.6,898.6,153.1 -2.0289473850055812,1.8289487004780751,1.832595714594046,114.3,2182.4,2310.1,1963.4,430.6,51.4 -2.028960778339668,1.8289590516831884,1.9634954084936205,192.8,2622.0,2402.5,1350.4,250.9,31.9 -2.028946705824155,1.8289467169742344,2.0943951023931953,350.3,2102.1,1974.9,1063.6,161.5,34.2 -2.0289172265986117,1.82889130694959,2.2252947962927703,832.1,1845.1,1786.3,918.9,106.5,47.7 -2.028913621415046,1.8288765929284903,2.356194490192345,1899.6,1751.1,1751.7,862.4,70.5,71.1 -2.028911906556585,1.828871092638075,2.4870941840919194,1992.7,1786.6,1846.1,876.5,47.7,106.8 -2.0289255016390904,1.8288305897079637,2.6179938779914944,2262.3,1976.6,1688.3,348.1,33.7,161.4 -2.0289290390139296,1.8288210577641,2.748893571891069,2407.4,1414.3,1194.7,192.5,32.5,252.5 -2.0289588953220417,1.8287954710454377,2.8797932657906435,1962.3,1111.6,984.0,114.4,52.1,431.9 -2.0289730061609568,1.828789377463879,3.010692959690218,1764.0,957.3,898.4,68.9,152.5,975.3 -2.0289411635734367,1.7285106803313017,0.0,1621.2,892.9,892.9,140.9,1928.9,1929.2 -2.0289891449007995,1.729263843158677,0.1308996938995747,1705.1,898.9,532.8,129.1,1971.7,2031.2 -2.028964873516823,1.7292559115765695,0.2617993877991494,1799.5,630.3,250.6,136.8,2181.3,2309.0 -2.028935168502507,1.729236707377851,0.39269908169872414,1192.5,392.2,172.9,173.5,2482.1,2263.0 -2.0289098649021726,1.7292107080279067,0.5235987755982988,971.8,276.7,149.0,271.3,1988.8,1861.1 -2.0289023050711297,1.7291929639231873,0.6544984694978736,876.6,210.0,150.9,616.6,1742.5,1683.4 -2.0288916686920175,1.7291523448535853,0.7853981633974483,863.1,170.8,170.3,1898.8,1651.5,1651.3 -2.0288927135665826,1.7291476091516977,0.916297857297023,619.3,150.9,209.7,1949.0,1683.2,1742.0 -2.028903393217345,1.7291145673242776,1.0471975511965976,272.7,149.4,276.7,2168.1,1859.5,1741.3 -2.0289261758020984,1.729075687540319,1.1780972450961724,173.3,172.5,391.6,2432.1,1418.3,1197.1 -2.028917398569325,1.7290830258912702,1.3089969389957472,136.7,250.0,629.2,1941.1,1112.0,984.8 -2.0289255221166926,1.7290787826990826,1.4398966328953218,129.1,541.4,1369.9,1703.2,956.2,897.8 -2.02899251861998,1.7290627217131498,1.5707963267948966,140.8,1929.0,1928.8,1621.3,893.3,893.0 -2.0289804731319934,1.729061364946276,1.7016960206944713,171.5,1969.7,2028.1,1660.7,898.5,541.4 -2.0289720891586827,1.7290576751476754,1.832595714594046,229.5,2182.6,2310.3,1848.5,629.1,250.0 -2.0290238856018723,1.729090240194396,1.9634954084936205,334.1,2480.7,2261.7,1350.4,391.6,172.5 -2.0290386391029895,1.7291069913035209,2.0943951023931953,549.2,1986.8,1859.5,1063.5,276.7,149.4 -2.029027703874435,1.7290843868234211,2.2252947962927703,1218.2,1742.1,1683.3,919.1,209.7,150.9 -2.0290325163459295,1.7291040064419412,2.356194490192345,1899.7,1651.3,1651.7,862.4,170.3,170.8 -2.029029626453975,1.7291314113589946,2.4870941840919194,1992.4,1683.7,1742.5,876.7,151.0,210.0 -2.0290339711341008,1.7291197009702461,2.6179938779914944,2262.6,1861.6,1717.7,546.9,149.0,276.7 -2.029021831150641,1.7291335920526214,2.748893571891069,2265.8,1414.5,1194.4,333.5,173.6,393.5 -2.0290320068417422,1.7291247445046305,2.8797932657906435,1846.9,1111.3,983.9,229.7,251.1,630.9 -2.029024444529417,1.729128558192846,3.010692959690218,1660.9,957.4,898.5,172.1,538.7,1361.5 -2.028967269459654,1.6288306677990545,0.0,1521.2,892.9,892.9,240.7,1929.1,1929.2 -2.028997959254802,1.6293260957979392,0.1308996938995747,1601.5,898.7,958.0,232.6,1971.9,2031.4 -2.0289629877184185,1.629314701068449,0.2617993877991494,1712.2,829.6,450.0,252.3,2181.5,2309.0 -2.0289256628534686,1.6292905716987474,0.39269908169872414,1192.3,533.4,314.1,315.2,2341.3,2121.5 -2.02889501352919,1.6292586856447357,0.5235987755982988,971.9,392.3,264.6,470.4,1873.0,1745.4 -2.028884133403284,1.6292346077151225,0.6544984694978736,876.7,313.6,254.5,1002.2,1639.2,1580.2 -2.0288720216518565,1.6291875206391269,0.7853981633974483,863.1,270.8,270.3,1899.0,1551.9,1551.1 -2.028873236498413,1.6291766922890907,0.916297857297023,919.4,254.4,313.1,1948.7,1579.7,1638.9 -2.0288855085118476,1.6291381932993025,1.0471975511965976,472.3,264.9,392.3,2167.8,1744.1,1692.3 -2.0289110011547415,1.6290947970462253,1.1780972450961724,315.0,313.6,532.7,2290.4,1418.3,1197.4 -2.028907172379225,1.6290969040381609,1.3089969389957472,252.2,449.2,828.3,1825.7,1112.3,984.6 -2.0289178318673713,1.6290911011502887,1.4398966328953218,232.5,931.1,1759.3,1599.5,956.2,897.9 -2.0289886748039394,1.6290739965611027,1.5707963267948966,240.8,1928.8,1928.4,1521.0,893.3,892.9 -2.0289805789260424,1.629072601070098,1.7016960206944713,275.0,1969.8,2027.7,1556.9,898.4,956.8 -2.0289758633722554,1.629069843047565,1.832595714594046,345.0,2182.6,2310.4,1732.6,828.5,449.1 -2.029030791802244,1.6291042064039694,1.9634954084936205,475.7,2340.0,2121.0,1350.5,532.7,313.6 -2.0290479016113143,1.6291233358310038,2.0943951023931953,748.9,1871.0,1743.7,1063.6,392.3,264.9 -2.0290384873865994,1.6291034109621547,2.2252947962927703,1605.3,1638.7,1579.9,919.2,313.1,254.3 -2.029043986421656,1.629125839928839,2.356194490192345,1899.9,1551.1,1551.9,862.5,270.2,270.8 -2.0290409836552943,1.629155943202494,2.4870941840919194,1992.0,1580.1,1639.4,876.7,254.5,313.6 -2.0290445608895595,1.6291465824292968,2.6179938779914944,2262.2,1745.9,1732.1,745.9,264.6,392.2 -2.029031112117816,1.6291623831338848,2.748893571891069,2124.1,1414.2,1194.4,474.9,315.0,534.9 -2.0290396652526455,1.6291548867351118,2.8797932657906435,1706.0,1111.3,984.0,345.2,450.5,830.3 -2.0290303218535652,1.6291594877600644,3.010692959690218,1557.1,957.4,898.5,275.6,925.8,1748.9 -2.028971093207002,1.5288600262489018,0.0,1421.6,893.0,893.0,340.7,1928.9,1929.0 -2.0289888622051735,1.5288586071420391,0.1308996938995747,1498.2,898.7,958.2,335.9,1971.6,2031.6 -2.029040670331396,1.528873492824752,0.2617993877991494,1709.0,983.8,649.1,367.8,2181.5,2308.8 -2.0290934469060695,1.5289055744147437,0.39269908169872414,1192.4,674.4,455.1,456.6,2199.6,1980.3 -2.029134821518597,1.5289508005874612,0.5235987755982988,972.0,507.8,380.1,669.4,1757.6,1630.6 -2.0291707932700276,1.5290139751862977,0.6544984694978736,876.8,417.1,358.0,1387.4,1535.6,1476.8 -2.0291799830048354,1.5290580029322451,0.7853981633974483,863.3,370.7,370.2,1898.6,1451.8,1451.3 -2.029178572367678,1.5291335219337319,0.916297857297023,919.4,357.8,416.7,1948.6,1476.2,1535.3 -2.0291674469129277,1.5291723080002573,1.0471975511965976,672.0,380.4,507.8,2168.0,1628.6,1692.3 -2.029153348207941,1.5291925057375324,1.1780972450961724,456.8,454.8,673.9,2148.7,1418.3,1197.4 -2.0290980787212467,1.5292434310173828,1.3089969389957472,367.9,648.6,1027.8,1709.7,1112.1,1044.5 -2.0290539153607394,1.529267102504262,1.4398966328953218,336.0,1321.2,1970.3,1495.9,956.2,897.9 -2.029066732163651,1.529263433729464,1.5707963267948966,340.9,1929.0,1928.7,1421.1,893.4,893.1 -2.029004124792593,1.529260355267175,1.7016960206944713,378.6,1969.9,2028.1,1453.5,898.6,957.1 -2.0289508935465737,1.5292430149374168,1.832595714594046,460.7,2182.6,2310.0,1617.2,983.6,648.6 -2.0289654022013695,1.5292521562193062,1.9634954084936205,617.4,2199.0,1979.8,1350.5,674.0,454.8 -2.028952613819117,1.5292392813729898,2.0943951023931953,948.8,1755.8,1628.3,1063.5,507.7,380.5 -2.0289242306916244,1.529183977434139,2.2252947962927703,1949.2,1535.3,1476.3,919.0,416.7,357.9 -2.0289212314985647,1.529169859346528,2.356194490192345,1899.8,1451.2,1451.9,862.3,370.2,370.8 -2.028919454275011,1.5291651187164996,2.4870941840919194,1992.6,1476.5,1535.4,876.8,358.0,417.1 -2.028932344745029,1.5291251632742822,2.6179938779914944,2262.2,1630.0,1688.6,971.5,380.2,507.9 -2.0289347123618384,1.529115684843587,2.748893571891069,1982.9,1414.2,1194.4,616.2,456.4,676.5 -2.028963263785081,1.5290894844108074,2.8797932657906435,1590.3,1111.3,984.0,460.8,650.1,1029.9 -2.0289762793601374,1.5290821331448572,3.010692959690218,1454.0,957.3,898.4,379.1,1312.9,1970.9 -2.0289440352594705,1.4288029078189715,0.0,1321.5,892.9,893.1,440.6,1928.5,1929.1 -2.0289920756653856,1.4293429861763505,0.1308996938995747,1394.6,898.8,958.2,439.8,1971.4,2031.1 -2.0289591066190797,1.4293321880086198,0.2617993877991494,1593.4,984.0,849.0,483.5,2180.9,2360.0 -2.0289205914269224,1.4293072804361002,0.39269908169872414,1192.1,815.8,596.5,598.6,2058.9,1839.3 -2.02888832009534,1.4292736203564118,0.5235987755982988,971.8,623.5,495.9,868.9,1642.0,1514.2 -2.028876263590688,1.4292473003390915,0.6544984694978736,876.6,520.7,461.6,1773.0,1432.0,1372.9 -2.028863587575584,1.4291977802433142,0.7853981633974483,863.0,470.9,470.2,1899.0,1351.6,1351.4 -2.0288646131275425,1.429230704777374,0.916297857297023,919.3,461.4,520.2,1948.6,1372.8,1431.5 -2.028886662993111,1.4291602392727487,1.0471975511965976,871.6,496.0,623.3,2168.1,1513.0,1640.2 -2.0289168030678875,1.4291094228450534,1.1780972450961724,598.4,595.8,815.0,2007.1,1418.3,1197.0 -2.0289121057501407,1.4291127272402007,1.3089969389957472,483.4,847.8,1227.2,1594.2,1112.2,984.6 -2.028922795680985,1.429106901870381,1.4398966328953218,439.4,1710.5,1970.5,1392.6,956.2,897.9 -2.028991771278429,1.4290901695369103,1.5707963267948966,440.7,1929.0,1928.9,1321.1,893.3,893.0 -2.0289814101671335,1.429088655162257,1.7016960206944713,482.0,1969.7,2028.0,1350.1,898.5,956.9 -2.028974520497507,1.429085211238886,1.832595714594046,576.3,2182.6,2309.8,1501.6,984.0,847.8 -2.0290276056093735,1.429118374364879,1.9634954084936205,759.0,2057.4,1838.8,1350.2,814.9,595.9 -2.0290433556680663,1.429135985486472,2.0943951023931953,1148.1,1640.1,1512.8,1063.7,623.3,495.9 -2.029033076453998,1.4291144101233875,2.2252947962927703,1949.2,1431.6,1373.1,919.0,520.1,461.3 -2.029038189579437,1.4291351424430339,2.356194490192345,1899.6,1351.0,1351.8,862.3,470.3,470.7 -2.0290349769640517,1.429210616470559,2.4870941840919194,1991.9,1373.0,1432.2,876.6,461.6,520.6 -2.029048336046569,1.42916932451352,2.6179938779914944,2336.6,1514.3,1642.0,971.4,495.9,623.4 -2.0290392693099566,1.42917820691869,2.748893571891069,1841.6,1414.6,1194.4,757.9,597.8,817.9 -2.029048013658754,1.4291705067277918,2.8797932657906435,1500.3,1111.2,983.8,576.3,849.5,1229.4 -2.029036800970391,1.4291760735535128,3.010692959690218,1350.3,957.3,898.4,482.7,1700.0,1970.9 -2.028936877402162,1.3288645064844034,0.0,1221.4,893.0,893.0,540.7,1929.1,1929.0 -2.028978541086331,1.3288639854665774,0.1308996938995747,1291.1,898.7,958.2,543.2,1971.6,2030.9 -2.029037217566125,1.3288809554625842,0.2617993877991494,1477.7,983.9,1086.1,598.9,2181.5,2308.8 -2.0290915478870155,1.3289139701628927,0.39269908169872414,1192.3,956.8,737.3,739.9,1917.3,1698.3 -2.029133021975446,1.3289592603821925,0.5235987755982988,972.0,739.0,611.3,1067.8,1526.7,1398.9 -2.029168840968415,1.329022091440659,0.6544984694978736,876.9,624.1,565.0,1992.4,1328.8,1269.5 -2.0291779194449058,1.3290656053051093,0.7853981633974483,863.3,570.8,570.3,1899.1,1251.7,1251.2 -2.0291765324961877,1.3293205735396443,0.916297857297023,919.6,564.9,623.7,1948.3,1269.1,1328.2 -2.0288023767390824,1.3290712155762838,1.0471975511965976,1063.2,611.4,738.6,2167.5,1396.9,1524.0 -2.0288278823377675,1.3290290152086794,1.1780972450961724,740.6,736.8,955.6,1866.1,1524.6,1198.0 -2.0288225346157955,1.3290339008929584,1.3089969389957472,599.3,1046.3,1425.3,1479.0,1112.6,984.8 -2.0288345131202052,1.3290283792745776,1.4398966328953218,543.0,2029.3,1970.5,1289.1,956.5,897.9 -2.0289053053940975,1.3290116063324113,1.5707963267948966,540.8,1929.3,1928.7,1221.3,893.4,893.1 -2.0288967336686685,1.3290105553201124,1.7016960206944713,585.2,1969.6,2028.2,1246.5,898.7,956.9 -2.028891318124259,1.3290081208961033,1.832595714594046,691.6,2181.8,2309.2,1385.4,983.7,1085.9 -2.028945660699809,1.3290421770853227,1.9634954084936205,900.4,1917.7,1698.3,1371.6,956.6,737.5 -2.028962495665992,1.3290606214682492,2.0943951023931953,1346.8,1525.0,1397.5,1064.1,739.2,611.7 -2.028952960871292,1.3290401639209202,2.2252947962927703,1949.2,1328.3,1269.4,919.3,623.9,565.0 -2.028958676621456,1.3290620492552854,2.356194490192345,1899.6,1251.2,1251.6,862.7,570.3,570.9 -2.028956357413115,1.3290916034851974,2.4870941840919194,1992.1,1269.3,1328.1,876.7,565.1,624.1 -2.0289605150228005,1.3290821332401173,2.6179938779914944,2261.8,1398.2,1526.2,971.3,611.5,738.9 -2.0289480047051613,1.329097951205044,2.748893571891069,1701.2,1527.1,1195.0,900.0,738.8,958.9 -2.028957116072486,1.3290908294839634,2.8797932657906435,1384.9,1111.8,984.2,692.3,1048.4,1427.5 -2.0289481672208907,1.329095947091143,3.010692959690218,1246.9,957.5,898.5,586.4,2029.6,1971.0 -2.0288886345685095,1.2287965223578232,0.0,1121.4,893.1,893.0,640.9,1929.1,1928.9 -2.0289065000172286,1.22879557701543,0.1308996938995747,1187.3,898.9,958.1,646.8,1971.4,2030.4 -2.02895820678709,1.2288106629648978,0.2617993877991494,1362.2,983.7,1111.0,714.5,2299.9,2207.5 -2.029010914341142,1.2288427503150676,0.39269908169872414,1193.2,1098.6,879.1,881.2,1777.3,1557.8 -2.029052232153452,1.228887778445043,0.5235987755982988,972.2,855.1,727.2,1266.4,1411.3,1283.7 -2.0290885499403304,1.228950823951156,0.6544984694978736,877.0,728.0,668.7,1992.3,1225.1,1166.1 -2.029098042028726,1.2289946128732319,0.7853981633974483,863.2,670.8,670.3,1898.5,1151.9,1151.1 -2.0290972765196913,1.2290702190968141,0.916297857297023,919.4,668.4,727.0,1948.6,1165.6,1224.3 -2.0290867962408132,1.2291093296443452,1.0471975511965976,1063.3,726.9,854.1,2264.1,1281.5,1408.6 -2.029073129971713,1.2291298310660617,1.1780972450961724,882.6,878.0,1096.9,1724.3,1419.0,1198.3 -2.029018223655267,1.2291813884988887,1.3089969389957472,715.0,1245.5,1624.4,1363.6,1112.9,984.9 -2.0289741897688205,1.2292059668739097,1.4398966328953218,646.5,2029.2,1970.4,1185.6,956.6,898.1 -2.028986803124516,1.229202702877976,1.5707963267948966,640.9,1928.8,1928.5,1121.0,893.4,893.1 -2.0289238511190675,1.2291999966305536,1.7016960206944713,688.9,1969.6,2027.8,1142.9,898.5,956.8 -2.0288701283047903,1.2291830500790266,1.832595714594046,807.3,2297.6,2205.3,1269.5,983.7,1111.2 -2.0288842390953588,1.2291920384379975,1.9634954084936205,1042.2,1776.1,1557.1,1389.3,1098.1,878.7 -2.0288713024663645,1.2291786803753828,2.0943951023931953,1546.3,1409.5,1282.1,1064.1,854.9,727.4 -2.028842870517377,1.2291230424573887,2.2252947962927703,1949.3,1224.8,1165.8,919.1,727.4,668.4 -2.0288400953153265,1.2292128447881203,2.356194490192345,1899.6,1151.1,1151.7,862.6,670.3,670.8 -2.02916669291472,1.2290692473717186,2.4870941840919194,1992.5,1165.7,1224.9,876.9,668.8,727.9 -2.029169257398418,1.2290622107074043,2.6179938779914944,2225.0,1283.0,1410.7,971.5,727.4,854.9 -2.029149845582578,1.2290875658463039,2.748893571891069,1559.1,1414.5,1194.5,1040.8,880.9,1100.9 -2.02914892982899,1.2290891254038443,2.8797932657906435,1269.3,1111.4,983.9,807.7,1248.8,1628.9 -2.029128241846911,1.229100174571884,3.010692959690218,1143.1,957.3,898.4,689.9,2029.9,1971.0 -2.0290548466118756,1.1287901268788003,0.0,1021.0,893.1,892.9,740.7,1928.7,1929.3 -2.029062357994944,1.1287891457959947,0.1308996938995747,1083.7,898.7,958.2,750.4,1972.0,2030.8 -2.029106295804219,1.1288023928697173,0.2617993877991494,1246.8,984.1,1111.4,830.1,2181.3,2006.1 -2.029152743676258,1.1288314133676387,0.39269908169872414,1192.3,1196.1,1020.0,1023.1,1635.2,1415.6 -2.0291892027642304,1.1288724678631978,0.5235987755982988,972.1,970.3,842.9,1466.6,1295.1,1167.6 -2.0292217865760676,1.1289307691093662,0.6544984694978736,876.5,831.3,772.3,1992.5,1121.6,1062.3 -2.0292291340039537,1.1289694695610661,0.7853981633974483,863.2,770.8,770.3,1899.0,1051.7,1051.2 -2.0292274549419083,1.1290397555685927,0.916297857297023,919.3,772.0,831.0,1948.4,1062.0,1121.1 -2.0292175186105688,1.1290737411736176,1.0471975511965976,1063.4,842.7,970.0,2168.0,1166.2,1293.3 -2.0292058081520707,1.12908996903177,1.1780972450961724,1023.8,1019.4,1238.6,1582.0,1415.3,1197.6 -2.0291537280039638,1.1291380725827032,1.3089969389957472,830.4,1445.9,1825.0,1247.0,1112.3,984.7 -2.0291132056386805,1.1291601584415263,1.4398966328953218,750.1,2028.7,1970.7,1082.0,956.2,897.8 -2.0291297306311105,1.1291561161839758,1.5707963267948966,740.8,1929.4,1928.9,1021.0,893.3,892.8 -2.0290704253093947,1.1291537486864716,1.7016960206944713,792.4,1969.7,2028.2,1039.6,898.4,956.9 -2.0290198822857524,1.1291379585354435,1.832595714594046,923.3,2182.5,2004.2,1154.4,983.6,1111.2 -2.029036343422102,1.1291491892373466,1.9634954084936205,1184.7,1634.0,1415.2,1350.4,1196.3,1019.3 -2.029024702691751,1.1291386013790274,2.0943951023931953,1747.5,1293.4,1166.2,1063.6,970.0,842.8 -2.0289967491780607,1.1290855305473926,2.2252947962927703,1949.1,1121.0,1062.3,919.0,830.8,772.1 -2.0289936356972866,1.1290734353356071,2.356194490192345,1899.6,1051.1,1051.7,862.3,770.3,770.9 -2.028991381858958,1.1290704031985004,2.4870941840919194,1992.4,1062.3,1121.2,876.6,772.2,831.4 -2.029003580865794,1.129031838793396,2.6179938779914944,2025.9,1167.4,1295.1,971.4,843.0,970.5 -2.029005173331426,1.129023491329365,2.748893571891069,1417.3,1414.3,1194.6,1194.4,1022.1,1242.2 -2.0290329003680707,1.1289982343323581,2.8797932657906435,1153.7,1111.3,983.7,923.2,1448.2,1828.1 -2.029045046584361,1.128991697426077,3.010692959690218,1039.9,957.2,898.4,793.1,2029.5,1970.9 -1.9290386198648062,1.8291484155137452,0.0,1721.1,993.0,992.9,40.9,1829.3,1828.9 -1.929021594038537,1.828526179860308,0.1308996938995747,1809.0,1002.3,149.0,25.6,1868.8,1927.8 -1.9290765174921802,1.8285440877348844,0.2617993877991494,1910.7,430.8,51.4,21.4,2066.2,2193.7 -1.929131598570564,1.828579800307029,0.39269908169872414,1333.1,251.1,31.9,32.1,2522.3,2403.0 -1.9291742996439418,1.8286287263251122,0.5235987755982988,1087.5,161.2,33.6,72.5,2103.6,1976.2 -1.929210630983354,1.828435820304747,0.6544984694978736,980.2,106.7,47.7,232.2,1845.3,1786.9 -1.9288117606519837,1.8289243921970944,0.7853981633974483,963.3,70.9,70.6,1798.6,1751.6,1751.2 -1.9288033008026666,1.829138800482467,0.916297857297023,232.1,47.6,106.6,1845.5,1786.8,1845.8 -1.9288538457663211,1.8289804517202608,1.0471975511965976,73.3,34.1,161.7,2053.4,1975.7,1961.9 -1.9288926253762995,1.828918997090058,1.1780972450961724,31.9,31.7,251.2,2514.1,1558.6,1338.2 -1.9288815726903827,1.8289302919935524,1.3089969389957472,21.3,51.3,431.3,2054.8,1264.6,1099.8 -1.9288779365566568,1.828933471294851,1.4398966328953218,25.9,153.4,984.8,1805.6,1059.6,1001.3 -1.9289292156982372,1.8289228307355225,1.5707963267948966,41.1,1829.3,1828.5,1721.3,993.4,993.2 -1.9289009422389611,1.8289223042233171,1.7016960206944713,68.4,1866.5,1925.3,1764.6,1002.3,151.9 -1.9288775303480346,1.828914728883096,1.832595714594046,114.3,2067.8,2195.8,1964.5,429.5,51.0 -1.9289163537224199,1.8289401957164486,1.9634954084936205,193.0,2526.0,2400.6,1490.7,250.4,31.7 -1.9289212363395842,1.8289475211972313,2.0943951023931953,350.7,2100.7,1974.0,1178.5,161.2,34.1 -1.9289043311850431,1.828913627977292,2.2252947962927703,834.8,1844.7,1786.2,1022.3,106.2,47.6 -1.9289067856851145,1.828921490923925,2.356194490192345,1799.3,1751.0,1751.6,962.4,70.4,71.1 -1.9289046217190502,1.8289380546683607,2.4870941840919194,1889.1,1787.3,1846.8,824.5,47.6,106.8 -1.92891295400796,1.8289168172807362,2.6179938779914944,2148.6,1977.4,1964.4,347.3,33.6,161.5 -1.928906315741419,1.828923544532993,2.748893571891069,2404.8,1554.6,1335.0,192.1,32.4,252.8 -1.9289236053923298,1.828909808442712,2.8797932657906435,1961.5,1226.4,1099.0,114.2,52.1,432.7 -1.9289234522098833,1.8289111491287975,3.010692959690218,1763.8,1060.9,1002.0,68.7,152.9,978.4 -1.9288748917569558,1.7286193486334045,0.0,1621.3,992.9,993.3,140.8,1828.5,1829.3 -1.9289117006329317,1.7292741357789334,0.1308996938995747,1705.6,1002.7,531.3,129.0,1868.5,1928.1 -1.9288840854778675,1.7292649820223294,0.2617993877991494,1910.0,629.4,250.3,136.9,2066.4,2194.8 -1.9288531122879629,1.7292446085892759,0.39269908169872414,1332.7,391.8,172.8,173.7,2480.8,2261.8 -1.9288275485555715,1.7292176366359242,0.5235987755982988,1087.2,276.5,149.0,271.6,1988.0,1860.2 -1.9288198976108777,1.7291988960707223,0.6544984694978736,980.2,209.9,151.0,618.3,1742.2,1683.1 -1.9288098009318468,1.7291576913277487,0.7853981633974483,963.2,170.7,170.4,1799.1,1651.8,1651.3 -1.9288112758955103,1.729152376304634,0.916297857297023,617.6,150.9,209.8,1845.4,1683.4,1742.4 -1.9288224923903674,1.7291189768429236,1.0471975511965976,272.3,149.4,276.9,2053.2,1860.5,1889.8 -1.9288459348077742,1.7290802831725536,1.1780972450961724,173.2,172.6,392.0,2430.1,1559.1,1338.3 -1.9288375295654514,1.7290877001515264,1.3089969389957472,136.6,250.3,630.1,1940.6,1227.5,1100.1 -1.9288458523034175,1.7290832668657057,1.4398966328953218,129.1,542.8,1373.7,1702.7,1059.5,1001.3 -1.9289130250190345,1.7290675564856797,1.5707963267948966,140.8,1828.7,1828.6,1621.1,993.2,993.2 -1.9289010489357448,1.7290662354054434,1.7016960206944713,171.6,1866.4,1925.5,1660.9,1002.2,540.0 -1.9288928494323245,1.729062089996826,1.832595714594046,229.6,2067.3,2195.3,1848.9,628.3,249.7 -1.9289448543045657,1.7290945058528924,1.9634954084936205,334.3,2479.2,2260.5,1490.5,391.2,172.5 -1.9289598410204682,1.7292004942831576,2.0943951023931953,550.1,1986.0,1858.6,1178.8,276.5,149.4 -1.9289445591147556,1.7290788742618757,2.2252947962927703,1221.1,1741.5,1682.7,1022.4,209.5,150.9 -1.928951551308258,1.7291055591376991,2.356194490192345,1799.7,1651.2,1651.8,962.6,170.2,170.9 -1.9289489199743253,1.7291349272873437,2.4870941840919194,1889.1,1683.7,1743.6,980.5,150.9,210.1 -1.9289538494984768,1.7291233348728907,2.6179938779914944,2147.6,1861.9,1885.4,546.2,149.0,276.9 -1.9289419895835347,1.729137216494613,2.748893571891069,2264.6,1555.1,1335.3,333.2,173.7,393.9 -1.9289527945104994,1.7291282432252637,2.8797932657906435,1846.5,1226.4,1099.1,229.5,251.3,631.7 -1.9289457306111446,1.7291320050460155,3.010692959690218,1660.4,1060.4,1002.0,172.1,540.0,1365.0 -1.9288893556100963,1.6288343030419108,0.0,1521.2,993.1,993.2,240.6,1829.0,1828.7 -1.9289089779769613,1.6288331085248435,0.1308996938995747,1602.3,1002.5,914.0,232.5,1868.8,1927.7 -1.9289621185499892,1.6288484446176206,0.2617993877991494,1825.5,828.2,449.2,252.3,2066.4,2194.0 -1.9290159677889231,1.6288810955405735,0.39269908169872414,1332.9,532.8,313.7,315.2,2339.4,2120.4 -1.9290583882078334,1.628927065636213,0.5235987755982988,1163.6,392.0,264.5,470.8,1872.3,1744.9 -1.9290949822103018,1.6289909248610397,0.6544984694978736,980.4,313.4,254.4,1004.2,1638.9,1579.6 -1.9291049367432682,1.629035960903156,0.7853981633974483,963.4,270.7,270.3,1798.5,1551.5,1551.2 -1.9291038385592114,1.6291123682318984,0.916297857297023,1023.5,254.4,313.3,1845.0,1579.9,1638.6 -1.9290928299272305,1.6291520898108458,1.0471975511965976,471.9,265.1,392.4,2053.2,1744.5,1872.1 -1.9290787285820636,1.6291735156368403,1.1780972450961724,314.9,313.9,533.3,2288.7,1558.8,1338.5 -1.9290230365741488,1.62922533955394,1.3089969389957472,252.2,449.9,829.6,1824.3,1227.5,1240.9 -1.9289781757541058,1.6292494285441326,1.4398966328953218,232.6,933.6,1764.2,1599.1,1059.5,1001.4 -1.9289902029359491,1.6292464125170432,1.5707963267948966,240.9,1828.8,1828.8,1520.8,993.4,993.2 -1.9289267293962715,1.6292434504654676,1.7016960206944713,275.2,1866.3,1924.9,1557.3,1002.5,929.2 -1.9288727987207643,1.6292255433978196,1.832595714594046,345.4,2067.4,2195.1,1733.1,827.5,448.9 -1.9288867439914683,1.6292341722303518,1.9634954084936205,476.2,2338.3,2119.6,1490.6,532.4,313.5 -1.928873597085823,1.6292207802969534,2.0943951023931953,749.9,1870.1,1743.3,1178.6,392.1,264.8 -1.9288453593651165,1.6291646312495258,2.2252947962927703,1609.3,1637.9,1579.6,1022.7,313.1,254.4 -1.928842772547153,1.6291498060669338,2.356194490192345,1799.8,1551.2,1551.7,962.3,270.3,270.9 -1.9288413737360979,1.6291447592201234,2.4870941840919194,1888.8,1580.4,1639.2,980.3,254.5,313.7 -1.9288550173642365,1.6291045388333378,2.6179938779914944,2147.6,1746.1,1873.9,745.2,264.6,392.5 -1.9288576980966066,1.6290952094834439,2.748893571891069,2123.3,1554.8,1335.1,474.6,315.2,535.4 -1.9288867372444332,1.629069187333952,2.8797932657906435,1731.0,1226.4,1099.2,345.0,451.0,831.4 -1.9289000159122363,1.6290620844833554,3.010692959690218,1557.4,1060.6,1002.1,275.5,927.8,1752.5 -1.9288681245489456,1.5287827985354079,0.0,1421.2,992.9,993.1,340.6,1828.7,1829.1 -1.9289267609896374,1.5293373325351145,0.1308996938995747,1498.4,1002.4,1062.0,336.2,1868.2,1927.9 -1.9288967616554542,1.5293273478761602,0.2617993877991494,1709.7,1028.2,649.0,368.0,2066.2,2194.1 -1.9288595129902106,1.5293029840181864,0.39269908169872414,1333.0,674.2,455.0,457.0,2198.4,1979.4 -1.9288280982804198,1.529269752062589,0.5235987755982988,1087.4,507.7,380.1,670.2,1757.0,1629.7 -1.928816521958051,1.5292437184482202,0.6544984694978736,980.3,417.0,358.0,1390.2,1535.3,1476.5 -1.9288044696901774,1.529194723515198,0.7853981633974483,963.1,370.7,370.3,1798.7,1451.7,1451.1 -1.9288060695526537,1.5291820313559241,0.916297857297023,1023.0,357.9,416.8,1845.3,1476.4,1535.5 -1.9288191508524717,1.529141971249048,1.0471975511965976,671.5,380.6,507.9,2052.8,1628.8,1756.1 -1.928845802766249,1.5290976188364913,1.1780972450961724,456.5,454.9,674.2,2147.8,1559.1,1338.5 -1.928841587669881,1.5291008188102573,1.3089969389957472,367.7,649.0,1028.5,1709.3,1227.4,1099.8 -1.9288547167236323,1.529093675202338,1.4398966328953218,336.0,1322.9,1866.8,1495.9,1059.7,1001.4 -1.9289269276277587,1.5290765153413355,1.5707963267948966,340.9,1829.1,1828.4,1421.5,993.2,993.1 -1.9289197429153506,1.529075162295083,1.7016960206944713,378.5,1866.5,1925.0,1453.5,1002.1,1060.8 -1.9289158232773869,1.5290722836386688,1.832595714594046,460.8,2066.9,2195.3,1617.0,1026.8,647.9 -1.928971434270654,1.5291068503744896,1.9634954084936205,617.7,2197.3,1978.5,1491.0,673.6,454.5 -1.9289891131052916,1.5291263803802493,2.0943951023931953,949.2,1755.1,1627.9,1178.8,507.6,380.3 -1.9289803505992524,1.529106735454465,2.2252947962927703,1845.3,1535.1,1476.1,1022.4,416.6,357.8 -1.9289864045351106,1.5291296045691403,2.356194490192345,1799.7,1451.1,1451.7,962.5,370.2,370.8 -1.928983645581519,1.5291604101959935,2.4870941840919194,1888.9,1476.7,1536.0,980.3,358.0,417.2 -1.9289874953666162,1.5291516629017656,2.6179938779914944,2147.8,1630.1,1758.3,944.4,380.3,508.1 -1.9289738005211219,1.5291682149754802,2.748893571891069,1982.1,1554.9,1335.6,616.0,456.6,676.8 -1.9289821179177389,1.529161280739033,2.8797932657906435,1615.6,1226.7,1099.4,460.6,650.6,1030.7 -1.928972326138597,1.5291662791306342,3.010692959690218,1453.9,1060.8,1002.1,379.1,1315.3,1867.2 -1.9289126565723693,1.4288661969643173,0.0,1321.6,993.1,993.1,440.6,1828.8,1829.1 -1.9289300206631985,1.428864738790121,0.1308996938995747,1395.0,1002.8,1061.9,439.6,1868.4,1927.7 -1.9289815314787309,1.428879428789609,0.2617993877991494,1594.1,1099.8,847.9,483.5,2066.1,2359.3 -1.9290341664194213,1.4289112101619281,0.39269908169872414,1333.1,815.1,596.0,598.6,2057.9,1838.8 -1.929075663638253,1.4289561526195536,0.5235987755982988,1087.3,623.2,495.7,869.5,1641.4,1513.9 -1.9291117213711986,1.4290189784638399,0.6544984694978736,980.3,520.5,461.4,1776.2,1431.8,1372.9 -1.929121309375486,1.4290628932873934,0.7853981633974483,963.4,470.7,470.3,1799.0,1351.6,1351.4 -1.929120165653888,1.4291382852925647,0.916297857297023,1023.4,461.4,520.2,1845.5,1372.9,1431.7 -1.9291093158023396,1.4291770594011237,1.0471975511965976,871.1,496.0,623.4,2052.9,1513.2,1640.7 -1.929095518992444,1.4291975460087376,1.1780972450961724,598.3,596.2,815.4,2006.2,1667.3,1338.8 -1.9290403373271576,1.4292486450349264,1.3089969389957472,483.4,848.5,1227.9,1593.5,1227.7,1100.2 -1.9289961319113682,1.4292722682410055,1.4398966328953218,439.5,1713.5,1866.5,1392.1,1059.8,1001.2 -1.929008886812223,1.429268825373601,1.5707963267948966,440.9,1828.7,1828.8,1321.2,993.4,993.2 -1.9289461707198237,1.4292657228912964,1.7016960206944713,482.0,1866.3,1924.5,1350.0,1002.1,1060.6 -1.9288929348599397,1.4292480095274027,1.832595714594046,576.5,2067.2,2313.5,1502.0,1099.7,847.2 -1.9289074974360942,1.4292569364535201,1.9634954084936205,759.6,2056.7,1837.6,1514.5,814.5,595.7 -1.9288948282720064,1.4292439457877018,2.0943951023931953,1149.0,1639.7,1512.4,1178.8,622.9,495.8 -1.9288668080465656,1.4291883762828037,2.2252947962927703,1845.5,1431.3,1372.6,1022.5,520.1,461.4 -1.92886423544649,1.4291741368711155,2.356194490192345,1799.4,1351.3,1351.7,962.6,470.2,470.8 -1.92886273285167,1.4291695552258152,2.4870941840919194,1889.1,1373.1,1432.5,980.2,461.6,520.8 -1.928876036601925,1.4291297454718985,2.6179938779914944,2147.3,1514.9,1642.7,1087.5,495.9,623.7 -1.9288784187936607,1.4291206243107362,2.748893571891069,1841.0,1670.3,1335.6,757.5,598.0,818.4 -1.9289070464559928,1.4290947013023492,2.8797932657906435,1500.1,1226.6,1099.3,576.2,850.0,1230.3 -1.928919965018002,1.4290875697732766,3.010692959690218,1350.5,1060.7,1002.0,482.5,1702.4,1867.2 -1.9288876699954682,1.3288080664389255,0.0,1221.4,993.0,993.3,540.6,1828.7,1829.1 -1.928944973724187,1.3293439025729326,0.1308996938995747,1290.8,1002.6,1061.8,543.4,1868.1,1927.8 -1.9289139124900276,1.329333607442891,0.2617993877991494,1478.1,1099.7,1047.7,599.2,2066.1,2193.6 -1.9288758130543575,1.3293087699412836,0.39269908169872414,1333.1,956.6,737.4,740.4,1916.6,1697.2 -1.9288437100571614,1.3292749273464186,0.5235987755982988,1087.2,738.9,611.2,1068.7,1526.0,1398.3 -1.9288538242957494,1.329292562315374,0.6544984694978736,980.0,624.1,565.1,1888.4,1328.5,1269.4 -1.9288339225457176,1.3292095658812846,0.7853981633974483,963.1,570.8,570.3,1798.8,1251.7,1251.4 -1.9288357276073507,1.3291883987245472,0.916297857297023,1022.9,564.9,623.8,1845.1,1269.4,1328.1 -1.9288487841195106,1.329148131756745,1.0471975511965976,1070.9,611.6,739.0,2052.8,1397.5,1525.1 -1.9288741218682506,1.3291056074254377,1.1780972450961724,740.0,737.2,956.5,1864.9,1559.4,1338.6 -1.9288677727672074,1.329110696636709,1.3089969389957472,598.9,1047.6,1427.2,1478.3,1227.8,1100.2 -1.92887832376739,1.3291049240278738,1.4398966328953218,542.9,1925.4,1866.9,1289.0,1059.6,1001.3 -1.9289477943544726,1.329088290949378,1.5707963267948966,540.8,1829.0,1828.7,1221.4,993.1,993.1 -1.9289380521913408,1.3290868253419255,1.7016960206944713,585.4,1866.3,1924.9,1247.1,1002.2,1060.7 -1.9289318370851962,1.3290833350110685,1.832595714594046,692.1,2067.1,2194.8,1386.0,1099.7,1046.4 -1.928985530734214,1.329116738915309,1.9634954084936205,901.2,1916.1,1697.1,1532.5,955.8,736.7 -1.9290017791405552,1.329134763178051,2.0943951023931953,1348.5,1524.3,1371.6,1179.1,738.6,611.4 -1.9290150878759846,1.3291589154704355,2.2252947962927703,1845.2,1327.9,1269.1,1022.5,623.5,564.8 -1.9290128276672056,1.3291460024225947,2.356194490192345,1799.8,1251.2,1252.1,962.6,570.2,570.9 -1.9290103935002072,1.3291672191942503,2.4870941840919194,1888.9,1269.5,1328.7,980.1,565.0,624.3 -1.9290144160289362,1.3291574943702957,2.6179938779914944,2147.2,1399.0,1526.7,1087.2,611.6,739.2 -1.9289998393415044,1.3291753449298342,2.748893571891069,1699.5,1555.4,1335.7,898.9,739.4,959.7 -1.9290064179278315,1.3291699182266736,2.8797932657906435,1384.6,1226.9,1099.2,691.7,1049.7,1429.8 -1.9289945054789537,1.329175983553693,3.010692959690218,1246.8,1060.9,1001.9,586.1,1926.2,1867.1 -1.9289321480052408,1.2288739263203352,0.0,1121.5,993.0,993.2,640.6,1828.9,1828.9 -1.9290079625395329,1.2288714730815833,0.1308996938995747,1187.8,1002.6,1061.8,646.8,1868.4,1927.5 -1.929019150744938,1.2288737645906411,0.2617993877991494,1362.6,1099.8,1227.2,714.6,2065.7,2160.9 -1.929063538000721,1.2289003761601176,0.39269908169872414,1333.7,1097.6,878.3,881.8,1775.6,1556.4 -1.9291052844404295,1.2289456514319967,0.5235987755982988,1087.4,854.4,726.8,1267.7,1410.7,1282.6 -1.9291429263066182,1.2290115320507002,0.6544984694978736,980.4,727.5,668.7,1888.6,1225.2,1166.0 -1.9291533521403037,1.2290595212566138,0.7853981633974483,963.3,670.8,670.2,1798.8,1151.8,1151.4 -1.9291520076462982,1.229139090225623,0.916297857297023,1023.0,668.4,727.3,1845.5,1166.1,1224.8 -1.929139921851646,1.2291816684613759,1.0471975511965976,1179.4,727.1,854.5,2078.5,1282.1,1409.3 -1.929124061190373,1.229205217313936,1.1780972450961724,881.6,878.5,1097.7,1723.3,1556.8,1338.9 -1.9290663583357535,1.2292585899824622,1.3089969389957472,714.5,1247.0,1626.5,1362.6,1227.7,1100.0 -1.929019358445506,1.2292837124194298,1.4398966328953218,646.4,1924.9,1867.4,1185.4,1059.6,1001.3 -1.9290292256130535,1.2292808473001657,1.5707963267948966,640.8,1828.9,1828.8,1121.1,993.5,993.2 -1.928963835824945,1.2292776402901815,1.7016960206944713,688.9,1866.7,1925.0,1143.1,1002.0,1060.6 -1.9289082074976036,1.229259291081223,1.832595714594046,807.8,2067.1,2158.3,1270.4,1099.6,1227.3 -1.9289207713303245,1.229267013350916,1.9634954084936205,1043.1,1774.9,1555.7,1491.3,1097.0,877.9 -1.9289066095130054,1.229252462166495,2.0943951023931953,1548.5,1408.6,1281.5,1179.0,854.1,726.9 -1.9288775624871095,1.2291952218687099,2.2252947962927703,1845.4,1224.7,1165.5,1022.4,727.1,668.4 -1.9288744561206421,1.229179219246767,2.356194490192345,1799.7,1151.1,1151.6,962.4,670.3,670.8 -1.928872937896793,1.2291728782147335,2.4870941840919194,1888.7,1165.9,1225.1,980.4,668.7,727.9 -1.9288865729236642,1.2291315231856355,2.6179938779914944,2147.3,1283.2,1411.0,1087.3,727.2,854.9 -1.928889720934191,1.2291210497096512,2.748893571891069,1558.8,1555.5,1335.6,1040.2,880.8,1101.0 -1.9289192970904716,1.2290941149329666,2.8797932657906435,1269.0,1226.8,1099.3,807.3,1249.3,1629.4 -1.9289333338529537,1.22908631288951,3.010692959690218,1143.3,1060.8,1002.1,689.6,1926.1,1867.2 -1.9289023765503317,1.1288078838101114,0.0,1021.4,993.1,993.1,740.7,1829.0,1828.8 -1.9289582266348653,1.1293456717097943,0.1308996938995747,1083.8,1002.6,1061.8,750.6,1868.2,1927.6 -1.928926646925535,1.129335237654315,0.2617993877991494,1246.8,1099.7,1227.3,830.4,2141.6,2005.3 -1.9288882454324627,1.1293102617304385,0.39269908169872414,1408.3,1239.0,1019.8,1024.0,1634.5,1415.5 -1.9288559043295768,1.1292762643798455,0.5235987755982988,1087.4,970.0,842.7,1467.2,1294.8,1167.4 -1.9288437493369173,1.1292494362245815,0.6544984694978736,980.2,831.2,772.1,1888.6,1121.2,1062.1 -1.9288312315599874,1.129199491473324,0.7853981633974483,963.2,770.8,770.2,1799.0,1051.8,1051.1 -1.9288326993620557,1.1291859176967463,0.916297857297023,1023.1,771.7,830.7,1845.3,1062.3,1121.2 -1.9288458643559738,1.1291450089902375,1.0471975511965976,1179.2,842.6,970.2,2052.7,1166.4,1293.7 -1.928872756809139,1.1290997792581376,1.1780972450961724,1023.3,1019.5,1238.6,1581.5,1415.5,1462.6 -1.9288690161051107,1.1291023375228488,1.3089969389957472,830.3,1446.0,1825.6,1247.3,1227.7,1100.2 -1.9288827674138465,1.1290948492695732,1.4398966328953218,749.7,1925.6,1867.0,1082.1,1059.5,1001.3 -1.9289847554636994,1.1290668978353757,1.5707963267948966,740.7,1829.1,1828.7,1021.2,993.3,993.2 -1.9289578590859824,1.1290648192910984,1.7016960206944713,792.4,1866.6,1924.8,1039.9,1002.0,1060.6 -1.9289507613499581,1.1290611071747705,1.832595714594046,923.2,2139.9,2003.7,1154.6,1099.5,1227.3 -1.9290079087714738,1.1290966966384346,1.9634954084936205,1184.6,1634.0,1414.8,1421.5,1238.1,1019.2 -1.9290277493441719,1.1291185977136928,2.0943951023931953,1748.0,1293.3,1166.0,1179.1,969.7,842.4 -1.9290204474779464,1.1291021131343402,2.2252947962927703,1845.4,1120.9,1062.2,1022.6,830.5,771.8 -1.929027063859147,1.1291283389696334,2.356194490192345,1799.4,1051.3,1051.9,962.4,770.2,770.9 -1.929024067134301,1.1291622548150455,2.4870941840919194,1888.9,1062.5,1121.7,980.4,772.2,831.3 -1.9290268397546395,1.1291562597886111,2.6179938779914944,2025.3,1167.7,1295.3,1087.2,842.7,970.6 -1.929011678623542,1.1291749578097585,2.748893571891069,1417.6,1417.8,1337.2,1181.8,1022.4,1242.4 -1.9290180949139721,1.1291696017475776,2.8797932657906435,1153.5,1226.8,1099.4,922.8,1448.6,1828.6 -1.9290062763079,1.1291755756982989,3.010692959690218,1039.7,1060.8,1001.9,793.2,1926.0,1867.4 -1.828996464059831,1.8292605841583935,0.0,1721.1,1093.0,1093.1,40.8,1729.1,1729.0 -1.8289831609973932,1.8285398770074506,0.1308996938995747,1808.4,965.3,149.2,25.6,1764.8,1823.6 -1.8290346407929696,1.8285565778313229,0.2617993877991494,2055.3,431.1,51.4,21.4,1950.6,2077.5 -1.8290880307312396,1.8285909968382055,0.39269908169872414,1474.8,251.3,31.9,32.1,2442.8,2404.1 -1.8291297754607463,1.8286385735901867,0.5235987755982988,1203.3,161.3,33.6,72.4,2104.5,1976.8 -1.8291658302192102,1.8287038133964888,0.6544984694978736,1084.0,106.7,47.6,231.8,1845.8,1787.1 -1.8291749430793431,1.8287495119531367,0.7853981633974483,1063.3,71.1,70.5,1698.7,1751.6,1750.7 -1.8291735722623728,1.82882648008433,0.916297857297023,233.3,47.7,106.5,1741.5,1786.4,1845.3 -1.8291626243292707,1.828866699492166,1.0471975511965976,73.7,34.2,161.5,1936.7,1974.6,2091.9 -1.8291487341578216,1.8288884640065644,1.1780972450961724,32.1,31.9,250.9,2371.2,1701.6,1480.9 -1.8290935573562177,1.8289412597407941,1.3089969389957472,21.4,51.4,430.5,2056.4,1343.7,1215.8 -1.8290491014843249,1.8289670838795173,1.4398966328953218,26.0,153.1,981.5,1806.2,1163.3,1105.0 -1.829061014601887,1.828965525435563,1.5707963267948966,41.1,1729.2,1728.9,1720.8,1093.5,1093.1 -1.8289969116858578,1.8289643286397668,1.7016960206944713,68.4,1762.6,1821.3,1763.7,982.0,153.2 -1.828941649943672,1.8289483610519517,1.832595714594046,114.3,1950.9,2078.5,1963.1,430.7,51.4 -1.8289538585039895,1.8289579891354604,1.9634954084936205,192.8,2444.2,2402.6,1633.1,251.0,31.9 -1.8289389248203403,1.8289446972858079,2.0943951023931953,350.2,2101.9,1974.7,1295.0,161.5,34.2 -1.8289088830937228,1.828888271148132,2.2252947962927703,831.6,1845.5,1786.5,1126.1,106.5,47.7 -1.8289050347978817,1.8288724985839646,2.356194490192345,1699.7,1751.0,1751.4,1062.4,70.6,71.1 -1.8289034068731016,1.828865963651171,2.4870941840919194,1785.0,1786.8,1845.7,828.2,47.7,106.8 -1.828917284641789,1.8288245929940041,2.6179938779914944,2031.4,1976.3,2087.1,348.3,33.7,161.3 -1.8289213554468389,1.8288143329697366,2.748893571891069,2407.2,1697.4,1477.6,192.5,32.5,252.5 -1.8289518116360086,1.8287882421793995,2.8797932657906435,1962.3,1342.4,1215.2,114.4,52.1,431.8 -1.8289725125194845,1.828779564382779,3.010692959690218,1764.2,1164.7,1105.6,68.9,152.4,974.8 -1.8289387256465703,1.7285136698840589,0.0,1621.3,1093.0,1092.9,140.9,1728.9,1729.1 -1.8289887344739035,1.7292580099928272,0.1308996938995747,1705.2,1106.1,532.7,129.0,1764.6,1824.1 -1.8289655148625663,1.7292504147538135,0.2617993877991494,1939.9,630.3,250.6,136.8,1950.3,2077.7 -1.8289365478298067,1.7292316885418395,0.39269908169872414,1474.4,392.3,172.9,173.5,2380.1,2263.0 -1.8289117571084248,1.729206257436661,0.5235987755982988,1344.4,276.7,149.0,271.3,1988.9,1861.2 -1.8289045154658985,1.7291891242109367,0.6544984694978736,1083.7,210.1,151.0,616.6,1742.6,1683.5 -1.828894016754291,1.7291491262167014,0.7853981633974483,1063.3,170.9,170.3,1698.9,1651.6,1651.2 -1.8288950427394435,1.7291449758465667,0.916297857297023,619.4,150.9,209.7,1741.7,1683.3,1742.2 -1.828905566709815,1.7291124571520897,1.0471975511965976,272.7,149.4,276.7,1936.8,1859.7,1986.6 -1.828928085960435,1.7290740068777104,1.1780972450961724,173.3,172.5,391.6,2371.3,1701.6,1480.9 -1.8289189784655944,1.7290816688244117,1.3089969389957472,136.7,250.1,629.2,1941.2,1343.4,1215.9 -1.8289267285370268,1.7290776428194796,1.4398966328953218,129.1,541.5,1369.9,1703.1,1163.1,1104.8 -1.8289933330725743,1.7290616837888728,1.5707963267948966,140.8,1729.1,1729.1,1621.1,1093.3,1093.2 -1.8289809171991744,1.7290603296029534,1.7016960206944713,171.6,1763.0,1821.7,1660.9,1105.6,541.4 -1.8289721981675164,1.729056557538755,1.832595714594046,229.5,1951.0,2078.7,1848.2,629.2,250.0 -1.8290237112164003,1.7290889610313611,1.9634954084936205,334.1,2381.6,2262.1,1632.6,391.6,172.5 -1.829038251874151,1.7291054979823945,2.0943951023931953,549.2,1986.6,1859.3,1294.7,276.7,149.4 -1.8290271769283082,1.7290826544729758,2.2252947962927703,1217.9,1742.0,1683.2,1126.0,209.7,150.9 -1.829031924444956,1.7291020223798101,2.356194490192345,1699.6,1651.5,1651.6,1062.5,170.3,170.8 -1.8290290431985539,1.7291291830691162,2.4870941840919194,1785.5,1684.0,1743.1,1083.9,150.9,210.0 -1.8290334535301074,1.7291172604686413,2.6179938779914944,2031.3,1861.1,1988.8,546.9,149.0,276.7 -1.8290214319389535,1.7291309769391177,2.748893571891069,2266.0,1697.3,1477.3,333.6,173.6,393.5 -1.8290317529570321,1.7291220059466192,2.8797932657906435,1846.8,1342.4,1215.1,229.7,251.1,630.9 -1.8290243516447635,1.7291257474159403,3.010692959690218,1661.1,1164.4,1105.5,172.2,538.8,1361.5 -1.8289673612853015,1.6288280032370142,0.0,1521.2,1092.9,1092.9,240.7,1728.9,1729.1 -1.8289867032466616,1.628826837205927,0.1308996938995747,1601.9,1105.9,916.2,232.5,1764.8,1824.0 -1.8290396253063799,1.6288422393222737,0.2617993877991494,1824.7,829.4,449.8,252.2,1950.0,2077.6 -1.829093197281756,1.6288749879374527,0.39269908169872414,1474.8,533.2,313.9,315.0,2341.1,2122.3 -1.8291351028415874,1.6289209522373158,0.5235987755982988,1203.0,392.2,264.5,470.3,1873.2,1745.6 -1.8291713965236462,1.6289848793363189,0.6544984694978736,1084.0,313.5,254.5,1002.0,1639.1,1580.0 -1.8291807171795866,1.6290296329675424,0.7853981633974483,1063.1,270.8,270.2,1699.0,1551.8,1551.2 -1.8291793027649812,1.62910583183344,0.916297857297023,1006.6,254.4,313.2,1741.7,1580.0,1638.3 -1.8291680522429468,1.6291452403730475,1.0471975511965976,472.5,264.9,392.3,1936.7,1744.1,1871.2 -1.829153722695991,1.6293860730010246,1.1780972450961724,315.1,313.7,532.8,2290.4,1701.8,1480.8 -1.8288085326224857,1.6289603601502733,1.3089969389957472,252.4,449.3,828.5,1825.5,1343.7,1216.0 -1.8288289885462743,1.6289503713134987,1.4398966328953218,232.7,931.0,1759.1,1599.4,1163.4,1105.0 -1.8289047041624233,1.6289330634495423,1.5707963267948966,240.9,1728.8,1728.5,1521.1,1093.4,1093.1 -1.8288990413044415,1.6289325913287116,1.7016960206944713,275.1,1762.6,1821.2,1556.9,1105.5,932.0 -1.8288956287103098,1.6289310523560179,1.832595714594046,345.1,1951.0,2078.3,1732.7,829.0,449.5 -1.8289513247731672,1.6289664503506296,1.9634954084936205,475.8,2340.1,2121.0,1633.2,533.0,313.9 -1.828968956332003,1.628986396410561,2.0943951023931953,748.9,1871.2,1744.1,1295.1,392.4,265.0 -1.8289599221182482,1.6289672311958308,2.2252947962927703,1604.7,1638.5,1579.6,1126.3,313.3,254.5 -1.8289658362471315,1.6289903480098218,2.356194490192345,1699.2,1551.2,1551.6,1062.3,270.4,270.9 -1.828963372747181,1.6290211298357393,2.4870941840919194,1785.0,1579.8,1638.8,1084.0,254.6,313.7 -1.828967392914842,1.6290126536463576,2.6179938779914944,2031.0,1745.2,1872.6,746.6,264.7,392.4 -1.8289543919529252,1.6290294755121941,2.748893571891069,2124.8,1697.7,1477.4,475.3,315.1,535.0 -1.8289630571848148,1.629023187924665,2.8797932657906435,1731.6,1343.0,1215.2,345.4,450.7,830.4 -1.828953499842545,1.6290290366131708,3.010692959690218,1557.5,1164.6,1105.5,275.8,925.5,1747.9 -1.8288932331149683,1.5287289511285298,0.0,1421.1,1093.2,1093.0,340.8,1728.9,1728.9 -1.8289103678932337,1.528728514842771,0.1308996938995747,1497.9,1106.1,1165.3,336.2,1764.5,1823.8 -1.8289613934980282,1.5287438789420693,0.2617993877991494,1709.0,1029.5,649.5,367.9,1949.9,2077.4 -1.829013417890993,1.5287760337568579,0.39269908169872414,1474.9,674.6,455.3,456.7,2200.4,1980.6 -1.8290541804419587,1.528820946876083,0.5235987755982988,1203.4,508.1,380.2,669.5,1757.9,1630.3 -1.8290899413230883,1.528883610152854,0.6544984694978736,1084.0,417.2,358.0,1387.3,1535.7,1476.5 -1.8290992340769436,1.5289269807512742,0.7853981633974483,1063.2,370.9,370.3,1698.9,1451.6,1451.0 -1.8290983834969003,1.529002026736686,0.916297857297023,1126.5,358.0,416.8,1741.6,1475.9,1534.8 -1.8290880846266024,1.5290406284131417,1.0471975511965976,672.5,380.6,507.8,1936.4,1628.0,1755.4 -1.82907486852427,1.5290609340399322,1.1780972450961724,457.1,454.9,673.9,2148.6,1807.4,1481.3 -1.8290204269788866,1.529112401335123,1.3089969389957472,368.1,648.8,1027.8,1709.3,1343.9,1216.2 -1.8289768396962658,1.5291369674491837,1.4398966328953218,336.2,1320.8,1763.6,1496.0,1163.4,1105.0 -1.8289898478972089,1.5291341449714222,1.5707963267948966,340.9,1729.1,1728.5,1421.2,1093.5,1093.0 -1.8289271021476714,1.529131884856177,1.7016960206944713,378.6,1763.0,1821.4,1453.2,1105.5,1163.9 -1.8288734523877412,1.5291152202826814,1.832595714594046,460.9,1950.8,2078.7,1616.6,1028.4,649.1 -1.828887457966131,1.5291245934237387,1.9634954084936205,617.6,2198.8,1979.6,1655.4,674.2,455.1 -1.828874287991458,1.529111575219161,2.0943951023931953,948.5,1755.5,1627.9,1294.9,507.9,380.6 -1.828845715811238,1.5290559858301243,2.2252947962927703,1742.2,1535.0,1476.3,1126.1,416.8,357.9 -1.8288428627164337,1.5290414828347976,2.356194490192345,1699.8,1451.2,1451.6,1062.4,370.5,371.0 -1.8288416267213141,1.5290363975824868,2.4870941840919194,1785.2,1476.5,1535.4,1083.8,358.1,417.3 -1.8288552008536239,1.5289964131664546,2.6179938779914944,2031.4,1629.7,1757.1,945.7,380.3,508.0 -1.8288584400442016,1.5289871870469245,2.748893571891069,1983.2,1810.3,1477.8,616.6,456.5,676.4 -1.8288876659051316,1.5289616047160661,2.8797932657906435,1615.7,1342.7,1215.1,461.0,650.2,1029.9 -1.8289011124715215,1.5289551003187585,3.010692959690218,1453.8,1164.4,1105.6,379.2,1312.4,1763.9 -1.8288686393002351,1.4286758388712428,0.0,1321.2,1092.9,1093.1,440.7,1729.2,1729.0 -1.8289457046630502,1.429307914638556,0.1308996938995747,1394.4,1106.1,1165.4,439.8,1764.8,1823.9 -1.8289224529207766,1.429300137036482,0.2617993877991494,1593.8,1215.5,848.6,483.5,1950.6,2078.3 -1.8288890541537115,1.4292783728814071,0.39269908169872414,1474.3,815.5,596.3,598.6,2057.8,1838.6 -1.8288599580885108,1.4292479197999564,0.5235987755982988,1202.9,623.4,495.9,869.2,1641.6,1513.9 -1.828849760448935,1.4292247830012914,0.6544984694978736,1083.9,520.5,461.5,1774.8,1432.0,1372.9 -1.8288381242238405,1.429178574643939,0.7853981633974483,1063.3,470.8,470.3,1699.1,1351.7,1351.1 -1.8288395187295705,1.4291685092328936,0.916297857297023,1126.6,461.5,520.2,1741.9,1373.0,1431.7 -1.8288517917850726,1.4291307476018846,1.0471975511965976,871.3,496.0,623.3,1937.3,1512.8,1640.6 -1.8288771476599834,1.4290881382259286,1.1780972450961724,598.3,596.0,815.2,2006.6,1701.0,1480.6 -1.8288714430744692,1.42909267363288,1.3089969389957472,483.5,848.2,1227.4,1593.9,1343.4,1215.6 -1.828882951935791,1.4290865042953176,1.4398966328953218,439.4,1711.9,1763.6,1369.8,1162.9,1104.7 -1.8289534686471474,1.429069670977949,1.5707963267948966,440.8,1729.1,1728.5,1321.4,1093.3,1093.1 -1.8289447101188903,1.4290683227124803,1.7016960206944713,481.9,1763.1,1821.3,1350.1,1105.7,1164.0 -1.8289393279133794,1.4290652411741442,1.832595714594046,576.4,1951.4,2079.0,1501.8,1215.6,847.5 -1.828993685462648,1.4290991759956266,1.9634954084936205,759.3,2057.5,1838.1,1673.9,814.7,595.7 -1.8290104010966775,1.4291177978366107,2.0943951023931953,1148.8,1639.9,1512.7,1295.0,623.2,495.9 -1.829000886997809,1.4290972183064776,2.2252947962927703,1741.8,1431.6,1372.5,1126.3,520.1,461.4 -1.829006491424348,1.4291190401561025,2.356194490192345,1699.6,1351.1,1351.6,1062.6,470.2,470.8 -1.8290036791758593,1.4291487092451882,2.4870941840919194,1785.2,1373.0,1432.5,1083.9,461.6,520.7 -1.829007649699348,1.4291389857354688,2.6179938779914944,2031.7,1514.1,1642.0,1177.5,495.9,623.7 -1.8289944884330174,1.4291546313650647,2.748893571891069,1841.4,1697.0,1477.1,757.6,598.0,817.9 -1.8290034115763385,1.4291470556700447,2.8797932657906435,1500.2,1342.2,1214.9,576.4,849.9,1229.8 -1.8289943641791109,1.4291516595686793,3.010692959690218,1350.3,1164.4,1105.6,482.6,1701.4,1763.4 -1.8289354883744728,1.328852328963415,0.0,1221.3,1093.1,1093.0,540.7,1728.7,1729.0 -1.8289534658078146,1.3288509750720627,0.1308996938995747,1291.1,1105.8,1165.6,543.2,1764.9,1824.3 -1.8290054089791423,1.3288659018193476,0.2617993877991494,1478.4,1215.3,1047.6,599.0,1950.3,2160.8 -1.8290583200754407,1.3288980011213198,0.39269908169872414,1474.4,956.5,737.3,739.9,1917.1,1697.8 -1.8290999009340851,1.3289432651319706,0.5235987755982988,1203.1,739.1,611.4,1068.4,1526.0,1398.6 -1.829136018507166,1.3290064490633116,0.6544984694978736,1210.1,624.1,565.0,1785.5,1328.3,1269.5 -1.829145469235258,1.3290506016951902,0.7853981633974483,1063.2,570.7,570.3,1698.8,1251.8,1251.3 -1.829144225832642,1.3291262381351896,0.916297857297023,1126.5,565.0,623.8,1741.7,1269.3,1328.1 -1.8291332397317595,1.3293515053869256,1.0471975511965976,1070.9,611.7,738.9,1937.0,1397.4,1524.9 -1.829113733622459,1.3291964410210622,1.1780972450961724,740.1,737.3,956.5,1864.7,1698.0,1480.6 -1.82906442845255,1.3292420218384917,1.3089969389957472,599.1,1047.6,1426.9,1478.3,1343.2,1215.9 -1.8290215934899277,1.3292650410751807,1.4398966328953218,543.1,1821.8,1763.3,1289.2,1163.3,1104.9 -1.8290338371859831,1.3292616814961769,1.5707963267948966,540.9,1728.8,1728.7,1221.1,1093.3,1093.2 -1.828970029125581,1.3292586171923308,1.7016960206944713,585.5,1763.0,1821.6,1246.5,1105.3,1164.1 -1.8289155616570392,1.3292407766764773,1.832595714594046,692.0,1951.5,2158.6,1385.9,1215.3,1046.8 -1.8289290019214264,1.3292491671434106,1.9634954084936205,901.1,1916.0,1697.2,1632.7,956.0,736.9 -1.8289154477496474,1.329235371386055,2.0943951023931953,1348.6,1524.3,1397.1,1294.2,738.8,611.6 -1.8288867239505933,1.3291789639818696,2.2252947962927703,1742.0,1305.5,1269.4,1126.1,623.6,565.0 -1.828883720889621,1.3291637740386872,2.356194490192345,1699.2,1251.3,1251.7,1062.3,570.3,570.8 -1.8288821530804076,1.329158150812689,2.4870941840919194,1785.4,1269.4,1328.7,1084.0,565.1,624.3 -1.8288955517641352,1.3291174424218752,2.6179938779914944,2136.9,1398.8,1526.7,1203.2,611.5,739.4 -1.8288984151473784,1.329107481444108,2.748893571891069,1699.9,1697.0,1477.0,899.1,739.4,959.5 -1.8289275926812134,1.329080961678774,2.8797932657906435,1384.7,1342.2,1215.0,691.8,1049.4,1429.5 -1.8289411931311872,1.3290734608344996,3.010692959690218,1247.0,1164.4,1105.5,586.1,1822.4,1763.6 -1.828909634992967,1.228794640398451,0.0,1121.4,1093.0,1093.2,640.6,1728.9,1729.1 -1.8289648901620406,1.2293414113187637,0.1308996938995747,1187.3,1106.0,1165.3,646.9,1764.5,1824.0 -1.8289336128056983,1.2293310930600394,0.2617993877991494,1362.5,1215.0,1247.4,714.6,1950.2,2077.7 -1.8288547085864757,1.2292845247320356,0.39269908169872414,1550.0,1097.9,878.8,881.8,1775.7,1556.7 -1.828843928546873,1.229273769782005,0.5235987755982988,1202.9,854.6,727.1,1268.0,1410.3,1282.8 -1.8288349635131718,1.229253081398084,0.6544984694978736,1083.9,727.8,668.7,1785.0,1224.7,1165.9 -1.8288221678681718,1.229202242463721,0.7853981633974483,1063.0,670.9,670.2,1698.7,1151.8,1151.2 -1.8288236939974039,1.2291855058554795,0.916297857297023,1126.6,668.4,727.2,1741.7,1165.8,1224.5 -1.8288379072336107,1.2291410263372549,1.0471975511965976,1294.6,727.1,854.4,1937.3,1282.1,1409.1 -1.8288667238774894,1.229092617322078,1.1780972450961724,881.7,878.4,1097.3,1723.2,1556.6,1603.8 -1.8288655011913872,1.2290927819042636,1.3089969389957472,714.5,1246.9,1626.3,1363.0,1343.6,1215.6 -1.8288821239807969,1.229083767509025,1.4398966328953218,646.3,1821.6,1763.2,1185.8,1163.2,1104.8 -1.8289579896553143,1.2290655676858606,1.5707963267948966,640.8,1728.9,1728.9,1121.3,1093.4,1093.1 -1.8289542715972205,1.2290642852743179,1.7016960206944713,688.9,1762.9,1821.1,1143.3,1105.5,1163.9 -1.8289533861884963,1.2290625193239055,1.832595714594046,807.6,1951.5,2079.0,1270.4,1215.2,1245.9 -1.829011504494047,1.2290987553905008,1.9634954084936205,1042.5,1775.0,1556.1,1563.4,1097.0,878.1 -1.829031004837739,1.229120321789384,2.0943951023931953,1547.9,1409.0,1281.7,1294.8,854.3,727.0 -1.8290232216086737,1.2291030455801997,2.2252947962927703,1741.8,1224.3,1165.6,1126.3,727.2,668.3 -1.8290295576427797,1.2291282757022945,2.356194490192345,1699.9,1151.2,1151.8,1062.5,670.3,670.8 -1.8290265710072715,1.229161158358516,2.4870941840919194,1785.5,1165.9,1225.0,1084.0,668.7,727.8 -1.8290295775344338,1.229154242331993,2.6179938779914944,2031.6,1283.3,1411.0,1203.0,727.1,854.8 -1.829014893342059,1.2291721494636199,2.748893571891069,1558.5,1559.5,1478.9,1040.3,880.8,1100.8 -1.8290219027250865,1.2291662092344038,2.8797932657906435,1243.7,1342.3,1214.8,807.3,1249.2,1628.8 -1.8290107660783328,1.2291718085248666,3.010692959690218,1143.2,1164.4,1105.5,689.6,1822.5,1763.4 -1.8289494129050585,1.1288706470139465,0.0,1021.5,1093.1,1093.0,740.9,1729.0,1729.2 -1.8289656543074668,1.1288691405423554,0.1308996938995747,1084.1,1105.8,1165.4,750.2,1765.0,1824.0 -1.8290163330404023,1.1288836088247836,0.2617993877991494,1247.1,1215.0,1342.8,830.1,2098.2,2005.6 -1.8290682916185206,1.1289150632855935,0.39269908169872414,1474.7,1238.9,1019.6,1023.4,1635.0,1415.6 -1.8291091667735697,1.1289595577596025,0.5235987755982988,1203.1,970.2,842.6,1466.7,1294.8,1167.4 -1.8291448408627098,1.129021932326404,0.6544984694978736,1083.8,831.2,772.1,1785.3,1121.4,1062.3 -1.8291540375726498,1.1290652345573138,0.7853981633974483,1063.3,770.7,770.3,1698.5,1051.7,1051.3 -1.8291527596414265,1.1291400711875066,0.916297857297023,1126.6,772.0,830.7,1741.7,1062.3,1121.2 -1.8291558896492102,1.1291329500016953,1.0471975511965976,1294.8,842.6,969.9,2018.4,1166.3,1293.8 -1.8291249715228501,1.1291802775599389,1.1780972450961724,1023.4,1019.6,1238.5,1581.8,1415.5,1480.6 -1.8290647612256514,1.1292358670579956,1.3089969389957472,830.3,1446.2,1825.1,1247.3,1343.5,1216.0 -1.8290215625841695,1.129258961055697,1.4398966328953218,749.8,1821.9,1763.4,1082.0,1163.2,1104.7 -1.829037745569461,1.1292545612296148,1.5707963267948966,740.8,1729.1,1728.7,1021.0,1093.4,1093.3 -1.828979020972754,1.1292515681161657,1.7016960206944713,792.5,1763.0,1821.0,1039.8,1105.5,1164.0 -1.8289295181006702,1.1292351865367432,1.832595714594046,923.2,2096.0,2003.7,1154.6,1215.1,1342.8 -1.828947232645673,1.1292462036581035,1.9634954084936205,1184.6,1633.9,1414.8,1421.4,1238.1,1019.2 -1.8289368732225606,1.1292357972105482,2.0943951023931953,1747.9,1293.3,1166.1,1294.7,969.6,842.4 -1.8289101483481551,1.1291831938909778,2.2252947962927703,1742.1,1120.9,1062.2,1126.0,830.6,771.9 -1.8289079987713837,1.1291719340913873,2.356194490192345,1699.5,1051.3,1052.0,1062.5,770.3,770.9 -1.8289062389645416,1.1291700250361605,2.4870941840919194,1785.5,1062.5,1121.4,1083.8,772.3,831.3 -1.8289357601887528,1.129077204079361,2.6179938779914944,2025.4,1167.7,1295.4,1202.9,842.6,970.5 -1.828915855516486,1.1291036142133948,2.748893571891069,1417.2,1417.8,1477.1,1181.8,1022.1,1242.2 -1.8289694785115556,1.129055667332541,2.8797932657906435,1128.3,1342.4,1215.1,922.9,1448.5,1828.2 -1.8289544269728224,1.1290632543868133,3.010692959690218,1039.8,1164.2,1105.6,793.2,1822.7,1763.9 -1.7289471862640815,1.8292453575967995,0.0,1721.2,1193.0,1192.9,40.8,1629.0,1628.9 -1.7289659957808643,1.8285581755849283,0.1308996938995747,1808.7,965.0,149.2,25.6,1660.9,1720.7 -1.7290246940897984,1.8285770797401213,0.2617993877991494,2055.7,431.0,51.4,21.4,1834.8,1962.4 -1.7290777082477984,1.8286112274095607,0.39269908169872414,1616.2,251.2,31.9,32.1,2291.7,2403.7 -1.7291175612910545,1.8286567190459562,0.5235987755982988,1319.0,161.3,59.0,72.4,2104.1,1976.7 -1.7291520475322657,1.8287189835533368,0.6544984694978736,1187.6,106.7,47.6,231.8,1845.9,1787.1 -1.72916042560731,1.8287613852723925,0.7853981633974483,1163.2,71.1,70.5,1598.8,1751.6,1750.8 -1.7291591576123881,1.8288351505965112,0.916297857297023,233.2,47.7,106.5,1638.1,1786.4,1845.7 -1.7288326323646575,1.8288639558455086,1.0471975511965976,73.3,34.1,161.6,1822.1,1975.5,2102.8 -1.728850498181515,1.8288353540376232,1.1780972450961724,31.9,31.7,251.1,2262.4,1842.0,1621.0 -1.7288447383613335,1.8288414039986307,1.3089969389957472,21.3,51.3,431.0,2055.3,1458.5,1330.9 -1.7288599096824393,1.828834493499125,1.4398966328953218,25.9,153.2,984.4,1805.8,1266.6,1208.2 -1.7289353103559675,1.8288182915206859,1.5707963267948966,41.1,1628.5,1628.8,1720.6,1193.3,1193.1 -1.728931012103025,1.828818640709999,1.7016960206944713,68.4,1659.7,1718.0,1764.0,977.9,151.9 -1.7289292759766388,1.828817853743125,1.832595714594046,114.3,1836.3,1964.0,1964.6,429.6,51.0 -1.72898618774723,1.8288549028583418,1.9634954084936205,192.9,2289.3,2401.1,1772.7,250.5,31.7 -1.7290043706779048,1.828876835051776,2.0943951023931953,350.7,2101.0,1974.0,1409.6,161.2,34.1 -1.7289957374979885,1.82885905986953,2.2252947962927703,834.2,1844.9,1786.2,1229.1,106.2,47.6 -1.7290017155118853,1.8288834570218588,2.356194490192345,1599.7,1750.9,1751.6,1162.4,70.4,71.1 -1.7289987571495185,1.8289156422160797,2.4870941840919194,1681.9,1787.0,1846.5,825.0,47.6,106.8 -1.7290026679719142,1.8289080659368473,2.6179938779914944,1916.6,1977.3,2105.3,347.4,33.6,161.5 -1.7289888548941479,1.8289259871376393,2.748893571891069,2374.0,1837.3,1617.1,192.1,32.5,252.8 -1.7289971354343252,1.8289205247782168,2.8797932657906435,1961.6,1457.6,1330.1,114.2,52.1,432.7 -1.7289870018965359,1.8289271640207898,3.010692959690218,1763.7,1267.6,1208.9,68.7,152.9,978.3 -1.7289264212314321,1.728626441823602,0.0,1621.4,1192.6,1193.4,140.8,1629.0,1628.6 -1.7289427630855816,1.728626784125149,0.1308996938995747,1705.4,1209.8,531.4,129.1,1661.3,1720.9 -1.7289930140254386,1.7286427224787606,0.2617993877991494,1941.1,629.3,250.3,136.9,1835.2,1962.8 -1.7290441465162822,1.728675207096015,0.39269908169872414,1614.8,391.9,172.9,173.8,2302.7,2260.9 -1.729084198639157,1.7287202592750062,0.5235987755982988,1363.2,276.6,149.1,272.0,1987.8,1860.4 -1.7291189394128283,1.7287825309904932,0.6544984694978736,1187.3,210.1,151.1,619.2,1742.3,1683.4 -1.7291278833299284,1.7288255535273322,0.7853981633974483,1163.5,170.9,170.5,1598.3,1651.5,1651.0 -1.7291266215929955,1.728899804381578,0.916297857297023,618.2,151.1,210.0,1638.2,1683.3,1742.3 -1.729116343377824,1.7289375897779746,1.0471975511965976,272.8,149.7,277.2,1847.1,1860.1,1987.5 -1.7291037034204115,1.7289577032177232,1.1780972450961724,173.5,173.0,392.4,2231.3,1842.3,1621.3 -1.7290498089375839,1.729008939895241,1.3089969389957472,136.9,250.9,630.6,1939.8,1458.5,1444.4 -1.7290067860004459,1.7290331839770108,1.4398966328953218,129.4,544.2,1375.1,1702.2,1266.3,1208.0 -1.7290203964348094,1.7290311367649613,1.5707963267948966,141.1,1628.8,1628.7,1620.8,1193.3,1193.2 -1.728957957914487,1.729029558902904,1.7016960206944713,172.0,1659.5,1718.1,1660.6,1209.2,540.8 -1.7289044720470228,1.7290131207513069,1.832595714594046,230.0,1836.0,1963.9,1848.8,628.9,250.2 -1.7289182994663186,1.7290231586372409,1.9634954084936205,334.8,2304.3,2260.7,1772.5,391.6,172.8 -1.7289046469626141,1.7290108618291211,2.0943951023931953,550.6,1985.3,1858.5,1409.7,276.8,149.7 -1.7288758248007916,1.7289553158667164,2.2252947962927703,1222.4,1741.1,1682.6,1229.4,209.8,151.2 -1.7288727747335197,1.7289407187955093,2.356194490192345,1599.5,1650.6,1651.5,1162.2,170.4,171.2 -1.7288711613206185,1.7289357249242265,2.4870941840919194,1682.2,1683.9,1742.6,1187.5,151.1,210.3 -1.728884999684792,1.7288955226482359,2.6179938779914944,1916.6,1861.7,1989.4,546.5,149.3,277.2 -1.728888069122801,1.728886462895939,2.748893571891069,2264.0,1837.4,1617.8,333.4,174.0,394.2 -1.7289176624552622,1.7288610316220656,2.8797932657906435,1846.1,1457.6,1330.0,229.8,251.8,632.3 -1.7289313686446472,1.7288548891275073,3.010692959690218,1660.6,1267.6,1208.9,172.2,540.9,1365.9 -1.7288995251565493,1.6285757620255898,0.0,1521.0,1192.9,1193.3,240.8,1628.9,1629.0 -1.7289444751814955,1.629281147155995,0.1308996938995747,1602.1,1209.6,915.6,232.6,1661.2,1720.7 -1.7289178673575945,1.6292723687043131,0.2617993877991494,1824.9,828.9,449.7,252.5,1835.1,1962.2 -1.7288863000115224,1.6292517619085403,0.39269908169872414,1615.2,533.1,314.0,315.3,2239.6,2120.7 -1.728859795763695,1.6292240573715153,0.5235987755982988,1318.8,392.1,264.5,470.8,1872.7,1745.2 -1.7288514760936586,1.629204400681719,0.6544984694978736,1187.3,313.5,254.5,1003.7,1639.1,1579.9 -1.7288408166096423,1.629162026557386,0.7853981633974483,1163.2,270.8,270.3,1598.7,1551.4,1551.5 -1.7288421454093545,1.629155612499412,0.916297857297023,1005.2,254.4,313.3,1638.1,1579.7,1638.8 -1.7288534871679704,1.629121155628807,1.0471975511965976,472.0,265.0,392.4,1821.9,1744.1,1871.7 -1.7288772490711608,1.629081372329898,1.1780972450961724,314.9,313.8,533.0,2230.9,1949.4,1622.0 -1.7288694521546326,1.6290880011271383,1.3089969389957472,252.2,449.7,829.2,1825.0,1458.9,1331.4 -1.7288785613684912,1.629083155637315,1.4398966328953218,232.5,932.4,1660.2,1599.6,1266.4,1208.2 -1.7289465710953893,1.62906704889718,1.5707963267948966,240.8,1629.2,1628.6,1521.3,1193.1,1193.2 -1.7289354288828407,1.6290657094422767,1.7016960206944713,275.1,1659.7,1718.1,1557.3,1209.0,929.7 -1.7289279259582104,1.6290619706462834,1.832595714594046,345.2,1835.9,1963.5,1733.0,827.6,448.9 -1.7289804967430553,1.6290948320410914,1.9634954084936205,476.0,2240.7,2120.0,1798.0,532.6,313.5 -1.7289958752171029,1.6291120935367303,2.0943951023931953,749.5,1870.7,1743.8,1410.2,392.0,264.9 -1.728985567469258,1.6290899206742715,2.2252947962927703,1607.7,1638.5,1579.6,1229.6,313.1,254.4 -1.7289908604417499,1.6291101083871253,2.356194490192345,1599.5,1551.1,1551.8,1162.4,270.2,270.9 -1.728988132074207,1.629138281467522,2.4870941840919194,1682.1,1580.1,1639.3,1187.7,254.5,313.7 -1.7289926190983806,1.6291272288042131,2.6179938779914944,1915.8,1746.0,1873.8,745.5,264.7,392.4 -1.7289801599930754,1.6291418521788383,2.748893571891069,2123.7,1952.5,1618.5,474.7,315.2,535.2 -1.7289900159594094,1.629133535859895,2.8797932657906435,1731.3,1457.8,1330.5,345.1,450.8,831.1 -1.7289819592340805,1.629137706441329,3.010692959690218,1557.3,1267.8,1209.1,275.6,927.2,1660.2 -1.7289242988597853,1.5288392159113733,0.0,1421.4,1192.9,1193.1,340.6,1628.7,1629.0 -1.7289430825557879,1.528837970303269,0.1308996938995747,1498.4,1209.6,1269.3,336.1,1661.2,1720.4 -1.7289956045921473,1.5288531376196968,0.2617993877991494,1709.5,1028.1,648.8,367.8,1835.0,1962.3 -1.729048945348029,1.5288855513890092,0.39269908169872414,1615.6,674.2,455.1,456.8,2199.1,1979.6 -1.729090868938275,1.528931189238655,0.5235987755982988,1318.6,507.7,380.1,670.0,1757.2,1629.5 -1.7291271676305509,1.528994731373627,0.6544984694978736,1187.5,416.9,358.0,1389.6,1535.3,1476.6 -1.7291367740233536,1.5290392951130096,0.7853981633974483,1163.3,370.8,370.2,1598.3,1452.1,1451.1 -1.7291355492181806,1.5291152869562115,0.916297857297023,1230.2,357.9,416.8,1638.2,1476.3,1535.1 -1.7291245149599754,1.5291545804480364,1.0471975511965976,671.6,380.5,507.9,1821.7,1628.5,1756.0 -1.72911044758112,1.5291754581204955,1.1780972450961724,456.6,455.0,674.3,2147.9,1843.1,1622.0 -1.7290549785746605,1.5292269001058578,1.3089969389957472,367.8,649.0,1028.7,1709.2,1459.0,1331.1 -1.729010455749569,1.5292508394687596,1.4398966328953218,336.0,1322.9,1659.9,1496.0,1266.7,1208.2 -1.729022847001551,1.5292475704403217,1.5707963267948966,340.9,1628.9,1628.7,1420.9,1193.4,1193.1 -1.7289597563517334,1.5292445976094906,1.7016960206944713,378.6,1659.4,1718.2,1453.9,1209.1,1267.3 -1.728906119093108,1.5292269813382164,1.832595714594046,460.9,1836.0,1963.4,1617.1,1027.2,648.1 -1.7289202893649236,1.529235858486912,1.9634954084936205,617.8,2198.4,1979.1,1815.8,673.7,454.7 -1.7289072769793021,1.5292226993737805,2.0943951023931953,949.3,1755.3,1627.9,1410.1,507.6,380.4 -1.7288789540941496,1.5291669200024514,2.2252947962927703,1638.3,1534.9,1476.0,1229.4,416.6,357.8 -1.7288761766167824,1.5291523939015952,2.356194490192345,1599.5,1451.0,1451.6,1162.6,370.2,370.8 -1.7288746209600616,1.529147464284161,2.4870941840919194,1681.7,1477.0,1535.9,1187.3,358.1,417.1 -1.7288879501049135,1.5291073530575081,2.6179938779914944,1916.3,1630.1,1757.8,944.7,380.2,508.1 -1.728890526010633,1.5290979590192906,2.748893571891069,1982.5,1838.3,1618.1,616.2,456.5,676.6 -1.7289193785729762,1.5290718762878999,2.8797932657906435,1615.4,1457.7,1330.7,460.7,650.4,1030.6 -1.7289325640766238,1.5290646950025646,3.010692959690218,1453.8,1268.0,1209.1,379.1,1314.8,1660.1 -1.7289005160881628,1.428785446808687,0.0,1321.3,1193.0,1193.0,440.7,1629.2,1629.0 -1.7289555636046936,1.429338217394077,0.1308996938995747,1394.8,1209.5,1269.0,439.8,1661.1,1743.2 -1.728924620866978,1.4293279915870005,0.2617993877991494,1593.5,1227.9,848.5,483.5,1834.7,1962.7 -1.7288870249729473,1.4293035262540827,0.39269908169872414,1615.6,815.6,596.3,598.7,2058.1,1838.8 -1.7288553645353364,1.429270254694954,0.5235987755982988,1318.9,623.4,495.8,869.2,1641.7,1514.2 -1.7288436548446406,1.4292442491808983,0.6544984694978736,1187.3,520.7,461.6,1681.6,1431.9,1372.8 -1.7288313589649744,1.4291951758924286,0.7853981633974483,1163.2,470.8,470.3,1598.8,1351.6,1351.1 -1.7288328159701785,1.4291824255701129,0.916297857297023,1229.8,461.4,520.3,1638.4,1372.8,1431.4 -1.7288457761633305,1.4291422606568314,1.0471975511965976,871.2,496.0,623.4,1821.4,1513.3,1640.4 -1.728872313650792,1.4290976642168531,1.1780972450961724,598.2,596.1,815.3,2006.5,1838.9,1622.2 -1.7288681074700627,1.4291006953733287,1.3089969389957472,483.4,848.2,1227.6,1593.7,1459.0,1331.2 -1.7288813233233322,1.4290935116837031,1.4398966328953218,439.4,1711.8,1660.1,1392.4,1266.6,1208.3 -1.7289536409613815,1.4290761873489117,1.5707963267948966,440.8,1628.8,1628.9,1321.3,1193.2,1193.1 -1.7289465914551707,1.4290748152270396,1.7016960206944713,482.0,1659.6,1718.2,1350.2,1209.1,1267.4 -1.7289427569217772,1.4290721141709837,1.832595714594046,576.4,1835.7,1963.6,1501.8,1226.2,847.2 -1.7289984232177849,1.429233026569821,1.9634954084936205,759.3,2057.2,1838.3,1773.6,814.7,595.7 -1.7290221507355266,1.4291305118073894,2.0943951023931953,1148.7,1639.7,1512.8,1410.1,623.1,495.9 -1.7290110129727985,1.4291068751418217,2.2252947962927703,1637.9,1431.6,1372.7,1229.6,520.1,461.3 -1.7290167214438128,1.4291291018934256,2.356194490192345,1599.2,1351.5,1351.9,1162.4,470.2,470.8 -1.7290138346449526,1.429160322900259,2.4870941840919194,1682.1,1372.9,1432.2,1187.4,461.5,520.7 -1.7290172544053906,1.4291522952777416,2.6179938779914944,1915.7,1514.7,1642.2,1143.9,495.9,623.6 -1.7290030930888831,1.4291694288704802,2.748893571891069,1841.4,1838.2,1618.3,757.6,598.0,818.1 -1.729010750929535,1.4291629463778097,2.8797932657906435,1500.0,1458.1,1330.4,576.3,850.0,1230.0 -1.729000297122015,1.4291682167388369,3.010692959690218,1350.4,1267.6,1209.1,482.5,1701.7,1660.3 -1.728939777081057,1.328867632632496,0.0,1221.4,1193.1,1193.1,540.6,1629.0,1628.7 -1.7289565870837156,1.3288661547363452,0.1308996938995747,1291.3,1209.5,1269.0,543.2,1660.9,1720.4 -1.7290076859870664,1.328880750505343,0.2617993877991494,1478.5,1331.0,1047.6,599.0,1834.8,2117.2 -1.7290599731826746,1.328912393529457,0.39269908169872414,1691.9,956.6,737.4,740.2,1917.2,1697.7 -1.7291011184713718,1.328957129600125,0.5235987755982988,1318.5,739.0,611.3,1068.2,1526.3,1398.5 -1.7291369584833747,1.3290197555653551,0.6544984694978736,1187.4,624.1,565.1,1681.7,1328.7,1269.7 -1.7291462850929116,1.3290633531711864,0.7853981633974483,1163.4,570.8,570.3,1598.7,1251.8,1251.3 -1.7291450362588539,1.329138461277219,0.916297857297023,1230.2,564.9,623.7,1638.3,1269.6,1328.2 -1.7291341548948924,1.3291769366152986,1.0471975511965976,1070.9,611.6,738.9,1821.7,1397.4,1524.7 -1.7291203727179607,1.3291970354179812,1.1780972450961724,740.0,737.2,956.3,1864.9,1697.8,1744.7 -1.7290653445097224,1.3292478650183357,1.3089969389957472,599.0,1047.7,1427.0,1478.4,1459.0,1331.5 -1.7290213771816556,1.3292713867903516,1.4398966328953218,542.9,1718.2,1659.9,1288.9,1266.7,1208.3 -1.729034388928588,1.3292677720270252,1.5707963267948966,540.9,1628.8,1628.6,1221.3,1193.2,1193.2 -1.7289719407069228,1.3292646734833862,1.7016960206944713,585.6,1659.4,1717.8,1246.7,1209.0,1267.5 -1.7289189044901863,1.3292471803859565,1.832595714594046,692.0,1835.6,2115.1,1386.0,1330.6,1046.8 -1.7289336128196955,1.329256295406265,1.9634954084936205,901.2,1916.3,1697.1,1704.9,956.1,737.0 -1.7289210209694434,1.3292434772807167,2.0943951023931953,1348.5,1524.6,1396.9,1410.1,738.7,611.5 -1.7288929198616694,1.3291881717512282,2.2252947962927703,1638.6,1327.8,1269.5,1229.5,623.6,564.9 -1.728890192929002,1.329174138864559,2.356194490192345,1599.7,1251.2,1251.8,1162.5,570.3,570.9 -1.7288885653062085,1.329169628226984,2.4870941840919194,1681.7,1269.4,1328.7,1187.3,565.2,624.4 -1.7289016387314415,1.3291298811436527,2.6179938779914944,1916.2,1399.2,1526.8,1318.7,611.5,739.2 -1.728903948459251,1.3291206992532216,2.748893571891069,1699.9,1700.8,1620.1,899.0,739.4,959.5 -1.7289324519332752,1.3290947229825192,2.8797932657906435,1384.6,1457.9,1330.8,691.6,1049.6,1429.5 -1.7289453170807263,1.3290875324520766,3.010692959690218,1246.9,1268.0,1209.1,586.1,1718.8,1660.1 -1.728912927487925,1.2288080726204251,0.0,1121.3,1192.8,1192.9,640.7,1628.8,1629.0 -1.7289663815046106,1.2293440736277774,0.1308996938995747,1187.4,1209.3,1268.8,646.9,1661.2,1720.4 -1.728934428323171,1.2293335410226782,0.2617993877991494,1362.4,1330.8,1247.4,714.6,1834.6,1962.2 -1.7288960797532282,1.2293086333057062,0.39269908169872414,1615.6,1097.9,878.7,881.9,1776.1,1556.6 -1.7288638449069318,1.2292748139745755,0.5235987755982988,1318.5,854.7,727.1,1267.7,1410.8,1282.7 -1.7288517759824475,1.2292482258001822,0.6544984694978736,1187.5,727.7,668.6,1681.6,1224.8,1166.0 -1.7288392507075763,1.229198510059447,0.7853981633974483,1163.1,670.8,670.3,1598.9,1151.8,1151.0 -1.728840400825548,1.2292312430886403,0.916297857297023,1230.2,668.5,727.4,1638.3,1165.6,1224.9 -1.7288626270318312,1.2291606370008834,1.0471975511965976,1270.5,727.2,854.3,1821.4,1282.0,1409.3 -1.728892982781104,1.2291098425282403,1.1780972450961724,881.7,878.2,1097.4,1723.2,1556.4,1622.1 -1.7288884227669192,1.2291131522272756,1.3089969389957472,714.6,1246.7,1626.1,1362.8,1459.0,1331.4 -1.728899200775355,1.2291072687821463,1.4398966328953218,646.4,1718.3,1659.9,1185.8,1266.5,1208.1 -1.728968254734781,1.2290906331347626,1.5707963267948966,640.8,1629.1,1628.8,1121.4,1193.2,1193.1 -1.7289579379022242,1.2290891345016095,1.7016960206944713,688.8,1659.2,1718.1,1143.5,1209.0,1267.8 -1.728951119824297,1.229085574842971,1.832595714594046,807.6,1835.6,1963.6,1270.2,1330.6,1246.0 -1.7290042803499648,1.2291187072392216,1.9634954084936205,1043.0,1774.8,1556.2,1563.4,1097.0,877.9 -1.7290201103349556,1.2291363361293488,2.0943951023931953,1548.1,1408.9,1281.6,1410.3,854.2,726.9 -1.729009996741133,1.2291147096460895,2.2252947962927703,1638.2,1224.5,1165.9,1229.5,727.2,668.4 -1.7290152866527961,1.2291354469332547,2.356194490192345,1599.8,1151.2,1151.7,1162.3,670.2,670.9 -1.729012164479904,1.229211088986635,2.4870941840919194,1681.8,1165.8,1225.1,1187.6,668.7,727.9 -1.7290256880197266,1.2291698651581997,2.6179938779914944,1966.8,1283.2,1410.9,1318.4,727.2,854.8 -1.7290166021376028,1.2291789233781898,2.748893571891069,1558.6,1559.2,1618.5,1040.5,880.7,1100.9 -1.7290253498079367,1.2291713616143092,2.8797932657906435,1269.1,1457.9,1330.8,807.3,1248.8,1628.9 -1.7290140637324505,1.2291770365357986,3.010692959690218,1143.4,1267.8,1209.0,689.6,1718.9,1659.8 -1.7289141943527622,1.1288653444669268,0.0,1021.4,1193.3,1192.8,740.6,1629.2,1628.7 -1.728955709073176,1.1288648248548463,0.1308996938995747,1084.1,1209.7,1269.0,750.3,1661.2,1720.4 -1.7290143026760412,1.1288817405829272,0.2617993877991494,1247.3,1330.9,1458.4,830.1,1834.7,1961.6 -1.7290686083166793,1.128914668025404,0.39269908169872414,1581.1,1239.0,1019.7,1023.5,1635.0,1415.5 -1.7291101540906864,1.1289598829032355,0.5235987755982988,1318.9,970.2,842.4,1466.8,1295.3,1167.4 -1.7291460168432191,1.1290226116359794,0.6544984694978736,1187.5,831.2,772.0,1681.4,1121.3,1062.4 -1.7291552571158721,1.1290661169139131,0.7853981633974483,1163.2,770.7,770.1,1598.7,1052.0,1051.3 -1.729153970448987,1.1291410928542884,0.916297857297023,1230.1,771.9,830.8,1638.2,1062.3,1120.9 -1.7291430858986345,1.1291794161650128,1.0471975511965976,1410.3,842.6,970.3,1821.3,1166.4,1293.8 -1.7291293261974758,1.129199329681953,1.1780972450961724,1023.5,1019.4,1238.5,1581.6,1415.4,1622.2 -1.729074378529496,1.1292500218613488,1.3089969389957472,830.4,1446.1,1825.3,1247.4,1459.2,1331.6 -1.7290305294832906,1.1292734739144987,1.4398966328953218,749.9,1718.5,1660.1,1081.8,1266.5,1208.2 -1.7290436724564426,1.129269771468627,1.5707963267948966,740.9,1628.9,1628.8,1021.3,1193.2,1193.3 -1.7289813625967232,1.1292666594479064,1.7016960206944713,792.4,1659.6,1717.9,1039.7,1208.9,1267.6 -1.7289284410331867,1.1292492433704195,1.832595714594046,923.1,1835.7,1960.0,1154.7,1330.7,1458.3 -1.7289432425688127,1.1292584358176923,1.9634954084936205,1184.8,1633.7,1415.0,1421.3,1238.2,1019.2 -1.728930712502076,1.1292457001420202,2.0943951023931953,1747.8,1293.3,1166.0,1410.0,969.8,842.6 -1.7289026054527843,1.129190518702743,2.2252947962927703,1638.3,1121.1,1062.2,1229.6,830.6,771.9 -1.728899833667648,1.1291765939529086,2.356194490192345,1599.5,1051.3,1051.8,1162.4,770.2,770.7 -1.7288981590107078,1.1291721419409777,2.4870941840919194,1681.9,1062.5,1121.4,1187.3,772.2,831.3 -1.728911135212256,1.1291324455637906,2.6179938779914944,1916.0,1167.5,1295.3,1318.6,842.7,970.6 -1.7289133967259855,1.1291232609666035,2.748893571891069,1417.3,1417.6,1618.6,1182.0,1022.2,1242.1 -1.7289418286159912,1.1290972741718535,2.8797932657906435,1153.6,1458.0,1330.5,923.0,1448.4,1828.3 -1.7289546480580327,1.1290900604297978,3.010692959690218,1039.7,1268.0,1209.0,793.1,1718.8,1660.4 -1.6289483436737064,1.8292489313910312,0.0,1721.5,1293.0,1292.8,40.8,1528.8,1528.7 -1.6289664235680588,1.8285533257786208,0.1308996938995747,1808.8,965.1,149.1,25.6,1557.6,1616.9 -1.6290255714268016,1.8285723780867689,0.2617993877991494,2055.3,431.1,51.4,21.4,1719.0,1846.4 -1.6289894265375873,1.8288531444245117,0.39269908169872414,1756.5,251.4,32.2,32.4,2097.4,2318.7 -1.6290616505414293,1.8278566785062165,0.5235987755982988,1437.3,164.3,35.3,74.4,2108.3,1979.2 -1.6293707512085078,1.8275293452981698,0.6544984694978736,1294.0,109.0,48.0,225.5,1849.7,1789.1 -1.628722991141441,1.8282261396568067,0.7853981633974483,1263.5,71.1,70.9,1498.5,1751.3,1751.1 -1.6287152639284386,1.8284606733818058,0.916297857297023,231.9,47.8,107.0,1534.9,1786.8,1846.6 -1.6287010715817625,1.8285124568520437,1.0471975511965976,73.7,34.4,162.2,1707.6,1976.4,2103.6 -1.628719539883865,1.8284861210239325,1.1780972450961724,63.4,32.2,252.0,2092.2,1981.7,1761.6 -1.6289826227871538,1.8287422997191956,1.3089969389957472,21.7,52.0,431.6,2055.0,1574.2,1446.7 -1.6292025081653856,1.8278109188858676,1.4398966328953218,27.5,158.9,987.7,1804.5,1369.8,1311.4 -1.6293283449836702,1.8283238127768888,1.5707963267948966,41.5,1529.0,1529.4,1720.6,1292.5,1292.9 -1.6293075411766145,1.828325915111732,1.7016960206944713,68.9,1557.1,1616.0,1764.3,972.3,151.6 -1.6293272926053368,1.8283335826508318,1.832595714594046,115.0,1722.9,1850.9,1965.6,428.5,95.0 -1.6293753499027102,1.8287436782430406,1.9634954084936205,194.5,2107.0,2329.6,1907.0,249.5,32.1 -1.6294739918725565,1.8269917679936702,2.0943951023931953,354.5,2098.4,1971.6,1524.0,163.3,36.3 -1.629093049122248,1.8280188953118395,2.2252947962927703,834.3,1844.7,1785.7,1333.2,107.2,48.4 -1.6291431053488397,1.8282491303434574,2.356194490192345,1499.6,1750.1,1750.6,1262.6,71.3,71.9 -1.62914352898606,1.8281782752700866,2.4870941840919194,1578.3,1785.8,1844.9,830.8,48.5,107.5 -1.6291538113829627,1.828152495652291,2.6179938779914944,1800.2,1975.6,2103.1,349.7,34.5,162.2 -1.6291384983281616,1.8281771552250636,2.748893571891069,2253.3,1980.5,1760.4,193.6,33.6,253.5 -1.6290561291942462,1.8282816364991685,2.8797932657906435,1960.6,1572.8,1445.5,115.1,53.7,434.2 -1.6292456802087392,1.8275338395528316,3.010692959690218,1762.1,1371.1,1312.1,70.7,160.0,984.5 -1.6291893310048358,1.7279314778549786,0.0,1620.6,1292.8,1292.9,141.6,1529.2,1529.3 -1.6291956013300846,1.7279371667503045,0.1308996938995747,1704.9,1313.2,534.0,129.9,1558.0,1617.5 -1.6292324002882168,1.7279543523056256,0.2617993877991494,1940.3,630.7,251.8,137.8,1719.9,1847.7 -1.629269800938007,1.727001371636952,0.39269908169872414,1755.4,392.9,174.0,175.0,2148.0,2259.8 -1.6293111213750997,1.728041488045879,0.5235987755982988,1433.5,277.5,150.0,273.6,1986.9,1859.1 -1.6293294003570877,1.7280806927653354,0.6544984694978736,1290.5,210.8,152.0,622.4,1741.0,1682.3 -1.6293321257986935,1.7281086617820574,0.7853981633974483,1262.9,171.6,171.3,1499.0,1650.6,1650.3 -1.6293296703499731,1.7281709878075568,0.916297857297023,620.8,151.8,210.8,1535.0,1682.6,1741.6 -1.6293221045358615,1.7281988425434867,1.0471975511965976,274.1,150.6,278.1,1707.1,1859.0,1986.8 -1.6293152827444548,1.728211637545893,1.1780972450961724,174.5,174.1,393.5,2121.8,2090.5,1762.5 -1.6292690049519236,1.7282587340904572,1.3089969389957472,137.7,252.4,632.4,1938.6,1573.4,1446.2 -1.6292342207483488,1.728282183659301,1.4398966328953218,130.1,547.4,1378.8,1701.3,1369.6,1311.0 -1.6292554280838019,1.7282826497653154,1.5707963267948966,141.9,1529.0,1529.1,1620.1,1292.9,1292.9 -1.6291986555296583,1.7282858975571043,1.7016960206944713,172.7,1556.8,1615.0,1659.8,1312.3,543.4 -1.6291484767402666,1.72827545641778,1.832595714594046,230.8,1721.1,1848.8,1847.7,630.1,251.6 -1.6291632196155712,1.7282916753822808,1.9634954084936205,335.9,2146.6,2258.5,1939.4,392.5,173.8 -1.6291485477577856,1.7282846833737806,2.0943951023931953,552.4,1984.5,1857.5,1524.4,277.5,175.9 -1.6291176950452344,1.7282329097489955,2.2252947962927703,1226.2,1740.5,1682.0,1332.4,210.5,151.9 -1.6291124923248381,1.7282205752099793,2.356194490192345,1499.9,1650.5,1650.8,1262.2,171.1,171.9 -1.6291093201320992,1.7282167733616796,2.4870941840919194,1579.0,1682.9,1742.3,1290.8,151.9,211.1 -1.6291227012024116,1.728177308145115,2.6179938779914944,1801.2,1860.7,1988.9,547.7,150.1,278.0 -1.6291262121985095,1.7281693696429976,2.748893571891069,2231.7,2094.2,1758.0,334.4,175.0,395.4 -1.6291568421438776,1.728145955337226,2.8797932657906435,1845.7,1572.8,1445.2,230.6,253.3,633.8 -1.6291714055770927,1.728142976702293,3.010692959690218,1659.7,1370.7,1312.2,172.9,544.0,1369.7 -1.6291392458125113,1.6278642777016277,0.0,1520.8,1292.7,1292.9,241.5,1529.0,1529.2 -1.6291012922816788,1.6288375521897105,0.1308996938995747,1600.8,1312.9,920.2,233.0,1557.5,1616.6 -1.6290684584483148,1.6288291321246002,0.2617993877991494,1823.5,831.3,451.1,252.7,1718.8,1846.3 -1.6290436414024594,1.6288156819522681,0.39269908169872414,1757.7,534.3,314.7,315.5,2158.5,2121.6 -1.6290243973370924,1.6287992714410229,0.5235987755982988,1434.7,392.9,265.1,470.7,1873.2,1745.5 -1.6290209940597336,1.628792641052695,0.6544984694978736,1290.8,314.1,254.9,1001.5,1639.1,1579.5 -1.629011654186207,1.6287630571992557,0.7853981633974483,1263.1,271.3,270.6,1499.2,1551.4,1550.9 -1.6290119336565851,1.628768661763698,0.916297857297023,1010.2,254.8,313.5,1534.5,1579.3,1638.2 -1.6290199885511263,1.628744869800007,1.0471975511965976,473.6,265.4,392.4,1705.5,1742.8,1870.0 -1.629038628068668,1.6287136838858702,1.1780972450961724,315.8,314.0,532.9,2088.1,1986.2,1764.9 -1.6290248592345105,1.6287275391097706,1.3089969389957472,252.7,449.6,828.4,1825.6,1575.2,1447.3 -1.6290271366771139,1.628728740165978,1.4398966328953218,232.9,930.7,1556.9,1599.3,1370.3,1311.6 -1.6290874382236706,1.6287162072635732,1.5707963267948966,241.1,1529.0,1528.7,1521.0,1293.1,1292.9 -1.6290684384628387,1.6287169475719225,1.7016960206944713,275.3,1555.9,1614.1,1556.6,1312.2,934.5 -1.629052935918112,1.6287139156633843,1.832595714594046,345.3,1719.6,1847.0,1731.7,830.1,450.4 -1.6290979745842291,1.6287449339965607,1.9634954084936205,475.9,2160.5,2121.5,1955.8,533.6,314.4 -1.6291070441260123,1.6287583117986681,2.0943951023931953,748.9,1871.3,1744.0,1526.3,392.9,265.4 -1.6290917564746048,1.6287312883379748,2.2252947962927703,1535.2,1638.7,1579.7,1332.9,313.6,254.8 -1.6290940954064632,1.6287455336508037,2.356194490192345,1499.6,1550.9,1551.4,1262.6,270.7,271.1 -1.6290910208254354,1.6287672023015238,2.4870941840919194,1578.1,1579.4,1638.5,1290.8,254.8,313.8 -1.6290968624275324,1.6287505662183892,2.6179938779914944,1799.8,1744.8,1872.4,747.6,265.0,392.5 -1.629088181724517,1.6287605478879061,2.748893571891069,2125.0,1981.2,1760.9,475.7,315.4,535.1 -1.6291024821113578,1.6287495716821296,2.8797932657906435,1731.6,1574.1,1446.5,345.8,451.0,830.2 -1.6290993499993534,1.6287530217086514,3.010692959690218,1557.1,1371.5,1312.7,276.1,925.4,1556.9 -1.6290463384803653,1.5284589184172674,0.0,1420.8,1292.9,1292.8,341.0,1528.9,1529.0 -1.6290682813137052,1.5284605563615972,0.1308996938995747,1497.4,1312.9,1372.3,336.4,1557.7,1616.2 -1.6291223929241716,1.52847879780139,0.2617993877991494,1708.1,1030.7,650.5,368.2,1718.9,1845.9 -1.6291760019807284,1.5285141617436562,0.39269908169872414,1757.9,675.4,455.9,456.9,2096.6,1980.8 -1.6292170643320747,1.5285621078208513,0.5235987755982988,1434.7,508.5,380.6,669.7,1757.7,1630.0 -1.6292524285700358,1.5286274023285538,0.6544984694978736,1291.0,417.6,358.4,1386.3,1535.7,1476.2 -1.6292607022818837,1.5286726642940316,0.7853981633974483,1263.0,371.2,370.6,1499.0,1451.4,1451.2 -1.6292588981614198,1.5287491101918778,0.916297857297023,1333.2,358.3,417.0,1534.5,1475.7,1534.3 -1.6292478036565854,1.5287887112059542,1.0471975511965976,673.4,380.9,507.9,1705.4,1627.5,1754.6 -1.6292339951987018,1.5288096972225884,1.1780972450961724,457.6,455.2,674.0,2087.8,1978.1,1765.3 -1.6291792771805635,1.5288620729056341,1.3089969389957472,368.5,648.8,1027.6,1710.2,1575.1,1447.7 -1.6291354640614475,1.5288879768265626,1.4398966328953218,336.5,1319.9,1556.8,1495.9,1370.4,1311.7 -1.6291479750565072,1.5288864729695413,1.5707963267948966,341.1,1529.2,1528.6,1420.5,1293.4,1292.9 -1.6290843458352355,1.528885772080329,1.7016960206944713,378.8,1555.9,1614.2,1453.1,1312.0,1370.6 -1.6290292362646983,1.5288707433054811,1.832595714594046,461.0,1719.4,1847.1,1616.0,1029.3,650.0 -1.6290413252836098,1.5288811235137862,1.9634954084936205,617.7,2097.7,1980.0,1916.1,674.9,455.5 -1.62902604583019,1.5288683681464907,2.0943951023931953,948.5,1755.8,1628.4,1526.1,508.5,381.0 -1.628995335563676,1.5288124717723242,2.2252947962927703,1535.3,1535.2,1476.2,1333.1,417.2,358.3 -1.6289907747964076,1.52879691762037,2.356194490192345,1499.6,1451.1,1451.3,1262.5,370.7,371.2 -1.6289886902206714,1.5287901978306209,2.4870941840919194,1577.9,1476.2,1534.9,1290.4,358.3,417.3 -1.6290021052546824,1.5287486220284627,2.6179938779914944,1799.6,1629.0,1756.6,946.9,380.5,508.0 -1.629006255441877,1.5287379857123318,2.748893571891069,1983.4,1981.0,1760.8,617.3,456.7,676.4 -1.6290368060457865,1.5287117157674759,2.8797932657906435,1616.0,1574.0,1446.4,461.4,650.2,1029.6 -1.629051855782847,1.5287053435316635,3.010692959690218,1453.7,1371.6,1312.5,379.5,1311.4,1557.0 -1.6290208649115387,1.4284276549492487,0.0,1320.9,1293.1,1292.8,441.1,1529.4,1528.9 -1.6290545741562936,1.429243253530558,0.1308996938995747,1394.3,1313.0,1372.1,439.7,1557.5,1616.9 -1.6290294389255744,1.429235212298655,0.2617993877991494,1593.1,1229.6,849.6,483.4,1719.0,1846.0 -1.6290012332042534,1.4292172475725244,0.39269908169872414,1831.7,816.3,596.7,598.3,2059.8,1839.9 -1.6289773998300772,1.4291933639441214,0.5235987755982988,1434.7,623.8,496.0,868.3,1642.6,1514.6 -1.6289708899264326,1.429178234949044,0.6544984694978736,1291.2,520.8,484.5,1578.6,1432.4,1373.3 -1.6289603353513085,1.4291401270366637,0.7853981633974483,1263.1,470.8,470.3,1498.7,1351.6,1351.0 -1.6289609919833796,1.4291378095785585,0.916297857297023,1333.3,461.4,520.1,1534.5,1372.7,1431.5 -1.6289707325087013,1.429106823098015,1.0471975511965976,872.5,495.9,623.0,1705.6,1512.4,1639.2 -1.6289921228637616,1.4290693038978874,1.1780972450961724,598.7,595.7,814.6,2007.6,1837.6,1884.7 -1.6289819194599058,1.4290776931121143,1.3089969389957472,483.6,847.2,1226.1,1594.6,1575.0,1447.3 -1.6289885944368894,1.4290743020333565,1.4398966328953218,439.6,1615.6,1556.8,1392.9,1370.2,1311.7 -1.629054107420888,1.4290583414835791,1.5707963267948966,440.8,1529.0,1528.8,1321.2,1293.2,1293.1 -1.6290407332476158,1.4290569557745383,1.7016960206944713,481.8,1555.7,1614.0,1349.8,1312.3,1370.5 -1.6290310706368463,1.429053277486752,1.832595714594046,576.0,1719.6,1847.3,1501.0,1227.9,848.4 -1.6290817467717091,1.4290853901433522,1.9634954084936205,758.8,2058.5,1839.4,1845.6,815.5,596.2 -1.6290955975074424,1.4291013991651695,2.0943951023931953,1147.2,1640.6,1513.2,1526.2,623.4,496.1 -1.629083790043242,1.4290781349122423,2.2252947962927703,1535.3,1431.7,1373.0,1333.2,520.3,461.4 -1.6290879472996433,1.4290969135177403,2.356194490192345,1499.6,1351.1,1351.6,1262.6,470.4,470.8 -1.6290848341318158,1.429123225673624,2.4870941840919194,1577.9,1372.8,1431.6,1290.7,461.5,520.6 -1.6290890133667528,1.429110566914323,2.6179938779914944,1799.4,1514.1,1642.0,1145.6,495.8,623.3 -1.62907731462042,1.4291234303501663,2.748893571891069,1842.6,1841.0,1888.4,758.2,597.6,817.4 -1.6290879581667284,1.4291138281180582,2.8797932657906435,1500.8,1574.1,1446.4,576.5,849.1,1228.5 -1.6290811001990801,1.429117132731791,3.010692959690218,1350.7,1371.5,1312.5,482.7,1615.9,1556.6 -1.6290246552822063,1.3288200950818734,0.0,1221.2,1292.9,1292.7,540.7,1529.2,1529.2 -1.629044476931932,1.3288189797945358,0.1308996938995747,1290.8,1313.1,1372.2,543.1,1557.6,1616.8 -1.6290977499211035,1.3288345993233277,0.2617993877991494,1477.4,1445.9,1048.9,598.8,1718.8,1845.7 -1.629151503618904,1.3288676760109173,0.39269908169872414,1757.8,957.5,737.9,739.6,1918.2,1699.0 -1.6291933139051409,1.3289139540719783,0.5235987755982988,1435.1,739.3,611.5,1067.1,1526.9,1398.9 -1.6292295453279582,1.3289782642966605,0.6544984694978736,1291.1,624.4,565.1,1578.2,1328.7,1269.6 -1.629238478927382,1.329023162852192,0.7853981633974483,1263.1,570.8,570.2,1498.7,1251.7,1250.9 -1.6292368066282312,1.3290995244291297,0.916297857297023,1333.0,564.9,623.6,1534.4,1269.2,1327.8 -1.6292252817936352,1.3291389808282945,1.0471975511965976,1072.2,611.5,738.5,1705.6,1397.0,1524.0 -1.629210641855396,1.32915945898504,1.1780972450961724,740.6,736.6,955.8,1866.1,1696.6,1765.3 -1.629154967811886,1.3292107089982648,1.3089969389957472,599.2,1046.3,1425.4,1479.1,1575.0,1447.7 -1.6291104482225205,1.3292348536653804,1.4398966328953218,543.1,1615.6,1556.6,1289.4,1370.4,1312.0 -1.6291228494623382,1.3292312417754202,1.5707963267948966,540.8,1528.9,1528.9,1221.3,1293.2,1293.0 -1.6290598442726982,1.3292283528011817,1.7016960206944713,585.4,1555.8,1614.1,1246.5,1312.4,1370.6 -1.62900609822176,1.3292114294216666,1.832595714594046,691.7,1720.0,1847.2,1385.3,1445.7,1047.8 -1.6290200670688804,1.329220656573114,1.9634954084936205,900.5,1917.2,1697.9,1703.8,956.8,737.5 -1.6290067655306597,1.3292076310556125,2.0943951023931953,1346.7,1525.0,1397.5,1525.9,739.2,611.6 -1.6289777388619469,1.3291522523707302,2.2252947962927703,1535.5,1328.0,1269.4,1333.2,623.8,587.7 -1.6289741813162442,1.3291378576194643,2.356194490192345,1499.6,1251.0,1251.8,1262.3,570.3,570.8 -1.6289721676316848,1.3291325518816417,2.4870941840919194,1578.1,1269.5,1328.2,1290.7,565.1,624.2 -1.6289848009498997,1.3290921210695035,2.6179938779914944,1799.7,1398.7,1525.8,1344.9,611.4,738.9 -1.6289874370709223,1.3290820441594473,2.748893571891069,1701.3,1699.7,1760.9,899.6,739.0,958.9 -1.6290162249582487,1.329055459456812,2.8797932657906435,1384.9,1574.0,1446.4,692.2,1048.3,1428.1 -1.6290296516964495,1.3290479050331472,3.010692959690218,1246.7,1371.4,1312.4,586.2,1615.6,1556.8 -1.6289977239918236,1.2287692006670792,0.0,1121.1,1292.9,1292.6,640.7,1529.2,1529.2 -1.6290383559147947,1.2293348282320844,0.1308996938995747,1187.0,1312.9,1372.1,646.8,1557.7,1616.4 -1.6290045827947124,1.2293238870672,0.2617993877991494,1362.4,1445.8,1248.4,714.6,1718.8,1919.2 -1.6289665043517236,1.22929946155057,0.39269908169872414,1721.7,1098.5,879.1,881.5,1776.8,1557.5 -1.6289346831663032,1.2292666651013553,0.5235987755982988,1434.8,855.2,727.2,1266.7,1411.2,1283.2 -1.628922969341203,1.2292414501217306,0.6544984694978736,1291.1,727.9,668.9,1578.6,1225.0,1166.0 -1.6289101579554581,1.2291929135455915,0.7853981633974483,1263.2,670.8,670.1,1498.7,1151.7,1151.3 -1.628911188516735,1.2291807212396306,0.916297857297023,1333.1,668.4,727.1,1534.4,1165.9,1224.3 -1.628923613339884,1.229140909403961,1.0471975511965976,1271.7,726.8,854.2,1705.7,1281.5,1408.8 -1.6289495009065362,1.2290961617197644,1.1780972450961724,882.1,878.1,1096.8,1724.3,1555.7,1764.7 -1.628944907018069,1.2290991182640083,1.3089969389957472,714.7,1245.6,1624.6,1363.3,1575.0,1447.4 -1.6289579009004225,1.2290920865269015,1.4398966328953218,646.5,1615.3,1556.8,1185.8,1370.2,1311.6 -1.6290300308837296,1.2290744262670874,1.5707963267948966,640.6,1529.0,1528.9,1121.4,1293.3,1293.2 -1.629022901660494,1.2290730012760358,1.7016960206944713,688.7,1556.0,1614.3,1142.9,1312.2,1370.6 -1.6290188921649202,1.2290706925285078,1.832595714594046,807.2,1719.5,1917.7,1269.9,1446.0,1246.9 -1.6290743629947197,1.2291055027753388,1.9634954084936205,1042.2,1776.3,1557.0,1562.8,1097.7,878.5 -1.6290918349608094,1.2291250963211735,2.0943951023931953,1546.3,1409.6,1281.8,1525.9,854.5,727.1 -1.6290824357863523,1.2291058398782884,2.2252947962927703,1535.0,1224.6,1166.0,1333.1,727.5,668.5 -1.6290877552060208,1.2291288579032105,2.356194490192345,1499.8,1151.4,1151.6,1262.6,670.3,670.7 -1.6290845633005104,1.2291593091976862,2.4870941840919194,1578.1,1166.0,1224.9,1290.9,668.6,727.5 -1.6290876956316962,1.2291502699756434,2.6179938779914944,1939.8,1282.8,1410.6,1433.8,726.9,854.6 -1.629074037158846,1.2291661389962183,2.748893571891069,1559.3,1558.2,1760.6,1041.2,880.3,1100.4 -1.6290822431268535,1.22915868305399,2.8797932657906435,1269.7,1574.2,1446.4,807.6,1247.9,1627.3 -1.6290726559178184,1.2291632639114307,3.010692959690218,1143.4,1371.6,1312.7,689.8,1615.6,1556.6 -1.6290130528029343,1.1288637561703343,0.0,1021.5,1293.1,1293.0,740.7,1529.2,1529.2 -1.6290306484435186,1.128862298992956,0.1308996938995747,1083.7,1312.8,1372.1,750.1,1557.4,1616.4 -1.6290823363063012,1.1288771728125002,0.2617993877991494,1246.5,1445.8,1447.7,829.9,1718.7,1846.6 -1.629134976895333,1.1289092690201254,0.39269908169872414,1580.3,1239.5,1020.1,1023.0,1635.3,1416.2 -1.629176095203575,1.1289544678130228,0.5235987755982988,1434.7,970.6,842.7,1465.5,1295.4,1167.8 -1.6292397728729069,1.1290738072224702,0.6544984694978736,1290.9,831.4,772.1,1578.3,1121.7,1062.5 -1.6292390247379025,1.1290756240204172,0.7853981633974483,1263.4,771.0,770.2,1498.8,1051.7,1051.3 -1.6292377809965986,1.1291411382156675,0.916297857297023,1333.3,771.8,830.7,1534.6,1062.0,1120.9 -1.6292263746863918,1.1291802735553964,1.0471975511965976,1515.6,842.3,969.5,1705.4,1166.0,1293.3 -1.6292102184194048,1.1292031788057302,1.1780972450961724,1024.1,1019.1,1237.7,1582.4,1414.6,1633.6 -1.6291518475845668,1.129256812389254,1.3089969389957472,830.5,1444.9,1719.4,1247.5,1575.1,1447.5 -1.6291040112214183,1.1292824952345588,1.4398966328953218,750.1,1615.1,1556.4,1082.2,1370.2,1311.3 -1.629112930524215,1.1292795202392014,1.5707963267948966,740.8,1529.2,1528.8,1021.3,1293.4,1292.9 -1.6290467025826827,1.1292763006349515,1.7016960206944713,792.4,1555.6,1614.0,1039.7,1312.6,1370.5 -1.6289901886153795,1.1292582211315407,1.832595714594046,922.9,1719.9,1847.1,1154.1,1445.9,1446.5 -1.6290019375629756,1.129265772084556,1.9634954084936205,1184.0,1634.8,1415.6,1420.4,1238.8,1019.7 -1.6289870683131218,1.129250779064539,2.0943951023931953,1705.9,1294.1,1166.3,1526.2,970.1,842.8 -1.6289779065358267,1.1292339524781778,2.2252947962927703,1535.4,1121.2,1062.2,1333.2,830.7,771.9 -1.6289670505445404,1.1291868870277728,2.356194490192345,1499.6,1051.3,1051.7,1262.4,770.3,771.0 -1.6289654714552873,1.1291726098203678,2.4870941840919194,1578.0,1062.2,1121.3,1290.7,772.1,831.1 -1.628978541488249,1.1291309636239109,2.6179938779914944,1799.7,1167.4,1294.9,1433.8,842.6,970.3 -1.6289805028269995,1.1291218567390349,2.748893571891069,1417.8,1417.0,1637.4,1182.5,1021.8,1241.4 -1.6290079375064592,1.1290964141383304,2.8797932657906435,1153.7,1574.1,1446.4,923.3,1447.2,1718.9 -1.629019636043696,1.1290896111476805,3.010692959690218,1039.9,1371.4,1312.8,793.2,1615.9,1557.0 diff --git a/tools/localisation_machine_learning/data/sectors.md b/tools/localisation_machine_learning/data/sectors.md deleted file mode 100644 index f93a7475..00000000 --- a/tools/localisation_machine_learning/data/sectors.md +++ /dev/null @@ -1,29 +0,0 @@ -# Why sectors ? - -The main problem of this localisation method is that for a global bach of data, severals positions can be computed with the same datas. To "solve" the problem, splitting the board into sectors is mandatory. - -## Sector 1 - -x in [0.0, 1.5] -y in [1.0, 2.0] - -## Sector 2 - -x in [0.0, 1.5] -y in [0.0, 1.0] - -## Sector 3 - -x in [1.5, 3.0] -y in [0.0, 1.0] - -## Sector 4 - -x in [1.5, 3.0] -y in [1.0, 2.0] - -## Schematic - -| 1 | 4 | -|---------|----------| -| 2 | 3 | diff --git a/tools/localisation_machine_learning/data_obtention.py b/tools/localisation_machine_learning/data_obtention.py deleted file mode 100644 index a65cb6d2..00000000 --- a/tools/localisation_machine_learning/data_obtention.py +++ /dev/null @@ -1,268 +0,0 @@ -""" -Need export PYTHONPATH=${WEBOTS_HOME}/lib/controller/python38 -""" - -from controller import Supervisor -from controller import Field -from os import environ - -import numpy as np -import math -import time -import os -import csv -import joblib - -folder_for_CSV = "/data" - - -obstacle_1 = [0.9, 1.85] -obstacle_2 = [1.5, 1.7] -obstacle_3 = [2.1, 1.85] - -fullPath = os.getcwd() + folder_for_CSV - -if not os.path.isdir("." + folder_for_CSV): - os.mkdir(fullPath) - -x = 0.171 -y = 0.171 - -x_sample = 30 -y_sample = 20 - -full_turn = [ - [1.0, 0.0, 0.0, -1.57], - [0.982902, -0.130198, -0.130198, -1.58804], - [-0.934738, 0.251261, 0.251261, 1.63823], - [-0.862359, 0.358006, 0.358006, 1.71834], - [0.775, -0.447, -0.447, -1.82], - [0.678, -0.52, -0.52, -1.95], - [0.577, -0.577, -0.577, -2.09], - [0.477, -0.622, -0.622, -2.25], - [0.378, -0.655, -0.655, -2.42], - [0.281, -0.679, -0.679, -2.59], - [0.186, -0.695, -0.695, -2.77], - [0.0927, -0.704, -0.704, -2.96], - [0.0, -0.707, -0.707, -3.14], - [0.0927, 0.704, 0.704, -2.96], - [0.186, 0.695, 0.695, -2.77], - [0.281, 0.679, 0.679, -2.59], - [0.378, 0.655, 0.655, -2.42], - [0.477, 0.622, 0.622, -2.25], - [0.577, 0.577, 0.577, -2.09], - [0.678, 0.52, 0.52, -1.95], - [0.775, 0.447, 0.447, -1.82], - [0.863, 0.357, 0.357, -1.72], - [0.935, 0.251, 0.251, -1.64], - [0.983, 0.129, 0.129, -1.59] -] - -angular_orientation = [] -for i in range(24): - angular_orientation.append(math.pi * i/12) - -environ["WEBOTS_ROBOT_NAME"] = "asterix" -robot = Supervisor() - -vlx_array = [] -for i in range(6): - vlx = robot.getDevice(f'vlx_0x3{i}') - vlx.enable(1) - vlx_array.append(vlx) - -asterix = robot.getFromDef('ASTERIX') -translationtion_field = asterix.getField('translation') -rotation_field = asterix.getField('rotation') - -def get_vlx_values(): - values = [] - for i in vlx_array: - values.append(round(i.getValue(), 1)) - return values - -def hitting_obstacle(t_x, t_y): - if t_x > (obstacle_1[0] - 0.2) and t_x < (obstacle_1[0] + 0.2) and t_y > obstacle_1[1] - 0.2: - return True - if t_x > (obstacle_2[0] - 0.2) and t_x < (obstacle_2[0] + 0.2) and t_y > obstacle_2[1] - 0.2: - return True - if t_x > (obstacle_3[0] - 0.2) and t_x < (obstacle_3[0] + 0.2) and t_y > obstacle_3[1] - 0.2: - return True - return False - -def remove_gobelets(): - for i in range(1,51): - gob = robot.getFromDef(f'GOB{i}') - gob.remove() - -def acquire_data(): - translationtion_field.setSFVec3f([x, 0.17, y]) - - for orien in range(0,4): - for sector in range(1,5): - with open(f'data/sector{sector}_orient{orien}.csv', 'w') as f: - writer = csv.writer(f, delimiter=',') - for j in range(13): - for k in range(8): - for i in range(int(len(full_turn)/4)): - if sector == 1: - tr_x = x + (j/10) - tr_y = y + (k/10) - if sector == 2: - tr_x = x + (j/10) - tr_y = 2.0 - y - (k/10) - if hitting_obstacle(tr_x, tr_y): - tr_x = x - tr_y = 2.0 - y - if sector == 3: - tr_x = 3.0 - x - (j/10) - tr_y = 2.0 - y - (k/10) - if hitting_obstacle(tr_x, tr_y): - tr_x = 3.0 - x - tr_y = 2.0 - y - if sector == 4: - tr_x = 3.0 - x - (j/10) - tr_y = y + (k/10) - rotation_field.setSFRotation(full_turn[orien*int(len(full_turn)/4) + i]) - translationtion_field.setSFVec3f([tr_x, 0.17, tr_y]) - robot.step(1) - time.sleep(0.0005) - values = get_vlx_values() - position = [asterix.getPosition()[0], 2 - asterix.getPosition()[2]] - writer.writerow(np.concatenate([position, [angular_orientation[orien*int(len(full_turn)/4) + i]], values])) - -def right_first_diag(x,y): - if x > 1.5 * y: - return True - return False - -def right_second_diag(x,y): - if x > 1.5 * (2- y): - return True - return False - -def check_for_sample(sector, x, y): - if sector in [1,6]: - return right_first_diag(x,y) - if sector in [2,5]: - return not right_first_diag(x,y) - if sector in [3,8]: - return not right_second_diag(x,y) - if sector in [4,7]: - return right_second_diag(x,y) - - -def acquire_data_rework(): - translationtion_field.setSFVec3f([x, 0.17, y]) - - for sector in range(1,9): - with open(f'data/sector{sector}.csv', 'w') as f: - writer = csv.writer(f, delimiter=',') - for k in range(y_sample): - for j in range(x_sample): - hit = False - angle = False - if sector in [1,2]: - tr_x = x + j*((1.5-x)/x_sample) - tr_y = y + k*((1.0-y)/y_sample) - if tr_x < 0.3 and tr_y < 0.3: - angle = True - if sector in [3,4]: - tr_x = x + j*((1.5-x)/x_sample) - tr_y = 2.0 - y - k*((1.0-y)/y_sample) - if hitting_obstacle(tr_x, tr_y): - hit = True - if tr_x < 0.3 and tr_y > 1.7: - angle = True - if sector in [5,6]: - tr_x = 3.0 - x - j*((1.5-x)/x_sample) - tr_y = 2.0 - y - k*((1.0-y)/y_sample) - if hitting_obstacle(tr_x, tr_y): - hit = True - if tr_x > 1.7 and tr_y > 1.7: - angle = True - if sector in [7,8]: - tr_x = 3.0 - x - j*((1.5-x)/x_sample) - tr_y = y + k*((1.0-y)/y_sample) - if tr_x > 1.7 and tr_y < 0.3: - angle = True - if check_for_sample(sector, tr_x, tr_y) and not hit and not angle: - translationtion_field.setSFVec3f([tr_x, 0.17, tr_y]) - for i in range(len(full_turn)): - rotation_field.setSFRotation(full_turn[i]) - robot.step(1) - time.sleep(0.0005) - values = get_vlx_values() - position = [asterix.getPosition()[0], 2 - asterix.getPosition()[2]] - writer.writerow(np.concatenate([position, [angular_orientation[i]], values])) - -def test_regression(): - regr = joblib.load('test.sav') - difftot = 0 - nb = 0 - max = 0 - nbmax = -1 - - for j in range(13): - for k in range(8): - for i in range(int(len(full_turn)/4)): - tr_x = x + (j/10) - tr_y = y + (k/10) - rotation_field.setSFRotation(full_turn[i]) - translationtion_field.setSFVec3f([tr_x, 0.17, tr_y]) - robot.step(1) - time.sleep(0.0005) - values = get_vlx_values() - predicted_position = regr.predict([values]) - position = [asterix.getPosition()[0], 2 - asterix.getPosition()[2]] - difftot += abs(predicted_position-position[0]) - nb += 1 - if abs(predicted_position-position[0])>max: - nbmax += 1 - max = abs(predicted_position-position[0]) - print(position) - print(difftot/nb) - print(max) - print(nbmax) - -def test_regression_rework(): - regr = joblib.load('test.sav') - difftot = 0 - nb = 0 - max = 0 - nbmax = -1 - - for k in range(y_sample): - for j in range(x_sample): - for i in range(len(full_turn)): - angle = False - tr_x = x + j*((1.5-x)/x_sample) - tr_y = y + k*((1.0-y)/y_sample) - if tr_x < 0.3 and tr_y < 0.3: - angle = True - if check_for_sample(1, tr_x, tr_y) and not angle: - rotation_field.setSFRotation(full_turn[i]) - translationtion_field.setSFVec3f([tr_x, 0.17, tr_y]) - robot.step(1) - time.sleep(0.0005) - values = get_vlx_values() - predicted_position = regr.predict([values]) - position = [asterix.getPosition()[0], 2 - asterix.getPosition()[2]] - difftot += abs(predicted_position-position[0]) - nb += 1 - if abs(predicted_position-position[0])>max: - nbmax += 1 - max = abs(predicted_position-position[0]) - print(position) - print(difftot/nb) - print(max) - print(nbmax) - - -def print_actual_vlx_states(): - print([asterix.getPosition()[0], 2 - asterix.getPosition()[2]]) - print(math.acos(asterix.getOrientation()[0])) - robot.step(1) - print(get_vlx_values()) - -test_regression_rework() diff --git a/tools/localisation_machine_learning/data_treatment.py b/tools/localisation_machine_learning/data_treatment.py deleted file mode 100644 index 7b12444a..00000000 --- a/tools/localisation_machine_learning/data_treatment.py +++ /dev/null @@ -1,31 +0,0 @@ -import numpy as np -import math -import os -import time -import pandas as pd -from sklearn.svm import NuSVR -from sklearn.pipeline import make_pipeline -from sklearn.preprocessing import StandardScaler -import joblib - -colnames = ["x", "y", "thetha", "vlx_0x30", "vlx_0x31", "vlx_0x32", "vlx_0x33", "vlx_0x34", "vlx_0x35"] - -data = pd.read_csv('data/sector1_orient0.csv', names=colnames) -x = data.x.tolist() -y = data.y.tolist() -theta = data.thetha.tolist() -vlx_0x30 = data.vlx_0x30.tolist() -vlx_0x31 = data.vlx_0x31.tolist() -vlx_0x32 = data.vlx_0x32.tolist() -vlx_0x33 = data.vlx_0x33.tolist() -vlx_0x34 = data.vlx_0x34.tolist() -vlx_0x35 = data.vlx_0x35.tolist() -target = x -vlx_array = np.array([vlx_0x30, vlx_0x31, vlx_0x32, vlx_0x33, vlx_0x34, vlx_0x35]).T -clf = make_pipeline(StandardScaler(), NuSVR(C=200.0, nu=1.0)) - -clf.fit(vlx_array, target) - -joblib.dump(clf, 'test.sav') - -print(clf.score(vlx_array, target)) From 1d66fe3509a2a24e8f5d4086db180cb284541e20 Mon Sep 17 00:00:00 2001 From: PhileasL Date: Fri, 26 Feb 2021 11:01:25 +0100 Subject: [PATCH 62/67] Blacked python code --- .../localisation/localisation_node.py | 8 ++++++-- src/modules/robot/robot/interfaces.py | 2 +- src/modules/robot/robot/launcher.py | 8 ++++---- src/navigation/teb_obstacles/setup.py | 18 ++++++++---------- 4 files changed, 19 insertions(+), 17 deletions(-) diff --git a/src/modules/localisation/localisation/localisation_node.py b/src/modules/localisation/localisation/localisation_node.py index 943f686e..cfec7cd9 100644 --- a/src/modules/localisation/localisation/localisation_node.py +++ b/src/modules/localisation/localisation/localisation_node.py @@ -29,8 +29,11 @@ def __init__(self): self._tf.header.frame_id = "map" self._tf.child_frame_id = "odom" self.update_transform() - self.get_initial_tf_srv = self.create_service(TransformixParametersTransformStamped, - 'get_odom_map_tf', self.get_initial_tf_srv_callback) + self.get_initial_tf_srv = self.create_service( + TransformixParametersTransformStamped, + "get_odom_map_tf", + self.get_initial_tf_srv_callback, + ) self.subscription_ = self.create_subscription( MarkerArray, "/allies_positions_markers", @@ -145,6 +148,7 @@ def get_initial_tf_srv_callback(self, request, response): response.transform_stamped = self._initial_tf return response + def main(args=None): """Entrypoint.""" rclpy.init(args=args) diff --git a/src/modules/robot/robot/interfaces.py b/src/modules/robot/robot/interfaces.py index de765453..3ea4abd9 100644 --- a/src/modules/robot/robot/interfaces.py +++ b/src/modules/robot/robot/interfaces.py @@ -40,7 +40,7 @@ def generate_launch_description(): Node( package="drive", executable="drive", - output={'both': 'log'}, + output={"both": "log"}, parameters=[params], remappings=remappings, ), diff --git a/src/modules/robot/robot/launcher.py b/src/modules/robot/robot/launcher.py index 174b5fab..8cabe0b9 100644 --- a/src/modules/robot/robot/launcher.py +++ b/src/modules/robot/robot/launcher.py @@ -127,10 +127,10 @@ def generate_robot_launch_description(robot_namespace: str, simulation=False): remappings=remappings, ), Node( - package='teb_obstacles', - executable='teb_obstacles', - output='screen', - parameters=[] + package="teb_obstacles", + executable="teb_obstacles", + output="screen", + parameters=[], ), IncludeLaunchDescription( PythonLaunchDescriptionSource( diff --git a/src/navigation/teb_obstacles/setup.py b/src/navigation/teb_obstacles/setup.py index bdcc7740..eafba6de 100644 --- a/src/navigation/teb_obstacles/setup.py +++ b/src/navigation/teb_obstacles/setup.py @@ -7,27 +7,25 @@ from os import path from setuptools import setup, find_packages -package_name = 'teb_obstacles' +package_name = "teb_obstacles" setup( name=package_name, - version='0.8.3', + version="0.8.3", packages=find_packages(), data_files=[ (path.join("share", package_name), ["package.xml"]), - ('share/ament_index/resource_index/packages', ['resource/' + package_name]), + ("share/ament_index/resource_index/packages", ["resource/" + package_name]), ], - install_requires=['setuptools'], + install_requires=["setuptools"], zip_safe=True, author="Philéas LAMBERT", - maintainer='Phileas LAMBERT', - maintainer_email='phileas.lambert@gmail.com', + maintainer="Phileas LAMBERT", + maintainer_email="phileas.lambert@gmail.com", keywords=["ROS2", "teb_obstacles", "CDFR"], - description='teb_obstacles node compute and send dynamic teb_obstacles', + description="teb_obstacles node compute and send dynamic teb_obstacles", license="ECAM Makers :: CDFR 2021", entry_points={ - 'console_scripts': [ - 'teb_obstacles = teb_obstacles.teb_obstacles:main' - ], + "console_scripts": ["teb_obstacles = teb_obstacles.teb_obstacles:main"], }, ) From be35ecbe6a19e42695cad1362f53f49be9bd3534 Mon Sep 17 00:00:00 2001 From: PhileasL Date: Fri, 26 Feb 2021 11:04:08 +0100 Subject: [PATCH 63/67] Blacked localisation_node + fix lexical problems --- .../teb_obstacles/teb_obstacles.py | 77 +++++++++++++------ 1 file changed, 52 insertions(+), 25 deletions(-) diff --git a/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py b/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py index 3e9cec52..f04385a5 100644 --- a/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py +++ b/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py @@ -15,43 +15,56 @@ from platform import machine from transformix_msgs.srv import TransformixParametersTransformStamped -class Teb_obstacles(Node): +class Teb_obstacles(Node): def __init__(self): super().__init__("teb_dynamic_obstacles_node") self.simulation = True if machine() != "aarch64" else False - self.allie = "obelix" if self.get_namespace().strip("/") == "asterix" else "asterix" + self.ally = ( + "obelix" if self.get_namespace().strip("/") == "asterix" else "asterix" + ) - self.get_allie_odom_transformation() + self.get_ally_odom_transformation() self.allies_subscription_ = self.create_subscription( - Odometry, f'/{self.allie}/odom', self.allies_subscription_callback, 10) - self.ennemies_subscription_ = self.create_subscription( - MarkerArray, '/ennemies_positions_markers', self.ennemies_subscription_callback, 10) + Odometry, f"/{self.ally}/odom", self.allies_subscription_callback, 10 + ) + self.enemies_subscription_ = self.create_subscription( + MarkerArray, + "/enemies_positions_markers", + self.enemies_subscription_callback, + 10, + ) self.allies_subscription_ - self.ennemies_subscription_ + self.enemies_subscription_ - self.obstacles_publisher_ = self.create_publisher(ObstacleArrayMsg, 'obstacles', 10) + self.obstacles_publisher_ = self.create_publisher( + ObstacleArrayMsg, "obstacles", 10 + ) self.dictionary_index_id = {"0":0, "1":0, "2":0} - self.last_time_allie_callback = self.get_clock().now().to_msg() + self.last_time_ally_callback = self.get_clock().now().to_msg() self.initObstaclesArray() self.create_timer(0.5, self.send_obstacles) - self.get_logger().info('teb_dynamic_obstacles node is ready') + self.get_logger().info("teb_dynamic_obstacles node is ready") - def get_allie_odom_transformation(self): + def get_ally_odom_transformation(self): if self.simulation: return - get_tf_client = self.create_client(TransformixParametersTransformStamped, f'/{self.allie}/get_odom_map_tf') + get_tf_client = self.create_client( + TransformixParametersTransformStamped, f"/{self.ally}/get_odom_map_tf" + ) if not get_tf_client.wait_for_service(timeout_sec=15.0): - self.get_logger().info(f'No service /{self.allie}/get_odom_map_tf availible, is there ony one robot?') + self.get_logger().info( + f"No service /{self.ally}/get_odom_map_tf availible, is there ony one robot?" + ) return get_tf_request = TransformixParametersTransformStamped.Request() future = get_tf_client.call_async(get_tf_request) @@ -59,12 +72,12 @@ def get_allie_odom_transformation(self): try: response = future.result() except Exception as e: - self.get_logger().info( - 'Service call failed %r' % (e,)) + self.get_logger().info("Service call failed %r" % (e,)) else: self.odom_map_tf = response.transform_stamped + def initObstaclesArray(self): - """ObstacleArray index 0: allie, index 1-2: ennemies""" + """ObstacleArray index 0: ally, index 1-2: enemies""" self.obstacles = ObstacleArrayMsg() self.obstacles.header.frame_id = "map" self.obstacles.obstacles.append(ObstacleMsg()) @@ -80,32 +93,45 @@ def initObstaclesArray(self): def get_diff_time(self, t1, t2): """Returns the nb of seconds between the two Time object""" - return float(t1.sec - t2.sec + (t1.nanosec - t2.nanosec)*1e-9) + return t1.sec - t2.sec + (t1.nanosec - t2.nanosec) * 1e-9 def set_obstacle(self, index, marker): """Set the marker as obstacle in ObstacleArrayMsg at the given index, - compute the linear velocities relative to the previous state""" - self.previous_obstacles.obstacles[index] = copy.deepcopy(self.obstacles.obstacles[index]) + compute the linear velocities relative to the previous state""" + self.previous_obstacles.obstacles[index] = copy.deepcopy( + self.obstacles.obstacles[index] + ) self.obstacles.obstacles[index].header = marker.header self.obstacles.obstacles[index].polygon.points[0].x = marker.pose.position.x self.obstacles.obstacles[index].polygon.points[0].y = marker.pose.position.y - dt = float(self.get_diff_time(marker.header.stamp, self.previous_obstacles.obstacles[index].header.stamp)) + dt = float( + self.get_diff_time( + marker.header.stamp, + self.previous_obstacles.obstacles[index].header.stamp, + ) + ) if dt != 0.0: self.obstacles.obstacles[index].velocities.twist.linear.x = ( - marker.pose.position.x - self.previous_obstacles.obstacles[index].polygon.points[0].x + marker.pose.position.x + - self.previous_obstacles.obstacles[index].polygon.points[0].x ) / dt self.obstacles.obstacles[index].velocities.twist.linear.y = ( - marker.pose.position.y - self.previous_obstacles.obstacles[index].polygon.points[0].y + marker.pose.position.y + - self.previous_obstacles.obstacles[index].polygon.points[0].y ) / dt - def allies_subscription_callback(self, msg): """Determine the pose of base_link in map - set the dynamic obstacle for teb_local_planner""" - if self.get_diff_time(self.get_clock().now().to_msg(), self.last_time_allie_callback) > 0.3: + set the dynamic obstacle for teb_local_planner""" + if ( + self.get_diff_time( + self.get_clock().now().to_msg(), self.last_time_ally_callback + ) + > 0.3 + ): pose = msg.pose.pose x = pose.position.x + self.odom_map_tf.transform.translation.x y = pose.position.y + self.odom_map_tf.transform.translation.y @@ -136,6 +162,7 @@ def ennemies_subscription_callback(self, msg): def send_obstacles(self): self.obstacles_publisher_.publish(self.obstacles) + def main(args=None): """Entrypoint.""" rclpy.init(args=args) From 1b50224ba950c7b8c32e03ecc8e1d5dd6bfb4017 Mon Sep 17 00:00:00 2001 From: PhileasL Date: Fri, 26 Feb 2021 11:10:35 +0100 Subject: [PATCH 64/67] Refactoring enemies_subscription_callback function --- .../teb_obstacles/teb_obstacles.py | 40 ++++++++++--------- 1 file changed, 21 insertions(+), 19 deletions(-) diff --git a/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py b/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py index f04385a5..72d3b8b5 100644 --- a/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py +++ b/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py @@ -43,7 +43,7 @@ def __init__(self): ObstacleArrayMsg, "obstacles", 10 ) - self.dictionary_index_id = {"0":0, "1":0, "2":0} + self.enemies_markers_ids = [0, 0] self.last_time_ally_callback = self.get_clock().now().to_msg() @@ -139,25 +139,27 @@ def allies_subscription_callback(self, msg): tmp_marker.pose.position.x = x tmp_marker.pose.position.y = y self.set_obstacle(0, tmp_marker) - self.last_time_allie_callback = self.get_clock().now().to_msg() - - def ennemies_subscription_callback(self, msg): - """Identity the ennemie marker in assurancetourix marker_array detection - set the dynamic obstacle for teb_local_planner""" - for ennemie_marker in msg.markers: - if ennemie_marker.id <= 10: - in_dict = False - for index in range(1,2): - if self.dictionary_index_id[f"{index}"] == ennemie_marker.id: - self.set_obstacle(index, ennemie_marker) - in_dict = True - if not in_dict: - if self.dictionary_index_id["1"] == 0: - self.dictionary_index_id["1"] = ennemie_marker.id - elif self.dictionary_index_id["2"] == 0: - self.dictionary_index_id["2"] = ennemie_marker.id + self.last_time_ally_callback = self.get_clock().now().to_msg() + + def enemies_subscription_callback(self, msg): + """Identify the enemy marker in assurancetourix marker_array detection + set the dynamic obstacle for teb_local_planner""" + for enemy_marker in msg.markers: + if enemy_marker.id <= 10: # >10 are predicted markers + marker_stored = False + for index in range(2): + if self.enemies_markers_ids[index] == enemy_marker.id: + self.set_obstacle(index+1, enemy_marker) + marker_stored = True + if not marker_stored: + if self.enemies_markers_ids[0] == 0: + self.enemies_markers_ids[0] = enemy_marker.id + elif self.enemies_markers_ids[1] == 0: + self.enemies_markers_ids[1] = enemy_marker.id else: - self.get_logger().info('obstacleArray index limit, is there 3 ennemies, or is it a bad marker detection') + self.get_logger().info( + "obstacleArray index limit, are there 3 enemies, or is it a bad marker detection" + ) def send_obstacles(self): self.obstacles_publisher_.publish(self.obstacles) From c9739f94f8c67899bc6c3df0d7a41581e7eb89ad Mon Sep 17 00:00:00 2001 From: PhileasL Date: Fri, 26 Feb 2021 11:13:31 +0100 Subject: [PATCH 65/67] Revert drive log: output="screen" --- src/modules/robot/robot/interfaces.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/robot/robot/interfaces.py b/src/modules/robot/robot/interfaces.py index 3ea4abd9..685c6d3f 100644 --- a/src/modules/robot/robot/interfaces.py +++ b/src/modules/robot/robot/interfaces.py @@ -40,7 +40,7 @@ def generate_launch_description(): Node( package="drive", executable="drive", - output={"both": "log"}, + output="screen", parameters=[params], remappings=remappings, ), From ded9c98b3fcf4a8d5725f840b930fe6ea27f1fcf Mon Sep 17 00:00:00 2001 From: PhileasL Date: Fri, 26 Feb 2021 11:22:50 +0100 Subject: [PATCH 66/67] Alright then, teb_obstacle is trully blacked now --- src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py b/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py index 72d3b8b5..173c23d4 100644 --- a/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py +++ b/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py @@ -145,11 +145,11 @@ def enemies_subscription_callback(self, msg): """Identify the enemy marker in assurancetourix marker_array detection set the dynamic obstacle for teb_local_planner""" for enemy_marker in msg.markers: - if enemy_marker.id <= 10: # >10 are predicted markers + if enemy_marker.id <= 10: # >10 are predicted markers marker_stored = False for index in range(2): if self.enemies_markers_ids[index] == enemy_marker.id: - self.set_obstacle(index+1, enemy_marker) + self.set_obstacle(index + 1, enemy_marker) marker_stored = True if not marker_stored: if self.enemies_markers_ids[0] == 0: From 5456500e29715e4e329e5e8063cca31493723130 Mon Sep 17 00:00:00 2001 From: PhileasL Date: Fri, 26 Feb 2021 12:33:53 +0100 Subject: [PATCH 67/67] Removing useless instructions --- src/modules/localisation/localisation/localisation_node.py | 1 - src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py | 2 -- 2 files changed, 3 deletions(-) diff --git a/src/modules/localisation/localisation/localisation_node.py b/src/modules/localisation/localisation/localisation_node.py index cfec7cd9..90174b23 100644 --- a/src/modules/localisation/localisation/localisation_node.py +++ b/src/modules/localisation/localisation/localisation_node.py @@ -40,7 +40,6 @@ def __init__(self): self.allies_subscription_callback, 10, ) - self.subscription_ # prevent unused variable warning self.tf_publisher_ = self.create_publisher( TransformStamped, "adjust_odometry", 10 ) diff --git a/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py b/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py index 173c23d4..c617c544 100644 --- a/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py +++ b/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py @@ -36,8 +36,6 @@ def __init__(self): self.enemies_subscription_callback, 10, ) - self.allies_subscription_ - self.enemies_subscription_ self.obstacles_publisher_ = self.create_publisher( ObstacleArrayMsg, "obstacles", 10